通过对main函数的分析,我们可以看到main函数中除了定义了一些gflags格式的参数外,大部分事情都是调用了node函数在执行。这个函数定义在node.h中,其主要的作用包括如下:
1、1. 注册并发布了5个Topic, 并为5个Topic分别设置了定时器函数,在定时器函数中定期向Topic上广播数据:
|===1) Topic 1: kSubmapListTopic: 广播构建出来的submap的list
|-----------发布数据的函数:Node::PublishSubmapList
|-----------调用函数:map_builder_bridge_.GetSubmapList();
|===2) Topic 2: kTrajectoryNodeListTopic:发布trajectory
|-----------发布数据的函数:Node::PublishTrajectoryNodeList Node::PublishTrajectoryStates:
|-----------调用函数:map_builder_bridge_.GetTrajectoryNodeList();
|===3) Topic3: kLandmarkPoseListTopic
|-----------发布数据的函数:Node::PublishLandmarkPosesList
|-----------调用的函数:map_builder_bridge_.GetLandmarkPoseList();
|===4) Topic4: kConstraintListTopic
|-----------发布数据的函数:Node::PublishConstraintList
|-----------调用的函数:map_builder_bridge_.GetConstraintList();
|===5)Topic5: kScanMatchedPointCloudTopic
|-----------发布数据的函数:Node::PublishTrajectoryStates
|-----------调用的函数:map_builder_bridge_.GetTrajectoryStates();
|-----------这个函数名与Topic名对应不上,但是查看Node::PublishTrajectoryStates不难发现,函数中有一句:
scan_matched_point_cloud_publisher_.publish(ToPointCloud2Message(
carto::common::ToUniversal(trajectory_state.local_slam_data->time),
node_options_.map_frame,
carto::sensor::TransformTimedPointCloud(
point_cloud, trajectory_state.local_to_map.cast<float>())));
|===1)Service 1: kSubmapQueryServiceName
|-----------句柄函数:Node::HandleSubmapQuery
|-----------实际处理的函数:map_builder_bridge_.HandleSubmapQuery
|===2) Service 2: kStartTrajectoryServiceName
|-----------句柄函数:Node::HandleStartTrajectory
|-----------实际处理的函数:map_builder_bridge_.AddTrajectory等;
|-----------这里需要额外注意的是Node::LaunchSubscribers这个函数。这个函数负责处理各个传感器函数。仔细读其中的每个处理函数,比如处理IMU的Node::HandleImuMessage函数,发现其实际调用的是map_builder_bridge_中的一个成员类sensor_bridge_ptr的函数来处理:sensor_bridge_ptr->HandleImuMessage。
|===3) Service 3: kFinishTrajectoryServiceName
|------------句柄函数:Node::HandleFinishTrajectory
|------------实际处理的函数:map_builder_bridge_.FinishTrajectory
|===4) Service 4: kWriteStateServiceName
|------------句柄函数:Node::HandleWriteState
|------------实际处理的函数:map_builder_bridge_.SerializeState
虽然node里面写了很多东西,但是实际上我们可以看到它其实更多的也是起到了一个调用的作用,所有的publisher都是由map_builder_bridge完成的。
node.cc分析:
#include "cartographer_ros/node.h"
#include
#include
#include
#include "Eigen/Core"
#include "absl/memory/memory.h"
#include "absl/strings/str_cat.h"
#include "cartographer/common/configuration_file_resolver.h"
#include "cartographer/common/lua_parameter_dictionary.h"
#include "cartographer/common/port.h"
#include "cartographer/common/time.h"
#include "cartographer/mapping/pose_graph_interface.h"
#include "cartographer/mapping/proto/submap_visualization.pb.h"
#include "cartographer/metrics/register.h"
#include "cartographer/sensor/point_cloud.h"
#include "cartographer/transform/rigid_transform.h"
#include "cartographer/transform/transform.h"
#include "cartographer_ros/metrics/family_factory.h"
#include "cartographer_ros/msg_conversion.h"
#include "cartographer_ros/sensor_bridge.h"
#include "cartographer_ros/tf_bridge.h"
#include "cartographer_ros/time_conversion.h"
#include "cartographer_ros_msgs/StatusCode.h"
#include "cartographer_ros_msgs/StatusResponse.h"
#include "glog/logging.h"
#include "nav_msgs/Odometry.h"
#include "ros/serialization.h"
#include "sensor_msgs/PointCloud2.h"
#include "tf2_eigen/tf2_eigen.h"
#include "visualization_msgs/MarkerArray.h"
namespace cartographer_ros {
namespace carto = ::cartographer;
using carto::transform::Rigid3d;
using TrajectoryState =
::cartographer::mapping::PoseGraphInterface::TrajectoryState;
namespace {
// Subscribes to the 'topic' for 'trajectory_id' using the 'node_handle' and
// calls 'handler' on the 'node' to handle messages. Returns the subscriber.
//使用“node”handle“订阅”trackline“id”的“topic”,并在“node”上调用“handler”来处理消息。返回订阅服务器。
template <typename MessageType>
::ros::Subscriber SubscribeWithHandler(
void (Node::*handler)(int, const std::string&,
const typename MessageType::ConstPtr&),
const int trajectory_id, const std::string& topic,
::ros::NodeHandle* const node_handle, Node* const node) {
return node_handle->subscribe<MessageType>(
topic, kInfiniteSubscriberQueueSize,
boost::function<void(const typename MessageType::ConstPtr&)>(
[node, handler, trajectory_id,
topic](const typename MessageType::ConstPtr& msg) {
(node->*handler)(trajectory_id, topic, msg);
}));
}
std::string TrajectoryStateToString(const TrajectoryState trajectory_state) {
switch (trajectory_state) {
case TrajectoryState::ACTIVE:
return "ACTIVE";
case TrajectoryState::FINISHED:
return "FINISHED";
case TrajectoryState::FROZEN:
return "FROZEN";
case TrajectoryState::DELETED:
return "DELETED";
}
return "";
}
} // namespace
//node对象类型cartographer_ros::Node构造函数的片段,它有三个输入参数。其中,node_options是node对象的各种配置参数,
//在node_main.cc中由函数Run中从配置文件中获取。map_builder是Cartographer用于建图的对象,
//而tf_buffer是ROS系统中常用的坐标变换库tf2的缓存对象。
//代码片段中的第3行的部分是C++标准的构造时对成员变量进行初始化的方法。
Node::Node(
const NodeOptions& node_options,
std::unique_ptr<cartographer::mapping::MapBuilderInterface> map_builder,
tf2_ros::Buffer* const tf_buffer, const bool collect_metrics)
: node_options_(node_options),
map_builder_bridge_(node_options_, std::move(map_builder), tf_buffer) {
absl::MutexLock lock(&mutex_);
//在构造函数一开始,先对互斥量mutex_加锁,防止因为多线程等并行运算的方式产生异常的行为。这里定义的是局部变量lock,
//会在其构造函数中对mutex_加锁, 当构造函数运行结束之后会销毁该变量,在其析构函数中释放mutex_。
if (collect_metrics) {
metrics_registry_ = absl::make_unique<metrics::FamilyFactory>();
carto::metrics::RegisterAllMetrics(metrics_registry_.get());
}
//通过ROS的节点句柄node_handle_注册发布了一堆主题。这里以前缀"k"开始的变量都是在node_constants.h中定义的常数,
//它们都是默认的发布消息的名称和消息队列大小。
submap_list_publisher_ =
node_handle_.advertise<::cartographer_ros_msgs::SubmapList>(
kSubmapListTopic, kLatestOnlyPublisherQueueSize);//变量:kSubmapListTopic 默认名称:/submap_list 作用:构建好的子图列表。
trajectory_node_list_publisher_ =
node_handle_.advertise<::visualization_msgs::MarkerArray>(
kTrajectoryNodeListTopic, kLatestOnlyPublisherQueueSize);//kTrajectoryNodeListTopic /trajectory_node_list 跟踪轨迹路径点列表。
landmark_poses_list_publisher_ =
node_handle_.advertise<::visualization_msgs::MarkerArray>(
kLandmarkPosesListTopic, kLatestOnlyPublisherQueueSize);//kLandmarkPosesListTopic /landmark_poses_list 路标点位姿列表。
constraint_list_publisher_ =
node_handle_.advertise<::visualization_msgs::MarkerArray>(
kConstraintListTopic, kLatestOnlyPublisherQueueSize);//kConstraintListTopic /constraint_list 优化约束。
//然后注册服务,并保存在容器service_servers_中。同样的前缀"k"开始的变量都是在node_constants.h中定义的常数,它们是默认的服务名称。
//在注册服务的时候还需要提供一个响应该服务的回调函数,
service_servers_.push_back(node_handle_.advertiseService(
kSubmapQueryServiceName, &Node::HandleSubmapQuery, this));
service_servers_.push_back(node_handle_.advertiseService(
kTrajectoryQueryServiceName, &Node::HandleTrajectoryQuery, this));
service_servers_.push_back(node_handle_.advertiseService(
kStartTrajectoryServiceName, &Node::HandleStartTrajectory, this));
service_servers_.push_back(node_handle_.advertiseService(
kFinishTrajectoryServiceName, &Node::HandleFinishTrajectory, this));
service_servers_.push_back(node_handle_.advertiseService(
kWriteStateServiceName, &Node::HandleWriteState, this));
service_servers_.push_back(node_handle_.advertiseService(
kGetTrajectoryStatesServiceName, &Node::HandleGetTrajectoryStates, this));
service_servers_.push_back(node_handle_.advertiseService(
kReadMetricsServiceName, &Node::HandleReadMetrics, this));
scan_matched_point_cloud_publisher_ =
node_handle_.advertise<sensor_msgs::PointCloud2>(
kScanMatchedPointCloudTopic, kLatestOnlyPublisherQueueSize);
//kScanMatchedPointCloudTopic /scan_matched_points2 匹配的2D点云数据。
//创建了一堆计时器保存在容器wall_timers_中,这些计时器的作用是通过超时回调函数定时的发布对应主题的消息。
wall_timers_.push_back(node_handle_.createWallTimer(
::ros::WallDuration(node_options_.submap_publish_period_sec),
&Node::PublishSubmapList, this));
if (node_options_.pose_publish_period_sec > 0) {
publish_local_trajectory_data_timer_ = node_handle_.createTimer(
::ros::Duration(node_options_.pose_publish_period_sec),
&Node::PublishLocalTrajectoryData, this);
}
wall_timers_.push_back(node_handle_.createWallTimer(
::ros::WallDuration(node_options_.trajectory_publish_period_sec),
&Node::PublishTrajectoryNodeList, this));
wall_timers_.push_back(node_handle_.createWallTimer(
::ros::WallDuration(node_options_.trajectory_publish_period_sec),
&Node::PublishLandmarkPosesList, this));
wall_timers_.push_back(node_handle_.createWallTimer(
::ros::WallDuration(kConstraintPublishPeriodSec),
&Node::PublishConstraintList, this));
}
Node::~Node() { FinishAllTrajectories(); }
::ros::NodeHandle* Node::node_handle() { return &node_handle_; }
//句柄函数,实际处理的函数:map_builder_bridge_.HandleSubmapQuery,似乎是用于子地图队列的查询?
//这个函数有两个参数,一个参数是一个::cartographer_ros_msgs::SubmapQuery::Request型的变量,
//对应是请求服务时的输入参数,另外一个参数是::cartographer_ros_msgs::SubmapQuery::Response型的变量,
//对应的是服务响应后的返回值。
//这个函数具体在map_builder_bridge.cc文件中。用于查询指定ID下的submap的一些信息
bool Node::HandleSubmapQuery(
::cartographer_ros_msgs::SubmapQuery::Request& request,
::cartographer_ros_msgs::SubmapQuery::Response& response) {
absl::MutexLock lock(&mutex_);
map_builder_bridge_.HandleSubmapQuery(request, response);
return true;
}
//同上
//以下来自于知乎:https://zhuanlan.zhihu.com/p/48105565 中博主的理解:
//一条trajectory可以理解为一次建图过程。如果只让机器人跑一圈,那么trajectory数就是1. 但比如说,
//建好图后又需要在图中走,这时候可以增加一条trajectory,把这条trajectory设置成/src/cartographer/
//configuration_files/trajectory_builder.lua中的pure_localization设为true,那么机器人再重新跑的过程
//中就会跟已经建好的图进行匹配,估计机器人在地图中的路径。所以,一次运行就代表了一条trajectory。
bool Node::HandleTrajectoryQuery(
::cartographer_ros_msgs::TrajectoryQuery::Request& request,
::cartographer_ros_msgs::TrajectoryQuery::Response& response) {
absl::MutexLock lock(&mutex_);
response.status = TrajectoryStateToStatus(
request.trajectory_id,
{TrajectoryState::ACTIVE, TrajectoryState::FINISHED,
TrajectoryState::FROZEN} /* valid states */);
if (response.status.code != cartographer_ros_msgs::StatusCode::OK) {
LOG(ERROR) << "Can't query trajectory from pose graph: "
<< response.status.message;
return true;
}
map_builder_bridge_.HandleTrajectoryQuery(request, response);
return true;
}
//调用了MapBuilderBridge类的成员函数GetSubmapList(),然后把返回的submap的列表发布出去
void Node::PublishSubmapList(const ::ros::WallTimerEvent& unused_timer_event) {
absl::MutexLock lock(&mutex_);
submap_list_publisher_.publish(map_builder_bridge_.GetSubmapList());
}
//添加推算器,Extrapolator似乎用于位姿推算
void Node::AddExtrapolator(const int trajectory_id,
const TrajectoryOptions& options) {
constexpr double kExtrapolationEstimationTimeSec = 0.001; // 1 ms
CHECK(extrapolators_.count(trajectory_id) == 0);
const double gravity_time_constant =
node_options_.map_builder_options.use_trajectory_builder_3d()
? options.trajectory_builder_options.trajectory_builder_3d_options()
.imu_gravity_time_constant()
: options.trajectory_builder_options.trajectory_builder_2d_options()
.imu_gravity_time_constant();
extrapolators_.emplace(
std::piecewise_construct, std::forward_as_tuple(trajectory_id),
std::forward_as_tuple(
::cartographer::common::FromSeconds(kExtrapolationEstimationTimeSec),
gravity_time_constant));
}
//插入一TrajectorySensorSamplers,采样器?里面有rangefinder_sampler,odometry_sampler,
//fixed_frame_pose_sampler,imu_sampler,landmark_sampler
void Node::AddSensorSamplers(const int trajectory_id,
const TrajectoryOptions& options) {
CHECK(sensor_samplers_.count(trajectory_id) == 0);
sensor_samplers_.emplace(
std::piecewise_construct, std::forward_as_tuple(trajectory_id),
std::forward_as_tuple(
options.rangefinder_sampling_ratio, options.odometry_sampling_ratio,
options.fixed_frame_pose_sampling_ratio, options.imu_sampling_ratio,
options.landmarks_sampling_ratio));
}
//发布局部轨迹数据
void Node::PublishLocalTrajectoryData(const ::ros::TimerEvent& timer_event) {
absl::MutexLock lock(&mutex_);
for (const auto& entry : map_builder_bridge_.GetLocalTrajectoryData()) {
const auto& trajectory_data = entry.second;
auto& extrapolator = extrapolators_.at(entry.first);
// We only publish a point cloud if it has changed. It is not needed at high
// frequency, and republishing it would be computationally wasteful.
if (trajectory_data.local_slam_data->time !=
extrapolator.GetLastPoseTime()) {
if (scan_matched_point_cloud_publisher_.getNumSubscribers() > 0) {
// TODO(gaschler): Consider using other message without time
// information.
carto::sensor::TimedPointCloud point_cloud;
point_cloud.reserve(trajectory_data.local_slam_data->range_data_in_local
.returns.size());
for (const cartographer::sensor::RangefinderPoint point :
trajectory_data.local_slam_data->range_data_in_local.returns) {
point_cloud.push_back(cartographer::sensor::ToTimedRangefinderPoint(
point, 0.f /* time */));
}
scan_matched_point_cloud_publisher_.publish(ToPointCloud2Message(
carto::common::ToUniversal(trajectory_data.local_slam_data->time),
node_options_.map_frame,
carto::sensor::TransformTimedPointCloud(
point_cloud, trajectory_data.local_to_map.cast<float>())));
}
extrapolator.AddPose(trajectory_data.local_slam_data->time,
trajectory_data.local_slam_data->local_pose);
}
geometry_msgs::TransformStamped stamped_transform;
// If we do not publish a new point cloud, we still allow time of the
// published poses to advance. If we already know a newer pose, we use its
// time instead. Since tf knows how to interpolate, providing newer
// information is better.
const ::cartographer::common::Time now = std::max(
FromRos(ros::Time::now()), extrapolator.GetLastExtrapolatedTime());
stamped_transform.header.stamp =
node_options_.use_pose_extrapolator
? ToRos(now)
: ToRos(trajectory_data.local_slam_data->time);
const Rigid3d tracking_to_local_3d =
node_options_.use_pose_extrapolator
? extrapolator.ExtrapolatePose(now)
: trajectory_data.local_slam_data->local_pose;
const Rigid3d tracking_to_local = [&] {
if (trajectory_data.trajectory_options.publish_frame_projected_to_2d) {
return carto::transform::Embed3D(
carto::transform::Project2D(tracking_to_local_3d));
}
return tracking_to_local_3d;
}();
const Rigid3d tracking_to_map =
trajectory_data.local_to_map * tracking_to_local;
if (trajectory_data.published_to_tracking != nullptr) {
if (trajectory_data.trajectory_options.provide_odom_frame) {
std::vector<geometry_msgs::TransformStamped> stamped_transforms;
stamped_transform.header.frame_id = node_options_.map_frame;
stamped_transform.child_frame_id =
trajectory_data.trajectory_options.odom_frame;
stamped_transform.transform =
ToGeometryMsgTransform(trajectory_data.local_to_map);
stamped_transforms.push_back(stamped_transform);
stamped_transform.header.frame_id =
trajectory_data.trajectory_options.odom_frame;
stamped_transform.child_frame_id =
trajectory_data.trajectory_options.published_frame;
stamped_transform.transform = ToGeometryMsgTransform(
tracking_to_local * (*trajectory_data.published_to_tracking));
stamped_transforms.push_back(stamped_transform);
tf_broadcaster_.sendTransform(stamped_transforms);
} else {
stamped_transform.header.frame_id = node_options_.map_frame;
stamped_transform.child_frame_id =
trajectory_data.trajectory_options.published_frame;
stamped_transform.transform = ToGeometryMsgTransform(
tracking_to_map * (*trajectory_data.published_to_tracking));
tf_broadcaster_.sendTransform(stamped_transform);
}
}
}
}
//发布轨迹节点列表
void Node::PublishTrajectoryNodeList(
const ::ros::WallTimerEvent& unused_timer_event) {
if (trajectory_node_list_publisher_.getNumSubscribers() > 0) {
absl::MutexLock lock(&mutex_);
trajectory_node_list_publisher_.publish(
map_builder_bridge_.GetTrajectoryNodeList());
}
}
void Node::PublishLandmarkPosesList(
const ::ros::WallTimerEvent& unused_timer_event) {
if (landmark_poses_list_publisher_.getNumSubscribers() > 0) {
absl::MutexLock lock(&mutex_);
landmark_poses_list_publisher_.publish(
map_builder_bridge_.GetLandmarkPosesList());
}
}
void Node::PublishConstraintList(
const ::ros::WallTimerEvent& unused_timer_event) {
if (constraint_list_publisher_.getNumSubscribers() > 0) {
absl::MutexLock lock(&mutex_);
constraint_list_publisher_.publish(map_builder_bridge_.GetConstraintList());
}
}
std::set<cartographer::mapping::TrajectoryBuilderInterface::SensorId>
Node::ComputeExpectedSensorIds(const TrajectoryOptions& options) const {
using SensorId = cartographer::mapping::TrajectoryBuilderInterface::SensorId;
using SensorType = SensorId::SensorType;
std::set<SensorId> expected_topics;
// Subscribe to all laser scan, multi echo laser scan, and point cloud topics.
for (const std::string& topic :
ComputeRepeatedTopicNames(kLaserScanTopic, options.num_laser_scans)) {
expected_topics.insert(SensorId{SensorType::RANGE, topic});
}
for (const std::string& topic : ComputeRepeatedTopicNames(
kMultiEchoLaserScanTopic, options.num_multi_echo_laser_scans)) {
expected_topics.insert(SensorId{SensorType::RANGE, topic});
}
for (const std::string& topic :
ComputeRepeatedTopicNames(kPointCloud2Topic, options.num_point_clouds)) {
expected_topics.insert(SensorId{SensorType::RANGE, topic});
}
// For 2D SLAM, subscribe to the IMU if we expect it. For 3D SLAM, the IMU is
// required.
if (node_options_.map_builder_options.use_trajectory_builder_3d() ||
(node_options_.map_builder_options.use_trajectory_builder_2d() &&
options.trajectory_builder_options.trajectory_builder_2d_options()
.use_imu_data())) {
expected_topics.insert(SensorId{SensorType::IMU, kImuTopic});
}
// Odometry is optional.
if (options.use_odometry) {
expected_topics.insert(SensorId{SensorType::ODOMETRY, kOdometryTopic});
}
// NavSatFix is optional.
if (options.use_nav_sat) {
expected_topics.insert(
SensorId{SensorType::FIXED_FRAME_POSE, kNavSatFixTopic});
}
// Landmark is optional.
if (options.use_landmarks) {
expected_topics.insert(SensorId{SensorType::LANDMARK, kLandmarkTopic});
}
return expected_topics;
}
//AddTrajectory的代码片段,首先通过函数ComputeExpectedSensorIds根据配置选项options获取SendorId。
//所谓的SensorId是定义在trajectory_builder_interface.h中的一个结构体,
//它一共有两个字段,type通过枚举描述了传感器的类型,id是一个字符串记录了传感器所对应的ROS主题名称。
int Node::AddTrajectory(const TrajectoryOptions& options) {
const std::set<cartographer::mapping::TrajectoryBuilderInterface::SensorId>
expected_sensor_ids = ComputeExpectedSensorIds(options);
//接着通过接口map_builder_bridge_向Cartographer添加一条新的轨迹并获取轨迹的索引。然后以该索引为键值,
//通过函数AddExtrapolator和AddSensorSamplers添加用于位姿插值(PoseExtrapolator)和传感器采样(TrajectorySensorSamplers)的对象。
const int trajectory_id =
map_builder_bridge_.AddTrajectory(expected_sensor_ids, options);
AddExtrapolator(trajectory_id, options);
AddSensorSamplers(trajectory_id, options);
//然后调用成员函数LaunchSubscribers完成传感器消息的订阅。只有订阅了传感器消息,才能够在传感器数据的作用下驱动系统运转,进而完成位姿估计和建图的任务。
LaunchSubscribers(options, trajectory_id);
wall_timers_.push_back(node_handle_.createWallTimer(
::ros::WallDuration(kTopicMismatchCheckDelaySec),
&Node::MaybeWarnAboutTopicMismatch, this, /*oneshot=*/true));
//最后记录当前正在更新的轨迹,以及订阅的主题,并返回新建的轨迹索引。
//按照ROS的套路,应用程序一般都可以说是数据驱动的。也就是说,节点会订阅来自不同数据源的主题,每当接收到感兴趣的消息就会通过一个回调函数完成对应的处理。
//在node对象中,通过成员函数LaunchSubscribers根据配置订阅需要的主题。
for (const auto& sensor_id : expected_sensor_ids) {
subscribed_topics_.insert(sensor_id.id);
}
return trajectory_id;
}
//在该函数中通过定义在node.cc中的模板函数SubscribeWithHandler调用ROS的节点句柄node_handle_来订阅传感器的主题。
//容器对象subscribers_中保存的是构建的订阅器,其中元素的数据类型是Node类型中定义的私有结构体Subscriber,
//有两个字段分别记录了订阅器和传感器主题。第2行中的for循环写法是C++11标准中新增的"for range"形式,
//函数ComputeRepeatedTopicNames是用来处理有多个相同类型的传感器的。
//比如这里的单线激光laser_scan,通过在配置文件中的num_laser_scans字段指定单线激光的数量。
//假如输入参数topics.laser_scan_topic中对应的主题名称是"scan",那么如果只有一个单线激光,
//就是用scan作为订阅主题名称,如果有多个单线激光则在主题名称之后在添加添加数字予以区别,即scan_1, scan_2, ...
void Node::LaunchSubscribers(const TrajectoryOptions& options,
const int trajectory_id) {
for (const std::string& topic :
ComputeRepeatedTopicNames(kLaserScanTopic, options.num_laser_scans)) {
subscribers_[trajectory_id].push_back(
{SubscribeWithHandler<sensor_msgs::LaserScan>(
&Node::HandleLaserScanMessage, trajectory_id, topic, &node_handle_,
this),
topic});
}
//类似的多线激光扫描数据(multi_echo_laser_scan)和点云数据(point_clouds)都以相同的套路完成主题订阅
for (const std::string& topic : ComputeRepeatedTopicNames(
kMultiEchoLaserScanTopic, options.num_multi_echo_laser_scans)) {
subscribers_[trajectory_id].push_back(
{SubscribeWithHandler<sensor_msgs::MultiEchoLaserScan>(
&Node::HandleMultiEchoLaserScanMessage, trajectory_id, topic,
&node_handle_, this),
topic});
}
for (const std::string& topic :
ComputeRepeatedTopicNames(kPointCloud2Topic, options.num_point_clouds)) {
subscribers_[trajectory_id].push_back(
{SubscribeWithHandler<sensor_msgs::PointCloud2>(
&Node::HandlePointCloud2Message, trajectory_id, topic,
&node_handle_, this),
topic});
}
// For 2D SLAM, subscribe to the IMU if we expect it. For 3D SLAM, the IMU is
// required.
//下面是订阅IMU传感器话题的代码片段,如果是三维建图就必须使用IMU,二维建图可以通过配置文件中的use_imu_data字段设置。
if (node_options_.map_builder_options.use_trajectory_builder_3d() ||
(node_options_.map_builder_options.use_trajectory_builder_2d() &&
options.trajectory_builder_options.trajectory_builder_2d_options()
.use_imu_data())) {
subscribers_[trajectory_id].push_back(
{SubscribeWithHandler<sensor_msgs::Imu>(&Node::HandleImuMessage,
trajectory_id, kImuTopic,
&node_handle_, this),
kImuTopic});
}
if (options.use_odometry) {
subscribers_[trajectory_id].push_back(
{SubscribeWithHandler<nav_msgs::Odometry>(&Node::HandleOdometryMessage,
trajectory_id, kOdometryTopic,
&node_handle_, this),
kOdometryTopic});
}
if (options.use_nav_sat) {
subscribers_[trajectory_id].push_back(
{SubscribeWithHandler<sensor_msgs::NavSatFix>(
&Node::HandleNavSatFixMessage, trajectory_id, kNavSatFixTopic,
&node_handle_, this),
kNavSatFixTopic});
}
if (options.use_landmarks) {
subscribers_[trajectory_id].push_back(
{SubscribeWithHandler<cartographer_ros_msgs::LandmarkList>(
&Node::HandleLandmarkMessage, trajectory_id, kLandmarkTopic,
&node_handle_, this),
kLandmarkTopic});
}
}
//2D轨迹与3D轨迹选择的处理
bool Node::ValidateTrajectoryOptions(const TrajectoryOptions& options) {
if (node_options_.map_builder_options.use_trajectory_builder_2d()) {
return options.trajectory_builder_options
.has_trajectory_builder_2d_options();
}
if (node_options_.map_builder_options.use_trajectory_builder_3d()) {
return options.trajectory_builder_options
.has_trajectory_builder_3d_options();
}
return false;
}
bool Node::ValidateTopicNames(const TrajectoryOptions& options) {
for (const auto& sensor_id : ComputeExpectedSensorIds(options)) {
const std::string& topic = sensor_id.id;
if (subscribed_topics_.count(topic) > 0) {
LOG(ERROR) << "Topic name [" << topic << "] is already used.";
return false;
}
}
return true;
}
cartographer_ros_msgs::StatusResponse Node::TrajectoryStateToStatus(
const int trajectory_id, const std::set<TrajectoryState>& valid_states) {
const auto trajectory_states = map_builder_bridge_.GetTrajectoryStates();
cartographer_ros_msgs::StatusResponse status_response;
const auto it = trajectory_states.find(trajectory_id);
if (it == trajectory_states.end()) {
status_response.message =
absl::StrCat("Trajectory ", trajectory_id, " doesn't exist.");
status_response.code = cartographer_ros_msgs::StatusCode::NOT_FOUND;
return status_response;
}
status_response.message =
absl::StrCat("Trajectory ", trajectory_id, " is in '",
TrajectoryStateToString(it->second), "' state.");
status_response.code =
valid_states.count(it->second)
? cartographer_ros_msgs::StatusCode::OK
: cartographer_ros_msgs::StatusCode::INVALID_ARGUMENT;
return status_response;
}
cartographer_ros_msgs::StatusResponse Node::FinishTrajectoryUnderLock(
const int trajectory_id) {
cartographer_ros_msgs::StatusResponse status_response;
if (trajectories_scheduled_for_finish_.count(trajectory_id)) {
status_response.message = absl::StrCat("Trajectory ", trajectory_id,
" already pending to finish.");
status_response.code = cartographer_ros_msgs::StatusCode::OK;
LOG(INFO) << status_response.message;
return status_response;
}
// First, check if we can actually finish the trajectory.
status_response = TrajectoryStateToStatus(
trajectory_id, {TrajectoryState::ACTIVE} /* valid states */);
if (status_response.code != cartographer_ros_msgs::StatusCode::OK) {
LOG(ERROR) << "Can't finish trajectory: " << status_response.message;
return status_response;
}
// Shutdown the subscribers of this trajectory.
// A valid case with no subscribers is e.g. if we just visualize states.
if (subscribers_.count(trajectory_id)) {
for (auto& entry : subscribers_[trajectory_id]) {
entry.subscriber.shutdown();
subscribed_topics_.erase(entry.topic);
LOG(INFO) << "Shutdown the subscriber of [" << entry.topic << "]";
}
CHECK_EQ(subscribers_.erase(trajectory_id), 1);
}
map_builder_bridge_.FinishTrajectory(trajectory_id);
trajectories_scheduled_for_finish_.emplace(trajectory_id);
status_response.message =
absl::StrCat("Finished trajectory ", trajectory_id, ".");
status_response.code = cartographer_ros_msgs::StatusCode::OK;
return status_response;
}
//下面是"/start_trajectory"的服务响应函数的代码片段,在函数主体中,先通过两个条件语句来检查输入参数。
//如果输入参数合法则通过函数AddTrajectory按照服务请求的订阅主题开启一个路径跟踪,
//并填充返回消息的相关字段,否则报错返回。
bool Node::HandleStartTrajectory(
::cartographer_ros_msgs::StartTrajectory::Request& request,
::cartographer_ros_msgs::StartTrajectory::Response& response) {
TrajectoryOptions trajectory_options;
std::tie(std::ignore, trajectory_options) = LoadOptions(
request.configuration_directory, request.configuration_basename);
if (request.use_initial_pose) {
const auto pose = ToRigid3d(request.initial_pose);
if (!pose.IsValid()) {
response.status.message =
"Invalid pose argument. Orientation quaternion must be normalized.";
LOG(ERROR) << response.status.message;
response.status.code =
cartographer_ros_msgs::StatusCode::INVALID_ARGUMENT;
return true;
}
// Check if the requested trajectory for the relative initial pose exists.
response.status = TrajectoryStateToStatus(
request.relative_to_trajectory_id,
{TrajectoryState::ACTIVE, TrajectoryState::FROZEN,
TrajectoryState::FINISHED} /* valid states */);
if (response.status.code != cartographer_ros_msgs::StatusCode::OK) {
LOG(ERROR) << "Can't start a trajectory with initial pose: "
<< response.status.message;
return true;
}
::cartographer::mapping::proto::InitialTrajectoryPose
initial_trajectory_pose;
initial_trajectory_pose.set_to_trajectory_id(
request.relative_to_trajectory_id);
*initial_trajectory_pose.mutable_relative_pose() =
cartographer::transform::ToProto(pose);
initial_trajectory_pose.set_timestamp(cartographer::common::ToUniversal(
::cartographer_ros::FromRos(ros::Time(0))));
*trajectory_options.trajectory_builder_options
.mutable_initial_trajectory_pose() = initial_trajectory_pose;
}
if (!ValidateTrajectoryOptions(trajectory_options)) {
response.status.message = "Invalid trajectory options.";
LOG(ERROR) << response.status.message;
response.status.code = cartographer_ros_msgs::StatusCode::INVALID_ARGUMENT;
} else if (!ValidateTopicNames(trajectory_options)) {
response.status.message = "Topics are already used by another trajectory.";
LOG(ERROR) << response.status.message;
response.status.code = cartographer_ros_msgs::StatusCode::INVALID_ARGUMENT;
} else {
response.status.message = "Success.";
response.trajectory_id = AddTrajectory(trajectory_options);
response.status.code = cartographer_ros_msgs::StatusCode::OK;
}
return true;
}
//在node_main.cc的函数Run中,通过调用node对象的成员函数StartTrajectoryWithDefaultTopics来开始轨迹跟踪。
//除此之外,还可以调用服务"start_trajectory"来开启。两者的不同是,前者使用系统默认的订阅主题,
//后者在调用服务的时候还需要提供轨迹配置和订阅主题。下面是StartTrajectoryWithDefaultTopics的函数实现。
//内容很简单,就三条语句。先加锁,在检查输入的配置是否合法,最后调用函数AddTrajectory开始轨迹跟踪。
//通过服务的形式开启轨迹跟踪,最终也是调用这个AddTrajectory。
void Node::StartTrajectoryWithDefaultTopics(const TrajectoryOptions& options) {
absl::MutexLock lock(&mutex_);
CHECK(ValidateTrajectoryOptions(options));
AddTrajectory(options);
}
std::vector<
std::set<cartographer::mapping::TrajectoryBuilderInterface::SensorId>>
Node::ComputeDefaultSensorIdsForMultipleBags(
const std::vector<TrajectoryOptions>& bags_options) const {
using SensorId = cartographer::mapping::TrajectoryBuilderInterface::SensorId;
std::vector<std::set<SensorId>> bags_sensor_ids;
for (size_t i = 0; i < bags_options.size(); ++i) {
std::string prefix;
if (bags_options.size() > 1) {
prefix = "bag_" + std::to_string(i + 1) + "_";
}
std::set<SensorId> unique_sensor_ids;
for (const auto& sensor_id : ComputeExpectedSensorIds(bags_options.at(i))) {
unique_sensor_ids.insert(SensorId{sensor_id.type, prefix + sensor_id.id});
}
bags_sensor_ids.push_back(unique_sensor_ids);
}
return bags_sensor_ids;
}
int Node::AddOfflineTrajectory(
const std::set<cartographer::mapping::TrajectoryBuilderInterface::SensorId>&
expected_sensor_ids,
const TrajectoryOptions& options) {
absl::MutexLock lock(&mutex_);
const int trajectory_id =
map_builder_bridge_.AddTrajectory(expected_sensor_ids, options);
AddExtrapolator(trajectory_id, options);
AddSensorSamplers(trajectory_id, options);
return trajectory_id;
}
bool Node::HandleGetTrajectoryStates(
::cartographer_ros_msgs::GetTrajectoryStates::Request& request,
::cartographer_ros_msgs::GetTrajectoryStates::Response& response) {
using TrajectoryState =
::cartographer::mapping::PoseGraphInterface::TrajectoryState;
absl::MutexLock lock(&mutex_);
response.status.code = ::cartographer_ros_msgs::StatusCode::OK;
response.trajectory_states.header.stamp = ros::Time::now();
for (const auto& entry : map_builder_bridge_.GetTrajectoryStates()) {
response.trajectory_states.trajectory_id.push_back(entry.first);
switch (entry.second) {
case TrajectoryState::ACTIVE:
response.trajectory_states.trajectory_state.push_back(
::cartographer_ros_msgs::TrajectoryStates::ACTIVE);
break;
case TrajectoryState::FINISHED:
response.trajectory_states.trajectory_state.push_back(
::cartographer_ros_msgs::TrajectoryStates::FINISHED);
break;
case TrajectoryState::FROZEN:
response.trajectory_states.trajectory_state.push_back(
::cartographer_ros_msgs::TrajectoryStates::FROZEN);
break;
case TrajectoryState::DELETED:
response.trajectory_states.trajectory_state.push_back(
::cartographer_ros_msgs::TrajectoryStates::DELETED);
break;
}
}
return true;
}
//下面是"/finish_trajectory"的服务响应函数的代码片段,调用函数FinishTrajectoryUnderLock停止路径跟踪。
bool Node::HandleFinishTrajectory(
::cartographer_ros_msgs::FinishTrajectory::Request& request,
::cartographer_ros_msgs::FinishTrajectory::Response& response) {
absl::MutexLock lock(&mutex_);
response.status = FinishTrajectoryUnderLock(request.trajectory_id);
return true;
}
//也是调用了map_builder_bridge_.SerializeState(request.filename)这个函数。猜测应该是将一些状态数据等写入文件系统的作用。
bool Node::HandleWriteState(
::cartographer_ros_msgs::WriteState::Request& request,
::cartographer_ros_msgs::WriteState::Response& response) {
absl::MutexLock lock(&mutex_);
if (map_builder_bridge_.SerializeState(request.filename,
request.include_unfinished_submaps)) {
response.status.code = cartographer_ros_msgs::StatusCode::OK;
response.status.message =
absl::StrCat("State written to '", request.filename, "'.");
} else {
response.status.code = cartographer_ros_msgs::StatusCode::INVALID_ARGUMENT;
response.status.message =
absl::StrCat("Failed to write '", request.filename, "'.");
}
return true;
}
bool Node::HandleReadMetrics(
::cartographer_ros_msgs::ReadMetrics::Request& request,
::cartographer_ros_msgs::ReadMetrics::Response& response) {
absl::MutexLock lock(&mutex_);
response.timestamp = ros::Time::now();
if (!metrics_registry_) {
response.status.code = cartographer_ros_msgs::StatusCode::UNAVAILABLE;
response.status.message = "Collection of runtime metrics is not activated.";
return true;
}
metrics_registry_->ReadMetrics(&response);
response.status.code = cartographer_ros_msgs::StatusCode::OK;
response.status.message = "Successfully read metrics.";
return true;
}
void Node::FinishAllTrajectories() {
absl::MutexLock lock(&mutex_);
for (const auto& entry : map_builder_bridge_.GetTrajectoryStates()) {
if (entry.second == TrajectoryState::ACTIVE) {
const int trajectory_id = entry.first;
CHECK_EQ(FinishTrajectoryUnderLock(trajectory_id).code,
cartographer_ros_msgs::StatusCode::OK);
}
}
}
bool Node::FinishTrajectory(const int trajectory_id) {
absl::MutexLock lock(&mutex_);
return FinishTrajectoryUnderLock(trajectory_id).code ==
cartographer_ros_msgs::StatusCode::OK;
}
void Node::RunFinalOptimization() {
{
for (const auto& entry : map_builder_bridge_.GetTrajectoryStates()) {
const int trajectory_id = entry.first;
if (entry.second == TrajectoryState::ACTIVE) {
LOG(WARNING)
<< "Can't run final optimization if there are one or more active "
"trajectories. Trying to finish trajectory with ID "
<< std::to_string(trajectory_id) << " now.";
CHECK(FinishTrajectory(trajectory_id))
<< "Failed to finish trajectory with ID "
<< std::to_string(trajectory_id) << ".";
}
}
}
// Assuming we are not adding new data anymore, the final optimization
// can be performed without holding the mutex.
map_builder_bridge_.RunFinalOptimization();
}
void Node::HandleOdometryMessage(const int trajectory_id,
const std::string& sensor_id,
const nav_msgs::Odometry::ConstPtr& msg) {
absl::MutexLock lock(&mutex_);
if (!sensor_samplers_.at(trajectory_id).odometry_sampler.Pulse()) {
return;
}
auto sensor_bridge_ptr = map_builder_bridge_.sensor_bridge(trajectory_id);
auto odometry_data_ptr = sensor_bridge_ptr->ToOdometryData(msg);
if (odometry_data_ptr != nullptr) {
extrapolators_.at(trajectory_id).AddOdometryData(*odometry_data_ptr);
}
sensor_bridge_ptr->HandleOdometryMessage(sensor_id, msg);
}
void Node::HandleNavSatFixMessage(const int trajectory_id,
const std::string& sensor_id,
const sensor_msgs::NavSatFix::ConstPtr& msg) {
absl::MutexLock lock(&mutex_);
if (!sensor_samplers_.at(trajectory_id).fixed_frame_pose_sampler.Pulse()) {
return;
}
map_builder_bridge_.sensor_bridge(trajectory_id)
->HandleNavSatFixMessage(sensor_id, msg);
}
void Node::HandleLandmarkMessage(
const int trajectory_id, const std::string& sensor_id,
const cartographer_ros_msgs::LandmarkList::ConstPtr& msg) {
absl::MutexLock lock(&mutex_);
if (!sensor_samplers_.at(trajectory_id).landmark_sampler.Pulse()) {
return;
}
map_builder_bridge_.sensor_bridge(trajectory_id)
->HandleLandmarkMessage(sensor_id, msg);
}
//下面是处理IMU的消息回调函数,除了要通过map_builder_bridge_传递给建图器之外,还需要将IMU数据传递给位姿估计器。
//这个位姿估计器的数据类型是定义在cartographer的PoseExtrapolator, 同样是在函数AddTrajectory中通过调用AddExtrapolator完成初始化操作。
void Node::HandleImuMessage(const int trajectory_id,
const std::string& sensor_id,
const sensor_msgs::Imu::ConstPtr& msg) {
absl::MutexLock lock(&mutex_);
if (!sensor_samplers_.at(trajectory_id).imu_sampler.Pulse()) {
return;
}
auto sensor_bridge_ptr = map_builder_bridge_.sensor_bridge(trajectory_id);
auto imu_data_ptr = sensor_bridge_ptr->ToImuData(msg);
if (imu_data_ptr != nullptr) {
extrapolators_.at(trajectory_id).AddImuData(*imu_data_ptr);
}
sensor_bridge_ptr->HandleImuMessage(sensor_id, msg);
}
void Node::HandleLaserScanMessage(const int trajectory_id,
const std::string& sensor_id,
const sensor_msgs::LaserScan::ConstPtr& msg) {
absl::MutexLock lock(&mutex_);
if (!sensor_samplers_.at(trajectory_id).rangefinder_sampler.Pulse()) {
return;
}
map_builder_bridge_.sensor_bridge(trajectory_id)
->HandleLaserScanMessage(sensor_id, msg);
}
//下面的代码片段是激光传感器的消息回调函数,在该函数的一开始先加锁,然后通过采样器对传感器的数据进行降采样之后,
//通过map_builder_bridge_将传感器数据喂给Cartographer。
//采样器, 它的数据类型是定义在node.h中的结构体TrajectorySensorSamplers, 在函数AddTrajectory中通过调用AddSensorSamplers完成初始化操作。
//其本质是对cartographer中的采样器(fixed_ratio_sampler.h, fixed_ratio_sampler.cc)的封装,
//用一个计数器来按照一个指定的频率对原始的数据进行降采样,采样频率可以通过轨迹参数文件来配置。
void Node::HandleMultiEchoLaserScanMessage(
const int trajectory_id, const std::string& sensor_id,
const sensor_msgs::MultiEchoLaserScan::ConstPtr& msg) {
absl::MutexLock lock(&mutex_);
if (!sensor_samplers_.at(trajectory_id).rangefinder_sampler.Pulse()) {
return;
}
map_builder_bridge_.sensor_bridge(trajectory_id)
->HandleMultiEchoLaserScanMessage(sensor_id, msg);
}
void Node::HandlePointCloud2Message(
const int trajectory_id, const std::string& sensor_id,
const sensor_msgs::PointCloud2::ConstPtr& msg) {
absl::MutexLock lock(&mutex_);
if (!sensor_samplers_.at(trajectory_id).rangefinder_sampler.Pulse()) {
return;
}
map_builder_bridge_.sensor_bridge(trajectory_id)
->HandlePointCloud2Message(sensor_id, msg);
}
void Node::SerializeState(const std::string& filename,
const bool include_unfinished_submaps) {
absl::MutexLock lock(&mutex_);
CHECK(
map_builder_bridge_.SerializeState(filename, include_unfinished_submaps))
<< "Could not write state.";
}
void Node::LoadState(const std::string& state_filename,
const bool load_frozen_state) {
absl::MutexLock lock(&mutex_);
map_builder_bridge_.LoadState(state_filename, load_frozen_state);
}
void Node::MaybeWarnAboutTopicMismatch(
const ::ros::WallTimerEvent& unused_timer_event) {
::ros::master::V_TopicInfo ros_topics;
::ros::master::getTopics(ros_topics);
std::set<std::string> published_topics;
std::stringstream published_topics_string;
for (const auto& it : ros_topics) {
std::string resolved_topic = node_handle_.resolveName(it.name, false);
published_topics.insert(resolved_topic);
published_topics_string << resolved_topic << ",";
}
bool print_topics = false;
for (const auto& entry : subscribers_) {
int trajectory_id = entry.first;
for (const auto& subscriber : entry.second) {
std::string resolved_topic = node_handle_.resolveName(subscriber.topic);
if (published_topics.count(resolved_topic) == 0) {
LOG(WARNING) << "Expected topic \"" << subscriber.topic
<< "\" (trajectory " << trajectory_id << ")"
<< " (resolved topic \"" << resolved_topic << "\")"
<< " but no publisher is currently active.";
print_topics = true;
}
}
}
if (print_topics) {
LOG(WARNING) << "Currently available topics are: "
<< published_topics_string.str();
}
}
} // namespace cartographer_ros
参考于:
https://zhuanlan.zhihu.com/p/48157120
以及
https://gaoyichao.com/Xiaotu/?book=Cartographer%E6%BA%90%E7%A0%81%E8%A7%A3%E8%AF%BB&title=cartographer_node%E7%9A%84%E5%A4%96%E5%A2%99_node%E5%AF%B9%E8%B1%A1