Fix race-condition when attempting to fetch trimmed submaps. (#812)

A simple solution for a slightly more complex scenario:
- a pure localization trajectory `X` gets finished & trimmed in the main node
- at the same time, the occupancy_grid_node handles an outdated SubmapList
  message in which a submap ID `id` of trajectory `X` is still present
- the call to FetchSubmapTextures(`id`, ...) leads to a crash

With this fix, the trimmed submap IDs are just ignored until the next
iteration (in which the occupancy grid node removes the trimmed IDs).
master
Michael Grupp 2018-04-09 17:30:21 +02:00 committed by Wally B. Feed
parent f818bc79d9
commit c0a97d88a3
1 changed files with 3 additions and 1 deletions

View File

@ -20,6 +20,7 @@
#include "cartographer/common/port.h" #include "cartographer/common/port.h"
#include "cartographer/transform/transform.h" #include "cartographer/transform/transform.h"
#include "cartographer_ros/msg_conversion.h" #include "cartographer_ros/msg_conversion.h"
#include "cartographer_ros_msgs/StatusCode.h"
#include "cartographer_ros_msgs/SubmapQuery.h" #include "cartographer_ros_msgs/SubmapQuery.h"
namespace cartographer_ros { namespace cartographer_ros {
@ -30,7 +31,8 @@ std::unique_ptr<::cartographer::io::SubmapTextures> FetchSubmapTextures(
::cartographer_ros_msgs::SubmapQuery srv; ::cartographer_ros_msgs::SubmapQuery srv;
srv.request.trajectory_id = submap_id.trajectory_id; srv.request.trajectory_id = submap_id.trajectory_id;
srv.request.submap_index = submap_id.submap_index; srv.request.submap_index = submap_id.submap_index;
if (!client->call(srv)) { if (!client->call(srv) ||
srv.response.status.code != ::cartographer_ros_msgs::StatusCode::OK) {
return nullptr; return nullptr;
} }
CHECK(!srv.response.textures.empty()); CHECK(!srv.response.textures.empty());