24 #include "cartographer_ros_msgs/StatusCode.h" 25 #include "cartographer_ros_msgs/StatusResponse.h" 30 using ::cartographer::transform::Rigid3d;
32 constexpr
double kTrajectoryLineStripMarkerScale = 0.07;
33 constexpr
double kLandmarkMarkerScale = 0.3;
34 constexpr
double kConstraintMarkerScale = 0.025;
37 ::std_msgs::ColorRGBA result;
45 visualization_msgs::Marker CreateTrajectoryMarker(
const int trajectory_id,
46 const std::string& frame_id) {
47 visualization_msgs::Marker marker;
48 marker.ns =
"Trajectory " + std::to_string(trajectory_id);
50 marker.type = visualization_msgs::Marker::LINE_STRIP;
52 marker.header.frame_id = frame_id;
54 marker.scale.x = kTrajectoryLineStripMarkerScale;
55 marker.pose.orientation.w = 1.;
56 marker.pose.position.z = 0.05;
61 const std::string& landmark_id,
62 std::unordered_map<std::string, int>* landmark_id_to_index) {
63 auto it = landmark_id_to_index->find(landmark_id);
64 if (it == landmark_id_to_index->end()) {
65 const int new_index = landmark_id_to_index->size();
66 landmark_id_to_index->emplace(landmark_id, new_index);
72 visualization_msgs::Marker CreateLandmarkMarker(
int landmark_index,
74 const std::string& frame_id) {
75 visualization_msgs::Marker marker;
76 marker.ns =
"Landmarks";
77 marker.id = landmark_index;
78 marker.type = visualization_msgs::Marker::CUBE;
80 marker.header.frame_id = frame_id;
81 marker.scale.x = kLandmarkMarkerScale;
82 marker.scale.y = kLandmarkMarkerScale;
83 marker.scale.z = kLandmarkMarkerScale;
89 void PushAndResetLineMarker(visualization_msgs::Marker* marker,
90 std::vector<visualization_msgs::Marker>* markers) {
91 markers->push_back(*marker);
93 marker->points.clear();
100 std::unique_ptr<cartographer::mapping::MapBuilderInterface> map_builder,
102 : node_options_(node_options),
104 tf_buffer_(tf_buffer) {}
107 bool load_frozen_state) {
109 const std::string suffix =
".pbstream";
110 CHECK_EQ(state_filename.substr(
111 std::max<int>(state_filename.size() - suffix.size(), 0)),
113 <<
"The file containing the state to be loaded must be a " 115 LOG(INFO) <<
"Loading saved state '" << state_filename <<
"'...";
121 const std::set<cartographer::mapping::TrajectoryBuilderInterface::SensorId>&
124 const int trajectory_id =
map_builder_->AddTrajectoryBuilder(
127 ::std::placeholders::_1, ::std::placeholders::_2,
128 ::std::placeholders::_3, ::std::placeholders::_4,
129 ::std::placeholders::_5));
130 LOG(INFO) <<
"Added trajectory with ID '" << trajectory_id <<
"'.";
135 cartographer::common::make_unique<SensorBridge>(
140 auto emplace_result =
142 CHECK(emplace_result.second ==
true);
143 return trajectory_id;
147 LOG(INFO) <<
"Finishing trajectory with ID '" << trajectory_id <<
"'...";
156 LOG(INFO) <<
"Running final trajectory optimization...";
163 return writer.
Close();
167 cartographer_ros_msgs::SubmapQuery::Request& request,
168 cartographer_ros_msgs::SubmapQuery::Response& response) {
169 cartographer::mapping::proto::SubmapQuery::Response response_proto;
171 request.submap_index};
172 const std::string error =
173 map_builder_->SubmapToProto(submap_id, &response_proto);
174 if (!error.empty()) {
176 response.status.code = cartographer_ros_msgs::StatusCode::NOT_FOUND;
177 response.status.message = error;
181 response.submap_version = response_proto.submap_version();
182 for (
const auto& texture_proto : response_proto.textures()) {
183 response.textures.emplace_back();
184 auto& texture = response.textures.back();
185 texture.cells.insert(texture.cells.begin(), texture_proto.cells().begin(),
186 texture_proto.cells().end());
187 texture.width = texture_proto.width();
188 texture.height = texture_proto.height();
189 texture.resolution = texture_proto.resolution();
193 response.status.message =
"Success.";
194 response.status.code = cartographer_ros_msgs::StatusCode::OK;
198 std::set<int> frozen_trajectory_ids;
199 const auto node_poses =
map_builder_->pose_graph()->GetTrajectoryNodePoses();
200 for (
const int trajectory_id : node_poses.trajectory_ids()) {
201 if (
map_builder_->pose_graph()->IsTrajectoryFrozen(trajectory_id)) {
202 frozen_trajectory_ids.insert(trajectory_id);
205 return frozen_trajectory_ids;
209 cartographer_ros_msgs::SubmapList submap_list;
212 for (
const auto& submap_id_pose :
214 cartographer_ros_msgs::SubmapEntry submap_entry;
215 submap_entry.trajectory_id = submap_id_pose.id.trajectory_id;
216 submap_entry.submap_index = submap_id_pose.id.submap_index;
217 submap_entry.submap_version = submap_id_pose.data.version;
219 submap_list.submap.push_back(submap_entry);
224 std::unordered_map<int, MapBuilderBridge::TrajectoryState>
226 std::unordered_map<int, TrajectoryState> trajectory_states;
228 const int trajectory_id = entry.first;
231 std::shared_ptr<const TrajectoryState::LocalSlamData> local_slam_data;
234 if (trajectory_state_data_.count(trajectory_id) == 0) {
237 local_slam_data = trajectory_state_data_.at(trajectory_id);
242 trajectory_states[trajectory_id] = {
244 map_builder_->pose_graph()->GetLocalToGlobalTransform(trajectory_id),
246 local_slam_data->time,
250 return trajectory_states;
254 visualization_msgs::MarkerArray trajectory_node_list;
255 const auto node_poses =
map_builder_->pose_graph()->GetTrajectoryNodePoses();
259 trajectory_to_last_inter_submap_constrained_node;
261 trajectory_to_last_inter_trajectory_constrained_node;
262 for (
const int trajectory_id : node_poses.trajectory_ids()) {
263 trajectory_to_last_inter_submap_constrained_node[trajectory_id] = 0;
264 trajectory_to_last_inter_trajectory_constrained_node[trajectory_id] = 0;
266 const auto constraints =
map_builder_->pose_graph()->constraints();
267 for (
const auto& constraint : constraints) {
268 if (constraint.tag ==
269 cartographer::mapping::PoseGraph::Constraint::INTER_SUBMAP) {
270 if (constraint.node_id.trajectory_id ==
271 constraint.submap_id.trajectory_id) {
272 trajectory_to_last_inter_submap_constrained_node[constraint.node_id
274 std::max(trajectory_to_last_inter_submap_constrained_node.at(
275 constraint.node_id.trajectory_id),
276 constraint.node_id.node_index);
278 trajectory_to_last_inter_trajectory_constrained_node
279 [constraint.node_id.trajectory_id] =
280 std::max(trajectory_to_last_inter_submap_constrained_node.at(
281 constraint.node_id.trajectory_id),
282 constraint.node_id.node_index);
287 for (
const int trajectory_id : node_poses.trajectory_ids()) {
288 visualization_msgs::Marker marker =
290 int last_inter_submap_constrained_node = std::max(
291 node_poses.trajectory(trajectory_id).begin()->id.node_index,
292 trajectory_to_last_inter_submap_constrained_node.at(trajectory_id));
293 int last_inter_trajectory_constrained_node = std::max(
294 node_poses.trajectory(trajectory_id).begin()->id.node_index,
295 trajectory_to_last_inter_trajectory_constrained_node.at(trajectory_id));
296 last_inter_submap_constrained_node =
297 std::max(last_inter_submap_constrained_node,
298 last_inter_trajectory_constrained_node);
300 if (
map_builder_->pose_graph()->IsTrajectoryFrozen(trajectory_id)) {
301 last_inter_submap_constrained_node =
302 (--node_poses.trajectory(trajectory_id).end())->
id.node_index;
303 last_inter_trajectory_constrained_node =
304 last_inter_submap_constrained_node;
307 marker.color.a = 1.0;
308 for (
const auto& node_id_data : node_poses.trajectory(trajectory_id)) {
309 if (!node_id_data.data.constant_pose_data.has_value()) {
310 PushAndResetLineMarker(&marker, &trajectory_node_list.markers);
313 const ::geometry_msgs::Point node_point =
315 marker.points.push_back(node_point);
317 if (node_id_data.id.node_index ==
318 last_inter_trajectory_constrained_node) {
319 PushAndResetLineMarker(&marker, &trajectory_node_list.markers);
320 marker.points.push_back(node_point);
321 marker.color.a = 0.5;
323 if (node_id_data.id.node_index == last_inter_submap_constrained_node) {
324 PushAndResetLineMarker(&marker, &trajectory_node_list.markers);
325 marker.points.push_back(node_point);
326 marker.color.a = 0.25;
330 if (marker.points.size() == 16384) {
331 PushAndResetLineMarker(&marker, &trajectory_node_list.markers);
333 marker.points.push_back(node_point);
336 PushAndResetLineMarker(&marker, &trajectory_node_list.markers);
337 size_t current_last_marker_id =
static_cast<size_t>(marker.id - 1);
341 marker.action = visualization_msgs::Marker::DELETE;
342 while (static_cast<size_t>(marker.id) <=
344 trajectory_node_list.markers.push_back(marker);
350 return trajectory_node_list;
354 visualization_msgs::MarkerArray landmark_poses_list;
355 const std::map<std::string, Rigid3d> landmark_poses =
357 for (
const auto& id_to_pose : landmark_poses) {
358 landmark_poses_list.markers.push_back(CreateLandmarkMarker(
362 return landmark_poses_list;
366 visualization_msgs::MarkerArray constraint_list;
368 visualization_msgs::Marker constraint_intra_marker;
369 constraint_intra_marker.id = marker_id++;
370 constraint_intra_marker.ns =
"Intra constraints";
371 constraint_intra_marker.type = visualization_msgs::Marker::LINE_LIST;
374 constraint_intra_marker.scale.x = kConstraintMarkerScale;
375 constraint_intra_marker.pose.orientation.w = 1.0;
377 visualization_msgs::Marker residual_intra_marker = constraint_intra_marker;
378 residual_intra_marker.id = marker_id++;
379 residual_intra_marker.ns =
"Intra residuals";
383 residual_intra_marker.pose.position.z = 0.1;
385 visualization_msgs::Marker constraint_inter_same_trajectory_marker =
386 constraint_intra_marker;
387 constraint_inter_same_trajectory_marker.id = marker_id++;
388 constraint_inter_same_trajectory_marker.ns =
389 "Inter constraints, same trajectory";
390 constraint_inter_same_trajectory_marker.pose.position.z = 0.1;
392 visualization_msgs::Marker residual_inter_same_trajectory_marker =
393 constraint_intra_marker;
394 residual_inter_same_trajectory_marker.id = marker_id++;
395 residual_inter_same_trajectory_marker.ns =
"Inter residuals, same trajectory";
396 residual_inter_same_trajectory_marker.pose.position.z = 0.1;
398 visualization_msgs::Marker constraint_inter_diff_trajectory_marker =
399 constraint_intra_marker;
400 constraint_inter_diff_trajectory_marker.id = marker_id++;
401 constraint_inter_diff_trajectory_marker.ns =
402 "Inter constraints, different trajectories";
403 constraint_inter_diff_trajectory_marker.pose.position.z = 0.1;
405 visualization_msgs::Marker residual_inter_diff_trajectory_marker =
406 constraint_intra_marker;
407 residual_inter_diff_trajectory_marker.id = marker_id++;
408 residual_inter_diff_trajectory_marker.ns =
409 "Inter residuals, different trajectories";
410 residual_inter_diff_trajectory_marker.pose.position.z = 0.1;
412 const auto trajectory_node_poses =
414 const auto submap_poses =
map_builder_->pose_graph()->GetAllSubmapPoses();
415 const auto constraints =
map_builder_->pose_graph()->constraints();
417 for (
const auto& constraint : constraints) {
418 visualization_msgs::Marker *constraint_marker, *residual_marker;
419 std_msgs::ColorRGBA color_constraint, color_residual;
420 if (constraint.tag ==
421 cartographer::mapping::PoseGraph::Constraint::INTRA_SUBMAP) {
422 constraint_marker = &constraint_intra_marker;
423 residual_marker = &residual_intra_marker;
427 color_constraint = ToMessage(
429 constraint.submap_id.trajectory_id + 25));
430 color_residual.a = 1.0;
431 color_residual.r = 1.0;
433 if (constraint.node_id.trajectory_id ==
434 constraint.submap_id.trajectory_id) {
435 constraint_marker = &constraint_inter_same_trajectory_marker;
436 residual_marker = &residual_inter_same_trajectory_marker;
438 color_constraint.a = 1.0;
439 color_constraint.r = color_constraint.g = 1.0;
441 constraint_marker = &constraint_inter_diff_trajectory_marker;
442 residual_marker = &residual_inter_diff_trajectory_marker;
444 color_constraint.a = 1.0;
445 color_constraint.r = 1.0;
446 color_constraint.g = 165. / 255.;
449 color_residual.a = 1.0;
450 color_residual.b = color_residual.g = 1.0;
453 for (
int i = 0; i < 2; ++i) {
454 constraint_marker->colors.push_back(color_constraint);
455 residual_marker->colors.push_back(color_residual);
458 const auto submap_it = submap_poses.find(constraint.submap_id);
459 if (submap_it == submap_poses.end()) {
462 const auto& submap_pose = submap_it->data.pose;
463 const auto node_it = trajectory_node_poses.find(constraint.node_id);
464 if (node_it == trajectory_node_poses.end()) {
467 const auto& trajectory_node_pose = node_it->data.global_pose;
468 const Rigid3d constraint_pose = submap_pose * constraint.pose.zbar_ij;
470 constraint_marker->points.push_back(
472 constraint_marker->points.push_back(
475 residual_marker->points.push_back(
477 residual_marker->points.push_back(
481 constraint_list.markers.push_back(constraint_intra_marker);
482 constraint_list.markers.push_back(residual_intra_marker);
483 constraint_list.markers.push_back(constraint_inter_same_trajectory_marker);
484 constraint_list.markers.push_back(residual_inter_same_trajectory_marker);
485 constraint_list.markers.push_back(constraint_inter_diff_trajectory_marker);
486 constraint_list.markers.push_back(residual_inter_diff_trajectory_marker);
487 return constraint_list;
495 const int trajectory_id, const ::cartographer::common::Time time,
496 const Rigid3d local_pose,
498 const std::unique_ptr<const ::cartographer::mapping::
499 TrajectoryBuilderInterface::InsertionResult>) {
500 std::shared_ptr<const TrajectoryState::LocalSlamData> local_slam_data =
501 std::make_shared<TrajectoryState::LocalSlamData>(
503 std::move(range_data_in_local)});
505 trajectory_state_data_[trajectory_id] = std::move(local_slam_data);
std::unordered_map< int, size_t > trajectory_to_highest_marker_id_
visualization_msgs::MarkerArray GetTrajectoryNodeList()
const NodeOptions node_options_
visualization_msgs::MarkerArray GetConstraintList()
geometry_msgs::Pose ToGeometryMsgPose(const Rigid3d &rigid3d)
geometry_msgs::Point ToGeometryMsgPoint(const Eigen::Vector3d &vector3d)
std::string tracking_frame
void HandleSubmapQuery(cartographer_ros_msgs::SubmapQuery::Request &request, cartographer_ros_msgs::SubmapQuery::Response &response)
cartographer::common::Mutex mutex_
std::unordered_map< int, TrajectoryState > GetTrajectoryStates() EXCLUDES(mutex_)
std::unique_ptr< MapBuilderInterface > map_builder_
void RunFinalOptimization()
std::unordered_map< std::string, int > landmark_to_index_
SensorBridge * sensor_bridge(int trajectory_id)
tf2_ros::Buffer *const tf_buffer_
visualization_msgs::MarkerArray GetLandmarkPosesList()
void FinishTrajectory(int trajectory_id)
int num_subdivisions_per_laser_scan
std::set< int > GetFrozenTrajectoryIds()
FloatColor GetColor(int id)
std::array< float, 3 > FloatColor
const TfBridge & tf_bridge() const
cartographer_ros_msgs::SubmapList GetSubmapList()
void LoadState(const std::string &state_filename, bool load_frozen_state)
std::unique_ptr<::cartographer::transform::Rigid3d > LookupToTracking(::cartographer::common::Time time, const std::string &frame_id) const
int AddTrajectory(const std::set< ::cartographer::mapping::TrajectoryBuilderInterface::SensorId > &expected_sensor_ids, const TrajectoryOptions &trajectory_options)
bool SerializeState(const std::string &filename)
::cartographer::mapping::proto::TrajectoryBuilderOptions trajectory_builder_options
std::unique_ptr< cartographer::mapping::MapBuilderInterface > map_builder_
void move(std::vector< T > &a, std::vector< T > &b)
std::unordered_map< int, TrajectoryOptions > trajectory_options_
double lookup_transform_timeout_sec
void OnLocalSlamResult(const int trajectory_id, const ::cartographer::common::Time time, const ::cartographer::transform::Rigid3d local_pose, ::cartographer::sensor::RangeData range_data_in_local, const std::unique_ptr< const ::cartographer::mapping::TrajectoryBuilderInterface::InsertionResult > insertion_result) EXCLUDES(mutex_)
Mutex::Locker MutexLocker
MapBuilderBridge(const NodeOptions &node_options, std::unique_ptr< cartographer::mapping::MapBuilderInterface > map_builder, tf2_ros::Buffer *tf_buffer)
std::unordered_map< int, std::unique_ptr< SensorBridge > > sensor_bridges_