Use PoseGraphInterface instead of PoseGraph. (#1547)

Tiny improvement to not depend on more than is needed.

Signed-off-by: Wolfgang Hess <whess@lyft.com>
master
Wolfgang Hess 2020-11-04 15:57:50 +01:00 committed by GitHub
parent 70612a4d40
commit b1dde03d52
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
1 changed files with 3 additions and 4 deletions

View File

@ -20,7 +20,6 @@
#include "absl/strings/str_cat.h" #include "absl/strings/str_cat.h"
#include "cartographer/io/color.h" #include "cartographer/io/color.h"
#include "cartographer/io/proto_stream.h" #include "cartographer/io/proto_stream.h"
#include "cartographer/mapping/pose_graph.h"
#include "cartographer_ros/msg_conversion.h" #include "cartographer_ros/msg_conversion.h"
#include "cartographer_ros/time_conversion.h" #include "cartographer_ros/time_conversion.h"
#include "cartographer_ros_msgs/StatusCode.h" #include "cartographer_ros_msgs/StatusCode.h"
@ -207,7 +206,7 @@ MapBuilderBridge::GetTrajectoryStates() {
for (const auto& sensor_bridge : sensor_bridges_) { for (const auto& sensor_bridge : sensor_bridges_) {
trajectory_states.insert(std::make_pair( trajectory_states.insert(std::make_pair(
sensor_bridge.first, sensor_bridge.first,
::cartographer::mapping::PoseGraph::TrajectoryState::ACTIVE)); ::cartographer::mapping::PoseGraphInterface::TrajectoryState::ACTIVE));
} }
return trajectory_states; return trajectory_states;
} }
@ -299,7 +298,7 @@ visualization_msgs::MarkerArray MapBuilderBridge::GetTrajectoryNodeList() {
const auto constraints = map_builder_->pose_graph()->constraints(); const auto constraints = map_builder_->pose_graph()->constraints();
for (const auto& constraint : constraints) { for (const auto& constraint : constraints) {
if (constraint.tag == if (constraint.tag ==
cartographer::mapping::PoseGraph::Constraint::INTER_SUBMAP) { cartographer::mapping::PoseGraphInterface::Constraint::INTER_SUBMAP) {
if (constraint.node_id.trajectory_id == if (constraint.node_id.trajectory_id ==
constraint.submap_id.trajectory_id) { constraint.submap_id.trajectory_id) {
trajectory_to_last_inter_submap_constrained_node[constraint.node_id trajectory_to_last_inter_submap_constrained_node[constraint.node_id
@ -451,7 +450,7 @@ visualization_msgs::MarkerArray MapBuilderBridge::GetConstraintList() {
visualization_msgs::Marker *constraint_marker, *residual_marker; visualization_msgs::Marker *constraint_marker, *residual_marker;
std_msgs::ColorRGBA color_constraint, color_residual; std_msgs::ColorRGBA color_constraint, color_residual;
if (constraint.tag == if (constraint.tag ==
cartographer::mapping::PoseGraph::Constraint::INTRA_SUBMAP) { cartographer::mapping::PoseGraphInterface::Constraint::INTRA_SUBMAP) {
constraint_marker = &constraint_intra_marker; constraint_marker = &constraint_intra_marker;
residual_marker = &residual_intra_marker; residual_marker = &residual_intra_marker;
// Color mapping for submaps of various trajectories - add trajectory id // Color mapping for submaps of various trajectories - add trajectory id