diff --git a/cartographer_ros/cartographer_ros/assets_writer_main.cc b/cartographer_ros/cartographer_ros/assets_writer_main.cc index 93d06e0..dc9589f 100644 --- a/cartographer_ros/cartographer_ros/assets_writer_main.cc +++ b/cartographer_ros/cartographer_ros/assets_writer_main.cc @@ -196,9 +196,8 @@ void Run(const string& pose_graph_filename, ReadStaticTransformsFromUrdf(urdf_filename, &tf_buffer); } - const auto transform_interpolation_buffer = - carto::transform::TransformInterpolationBuffer::FromTrajectory( - trajectory_proto); + const carto::transform::TransformInterpolationBuffer + transform_interpolation_buffer(trajectory_proto); rosbag::Bag bag; bag.open(bag_filename, rosbag::bagmode::Read); rosbag::View view(bag); @@ -211,15 +210,15 @@ void Run(const string& pose_graph_filename, if (message.isType()) { points_batch = HandleMessage( *message.instantiate(), tracking_frame, - tf_buffer, *transform_interpolation_buffer); + tf_buffer, transform_interpolation_buffer); } else if (message.isType()) { points_batch = HandleMessage( *message.instantiate(), - tracking_frame, tf_buffer, *transform_interpolation_buffer); + tracking_frame, tf_buffer, transform_interpolation_buffer); } else if (message.isType()) { points_batch = HandleMessage( *message.instantiate(), tracking_frame, - tf_buffer, *transform_interpolation_buffer); + tf_buffer, transform_interpolation_buffer); } if (points_batch != nullptr) { points_batch->trajectory_id = trajectory_id; diff --git a/cartographer_ros/cartographer_ros/offline_node_main.cc b/cartographer_ros/cartographer_ros/offline_node_main.cc index a413dab..87a039f 100644 --- a/cartographer_ros/cartographer_ros/offline_node_main.cc +++ b/cartographer_ros/cartographer_ros/offline_node_main.cc @@ -213,7 +213,8 @@ void Run(const std::vector& bag_filenames) { } // Ensure the clock is republished after the bag has been finished, during the - // final optimization, serialization, and optional indefinite spinning at the end. + // final optimization, serialization, and optional indefinite spinning at the + // end. clock_republish_timer.start(); node.RunFinalOptimization();