diff --git a/cartographer_ros/cartographer_ros/msg_conversion.cc b/cartographer_ros/cartographer_ros/msg_conversion.cc index 3b3afe5..35244cc 100644 --- a/cartographer_ros/cartographer_ros/msg_conversion.cc +++ b/cartographer_ros/cartographer_ros/msg_conversion.cc @@ -276,7 +276,7 @@ ToPointCloudWithIntensities(const sensor_msgs::PointCloud2& msg) { LandmarkData ToLandmarkData(const LandmarkList& landmark_list) { LandmarkData landmark_data; landmark_data.time = FromRos(landmark_list.header.stamp); - for (const LandmarkEntry& entry : landmark_list.landmark) { + for (const LandmarkEntry& entry : landmark_list.landmarks) { landmark_data.landmark_observations.push_back( {entry.id, ToRigid3d(entry.tracking_from_landmark_transform), entry.translation_weight, entry.rotation_weight}); diff --git a/cartographer_ros/cartographer_ros/msg_conversion_test.cc b/cartographer_ros/cartographer_ros/msg_conversion_test.cc index 0f34536..0ba87ae 100644 --- a/cartographer_ros/cartographer_ros/msg_conversion_test.cc +++ b/cartographer_ros/cartographer_ros/msg_conversion_test.cc @@ -121,7 +121,7 @@ TEST(MsgConversion, LandmarkListToLandmarkData) { landmark_0.tracking_from_landmark_transform.orientation.z = 0.0; landmark_0.translation_weight = 1.0; landmark_0.rotation_weight = 2.0; - message.landmark.push_back(landmark_0); + message.landmarks.push_back(landmark_0); LandmarkData actual_landmark_data = ToLandmarkData(message); EXPECT_THAT(actual_landmark_data, diff --git a/cartographer_ros_msgs/msg/LandmarkList.msg b/cartographer_ros_msgs/msg/LandmarkList.msg index 5c5bd2d..a8e25ef 100644 --- a/cartographer_ros_msgs/msg/LandmarkList.msg +++ b/cartographer_ros_msgs/msg/LandmarkList.msg @@ -13,4 +13,4 @@ # limitations under the License. std_msgs/Header header -cartographer_ros_msgs/LandmarkEntry[] landmark +cartographer_ros_msgs/LandmarkEntry[] landmarks