ROBOTIS-GIT / hls_lfcd_lds_driver

ROS package for HLDS HLS-LFCD LDS driver
http://turtlebot3.robotis.com
BSD 3-Clause "New" or "Revised" License
88 stars 70 forks source link

Compilation error on ROS Foxy #65

Open lucascoelhof opened 3 years ago

lucascoelhof commented 3 years ago

Hello,

When trying to compile this package on ROS Foxy, I'm getting this error:

/home/lucas/ros2_ws/src/utils/hls_lfcd_lds_driver/src/hlds_laser_publisher.cpp: In function ‘int main(int, char**)’:
/home/lucas/ros2_ws/src/utils/hls_lfcd_lds_driver/src/hlds_laser_publisher.cpp:148:46: error: no matching function for call to ‘rclcpp::Node::declare_parameter<std::string>(const char [5])’
  148 |   node->declare_parameter<std::string>("port");
      |                                              ^
In file included from /opt/ros/foxy/include/rclcpp/node.hpp:1221,
                 from /opt/ros/foxy/include/rclcpp/executors/single_threaded_executor.hpp:28,
                 from /opt/ros/foxy/include/rclcpp/executors.hpp:22,
                 from /opt/ros/foxy/include/rclcpp/rclcpp.hpp:146,
                 from /home/lucas/ros2_ws/src/utils/hls_lfcd_lds_driver/src/hlds_laser_publisher.cpp:35:
/opt/ros/foxy/include/rclcpp/node_impl.hpp:157:1: note: candidate: ‘auto rclcpp::Node::declare_parameter(const string&, const ParameterT&, const ParameterDescriptor&, bool) [with ParameterT = std::__cxx11::basic_string<char>; std::string = std::__cxx11::basic_string<char>; rcl_interfaces::msg::ParameterDescriptor = rcl_interfaces::msg::ParameterDescriptor_<std::allocator<void> >]’
  157 | Node::declare_parameter(
      | ^~~~
/opt/ros/foxy/include/rclcpp/node_impl.hpp:157:1: note:   candidate expects 4 arguments, 1 provided

From the rclcpp API, we can see that the declare_parameter method that uses a template requires a default value. Do you also get this problem on your side? Please let me know, I can also work on a fix and open a pull request.

Best regards,

ROBOTIS-Will commented 3 years ago

Hi @lucascoelhof The current ros2 or ros2-devel branch is reflecting the latest changes of upcoming ROS2 version (Galactic in this case). Since Galactic uses static param types as described here, Foxy will fail to build with the latest code. Please use foxy-devel branch when compiling on Foxy. Thanks!

Zaryob commented 2 years ago

I checked out to foxy-devel, and new errors came up

--- stderr: hls_lfcd_lds_driver                                                
/home/ubuntu/turtlebot3_ws/src/utils/hls_lfcd_lds_driver/src/hlds_laser_publisher.cpp: In function \u2018int main(int, char**)\u2019:
/home/ubuntu/turtlebot3_ws/src/utils/hls_lfcd_lds_driver/src/hlds_laser_publisher.cpp:148:46: error: no matching function for call to \u2018rclcpp::Node::declare_parameter<std::string>(const char [5])\u2019
  148 |   node->declare_parameter<std::string>("port");
      |                                              ^
In file included from /opt/ros/foxy/include/rclcpp/node.hpp:1224,
                 from /opt/ros/foxy/include/rclcpp/executors/single_threaded_executor.hpp:28,
                 from /opt/ros/foxy/include/rclcpp/executors.hpp:22,
                 from /opt/ros/foxy/include/rclcpp/rclcpp.hpp:146,
                 from /home/ubuntu/turtlebot3_ws/src/utils/hls_lfcd_lds_driver/src/hlds_laser_publisher.cpp:35:
/opt/ros/foxy/include/rclcpp/node_impl.hpp:157:1: note: candidate: \u2018auto rclcpp::Node::declare_parameter(const string&, const ParameterT&, const ParameterDescriptor&, bool) [with ParameterT = std::__cxx11::basic_string<char>; std::string = std::__cxx11::basic_string<char>; rcl_interfaces::msg::ParameterDescriptor = rcl_interfaces::msg::ParameterDescriptor_<std::allocator<void> >]\u2019
  157 | Node::declare_parameter(
      | ^~~~
/opt/ros/foxy/include/rclcpp/node_impl.hpp:157:1: note:   candidate expects 4 arguments, 1 provided
/home/ubuntu/turtlebot3_ws/src/utils/hls_lfcd_lds_driver/src/hlds_laser_publisher.cpp:149:50: error: no matching function for call to \u2018rclcpp::Node::declare_parameter<std::string>(const char [9])\u2019
  149 |   node->declare_parameter<std::string>("frame_id");
      |                                                  ^
In file included from /opt/ros/foxy/include/rclcpp/node.hpp:1224,
                 from /opt/ros/foxy/include/rclcpp/executors/single_threaded_executor.hpp:28,
                 from /opt/ros/foxy/include/rclcpp/executors.hpp:22,
                 from /opt/ros/foxy/include/rclcpp/rclcpp.hpp:146,
                 from /home/ubuntu/turtlebot3_ws/src/utils/hls_lfcd_lds_driver/src/hlds_laser_publisher.cpp:35:
/opt/ros/foxy/include/rclcpp/node_impl.hpp:157:1: note: candidate: \u2018auto rclcpp::Node::declare_parameter(const string&, const ParameterT&, const ParameterDescriptor&, bool) [with ParameterT = std::__cxx11::basic_string<char>; std::string = std::__cxx11::basic_string<char>; rcl_interfaces::msg::ParameterDescriptor = rcl_interfaces::msg::ParameterDescriptor_<std::allocator<void> >]\u2019
  157 | Node::declare_parameter(
      | ^~~~
/opt/ros/foxy/include/rclcpp/node_impl.hpp:157:1: note:   candidate expects 4 arguments, 1 provided
make[2]: *** [CMakeFiles/hlds_laser_publisher.dir/build.make:63: CMakeFiles/hlds_laser_publisher.dir/src/hlds_laser_publisher.cpp.o] Error 1
make[1]: *** [CMakeFiles/Makefile2:78: CMakeFiles/hlds_laser_publisher.dir/all] Error 2
make: *** [Makefile:141: all] Error 2
---
Failed   <<< hls_lfcd_lds_driver [10.8s, exited with code 2]
Aborted  <<< turtlebot3_fake_node [11.8s]          
Aborted  <<< turtlebot3_node [15.8s]                                   

Summary: 10 packages finished [18.5s]
  1 package failed: hls_lfcd_lds_driver
  2 packages aborted: turtlebot3_fake_node turtlebot3_node
  3 packages had stderr output: hls_lfcd_lds_driver turtlebot3_fake_node turtlebot3_node
  3 packages not processed
ROBOTIS-Will commented 2 years ago

Hi @Zaryob

It looks like you have mistakenly checkout out other branches than foxy-devel The relevant code section of the hlds_laser_publisher.cpp for ROS2 Foxy looks like below.

node->declare_parameter("port");
node->declare_parameter("frame_id");
guchangjun commented 1 year ago

I solve the problem by changing the function as: speed_to_erpmgain = declare_parameter("speed_to_erpm_gain",speed_to_erpmgain);