You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
I am getting compilation errors while using the latest master of sick_scan_xd, for ROS2 .
Setup Environment:
ros2 foxy
ubuntu 20.04
latest main with commit hash: eacf743e3d432febeb9799b2fe9019f2eb46ba90
Error messages
Starting >>> sick_scan
[Processing: sick_scan]
[Processing: sick_scan]
--- stderr: sick_scan
/home/youliang/ros2_ws/src/sick_scan_xd/driver/src/sick_scan_common.cpp: In member function ‘int sick_scan::SickScanCommon::loopOnce(rosNodePtr)’:
/home/youliang/ros2_ws/src/sick_scan_xd/driver/src/sick_scan_common.cpp:4531:44: error: cannot convert ‘rosNodePtr’ {aka ‘std::shared_ptr<rclcpp::Node>’} to ‘sick_scan::Handle’ {aka ‘void*’}
4531 | notifyPointcloudListener(nh, &cloud_);
| ^~
| |
| rosNodePtr {aka std::shared_ptr<rclcpp::Node>}
In file included from /home/youliang/ros2_ws/src/sick_scan_xd/include/sick_scan/sick_scan_common.h:73,
from /home/youliang/ros2_ws/src/sick_scan_xd/driver/src/sick_scan_common.cpp:74:
/home/youliang/ros2_ws/src/sick_scan_xd/include/sick_scan/sick_generic_callback.h:69:42: note: initializing argument 1 of ‘void sick_scan::notifyPointcloudListener(sick_scan::Handle, const PointCloud2*)’
69 | void notifyPointcloudListener(Handle handle, const ros_sensor_msgs::PointCloud2* msg);
| ~~~~~~~^~~~~~
/home/youliang/ros2_ws/src/sick_scan_xd/driver/src/sick_scan_common.cpp: In member function ‘int sick_scan::SickScanCommon::loopOnce(rosNodePtr)’:
/home/youliang/ros2_ws/src/sick_scan_xd/driver/src/sick_scan_common.cpp:4531:44: error: cannot convert ‘rosNodePtr’ {aka ‘std::shared_ptr<rclcpp::Node>’} to ‘sick_scan::Handle’ {aka ‘void*’}
4531 | notifyPointcloudListener(nh, &cloud_);
| ^~
| |
| rosNodePtr {aka std::shared_ptr<rclcpp::Node>}
In file included from /home/youliang/ros2_ws/src/sick_scan_xd/include/sick_scan/sick_scan_common.h:73,
from /home/youliang/ros2_ws/src/sick_scan_xd/driver/src/sick_scan_common.cpp:74:
/home/youliang/ros2_ws/src/sick_scan_xd/include/sick_scan/sick_generic_callback.h:69:42: note: initializing argument 1 of ‘void sick_scan::notifyPointcloudListener(sick_scan::Handle, const PointCloud2*)’
69 | void notifyPointcloudListener(Handle handle, const ros_sensor_msgs::PointCloud2* msg);
It seems like the error is related to the newly created notifyPointcloudListener class in #82 PR. Meanwhile, to run the driver with ros2, I am still using the commit after the merge of #76, which seems to work fine till now.
To ensure pkg stability, the recommendation is to have a simple CI process here in this repo. FYI, this can be easily implemented by using github action's ros-tooling/setup-ros.
The text was updated successfully, but these errors were encountered:
Issue Description
I am getting compilation errors while using the latest master of
sick_scan_xd
, for ROS2 .Setup Environment:
ros2
foxyeacf743e3d432febeb9799b2fe9019f2eb46ba90
Error messages
It seems like the error is related to the newly created
notifyPointcloudListener
class in #82 PR. Meanwhile, to run the driver withros2
, I am still using the commit after the merge of #76, which seems to work fine till now.To ensure pkg stability, the recommendation is to have a simple CI process here in this repo. FYI, this can be easily implemented by using github action's ros-tooling/setup-ros.
The text was updated successfully, but these errors were encountered: