Track changes in Cartographer. (#331)

googlecartographer/cartographer#268 changes the API.

PAIR=wohe
master
Holger Rapp 2017-05-09 16:06:04 +02:00 committed by GitHub
parent f6fc7ac6b2
commit d624b1c250
1 changed files with 4 additions and 4 deletions

View File

@ -111,11 +111,11 @@ cartographer_ros_msgs::SubmapList MapBuilderBridge::GetSubmapList() {
const cartographer::mapping::Submaps* submaps = const cartographer::mapping::Submaps* submaps =
map_builder_.GetTrajectoryBuilder(trajectory_id)->submaps(); map_builder_.GetTrajectoryBuilder(trajectory_id)->submaps();
const std::vector<cartographer::transform::Rigid3d> submap_transforms = const std::vector<cartographer::transform::Rigid3d> submap_transforms =
map_builder_.sparse_pose_graph()->GetSubmapTransforms(*submaps); map_builder_.sparse_pose_graph()->GetSubmapTransforms(submaps);
CHECK_EQ(submap_transforms.size(), submaps->size()); CHECK_LE(submap_transforms.size(), submaps->size());
cartographer_ros_msgs::TrajectorySubmapList trajectory_submap_list; cartographer_ros_msgs::TrajectorySubmapList trajectory_submap_list;
for (int submap_index = 0; submap_index != submaps->size(); for (size_t submap_index = 0; submap_index != submap_transforms.size();
++submap_index) { ++submap_index) {
cartographer_ros_msgs::SubmapEntry submap_entry; cartographer_ros_msgs::SubmapEntry submap_entry;
submap_entry.submap_version = submaps->Get(submap_index)->num_range_data; submap_entry.submap_version = submaps->Get(submap_index)->num_range_data;
@ -164,7 +164,7 @@ MapBuilderBridge::GetTrajectoryStates() {
trajectory_states[trajectory_id] = { trajectory_states[trajectory_id] = {
pose_estimate, pose_estimate,
map_builder_.sparse_pose_graph()->GetLocalToGlobalTransform( map_builder_.sparse_pose_graph()->GetLocalToGlobalTransform(
*trajectory_builder->submaps()), trajectory_builder->submaps()),
sensor_bridge.tf_bridge().LookupToTracking(pose_estimate.time, sensor_bridge.tf_bridge().LookupToTracking(pose_estimate.time,
options_.published_frame)}; options_.published_frame)};
} }