Skip to content

Commit d4e6dc3

Browse files
committed
Clean up Windows warnings.
Signed-off-by: Michael Carroll <[email protected]>
1 parent 2c30e1d commit d4e6dc3

File tree

4 files changed

+13
-13
lines changed

4 files changed

+13
-13
lines changed

sensor_msgs/include/sensor_msgs/impl/point_cloud2_iterator.hpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -129,15 +129,15 @@ inline void PointCloud2Modifier::resize(size_t size)
129129

130130
// Update height/width
131131
if (cloud_msg_.height == 1) {
132-
cloud_msg_.width = size;
133-
cloud_msg_.row_step = size * cloud_msg_.point_step;
132+
cloud_msg_.width = static_cast<uint32_t>(size);
133+
cloud_msg_.row_step = static_cast<uint32_t>(size * cloud_msg_.point_step);
134134
} else {
135135
if (cloud_msg_.width == 1) {
136-
cloud_msg_.height = size;
136+
cloud_msg_.height = static_cast<uint32_t>(size);
137137
} else {
138138
cloud_msg_.height = 1;
139-
cloud_msg_.width = size;
140-
cloud_msg_.row_step = size * cloud_msg_.point_step;
139+
cloud_msg_.width = static_cast<uint32_t>(size);
140+
cloud_msg_.row_step = static_cast<uint32_t>(size * cloud_msg_.point_step);
141141
}
142142
}
143143
}

sensor_msgs/include/sensor_msgs/point_cloud_conversion.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -60,7 +60,7 @@ static inline int getPointCloud2FieldIndex(
6060
// Get the index we need
6161
for (size_t d = 0; d < cloud.fields.size(); ++d) {
6262
if (cloud.fields[d].name == field_name) {
63-
return d;
63+
return static_cast<int>(d);
6464
}
6565
}
6666
return -1;
@@ -76,7 +76,7 @@ static inline bool convertPointCloudToPointCloud2(
7676
sensor_msgs::msg::PointCloud2 & output)
7777
{
7878
output.header = input.header;
79-
output.width = input.points.size();
79+
output.width = static_cast<uint32_t>(input.points.size());
8080
output.height = 1;
8181
output.fields.resize(3 + input.channels.size());
8282
// Convert x/y/z to fields

sensor_msgs/test/test_pointcloud_conversion.cpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -36,13 +36,13 @@ TEST(sensor_msgs, PointCloudConversion)
3636

3737
for (size_t ii = 0; ii < 100; ++ii) {
3838
auto pt = geometry_msgs::msg::Point32();
39-
pt.x = ii;
40-
pt.y = 2 * ii;
41-
pt.z = 3 * ii;
39+
pt.x = static_cast<float>(1 * ii);
40+
pt.y = static_cast<float>(2 * ii);
41+
pt.z = static_cast<float>(3 * ii);
4242
cloud.points.push_back(pt);
4343

44-
intensity.values.push_back(4 * ii);
45-
range.values.push_back(5 * ii);
44+
intensity.values.push_back(static_cast<float>(4 * ii));
45+
range.values.push_back(static_cast<float>(5 * ii));
4646
}
4747
cloud.channels.push_back(intensity);
4848
cloud.channels.push_back(range);

sensor_msgs/test/test_pointcloud_iterator.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -45,7 +45,7 @@ TEST(sensor_msgs, PointCloud2Iterator)
4545
// Create a dummy PointCloud2
4646
size_t n_points = 4;
4747
sensor_msgs::msg::PointCloud2 cloud_msg_1, cloud_msg_2;
48-
cloud_msg_1.height = n_points;
48+
cloud_msg_1.height = static_cast<uint32_t>(n_points);
4949
cloud_msg_1.width = 1;
5050
sensor_msgs::PointCloud2Modifier modifier(cloud_msg_1);
5151
modifier.setPointCloud2FieldsByString(2, "xyz", "rgb");

0 commit comments

Comments
 (0)