Use absl::SkipEmpty() predicate. (#1042)

Fixes empty splits for default "" arguments. Follow up to #1026, thx to @ojura.
master
Michael Grupp 2018-10-04 15:18:21 +02:00 committed by Wally B. Feed
parent 8fab3fe4c4
commit 588c392b50
2 changed files with 5 additions and 4 deletions

View File

@ -55,7 +55,8 @@ int main(int argc, char** argv) {
<< "-pose_graph_filename is missing."; << "-pose_graph_filename is missing.";
::cartographer_ros::AssetsWriter asset_writer( ::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); FLAGS_output_file_prefix);
asset_writer.Run(FLAGS_configuration_directory, FLAGS_configuration_basename, asset_writer.Run(FLAGS_configuration_directory, FLAGS_configuration_basename,

View File

@ -87,10 +87,10 @@ void RunOfflineNode(const MapBuilderFactory& map_builder_factory) {
CHECK(!(FLAGS_bag_filenames.empty() && FLAGS_load_state_filename.empty())) CHECK(!(FLAGS_bag_filenames.empty() && FLAGS_load_state_filename.empty()))
<< "-bag_filenames and -load_state_filename cannot both be unspecified."; << "-bag_filenames and -load_state_filename cannot both be unspecified.";
const std::vector<std::string> bag_filenames = const std::vector<std::string> bag_filenames =
absl::StrSplit(FLAGS_bag_filenames, ','); absl::StrSplit(FLAGS_bag_filenames, ',', absl::SkipEmpty());
cartographer_ros::NodeOptions node_options; cartographer_ros::NodeOptions node_options;
const std::vector<std::string> configuration_basenames = const std::vector<std::string> configuration_basenames =
absl::StrSplit(FLAGS_configuration_basenames, ','); absl::StrSplit(FLAGS_configuration_basenames, ',', absl::SkipEmpty());
std::vector<TrajectoryOptions> bag_trajectory_options(1); std::vector<TrajectoryOptions> bag_trajectory_options(1);
std::tie(node_options, bag_trajectory_options.at(0)) = std::tie(node_options, bag_trajectory_options.at(0)) =
LoadOptions(FLAGS_configuration_directory, configuration_basenames.at(0)); LoadOptions(FLAGS_configuration_directory, configuration_basenames.at(0));
@ -123,7 +123,7 @@ void RunOfflineNode(const MapBuilderFactory& map_builder_factory) {
std::vector<geometry_msgs::TransformStamped> urdf_transforms; std::vector<geometry_msgs::TransformStamped> urdf_transforms;
const std::vector<std::string> urdf_filenames = const std::vector<std::string> urdf_filenames =
absl::StrSplit(FLAGS_urdf_filenames, ','); absl::StrSplit(FLAGS_urdf_filenames, ',', absl::SkipEmpty());
for (const auto& urdf_filename : urdf_filenames) { for (const auto& urdf_filename : urdf_filenames) {
const auto current_urdf_transforms = const auto current_urdf_transforms =
ReadStaticTransformsFromUrdf(urdf_filename, &tf_buffer); ReadStaticTransformsFromUrdf(urdf_filename, &tf_buffer);