25 #include "cartographer/mapping/proto/pose_graph.pb.h" 29 #include "gflags/gflags.h" 30 #include "glog/logging.h" 36 #include "tf2_msgs/TFMessage.h" 39 "Bags to process, must be in the same order as the trajectories " 40 "in 'pose_graph_filename'.");
42 "Proto stream file containing the pose graph.");
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; })) /
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";
63 result <<
"100%: " << v->back() <<
"\n";
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);
79 std::vector<double> deviation_translation, deviation_rotation;
80 const double signal_maximum = std::numeric_limits<double>::max();
82 if (!message.isType<tf2_msgs::TFMessage>()) {
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") {
93 if (!transform_interpolation_buffer.Has(transform_time)) {
94 deviation_translation.push_back(signal_maximum);
95 deviation_rotation.push_back(signal_maximum);
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())
104 deviation_rotation.push_back(
105 published_transform.rotation().angularDistance(
106 optimized_transform.rotation()));
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);
127 int main(
int argc,
char** argv) {
128 FLAGS_alsologtostderr =
true;
129 google::InitGoogleLogging(argv[0]);
130 google::SetUsageMessage(
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);
void open(std::string const &filename, uint32_t mode=bagmode::Read)
int main(int argc, char **argv)
Rigid3d ToRigid3d(const geometry_msgs::TransformStamped &transform)
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)