Make MapBuilderBridge use GetAllTrajectoryNodePoses() (#649)

master
Christoph Schütte 2018-01-08 11:10:14 +01:00 committed by Wally B. Feed
parent dd00ede58a
commit a6095979aa
1 changed files with 4 additions and 4 deletions

View File

@ -201,13 +201,13 @@ MapBuilderBridge::GetTrajectoryStates() {
visualization_msgs::MarkerArray MapBuilderBridge::GetTrajectoryNodeList() {
visualization_msgs::MarkerArray trajectory_node_list;
const auto nodes = map_builder_->pose_graph()->GetTrajectoryNodes();
for (const int trajectory_id : nodes.trajectory_ids()) {
const auto node_poses = map_builder_->pose_graph()->GetTrajectoryNodePoses();
for (const int trajectory_id : node_poses.trajectory_ids()) {
visualization_msgs::Marker marker =
CreateTrajectoryMarker(trajectory_id, node_options_.map_frame);
for (const auto& node_id_data : nodes.trajectory(trajectory_id)) {
if (node_id_data.data.constant_data == nullptr) {
for (const auto& node_id_data : node_poses.trajectory(trajectory_id)) {
if (node_id_data.data.has_constant_data) {
PushAndResetLineMarker(&marker, &trajectory_node_list.markers);
continue;
}