trajectory_comparison_main.cc
Go to the documentation of this file.
1 /*
2  * Copyright 2018 The Cartographer Authors
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 #include <algorithm>
18 #include <fstream>
19 #include <iostream>
20 #include <string>
21 #include <vector>
22 
25 #include "cartographer/mapping/proto/pose_graph.pb.h"
29 #include "gflags/gflags.h"
30 #include "glog/logging.h"
31 #include "ros/ros.h"
32 #include "ros/time.h"
33 #include "rosbag/bag.h"
34 #include "rosbag/view.h"
35 #include "tf2_eigen/tf2_eigen.h"
36 #include "tf2_msgs/TFMessage.h"
37 
38 DEFINE_string(bag_filename, "",
39  "Bags to process, must be in the same order as the trajectories "
40  "in 'pose_graph_filename'.");
41 DEFINE_string(pbstream_filename, "",
42  "Proto stream file containing the pose graph.");
43 
44 namespace cartographer_ros {
45 namespace {
46 
47 double FractionSmallerThan(const std::vector<double>& v, double x) {
48  return static_cast<double>(std::count_if(
49  v.begin(), v.end(), [=](double value) { return value < x; })) /
50  v.size();
51 }
52 
53 std::string QuantilesToString(std::vector<double>* v) {
54  if (v->empty()) return "(empty vector)";
55  std::sort(v->begin(), v->end());
56  std::stringstream result;
57  const int kNumQuantiles = 10;
58  for (int i = 0; i < kNumQuantiles; ++i) {
59  auto value = v->at(v->size() * i / kNumQuantiles);
60  auto percentage = 100 * i / kNumQuantiles;
61  result << percentage << "%: " << value << "\n";
62  }
63  result << "100%: " << v->back() << "\n";
64  return result.str();
65 }
66 
67 void Run(const std::string& pbstream_filename,
68  const std::string& bag_filename) {
69  cartographer::mapping::proto::PoseGraph pose_graph_proto =
71  const cartographer::mapping::proto::Trajectory& last_trajectory_proto =
72  *pose_graph_proto.mutable_trajectory()->rbegin();
74  transform_interpolation_buffer(last_trajectory_proto);
75 
76  rosbag::Bag bag;
77  bag.open(bag_filename, rosbag::bagmode::Read);
78  rosbag::View view(bag);
79  std::vector<double> deviation_translation, deviation_rotation;
80  const double signal_maximum = std::numeric_limits<double>::max();
81  for (const rosbag::MessageInstance& message : view) {
82  if (!message.isType<tf2_msgs::TFMessage>()) {
83  continue;
84  }
85  auto tf_message = message.instantiate<tf2_msgs::TFMessage>();
86  for (const auto& transform : tf_message->transforms) {
87  if (transform.header.frame_id != "map" ||
88  transform.child_frame_id != "base_link") {
89  continue;
90  }
91  const cartographer::common::Time transform_time =
92  FromRos(message.getTime());
93  if (!transform_interpolation_buffer.Has(transform_time)) {
94  deviation_translation.push_back(signal_maximum);
95  deviation_rotation.push_back(signal_maximum);
96  continue;
97  }
98  auto optimized_transform =
99  transform_interpolation_buffer.Lookup(transform_time);
100  auto published_transform = ToRigid3d(transform);
101  deviation_translation.push_back((published_transform.translation() -
102  optimized_transform.translation())
103  .norm());
104  deviation_rotation.push_back(
105  published_transform.rotation().angularDistance(
106  optimized_transform.rotation()));
107  }
108  }
109  bag.close();
110  LOG(INFO) << "Distribution of translation difference:\n"
111  << QuantilesToString(&deviation_translation);
112  LOG(INFO) << "Distribution of rotation difference:\n"
113  << QuantilesToString(&deviation_rotation);
114  LOG(INFO) << "Fraction of translation difference smaller than 1m: "
115  << FractionSmallerThan(deviation_translation, 1);
116  LOG(INFO) << "Fraction of translation difference smaller than 0.1m: "
117  << FractionSmallerThan(deviation_translation, 0.1);
118  LOG(INFO) << "Fraction of translation difference smaller than 0.05m: "
119  << FractionSmallerThan(deviation_translation, 0.05);
120  LOG(INFO) << "Fraction of translation difference smaller than 0.01m: "
121  << FractionSmallerThan(deviation_translation, 0.01);
122 }
123 
124 } // namespace
125 } // namespace cartographer_ros
126 
127 int main(int argc, char** argv) {
128  FLAGS_alsologtostderr = true;
129  google::InitGoogleLogging(argv[0]);
130  google::SetUsageMessage(
131  "\n\n"
132  "This compares a trajectory from a bag file against the "
133  "last trajectory in a pbstream file.\n");
134  google::ParseCommandLineFlags(&argc, &argv, true);
135  CHECK(!FLAGS_bag_filename.empty()) << "-bag_filename is missing.";
136  CHECK(!FLAGS_pbstream_filename.empty()) << "-pbstream_filename is missing.";
137  ::cartographer_ros::Run(FLAGS_pbstream_filename, FLAGS_bag_filename);
138 }
void open(std::string const &filename, uint32_t mode=bagmode::Read)
int main(int argc, char **argv)
Rigid3d ToRigid3d(const geometry_msgs::TransformStamped &transform)
void close()
UniversalTimeScaleClock::time_point Time
DEFINE_string(bag_filename, "", "Bags to process, must be in the same order as the trajectories " "in 'pose_graph_filename'.")
mapping::proto::PoseGraph DeserializePoseGraphFromFile(const std::string &file_name)
::cartographer::common::Time FromRos(const ::ros::Time &time)
void Run(const std::string &configuration_directory, const std::string &configuration_basename)


cartographer_ros
Author(s): The Cartographer Authors
autogenerated on Mon Feb 28 2022 22:06:05