Updates to udp_driver Broke Velodyne Node
Description
The ROS Dashing sync has gone through and the udp_driver
package from https://github.com/ros-drivers/transport_drivers has been updated to version 0.0.4. Unfortunately, this change breaks the velodyne_nodes
package when the environment is built outside of ADE.
How to Reproduce
3 ways to test:
- Create an MR and let CI run
- Run the commands from the
build_barebones
job in Docker - In ADE, run
sudo apt update && sudo apt upgrade
, then build AutowareAuto
Current Behavior
In the build_barebones
job, the following errors occur:
--- stderr: velodyne_node
In file included from /builds/autowarefoundation/autoware.auto/AutowareAuto/src/drivers/velodyne_node/include/velodyne_node/velodyne_cloud_node.hpp:29:0,
from /builds/autowarefoundation/autoware.auto/AutowareAuto/src/drivers/velodyne_node/src/velodyne_cloud_node.cpp:23:
/opt/ros/dashing/include/udp_driver/udp_driver_node.hpp:56:5: error: type qualifiers ignored on function return type [-Werror=ignored-qualifiers]
const uint16_t get_port() const
^~~~~
/builds/autowarefoundation/autoware.auto/AutowareAuto/src/drivers/velodyne_node/src/velodyne_cloud_node.cpp: In constructor 'autoware::drivers::velodyne_node::VelodyneCloudNode::VelodyneCloudNode(const string&, const string&, const string&, uint16_t, const string&, std::size_t, const autoware::drivers::velodyne_driver::Vlp16Translator::Config&)':
/builds/autowarefoundation/autoware.auto/AutowareAuto/src/drivers/velodyne_node/src/velodyne_cloud_node.cpp:52:26: error: no matching function for call to 'autoware::drivers::udp_driver::UdpDriverNode<autoware::drivers::velodyne_driver::Vlp16Translator::Packet, sensor_msgs::msg::PointCloud2_<std::allocator<void> > >::UdpDriverNode(const string&, const string&, const string&, const uint16_t&)'
m_cloud_size(cloud_size)
^
In file included from /builds/autowarefoundation/autoware.auto/AutowareAuto/src/drivers/velodyne_node/include/velodyne_node/velodyne_cloud_node.hpp:29:0,
from /builds/autowarefoundation/autoware.auto/AutowareAuto/src/drivers/velodyne_node/src/velodyne_cloud_node.cpp:23:
/opt/ros/dashing/include/udp_driver/udp_driver_node.hpp:86:3: note: candidate: autoware::drivers::udp_driver::UdpDriverNode<PacketT, OutputT>::UdpDriverNode(const string&, const string&) [with PacketT = autoware::drivers::velodyne_driver::Vlp16Translator::Packet; OutputT = sensor_msgs::msg::PointCloud2_<std::allocator<void> >; std::__cxx11::string = std::__cxx11::basic_string<char>]
UdpDriverNode(
^~~~~~~~~~~~~
/opt/ros/dashing/include/udp_driver/udp_driver_node.hpp:86:3: note: candidate expects 2 arguments, 4 provided
/opt/ros/dashing/include/udp_driver/udp_driver_node.hpp:72:3: note: candidate: autoware::drivers::udp_driver::UdpDriverNode<PacketT, OutputT>::UdpDriverNode(const string&, const string&, const autoware::drivers::udp_driver::UdpDriverNode<PacketT, OutputT>::UdpConfig&) [with PacketT = autoware::drivers::velodyne_driver::Vlp16Translator::Packet; OutputT = sensor_msgs::msg::PointCloud2_<std::allocator<void> >; std::__cxx11::string = std::__cxx11::basic_string<char>]
UdpDriverNode(
^~~~~~~~~~~~~
/opt/ros/dashing/include/udp_driver/udp_driver_node.hpp:72:3: note: candidate expects 3 arguments, 4 provided
cc1plus: all warnings being treated as errors
make[2]: *** [CMakeFiles/velodyne_cloud_node.dir/src/velodyne_cloud_node.cpp.o] Error 1
make[1]: *** [CMakeFiles/velodyne_cloud_node.dir/all] Error 2
make: *** [all] Error 2
---
Failed <<< velodyne_node [ Exited with code 2 ]
Expected behavior
Jobs should complete successfully.
Edited by Joshua Whitley