Commit bb5cc41
committed
pcl_conversions: Fix compile errors caused by rosidl_buffer introduction
Compiling pcl_ros package in rolling results in errors like this:
In file included from
/build/perception_pcl-release-release-rolling-pcl_ros-2.8.0-1/tools/combined_pointcloud_to_pcd.cpp:47:
/ros-rolling-pcl-conversions-2.8.0-r1/include/pcl_conversions/pcl_conversions/pcl_conversions.h: In
function 'void pcl_conversions::moveFromPCL(pcl::PCLImage&, sensor_msgs::msg::Image&)':
/ros-rolling-pcl-conversions-2.8.0-r1/include/pcl_conversions/pcl_conversions/pcl_conversions.h:172:16:
error: 'using sensor_msgs::msg::Image_<std::allocator<void> >::_data_type = class
rosidl::Buffer<unsigned char, std::allocator<unsigned char> >' {aka 'class rosidl::Buffer<unsigned
char, std::allocator<unsigned char> >'} has no member named 'swap'
172 | image.data.swap(pcl_image.data);
| ^~~~
These are caused by ros2/rosidl#941 and
followup PRs, which change the type of `uint8[]` message fields from
`std::vector<uint8_t>` to `rosidl::Buffer<uint8_t>`. To maintain the
previous functionality, explicit typecasting is needed at a few
places. This causes invocation of the conversion operator [1], which
returns a reference to the underlying std::vector.
[1]: https://github.com/ros2/rosidl/blob/7c4e0f90f2979c16c906d65058fc7966360f52e1/rosidl_buffer/include/rosidl_buffer/buffer.hpp#L420
Signed-off-by: Michal Sojka <michal.sojka@cvut.cz>1 parent b7013aa commit bb5cc41
1 file changed
+3
-3
lines changed| Original file line number | Diff line number | Diff line change | |
|---|---|---|---|
| |||
169 | 169 | | |
170 | 170 | | |
171 | 171 | | |
172 | | - | |
| 172 | + | |
173 | 173 | | |
174 | 174 | | |
175 | 175 | | |
| |||
194 | 194 | | |
195 | 195 | | |
196 | 196 | | |
197 | | - | |
| 197 | + | |
198 | 198 | | |
199 | 199 | | |
200 | 200 | | |
| |||
269 | 269 | | |
270 | 270 | | |
271 | 271 | | |
272 | | - | |
| 272 | + | |
273 | 273 | | |
274 | 274 | | |
275 | 275 | | |
| |||
0 commit comments