diff --git a/cartographer_ros/cartographer_ros/node_main.cc b/cartographer_ros/cartographer_ros/node_main.cc index 75b195a..b41972c 100644 --- a/cartographer_ros/cartographer_ros/node_main.cc +++ b/cartographer_ros/cartographer_ros/node_main.cc @@ -54,8 +54,7 @@ void Run() { auto map_builder = cartographer::common::make_unique( - node_options.map_builder_options, - nullptr /* global_slam_result_callback*/); + node_options.map_builder_options); Node node(node_options, std::move(map_builder), &tf_buffer); if (!FLAGS_load_state_filename.empty()) { node.LoadState(FLAGS_load_state_filename, FLAGS_load_frozen_state); diff --git a/cartographer_ros/cartographer_ros/offline_node_main.cc b/cartographer_ros/cartographer_ros/offline_node_main.cc index 8290480..845954f 100644 --- a/cartographer_ros/cartographer_ros/offline_node_main.cc +++ b/cartographer_ros/cartographer_ros/offline_node_main.cc @@ -33,8 +33,7 @@ int main(int argc, char** argv) { [](const ::cartographer::mapping::proto::MapBuilderOptions& map_builder_options) { return ::cartographer::common::make_unique< - ::cartographer::mapping::MapBuilder>( - map_builder_options, nullptr /* global_slam_result_callback */); + ::cartographer::mapping::MapBuilder>(map_builder_options); }; cartographer_ros::RunOfflineNode(map_builder_factory);