diff --git a/cartographer_ros/cartographer_ros/assets_writer_main.cc b/cartographer_ros/cartographer_ros/assets_writer_main.cc index c4dff01..238f0df 100644 --- a/cartographer_ros/cartographer_ros/assets_writer_main.cc +++ b/cartographer_ros/cartographer_ros/assets_writer_main.cc @@ -55,7 +55,8 @@ int main(int argc, char** argv) { << "-pose_graph_filename is missing."; ::cartographer_ros::AssetsWriter asset_writer( - FLAGS_pose_graph_filename, absl::StrSplit(FLAGS_bag_filenames, ','), + FLAGS_pose_graph_filename, + absl::StrSplit(FLAGS_bag_filenames, ',', absl::SkipEmpty()), FLAGS_output_file_prefix); asset_writer.Run(FLAGS_configuration_directory, FLAGS_configuration_basename, diff --git a/cartographer_ros/cartographer_ros/offline_node.cc b/cartographer_ros/cartographer_ros/offline_node.cc index 58bca6a..691b039 100644 --- a/cartographer_ros/cartographer_ros/offline_node.cc +++ b/cartographer_ros/cartographer_ros/offline_node.cc @@ -87,10 +87,10 @@ void RunOfflineNode(const MapBuilderFactory& map_builder_factory) { CHECK(!(FLAGS_bag_filenames.empty() && FLAGS_load_state_filename.empty())) << "-bag_filenames and -load_state_filename cannot both be unspecified."; const std::vector bag_filenames = - absl::StrSplit(FLAGS_bag_filenames, ','); + absl::StrSplit(FLAGS_bag_filenames, ',', absl::SkipEmpty()); cartographer_ros::NodeOptions node_options; const std::vector configuration_basenames = - absl::StrSplit(FLAGS_configuration_basenames, ','); + absl::StrSplit(FLAGS_configuration_basenames, ',', absl::SkipEmpty()); std::vector bag_trajectory_options(1); std::tie(node_options, bag_trajectory_options.at(0)) = LoadOptions(FLAGS_configuration_directory, configuration_basenames.at(0)); @@ -123,7 +123,7 @@ void RunOfflineNode(const MapBuilderFactory& map_builder_factory) { std::vector urdf_transforms; const std::vector urdf_filenames = - absl::StrSplit(FLAGS_urdf_filenames, ','); + absl::StrSplit(FLAGS_urdf_filenames, ',', absl::SkipEmpty()); for (const auto& urdf_filename : urdf_filenames) { const auto current_urdf_transforms = ReadStaticTransformsFromUrdf(urdf_filename, &tf_buffer);