diff --git a/cartographer_ros/cartographer_ros/start_trajectory_main.cc b/cartographer_ros/cartographer_ros/start_trajectory_main.cc index 18ea230..6e2b231 100644 --- a/cartographer_ros/cartographer_ros/start_trajectory_main.cc +++ b/cartographer_ros/cartographer_ros/start_trajectory_main.cc @@ -59,11 +59,14 @@ bool Run() { kStartTrajectoryServiceName); cartographer_ros_msgs::StartTrajectory srv; srv.request.options = ToRosMessage(LoadOptions()); - srv.request.topics.laser_scan_topic = kLaserScanTopic; - srv.request.topics.multi_echo_laser_scan_topic = kMultiEchoLaserScanTopic; - srv.request.topics.point_cloud2_topic = kPointCloud2Topic; - srv.request.topics.imu_topic = kImuTopic; - srv.request.topics.odometry_topic = kOdometryTopic; + srv.request.topics.laser_scan_topic = + ros::names::resolve(kLaserScanTopic, true /* apply topic remapping */); + srv.request.topics.multi_echo_laser_scan_topic = + ros::names::resolve(kMultiEchoLaserScanTopic, true); + srv.request.topics.point_cloud2_topic = + ros::names::resolve(kPointCloud2Topic, true); + srv.request.topics.imu_topic = ros::names::resolve(kImuTopic, true); + srv.request.topics.odometry_topic = ros::names::resolve(kOdometryTopic, true); if (!client.call(srv)) { LOG(ERROR) << "Error starting trajectory.";