Skip to content

Commit

Permalink
fix typo and change literals type
Browse files Browse the repository at this point in the history
  • Loading branch information
tonylitianyu committed May 31, 2022
1 parent defc177 commit 04b7adc
Show file tree
Hide file tree
Showing 2 changed files with 17 additions and 17 deletions.
2 changes: 1 addition & 1 deletion sensor_msgs/include/sensor_msgs/point_cloud2_iterator.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -127,7 +127,7 @@ class PointCloud2Modifier

/**
* @param width The new width of the point cloud.
* @param height THe new height of the point cloud.
* @param height The new height of the point cloud.
*/
void resize(size_t width, size_t height);

Expand Down
32 changes: 16 additions & 16 deletions sensor_msgs/test/test_pointcloud_iterator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -135,11 +135,11 @@ TEST(sensor_msgs, PointCloud2Resize)
sensor_msgs::PointCloud2Modifier modifier(cloud_msg_1);
modifier.setPointCloud2FieldsByString(2, "xyz", "rgb");
modifier.resize(1 * n_points);
EXPECT_EQ((unsigned int)1, cloud_msg_1.width);
EXPECT_EQ((unsigned int)4, cloud_msg_1.height);
EXPECT_EQ(static_cast<uint32_t>(1), cloud_msg_1.width);
EXPECT_EQ(static_cast<uint32_t>(4), cloud_msg_1.height);
modifier.resize(1, n_points);
EXPECT_EQ((unsigned int)1, cloud_msg_1.width);
EXPECT_EQ((unsigned int)4, cloud_msg_1.height);
EXPECT_EQ(static_cast<uint32_t>(1), cloud_msg_1.width);
EXPECT_EQ(static_cast<uint32_t>(4), cloud_msg_1.height);

// Check if size will retain when width and height given explicitly (height == 1)
size_t n_points2 = 5;
Expand All @@ -149,13 +149,13 @@ TEST(sensor_msgs, PointCloud2Resize)
sensor_msgs::PointCloud2Modifier modifier2(cloud_msg_2);
modifier2.setPointCloud2FieldsByString(2, "xyz", "rgb");
modifier2.resize(1 * n_points2);
EXPECT_EQ((unsigned int)5, cloud_msg_2.width);
EXPECT_EQ((unsigned int)1, cloud_msg_2.height);
EXPECT_EQ((unsigned int)160, cloud_msg_2.row_step);
EXPECT_EQ(static_cast<uint32_t>(5), cloud_msg_2.width);
EXPECT_EQ(static_cast<uint32_t>(1), cloud_msg_2.height);
EXPECT_EQ(static_cast<uint32_t>(160), cloud_msg_2.row_step);
modifier2.resize(n_points2, 1);
EXPECT_EQ((unsigned int)5, cloud_msg_2.width);
EXPECT_EQ((unsigned int)1, cloud_msg_2.height);
EXPECT_EQ((unsigned int)160, cloud_msg_2.row_step);
EXPECT_EQ(static_cast<uint32_t>(5), cloud_msg_2.width);
EXPECT_EQ(static_cast<uint32_t>(1), cloud_msg_2.height);
EXPECT_EQ(static_cast<uint32_t>(160), cloud_msg_2.row_step);

// Check if resize works when width and height are changed
sensor_msgs::msg::PointCloud2 cloud_msg_3;
Expand All @@ -164,11 +164,11 @@ TEST(sensor_msgs, PointCloud2Resize)
sensor_msgs::PointCloud2Modifier modifier3(cloud_msg_3);
modifier3.setPointCloud2FieldsByString(2, "xyz", "rgb");
modifier3.resize(10);
EXPECT_EQ((unsigned int)10, cloud_msg_3.width);
EXPECT_EQ((unsigned int)1, cloud_msg_3.height);
EXPECT_EQ((unsigned int)320, cloud_msg_3.row_step);
EXPECT_EQ(static_cast<uint32_t>(10), cloud_msg_3.width);
EXPECT_EQ(static_cast<uint32_t>(1), cloud_msg_3.height);
EXPECT_EQ(static_cast<uint32_t>(320), cloud_msg_3.row_step);
modifier3.resize(11, 11);
EXPECT_EQ((unsigned int)11, cloud_msg_3.width);
EXPECT_EQ((unsigned int)11, cloud_msg_3.height);
EXPECT_EQ((unsigned int)3872, cloud_msg_3.row_step);
EXPECT_EQ(static_cast<uint32_t>(11), cloud_msg_3.width);
EXPECT_EQ(static_cast<uint32_t>(11), cloud_msg_3.height);
EXPECT_EQ(static_cast<uint32_t>(3872), cloud_msg_3.row_step);
}

0 comments on commit 04b7adc

Please sign in to comment.