Make Node thread-safe. (#443)
Accessing the MapBuilderBridge was not previously guarded by a mutex.master
parent
061731399a
commit
76b1903488
|
@ -106,8 +106,6 @@ Node::~Node() {}
|
||||||
|
|
||||||
::ros::NodeHandle* Node::node_handle() { return &node_handle_; }
|
::ros::NodeHandle* Node::node_handle() { return &node_handle_; }
|
||||||
|
|
||||||
MapBuilderBridge* Node::map_builder_bridge() { return &map_builder_bridge_; }
|
|
||||||
|
|
||||||
bool Node::HandleSubmapQuery(
|
bool Node::HandleSubmapQuery(
|
||||||
::cartographer_ros_msgs::SubmapQuery::Request& request,
|
::cartographer_ros_msgs::SubmapQuery::Request& request,
|
||||||
::cartographer_ros_msgs::SubmapQuery::Response& response) {
|
::cartographer_ros_msgs::SubmapQuery::Response& response) {
|
||||||
|
@ -455,6 +453,57 @@ void Node::FinishAllTrajectories() {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void Node::FinishTrajectory(const int trajectory_id) {
|
||||||
|
carto::common::MutexLocker lock(&mutex_);
|
||||||
|
CHECK(is_active_trajectory_.at(trajectory_id));
|
||||||
|
map_builder_bridge_.FinishTrajectory(trajectory_id);
|
||||||
|
is_active_trajectory_[trajectory_id] = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
void Node::HandleOdometryMessage(const int trajectory_id,
|
||||||
|
const string& sensor_id,
|
||||||
|
const nav_msgs::Odometry::ConstPtr& msg) {
|
||||||
|
carto::common::MutexLocker lock(&mutex_);
|
||||||
|
map_builder_bridge_.sensor_bridge(trajectory_id)
|
||||||
|
->HandleOdometryMessage(sensor_id, msg);
|
||||||
|
}
|
||||||
|
|
||||||
|
void Node::HandleImuMessage(const int trajectory_id, const string& sensor_id,
|
||||||
|
const sensor_msgs::Imu::ConstPtr& msg) {
|
||||||
|
carto::common::MutexLocker lock(&mutex_);
|
||||||
|
map_builder_bridge_.sensor_bridge(trajectory_id)
|
||||||
|
->HandleImuMessage(sensor_id, msg);
|
||||||
|
}
|
||||||
|
|
||||||
|
void Node::HandleLaserScanMessage(const int trajectory_id,
|
||||||
|
const string& sensor_id,
|
||||||
|
const sensor_msgs::LaserScan::ConstPtr& msg) {
|
||||||
|
carto::common::MutexLocker lock(&mutex_);
|
||||||
|
map_builder_bridge_.sensor_bridge(trajectory_id)
|
||||||
|
->HandleLaserScanMessage(sensor_id, msg);
|
||||||
|
}
|
||||||
|
|
||||||
|
void Node::HandleMultiEchoLaserScanMessage(
|
||||||
|
int trajectory_id, const string& sensor_id,
|
||||||
|
const sensor_msgs::MultiEchoLaserScan::ConstPtr& msg) {
|
||||||
|
carto::common::MutexLocker lock(&mutex_);
|
||||||
|
map_builder_bridge_.sensor_bridge(trajectory_id)
|
||||||
|
->HandleMultiEchoLaserScanMessage(sensor_id, msg);
|
||||||
|
}
|
||||||
|
|
||||||
|
void Node::HandlePointCloud2Message(
|
||||||
|
const int trajectory_id, const string& sensor_id,
|
||||||
|
const sensor_msgs::PointCloud2::ConstPtr& msg) {
|
||||||
|
carto::common::MutexLocker lock(&mutex_);
|
||||||
|
map_builder_bridge_.sensor_bridge(trajectory_id)
|
||||||
|
->HandlePointCloud2Message(sensor_id, msg);
|
||||||
|
}
|
||||||
|
|
||||||
|
void Node::SerializeState(const string& filename) {
|
||||||
|
carto::common::MutexLocker lock(&mutex_);
|
||||||
|
map_builder_bridge_.SerializeState(filename);
|
||||||
|
}
|
||||||
|
|
||||||
void Node::LoadMap(const std::string& map_filename) {
|
void Node::LoadMap(const std::string& map_filename) {
|
||||||
carto::common::MutexLocker lock(&mutex_);
|
carto::common::MutexLocker lock(&mutex_);
|
||||||
map_builder_bridge_.LoadMap(map_filename);
|
map_builder_bridge_.LoadMap(map_filename);
|
||||||
|
|
|
@ -53,6 +53,8 @@ class Node {
|
||||||
|
|
||||||
// Finishes all yet active trajectories.
|
// Finishes all yet active trajectories.
|
||||||
void FinishAllTrajectories();
|
void FinishAllTrajectories();
|
||||||
|
// Finishes a single given trajectory.
|
||||||
|
void FinishTrajectory(int trajectory_id);
|
||||||
|
|
||||||
// Starts the first trajectory with the default topics.
|
// Starts the first trajectory with the default topics.
|
||||||
void StartTrajectoryWithDefaultTopics(const TrajectoryOptions& options);
|
void StartTrajectoryWithDefaultTopics(const TrajectoryOptions& options);
|
||||||
|
@ -66,11 +68,26 @@ class Node {
|
||||||
const std::unordered_set<string>& expected_sensor_ids,
|
const std::unordered_set<string>& expected_sensor_ids,
|
||||||
const TrajectoryOptions& options);
|
const TrajectoryOptions& options);
|
||||||
|
|
||||||
|
// The following functions handle adding sensor data to a trajectory.
|
||||||
|
void HandleOdometryMessage(int trajectory_id, const string& sensor_id,
|
||||||
|
const nav_msgs::Odometry::ConstPtr& msg);
|
||||||
|
void HandleImuMessage(int trajectory_id, const string& sensor_id,
|
||||||
|
const sensor_msgs::Imu::ConstPtr& msg);
|
||||||
|
void HandleLaserScanMessage(int trajectory_id, const string& sensor_id,
|
||||||
|
const sensor_msgs::LaserScan::ConstPtr& msg);
|
||||||
|
void HandleMultiEchoLaserScanMessage(
|
||||||
|
int trajectory_id, const string& sensor_id,
|
||||||
|
const sensor_msgs::MultiEchoLaserScan::ConstPtr& msg);
|
||||||
|
void HandlePointCloud2Message(int trajectory_id, const string& sensor_id,
|
||||||
|
const sensor_msgs::PointCloud2::ConstPtr& msg);
|
||||||
|
|
||||||
|
// Serializes the complete Node state.
|
||||||
|
void SerializeState(const string& filename);
|
||||||
|
|
||||||
// Loads a persisted state to use as a map.
|
// Loads a persisted state to use as a map.
|
||||||
void LoadMap(const std::string& map_filename);
|
void LoadMap(const std::string& map_filename);
|
||||||
|
|
||||||
::ros::NodeHandle* node_handle();
|
::ros::NodeHandle* node_handle();
|
||||||
MapBuilderBridge* map_builder_bridge();
|
|
||||||
|
|
||||||
private:
|
private:
|
||||||
bool HandleSubmapQuery(
|
bool HandleSubmapQuery(
|
||||||
|
|
|
@ -173,35 +173,28 @@ void Run(const std::vector<string>& bag_filenames) {
|
||||||
const string topic = node.node_handle()->resolveName(
|
const string topic = node.node_handle()->resolveName(
|
||||||
delayed_msg.getTopic(), false /* resolve */);
|
delayed_msg.getTopic(), false /* resolve */);
|
||||||
if (delayed_msg.isType<sensor_msgs::LaserScan>()) {
|
if (delayed_msg.isType<sensor_msgs::LaserScan>()) {
|
||||||
node.map_builder_bridge()
|
node.HandleLaserScanMessage(
|
||||||
->sensor_bridge(trajectory_id)
|
trajectory_id, topic,
|
||||||
->HandleLaserScanMessage(
|
delayed_msg.instantiate<sensor_msgs::LaserScan>());
|
||||||
topic, delayed_msg.instantiate<sensor_msgs::LaserScan>());
|
|
||||||
}
|
}
|
||||||
if (delayed_msg.isType<sensor_msgs::MultiEchoLaserScan>()) {
|
if (delayed_msg.isType<sensor_msgs::MultiEchoLaserScan>()) {
|
||||||
node.map_builder_bridge()
|
node.HandleMultiEchoLaserScanMessage(
|
||||||
->sensor_bridge(trajectory_id)
|
trajectory_id, topic,
|
||||||
->HandleMultiEchoLaserScanMessage(
|
|
||||||
topic,
|
|
||||||
delayed_msg.instantiate<sensor_msgs::MultiEchoLaserScan>());
|
delayed_msg.instantiate<sensor_msgs::MultiEchoLaserScan>());
|
||||||
}
|
}
|
||||||
if (delayed_msg.isType<sensor_msgs::PointCloud2>()) {
|
if (delayed_msg.isType<sensor_msgs::PointCloud2>()) {
|
||||||
node.map_builder_bridge()
|
node.HandlePointCloud2Message(
|
||||||
->sensor_bridge(trajectory_id)
|
trajectory_id, topic,
|
||||||
->HandlePointCloud2Message(
|
delayed_msg.instantiate<sensor_msgs::PointCloud2>());
|
||||||
topic, delayed_msg.instantiate<sensor_msgs::PointCloud2>());
|
|
||||||
}
|
}
|
||||||
if (delayed_msg.isType<sensor_msgs::Imu>()) {
|
if (delayed_msg.isType<sensor_msgs::Imu>()) {
|
||||||
node.map_builder_bridge()
|
node.HandleImuMessage(trajectory_id, topic,
|
||||||
->sensor_bridge(trajectory_id)
|
|
||||||
->HandleImuMessage(topic,
|
|
||||||
delayed_msg.instantiate<sensor_msgs::Imu>());
|
delayed_msg.instantiate<sensor_msgs::Imu>());
|
||||||
}
|
}
|
||||||
if (delayed_msg.isType<nav_msgs::Odometry>()) {
|
if (delayed_msg.isType<nav_msgs::Odometry>()) {
|
||||||
node.map_builder_bridge()
|
node.HandleOdometryMessage(
|
||||||
->sensor_bridge(trajectory_id)
|
trajectory_id, topic,
|
||||||
->HandleOdometryMessage(
|
delayed_msg.instantiate<nav_msgs::Odometry>());
|
||||||
topic, delayed_msg.instantiate<nav_msgs::Odometry>());
|
|
||||||
}
|
}
|
||||||
rosgraph_msgs::Clock clock;
|
rosgraph_msgs::Clock clock;
|
||||||
clock.clock = delayed_msg.getTime();
|
clock.clock = delayed_msg.getTime();
|
||||||
|
@ -225,7 +218,7 @@ void Run(const std::vector<string>& bag_filenames) {
|
||||||
}
|
}
|
||||||
|
|
||||||
bag.close();
|
bag.close();
|
||||||
node.map_builder_bridge()->FinishTrajectory(trajectory_id);
|
node.FinishTrajectory(trajectory_id);
|
||||||
}
|
}
|
||||||
|
|
||||||
const std::chrono::time_point<std::chrono::steady_clock> end_time =
|
const std::chrono::time_point<std::chrono::steady_clock> end_time =
|
||||||
|
@ -243,8 +236,7 @@ void Run(const std::vector<string>& bag_filenames) {
|
||||||
<< (cpu_timespec.tv_sec + 1e-9 * cpu_timespec.tv_nsec) << " s";
|
<< (cpu_timespec.tv_sec + 1e-9 * cpu_timespec.tv_nsec) << " s";
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
node.map_builder_bridge()->SerializeState(bag_filenames.front() +
|
node.SerializeState(bag_filenames.front() + ".pbstream");
|
||||||
".pbstream");
|
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace
|
} // namespace
|
||||||
|
|
Loading…
Reference in New Issue