Open minghaohsu410168 opened 2 years ago
ros1_bridge
already has builtin conversions for ROS 2 builtin_interfaces/Time
, which converts to and from a std_msgs/Time
in ROS 1. So this should just work out-of-the-box. Can you give more details on what problem you are having?
I'm having this exact issue, so I'll outline my own problems.
I have a largish ROS 2 project with many message types within it, all using builtin_interfaces
. I need to bridge these messages over to ROS 1. The fastest way for me to do this was to create a ROS 1 workspace where I copied all of the ROS 2 message packages over to the ROS 1 workspace, then convert the CMakeLists.txt
and package.xml
to their ROS 1 equivalents. However, since ROS 1 doesn't have the builtin_interfaces
package, I had two choices:
Duration
and Time
types map to in ROS 1 (maybe share/std_msgs/msg/(Duration.msg|Time.msg)
?), and replace all uses of the types in my ROS 1 workspace with those typesbuiltin_interfaces
package into my ROS 1 workspace, and rebuild everything there.The second choice allowed me to build all of my messages in both the ROS 1 and ROS 2 workspaces, but when I build the bridge I get linking errors. I tried to create a custom mapping using a YAML file, but I don't know how to correctly do that. If you can give us a step-by-step guide on what we need to do, it would be much appreciated.
So, an update. After looking into the source code for the bridge, I decided to try removing my copy of builtin_interfaces
, and replace all ROS 1 workspace uses of builtin_interfaces/Duration
with std_msgs/Duration
, and likewise for Time
. Unfortunately, that didn't work. Here are the errors I'm getting:
--- stderr: ros1_bridge
/usr/bin/ld: libros1_bridge.so: undefined reference to `void ros1_bridge::convert_2_to_1<std_msgs::Time_<std::allocator<void> >, builtin_interfaces::msg::Time_<std::allocator<void> > >(builtin_interfaces::msg::Time_<std::allocator<void> > const&, std_msgs::Time_<std::allocator<void> >&)'
/usr/bin/ld: libros1_bridge.so: undefined reference to `void ros1_bridge::convert_1_to_2<std_msgs::Time_<std::allocator<void> >, builtin_interfaces::msg::Time_<std::allocator<void> > >(std_msgs::Time_<std::allocator<void> > const&, builtin_interfaces::msg::Time_<std::allocator<void> >&)'
/usr/bin/ld: libros1_bridge.so: undefined reference to `ros1_bridge::Factory<arl_unity_ros::JointDescription_<std::allocator<void> >, arl_unity_ros::msg::JointDescription_<std::allocator<void> > >::convert_1_to_2(arl_unity_ros::JointDescription_<std::allocator<void> > const&, arl_unity_ros::msg::JointDescription_<std::allocator<void> >&)'
/usr/bin/ld: libros1_bridge.so: undefined reference to `void ros1_bridge::convert_1_to_2<std_msgs::Duration_<std::allocator<void> >, builtin_interfaces::msg::Duration_<std::allocator<void> > >(std_msgs::Duration_<std::allocator<void> > const&, builtin_interfaces::msg::Duration_<std::allocator<void> >&)'
/usr/bin/ld: libros1_bridge.so: undefined reference to `ros1_bridge::Factory<arl_unity_ros::JointDescription_<std::allocator<void> >, arl_unity_ros::msg::JointDescription_<std::allocator<void> > >::convert_2_to_1(arl_unity_ros::msg::JointDescription_<std::allocator<void> > const&, arl_unity_ros::JointDescription_<std::allocator<void> >&)'
/usr/bin/ld: libros1_bridge.so: undefined reference to `void ros1_bridge::convert_2_to_1<std_msgs::Duration_<std::allocator<void> >, builtin_interfaces::msg::Duration_<std::allocator<void> > >(builtin_interfaces::msg::Duration_<std::allocator<void> > const&, std_msgs::Duration_<std::allocator<void> >&)'
collect2: error: ld returned 1 exit status
make[2]: *** [CMakeFiles/parameter_bridge.dir/build.make:597: parameter_bridge] Error 1
make[1]: *** [CMakeFiles/Makefile2:317: CMakeFiles/parameter_bridge.dir/all] Error 2
make[1]: *** Waiting for unfinished jobs....
/usr/bin/ld: libros1_bridge.so: undefined reference to `void ros1_bridge::convert_2_to_1<std_msgs::Time_<std::allocator<void> >, builtin_interfaces::msg::Time_<std::allocator<void> > >(builtin_interfaces::msg::Time_<std::allocator<void> > const&, std_msgs::Time_<std::allocator<void> >&)'
/usr/bin/ld: libros1_bridge.so: undefined reference to `void ros1_bridge::convert_1_to_2<std_msgs::Time_<std::allocator<void> >, builtin_interfaces::msg::Time_<std::allocator<void> > >(std_msgs::Time_<std::allocator<void> > const&, builtin_interfaces::msg::Time_<std::allocator<void> >&)'
/usr/bin/ld: libros1_bridge.so: undefined reference to `ros1_bridge::Factory<arl_unity_ros::JointDescription_<std::allocator<void> >, arl_unity_ros::msg::JointDescription_<std::allocator<void> > >::convert_1_to_2(arl_unity_ros::JointDescription_<std::allocator<void> > const&, arl_unity_ros::msg::JointDescription_<std::allocator<void> >&)'
/usr/bin/ld: libros1_bridge.so: undefined reference to `void ros1_bridge::convert_1_to_2<std_msgs::Duration_<std::allocator<void> >, builtin_interfaces::msg::Duration_<std::allocator<void> > >(std_msgs::Duration_<std::allocator<void> > const&, builtin_interfaces::msg::Duration_<std::allocator<void> >&)'
/usr/bin/ld: libros1_bridge.so: undefined reference to `ros1_bridge::Factory<arl_unity_ros::JointDescription_<std::allocator<void> >, arl_unity_ros::msg::JointDescription_<std::allocator<void> > >::convert_2_to_1(arl_unity_ros::msg::JointDescription_<std::allocator<void> > const&, arl_unity_ros::JointDescription_<std::allocator<void> >&)'
/usr/bin/ld: libros1_bridge.so: undefined reference to `void ros1_bridge::convert_2_to_1<std_msgs::Duration_<std::allocator<void> >, builtin_interfaces::msg::Duration_<std::allocator<void> > >(builtin_interfaces::msg::Duration_<std::allocator<void> > const&, std_msgs::Duration_<std::allocator<void> >&)'
collect2: error: ld returned 1 exit status
make[2]: *** [CMakeFiles/static_bridge.dir/build.make:597: static_bridge] Error 1
make[1]: *** [CMakeFiles/Makefile2:182: CMakeFiles/static_bridge.dir/all] Error 2
/usr/bin/ld: libros1_bridge.so: undefined reference to `void ros1_bridge::convert_2_to_1<std_msgs::Time_<std::allocator<void> >, builtin_interfaces::msg::Time_<std::allocator<void> > >(builtin_interfaces::msg::Time_<std::allocator<void> > const&, std_msgs::Time_<std::allocator<void> >&)'
/usr/bin/ld: libros1_bridge.so: undefined reference to `void ros1_bridge::convert_1_to_2<std_msgs::Time_<std::allocator<void> >, builtin_interfaces::msg::Time_<std::allocator<void> > >(std_msgs::Time_<std::allocator<void> > const&, builtin_interfaces::msg::Time_<std::allocator<void> >&)'
/usr/bin/ld: libros1_bridge.so: undefined reference to `ros1_bridge::Factory<arl_unity_ros::JointDescription_<std::allocator<void> >, arl_unity_ros::msg::JointDescription_<std::allocator<void> > >::convert_1_to_2(arl_unity_ros::JointDescription_<std::allocator<void> > const&, arl_unity_ros::msg::JointDescription_<std::allocator<void> >&)'
/usr/bin/ld: libros1_bridge.so: undefined reference to `void ros1_bridge::convert_1_to_2<std_msgs::Duration_<std::allocator<void> >, builtin_interfaces::msg::Duration_<std::allocator<void> > >(std_msgs::Duration_<std::allocator<void> > const&, builtin_interfaces::msg::Duration_<std::allocator<void> >&)'
/usr/bin/ld: libros1_bridge.so: undefined reference to `ros1_bridge::Factory<arl_unity_ros::JointDescription_<std::allocator<void> >, arl_unity_ros::msg::JointDescription_<std::allocator<void> > >::convert_2_to_1(arl_unity_ros::msg::JointDescription_<std::allocator<void> > const&, arl_unity_ros::JointDescription_<std::allocator<void> >&)'
/usr/bin/ld: libros1_bridge.so: undefined reference to `void ros1_bridge::convert_2_to_1<std_msgs::Duration_<std::allocator<void> >, builtin_interfaces::msg::Duration_<std::allocator<void> > >(builtin_interfaces::msg::Duration_<std::allocator<void> > const&, std_msgs::Duration_<std::allocator<void> >&)'
collect2: error: ld returned 1 exit status
make[2]: *** [CMakeFiles/dynamic_bridge.dir/build.make:597: dynamic_bridge] Error 1
make[1]: *** [CMakeFiles/Makefile2:398: CMakeFiles/dynamic_bridge.dir/all] Error 2
make: *** [Makefile:141: all] Error 2
---
Failed <<< ros1_bridge [38min 12s, exited with code 2]
Any suggestions would be much appreciated.
@minghaohsu410168 it appears that the ROS 1 equivalent of builtin_interfaces/Time
is just time
, and builtin_interfaces/Duration
is just duration
. I just got it working in my project and haven't had a chance to properly test it, so it might not work for you.
Thanks @ckaran, with your comment I managed to get it working as well.
In case you want don't want to have separate ros1 and ros2 message packages, I came up with a solution that allows building the same package with colcon and catkin.
I use cmake to define the correct duration type in the configure phase.
If there's a simpler solution, let me know but the following works just fine:
Hello, I have a custom msg in ROS2 needs to be bridge to ROS1. The msg file contains builtin_interfaces/Time but in ROS1 it does not have same message type.
How should i do? Write own map yaml? Thank you for your help!