Fix bug in MapBuilderBridge::GetTrajectoryStates() (#652)
parent
4a1366501d
commit
7a7b210c94
|
@ -207,7 +207,7 @@ visualization_msgs::MarkerArray MapBuilderBridge::GetTrajectoryNodeList() {
|
||||||
CreateTrajectoryMarker(trajectory_id, node_options_.map_frame);
|
CreateTrajectoryMarker(trajectory_id, node_options_.map_frame);
|
||||||
|
|
||||||
for (const auto& node_id_data : node_poses.trajectory(trajectory_id)) {
|
for (const auto& node_id_data : node_poses.trajectory(trajectory_id)) {
|
||||||
if (node_id_data.data.has_constant_data) {
|
if (!node_id_data.data.has_constant_data) {
|
||||||
PushAndResetLineMarker(&marker, &trajectory_node_list.markers);
|
PushAndResetLineMarker(&marker, &trajectory_node_list.markers);
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue