diff --git a/cartographer_ros/cartographer_ros/node.cc b/cartographer_ros/cartographer_ros/node.cc index 84ce7d3..7570451 100644 --- a/cartographer_ros/cartographer_ros/node.cc +++ b/cartographer_ros/cartographer_ros/node.cc @@ -217,11 +217,13 @@ void Node::PublishTrajectoryStates(const ::ros::WallTimerEvent& timer_event) { FromRos(ros::Time::now()), extrapolator.GetLastExtrapolatedTime()); stamped_transform.header.stamp = ToRos(now); - Rigid3d tracking_to_local = extrapolator.ExtrapolatePose(now); - if (trajectory_state.trajectory_options.publish_frame_projected_to_2d) { - tracking_to_local = carto::transform::Embed3D( - carto::transform::Project2D(tracking_to_local)); - } + const Rigid3d tracking_to_local = [&] { + if (trajectory_state.trajectory_options.publish_frame_projected_to_2d) { + return carto::transform::Embed3D( + carto::transform::Project2D(extrapolator.ExtrapolatePose(now))); + } + return extrapolator.ExtrapolatePose(now); + }(); const Rigid3d tracking_to_map = trajectory_state.local_to_map * tracking_to_local;