Use 'landmarks' instead of 'landmark'. (#931)
parent
0aa6ecc40f
commit
944b22575f
|
@ -276,7 +276,7 @@ ToPointCloudWithIntensities(const sensor_msgs::PointCloud2& msg) {
|
||||||
LandmarkData ToLandmarkData(const LandmarkList& landmark_list) {
|
LandmarkData ToLandmarkData(const LandmarkList& landmark_list) {
|
||||||
LandmarkData landmark_data;
|
LandmarkData landmark_data;
|
||||||
landmark_data.time = FromRos(landmark_list.header.stamp);
|
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(
|
landmark_data.landmark_observations.push_back(
|
||||||
{entry.id, ToRigid3d(entry.tracking_from_landmark_transform),
|
{entry.id, ToRigid3d(entry.tracking_from_landmark_transform),
|
||||||
entry.translation_weight, entry.rotation_weight});
|
entry.translation_weight, entry.rotation_weight});
|
||||||
|
|
|
@ -121,7 +121,7 @@ TEST(MsgConversion, LandmarkListToLandmarkData) {
|
||||||
landmark_0.tracking_from_landmark_transform.orientation.z = 0.0;
|
landmark_0.tracking_from_landmark_transform.orientation.z = 0.0;
|
||||||
landmark_0.translation_weight = 1.0;
|
landmark_0.translation_weight = 1.0;
|
||||||
landmark_0.rotation_weight = 2.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);
|
LandmarkData actual_landmark_data = ToLandmarkData(message);
|
||||||
EXPECT_THAT(actual_landmark_data,
|
EXPECT_THAT(actual_landmark_data,
|
||||||
|
|
|
@ -13,4 +13,4 @@
|
||||||
# limitations under the License.
|
# limitations under the License.
|
||||||
|
|
||||||
std_msgs/Header header
|
std_msgs/Header header
|
||||||
cartographer_ros_msgs/LandmarkEntry[] landmark
|
cartographer_ros_msgs/LandmarkEntry[] landmarks
|
||||||
|
|
Loading…
Reference in New Issue