|
|
(18 intermediate revisions by 3 users not shown) |
Line 6: |
Line 6: |
| | | |
| = Prerequisite = | | = Prerequisite = |
− | Please make sure that ROS1 and ROS2( [https://www.advantech.com/en/form/11905901-d135-4dc1-a72d-0450b233d62e?callback=2af806b3-06a3-4f48-9edb-555899ff4da6 ROS2 Suite]) have been installed in your environment, for example, ROS1 (Noetic) and ROS2 (Foxy) in Ubuntu 20.04. | + | Please make sure that ROS1 and ROS2( [https://www.advantech.com/en/form/11905901-d135-4dc1-a72d-0450b233d62e?callback=2af806b3-06a3-4f48-9edb-555899ff4da6 Advantech Robotic Suite]) have been installed in your environment, for example, ROS1 (Noetic) and ROS2 (Foxy) in Ubuntu 20.04. |
− | = Install ros1-bridge = | + | = Installation= |
| <syntaxhighlight lang="bash">$ sudo apt-get install ros-foxy-ros1-bridge</syntaxhighlight> | | <syntaxhighlight lang="bash">$ sudo apt-get install ros-foxy-ros1-bridge</syntaxhighlight> |
| | | |
| = How To = | | = How To = |
− | === Supported ROS 2 <=> ROS 1 message and service type === | + | |
− | First check if the topic type is supported, you can list all ros1_bridge supported type by using following command.
| + | === Step1: Confrim Converting Message Format === |
| + | |
| + | You can list all ros1_bridge supported data type by following command to confirm that the data format you want to convert to is supported. |
| + | |
| <syntaxhighlight lang="bash">$ ros2 run ros1_bridge dynamic_bridge --print-pairs</syntaxhighlight> | | <syntaxhighlight lang="bash">$ ros2 run ros1_bridge dynamic_bridge --print-pairs</syntaxhighlight> |
− | * Supported ROS 2 <=> ROS 1 message type conversion:
| + | [[File:ROS2 Suite ros1-bridge-format.png|ros1-bridge-format]] |
− | <syntaxhighlight lang="bash">
| |
− | - 'actionlib_msgs/msg/GoalID' (ROS 2) <=> 'actionlib_msgs/GoalID' (ROS 1)
| |
− | - 'actionlib_msgs/msg/GoalStatus' (ROS 2) <=> 'actionlib_msgs/GoalStatus' (ROS 1)
| |
− | - 'actionlib_msgs/msg/GoalStatusArray' (ROS 2) <=> 'actionlib_msgs/GoalStatusArray' (ROS 1)
| |
− | - 'builtin_interfaces/msg/Duration' (ROS 2) <=> 'std_msgs/Duration' (ROS 1)
| |
− | - 'builtin_interfaces/msg/Time' (ROS 2) <=> 'std_msgs/Time' (ROS 1)
| |
− | - 'diagnostic_msgs/msg/DiagnosticArray' (ROS 2) <=> 'diagnostic_msgs/DiagnosticArray' (ROS 1)
| |
− | - 'diagnostic_msgs/msg/DiagnosticStatus' (ROS 2) <=> 'diagnostic_msgs/DiagnosticStatus' (ROS 1)
| |
− | - 'diagnostic_msgs/msg/KeyValue' (ROS 2) <=> 'diagnostic_msgs/KeyValue' (ROS 1)
| |
− | - 'gazebo_msgs/msg/ContactState' (ROS 2) <=> 'gazebo_msgs/ContactState' (ROS 1)
| |
− | - 'gazebo_msgs/msg/ContactsState' (ROS 2) <=> 'gazebo_msgs/ContactsState' (ROS 1)
| |
− | - 'gazebo_msgs/msg/LinkState' (ROS 2) <=> 'gazebo_msgs/LinkState' (ROS 1)
| |
− | - 'gazebo_msgs/msg/LinkStates' (ROS 2) <=> 'gazebo_msgs/LinkStates' (ROS 1)
| |
− | - 'gazebo_msgs/msg/ModelState' (ROS 2) <=> 'gazebo_msgs/ModelState' (ROS 1)
| |
− | - 'gazebo_msgs/msg/ModelStates' (ROS 2) <=> 'gazebo_msgs/ModelStates' (ROS 1)
| |
− | - 'gazebo_msgs/msg/ODEJointProperties' (ROS 2) <=> 'gazebo_msgs/ODEJointProperties' (ROS 1)
| |
− | - 'gazebo_msgs/msg/ODEPhysics' (ROS 2) <=> 'gazebo_msgs/ODEPhysics' (ROS 1)
| |
− | - 'gazebo_msgs/msg/PerformanceMetrics' (ROS 2) <=> 'gazebo_msgs/PerformanceMetrics' (ROS 1)
| |
− | - 'gazebo_msgs/msg/SensorPerformanceMetric' (ROS 2) <=> 'gazebo_msgs/SensorPerformanceMetric' (ROS 1)
| |
− | - 'gazebo_msgs/msg/WorldState' (ROS 2) <=> 'gazebo_msgs/WorldState' (ROS 1)
| |
− | - 'geometry_msgs/msg/Accel' (ROS 2) <=> 'geometry_msgs/Accel' (ROS 1)
| |
− | - 'geometry_msgs/msg/AccelStamped' (ROS 2) <=> 'geometry_msgs/AccelStamped' (ROS 1)
| |
− | - 'geometry_msgs/msg/AccelWithCovariance' (ROS 2) <=> 'geometry_msgs/AccelWithCovariance' (ROS 1)
| |
− | - 'geometry_msgs/msg/AccelWithCovarianceStamped' (ROS 2) <=> 'geometry_msgs/AccelWithCovarianceStamped' (ROS 1)
| |
− | - 'geometry_msgs/msg/Inertia' (ROS 2) <=> 'geometry_msgs/Inertia' (ROS 1)
| |
− | - 'geometry_msgs/msg/InertiaStamped' (ROS 2) <=> 'geometry_msgs/InertiaStamped' (ROS 1)
| |
− | - 'geometry_msgs/msg/Point' (ROS 2) <=> 'geometry_msgs/Point' (ROS 1)
| |
− | - 'geometry_msgs/msg/Point32' (ROS 2) <=> 'geometry_msgs/Point32' (ROS 1)
| |
− | - 'geometry_msgs/msg/PointStamped' (ROS 2) <=> 'geometry_msgs/PointStamped' (ROS 1)
| |
− | - 'geometry_msgs/msg/Polygon' (ROS 2) <=> 'geometry_msgs/Polygon' (ROS 1)
| |
− | - 'geometry_msgs/msg/PolygonStamped' (ROS 2) <=> 'geometry_msgs/PolygonStamped' (ROS 1)
| |
− | - 'geometry_msgs/msg/Pose' (ROS 2) <=> 'geometry_msgs/Pose' (ROS 1)
| |
− | - 'geometry_msgs/msg/Pose2D' (ROS 2) <=> 'geometry_msgs/Pose2D' (ROS 1)
| |
− | - 'geometry_msgs/msg/PoseArray' (ROS 2) <=> 'geometry_msgs/PoseArray' (ROS 1)
| |
− | - 'geometry_msgs/msg/PoseStamped' (ROS 2) <=> 'geometry_msgs/PoseStamped' (ROS 1)
| |
− | - 'geometry_msgs/msg/PoseWithCovariance' (ROS 2) <=> 'geometry_msgs/PoseWithCovariance' (ROS 1)
| |
− | - 'geometry_msgs/msg/PoseWithCovarianceStamped' (ROS 2) <=> 'geometry_msgs/PoseWithCovarianceStamped' (ROS 1)
| |
− | - 'geometry_msgs/msg/Quaternion' (ROS 2) <=> 'geometry_msgs/Quaternion' (ROS 1)
| |
− | - 'geometry_msgs/msg/QuaternionStamped' (ROS 2) <=> 'geometry_msgs/QuaternionStamped' (ROS 1)
| |
− | - 'geometry_msgs/msg/Transform' (ROS 2) <=> 'geometry_msgs/Transform' (ROS 1)
| |
− | - 'geometry_msgs/msg/TransformStamped' (ROS 2) <=> 'geometry_msgs/TransformStamped' (ROS 1)
| |
− | - 'geometry_msgs/msg/Twist' (ROS 2) <=> 'geometry_msgs/Twist' (ROS 1)
| |
− | - 'geometry_msgs/msg/TwistStamped' (ROS 2) <=> 'geometry_msgs/TwistStamped' (ROS 1)
| |
− | - 'geometry_msgs/msg/TwistWithCovariance' (ROS 2) <=> 'geometry_msgs/TwistWithCovariance' (ROS 1)
| |
− | - 'geometry_msgs/msg/TwistWithCovarianceStamped' (ROS 2) <=> 'geometry_msgs/TwistWithCovarianceStamped' (ROS 1)
| |
− | - 'geometry_msgs/msg/Vector3' (ROS 2) <=> 'geometry_msgs/Vector3' (ROS 1)
| |
− | - 'geometry_msgs/msg/Vector3Stamped' (ROS 2) <=> 'geometry_msgs/Vector3Stamped' (ROS 1)
| |
− | - 'geometry_msgs/msg/Wrench' (ROS 2) <=> 'geometry_msgs/Wrench' (ROS 1)
| |
− | - 'geometry_msgs/msg/WrenchStamped' (ROS 2) <=> 'geometry_msgs/WrenchStamped' (ROS 1)
| |
− | - 'nav_msgs/msg/GridCells' (ROS 2) <=> 'nav_msgs/GridCells' (ROS 1)
| |
− | - 'nav_msgs/msg/MapMetaData' (ROS 2) <=> 'nav_msgs/MapMetaData' (ROS 1)
| |
− | - 'nav_msgs/msg/OccupancyGrid' (ROS 2) <=> 'nav_msgs/OccupancyGrid' (ROS 1)
| |
− | - 'nav_msgs/msg/Odometry' (ROS 2) <=> 'nav_msgs/Odometry' (ROS 1)
| |
− | - 'nav_msgs/msg/Path' (ROS 2) <=> 'nav_msgs/Path' (ROS 1)
| |
− | - 'rcl_interfaces/msg/Log' (ROS 2) <=> 'rosgraph_msgs/Log' (ROS 1)
| |
− | - 'rosgraph_msgs/msg/Clock' (ROS 2) <=> 'rosgraph_msgs/Clock' (ROS 1)
| |
− | - 'sensor_msgs/msg/BatteryState' (ROS 2) <=> 'sensor_msgs/BatteryState' (ROS 1)
| |
− | - 'sensor_msgs/msg/CameraInfo' (ROS 2) <=> 'sensor_msgs/CameraInfo' (ROS 1)
| |
− | - 'sensor_msgs/msg/ChannelFloat32' (ROS 2) <=> 'sensor_msgs/ChannelFloat32' (ROS 1)
| |
− | - 'sensor_msgs/msg/CompressedImage' (ROS 2) <=> 'sensor_msgs/CompressedImage' (ROS 1)
| |
− | - 'sensor_msgs/msg/FluidPressure' (ROS 2) <=> 'sensor_msgs/FluidPressure' (ROS 1)
| |
− | - 'sensor_msgs/msg/Illuminance' (ROS 2) <=> 'sensor_msgs/Illuminance' (ROS 1)
| |
− | - 'sensor_msgs/msg/Image' (ROS 2) <=> 'sensor_msgs/Image' (ROS 1)
| |
− | - 'sensor_msgs/msg/Imu' (ROS 2) <=> 'sensor_msgs/Imu' (ROS 1)
| |
− | - 'sensor_msgs/msg/JointState' (ROS 2) <=> 'sensor_msgs/JointState' (ROS 1)
| |
− | - 'sensor_msgs/msg/Joy' (ROS 2) <=> 'sensor_msgs/Joy' (ROS 1)
| |
− | - 'sensor_msgs/msg/JoyFeedback' (ROS 2) <=> 'sensor_msgs/JoyFeedback' (ROS 1)
| |
− | - 'sensor_msgs/msg/JoyFeedbackArray' (ROS 2) <=> 'sensor_msgs/JoyFeedbackArray' (ROS 1)
| |
− | - 'sensor_msgs/msg/LaserEcho' (ROS 2) <=> 'sensor_msgs/LaserEcho' (ROS 1)
| |
− | - 'sensor_msgs/msg/LaserScan' (ROS 2) <=> 'sensor_msgs/LaserScan' (ROS 1)
| |
− | - 'sensor_msgs/msg/MagneticField' (ROS 2) <=> 'sensor_msgs/MagneticField' (ROS 1)
| |
− | - 'sensor_msgs/msg/MultiDOFJointState' (ROS 2) <=> 'sensor_msgs/MultiDOFJointState' (ROS 1)
| |
− | - 'sensor_msgs/msg/MultiEchoLaserScan' (ROS 2) <=> 'sensor_msgs/MultiEchoLaserScan' (ROS 1)
| |
− | - 'sensor_msgs/msg/NavSatFix' (ROS 2) <=> 'sensor_msgs/NavSatFix' (ROS 1)
| |
− | - 'sensor_msgs/msg/NavSatStatus' (ROS 2) <=> 'sensor_msgs/NavSatStatus' (ROS 1)
| |
− | - 'sensor_msgs/msg/PointCloud' (ROS 2) <=> 'sensor_msgs/PointCloud' (ROS 1)
| |
− | - 'sensor_msgs/msg/PointCloud2' (ROS 2) <=> 'sensor_msgs/PointCloud2' (ROS 1)
| |
− | - 'sensor_msgs/msg/PointField' (ROS 2) <=> 'sensor_msgs/PointField' (ROS 1)
| |
− | - 'sensor_msgs/msg/Range' (ROS 2) <=> 'sensor_msgs/Range' (ROS 1)
| |
− | - 'sensor_msgs/msg/RegionOfInterest' (ROS 2) <=> 'sensor_msgs/RegionOfInterest' (ROS 1)
| |
− | - 'sensor_msgs/msg/RelativeHumidity' (ROS 2) <=> 'sensor_msgs/RelativeHumidity' (ROS 1)
| |
− | - 'sensor_msgs/msg/Temperature' (ROS 2) <=> 'sensor_msgs/Temperature' (ROS 1)
| |
− | - 'sensor_msgs/msg/TimeReference' (ROS 2) <=> 'sensor_msgs/TimeReference' (ROS 1)
| |
− | - 'shape_msgs/msg/Mesh' (ROS 2) <=> 'shape_msgs/Mesh' (ROS 1)
| |
− | - 'shape_msgs/msg/MeshTriangle' (ROS 2) <=> 'shape_msgs/MeshTriangle' (ROS 1)
| |
− | - 'shape_msgs/msg/Plane' (ROS 2) <=> 'shape_msgs/Plane' (ROS 1)
| |
− | - 'shape_msgs/msg/SolidPrimitive' (ROS 2) <=> 'shape_msgs/SolidPrimitive' (ROS 1)
| |
− | - 'std_msgs/msg/Bool' (ROS 2) <=> 'std_msgs/Bool' (ROS 1)
| |
− | - 'std_msgs/msg/Byte' (ROS 2) <=> 'std_msgs/Byte' (ROS 1)
| |
− | - 'std_msgs/msg/ByteMultiArray' (ROS 2) <=> 'std_msgs/ByteMultiArray' (ROS 1)
| |
− | - 'std_msgs/msg/Char' (ROS 2) <=> 'std_msgs/Char' (ROS 1)
| |
− | - 'std_msgs/msg/ColorRGBA' (ROS 2) <=> 'std_msgs/ColorRGBA' (ROS 1)
| |
− | - 'std_msgs/msg/Empty' (ROS 2) <=> 'std_msgs/Empty' (ROS 1)
| |
− | - 'std_msgs/msg/Float32' (ROS 2) <=> 'std_msgs/Float32' (ROS 1)
| |
− | - 'std_msgs/msg/Float32MultiArray' (ROS 2) <=> 'std_msgs/Float32MultiArray' (ROS 1)
| |
− | - 'std_msgs/msg/Float64' (ROS 2) <=> 'std_msgs/Float64' (ROS 1)
| |
− | - 'std_msgs/msg/Float64MultiArray' (ROS 2) <=> 'std_msgs/Float64MultiArray' (ROS 1)
| |
− | - 'std_msgs/msg/Header' (ROS 2) <=> 'std_msgs/Header' (ROS 1)
| |
− | - 'std_msgs/msg/Int16' (ROS 2) <=> 'std_msgs/Int16' (ROS 1)
| |
− | - 'std_msgs/msg/Int16MultiArray' (ROS 2) <=> 'std_msgs/Int16MultiArray' (ROS 1)
| |
− | - 'std_msgs/msg/Int32' (ROS 2) <=> 'std_msgs/Int32' (ROS 1)
| |
− | - 'std_msgs/msg/Int32MultiArray' (ROS 2) <=> 'std_msgs/Int32MultiArray' (ROS 1)
| |
− | - 'std_msgs/msg/Int64' (ROS 2) <=> 'std_msgs/Int64' (ROS 1)
| |
− | - 'std_msgs/msg/Int64MultiArray' (ROS 2) <=> 'std_msgs/Int64MultiArray' (ROS 1)
| |
− | - 'std_msgs/msg/Int8' (ROS 2) <=> 'std_msgs/Int8' (ROS 1)
| |
− | - 'std_msgs/msg/Int8MultiArray' (ROS 2) <=> 'std_msgs/Int8MultiArray' (ROS 1)
| |
− | - 'std_msgs/msg/MultiArrayDimension' (ROS 2) <=> 'std_msgs/MultiArrayDimension' (ROS 1)
| |
− | - 'std_msgs/msg/MultiArrayLayout' (ROS 2) <=> 'std_msgs/MultiArrayLayout' (ROS 1)
| |
− | - 'std_msgs/msg/String' (ROS 2) <=> 'std_msgs/String' (ROS 1)
| |
− | - 'std_msgs/msg/UInt16' (ROS 2) <=> 'std_msgs/UInt16' (ROS 1)
| |
− | - 'std_msgs/msg/UInt16MultiArray' (ROS 2) <=> 'std_msgs/UInt16MultiArray' (ROS 1)
| |
− | - 'std_msgs/msg/UInt32' (ROS 2) <=> 'std_msgs/UInt32' (ROS 1)
| |
− | - 'std_msgs/msg/UInt32MultiArray' (ROS 2) <=> 'std_msgs/UInt32MultiArray' (ROS 1)
| |
− | - 'std_msgs/msg/UInt64' (ROS 2) <=> 'std_msgs/UInt64' (ROS 1)
| |
− | - 'std_msgs/msg/UInt64MultiArray' (ROS 2) <=> 'std_msgs/UInt64MultiArray' (ROS 1)
| |
− | - 'std_msgs/msg/UInt8' (ROS 2) <=> 'std_msgs/UInt8' (ROS 1)
| |
− | - 'std_msgs/msg/UInt8MultiArray' (ROS 2) <=> 'std_msgs/UInt8MultiArray' (ROS 1)
| |
− | - 'stereo_msgs/msg/DisparityImage' (ROS 2) <=> 'stereo_msgs/DisparityImage' (ROS 1)
| |
− | - 'tf2_msgs/msg/TF2Error' (ROS 2) <=> 'tf2_msgs/TF2Error' (ROS 1)
| |
− | - 'tf2_msgs/msg/TFMessage' (ROS 2) <=> 'tf2_msgs/TFMessage' (ROS 1)
| |
− | - 'tf2_msgs/msg/TFMessage' (ROS 2) <=> 'tf/tfMessage' (ROS 1)
| |
− | - 'trajectory_msgs/msg/JointTrajectory' (ROS 2) <=> 'trajectory_msgs/JointTrajectory' (ROS 1)
| |
− | - 'trajectory_msgs/msg/JointTrajectoryPoint' (ROS 2) <=> 'trajectory_msgs/JointTrajectoryPoint' (ROS 1)
| |
− | - 'trajectory_msgs/msg/MultiDOFJointTrajectory' (ROS 2) <=> 'trajectory_msgs/MultiDOFJointTrajectory' (ROS 1)
| |
− | - 'trajectory_msgs/msg/MultiDOFJointTrajectoryPoint' (ROS 2) <=> 'trajectory_msgs/MultiDOFJointTrajectoryPoint' (ROS 1)
| |
− | - 'visualization_msgs/msg/ImageMarker' (ROS 2) <=> 'visualization_msgs/ImageMarker' (ROS 1)
| |
− | - 'visualization_msgs/msg/InteractiveMarker' (ROS 2) <=> 'visualization_msgs/InteractiveMarker' (ROS 1)
| |
− | - 'visualization_msgs/msg/InteractiveMarkerControl' (ROS 2) <=> 'visualization_msgs/InteractiveMarkerControl' (ROS 1)
| |
− | - 'visualization_msgs/msg/InteractiveMarkerFeedback' (ROS 2) <=> 'visualization_msgs/InteractiveMarkerFeedback' (ROS 1)
| |
− | - 'visualization_msgs/msg/InteractiveMarkerInit' (ROS 2) <=> 'visualization_msgs/InteractiveMarkerInit' (ROS 1)
| |
− | - 'visualization_msgs/msg/InteractiveMarkerPose' (ROS 2) <=> 'visualization_msgs/InteractiveMarkerPose' (ROS 1)
| |
− | - 'visualization_msgs/msg/InteractiveMarkerUpdate' (ROS 2) <=> 'visualization_msgs/InteractiveMarkerUpdate' (ROS 1)
| |
− | - 'visualization_msgs/msg/Marker' (ROS 2) <=> 'visualization_msgs/Marker' (ROS 1)
| |
− | - 'visualization_msgs/msg/MarkerArray' (ROS 2) <=> 'visualization_msgs/MarkerArray' (ROS 1)
| |
− | - 'visualization_msgs/msg/MenuEntry' (ROS 2) <=> 'visualization_msgs/MenuEntry' (ROS 1)
| |
− | </syntaxhighlight>
| |
− | * Supported ROS 2 <=> ROS 1 service type conversion:
| |
− | <syntaxhighlight lang="bash">
| |
− | - 'diagnostic_msgs/srv/AddDiagnostics' (ROS 2) <=> 'diagnostic_msgs/AddDiagnostics' (ROS 1)
| |
− | - 'diagnostic_msgs/srv/SelfTest' (ROS 2) <=> 'diagnostic_msgs/SelfTest' (ROS 1)
| |
− | - 'example_interfaces/srv/AddTwoInts' (ROS 2) <=> 'roscpp_tutorials/TwoInts' (ROS 1)
| |
− | - 'example_interfaces/srv/AddTwoInts' (ROS 2) <=> 'rospy_tutorials/AddTwoInts' (ROS 1)
| |
− | - 'gazebo_msgs/srv/BodyRequest' (ROS 2) <=> 'gazebo_msgs/BodyRequest' (ROS 1)
| |
− | - 'gazebo_msgs/srv/DeleteLight' (ROS 2) <=> 'gazebo_msgs/DeleteLight' (ROS 1)
| |
− | - 'gazebo_msgs/srv/DeleteModel' (ROS 2) <=> 'gazebo_msgs/DeleteModel' (ROS 1)
| |
− | - 'gazebo_msgs/srv/GetJointProperties' (ROS 2) <=> 'gazebo_msgs/GetJointProperties' (ROS 1)
| |
− | - 'gazebo_msgs/srv/GetLightProperties' (ROS 2) <=> 'gazebo_msgs/GetLightProperties' (ROS 1)
| |
− | - 'gazebo_msgs/srv/GetLinkProperties' (ROS 2) <=> 'gazebo_msgs/GetLinkProperties' (ROS 1)
| |
− | - 'gazebo_msgs/srv/GetLinkState' (ROS 2) <=> 'gazebo_msgs/GetLinkState' (ROS 1)
| |
− | - 'gazebo_msgs/srv/GetModelProperties' (ROS 2) <=> 'gazebo_msgs/GetModelProperties' (ROS 1)
| |
− | - 'gazebo_msgs/srv/GetModelState' (ROS 2) <=> 'gazebo_msgs/GetModelState' (ROS 1)
| |
− | - 'gazebo_msgs/srv/GetPhysicsProperties' (ROS 2) <=> 'gazebo_msgs/GetPhysicsProperties' (ROS 1)
| |
− | - 'gazebo_msgs/srv/GetWorldProperties' (ROS 2) <=> 'gazebo_msgs/GetWorldProperties' (ROS 1)
| |
− | - 'gazebo_msgs/srv/JointRequest' (ROS 2) <=> 'gazebo_msgs/JointRequest' (ROS 1)
| |
− | - 'gazebo_msgs/srv/SetJointProperties' (ROS 2) <=> 'gazebo_msgs/SetJointProperties' (ROS 1)
| |
− | - 'gazebo_msgs/srv/SetJointTrajectory' (ROS 2) <=> 'gazebo_msgs/SetJointTrajectory' (ROS 1)
| |
− | - 'gazebo_msgs/srv/SetLinkProperties' (ROS 2) <=> 'gazebo_msgs/SetLinkProperties' (ROS 1)
| |
− | - 'gazebo_msgs/srv/SetLinkState' (ROS 2) <=> 'gazebo_msgs/SetLinkState' (ROS 1)
| |
− | - 'gazebo_msgs/srv/SetModelConfiguration' (ROS 2) <=> 'gazebo_msgs/SetModelConfiguration' (ROS 1)
| |
− | - 'gazebo_msgs/srv/SetModelState' (ROS 2) <=> 'gazebo_msgs/SetModelState' (ROS 1)
| |
− | - 'gazebo_msgs/srv/SetPhysicsProperties' (ROS 2) <=> 'gazebo_msgs/SetPhysicsProperties' (ROS 1)
| |
− | - 'gazebo_msgs/srv/SpawnModel' (ROS 2) <=> 'gazebo_msgs/SpawnModel' (ROS 1)
| |
− | - 'nav_msgs/srv/GetMap' (ROS 2) <=> 'nav_msgs/GetMap' (ROS 1)
| |
− | - 'nav_msgs/srv/GetPlan' (ROS 2) <=> 'nav_msgs/GetPlan' (ROS 1)
| |
− | - 'nav_msgs/srv/SetMap' (ROS 2) <=> 'nav_msgs/SetMap' (ROS 1)
| |
− | - 'sensor_msgs/srv/SetCameraInfo' (ROS 2) <=> 'sensor_msgs/SetCameraInfo' (ROS 1)
| |
− | - 'std_srvs/srv/Empty' (ROS 2) <=> 'std_srvs/Empty' (ROS 1)
| |
− | - 'std_srvs/srv/SetBool' (ROS 2) <=> 'std_srvs/SetBool' (ROS 1)
| |
− | - 'std_srvs/srv/Trigger' (ROS 2) <=> 'std_srvs/Trigger' (ROS 1)
| |
− | - 'tf2_msgs/srv/FrameGraph' (ROS 2) <=> 'tf2_msgs/FrameGraph' (ROS 1)
| |
− | </syntaxhighlight>
| |
| | | |
− | === Dynamic_bridge === | + | === Step 2: Run the Dynamic_bridge === |
− | The <code>dynamic_bridge</code> will watch the available ROS 1 and ROS 2 topics, once a matching topic has been detected it starts to bridge the messages on this topic. | + | |
− | *Bidirectional bridge between ROS1 and ROS2 | + | The <code>dynamic_bridge</code> will watch the available ROS 1 and ROS 2 topics, once a matching topic has been detected it starts to bridge the messages on this topic. |
| + | |
| + | *<span style="font-size:larger;">'''Bidirectional'''</span> |
| <syntaxhighlight lang="bash">$ ros2 run ros1_bridge dynamic_bridge --bridge-all-topics</syntaxhighlight> | | <syntaxhighlight lang="bash">$ ros2 run ros1_bridge dynamic_bridge --bridge-all-topics</syntaxhighlight> |
− | *ROS1 to ROS2 bridge | + | |
| + | *'''<span style="font-size:larger;">Unidirectional:</span>''' '''<span style="font-size:large;">ROS1 to ROS2 </span>''' |
| <syntaxhighlight lang="bash">$ ros2 run ros1_bridge dynamic_bridge --bridge-all-1to2-topics</syntaxhighlight> | | <syntaxhighlight lang="bash">$ ros2 run ros1_bridge dynamic_bridge --bridge-all-1to2-topics</syntaxhighlight> |
− | *ROS2 to ROS1 bridge | + | |
| + | *'''<span style="font-size:larger;">Unidirectional: ROS2 to ROS1 </span>''' |
| <syntaxhighlight lang="bash">$ ros2 run ros1_bridge dynamic_bridge --bridge-all-2to1-topics</syntaxhighlight> | | <syntaxhighlight lang="bash">$ ros2 run ros1_bridge dynamic_bridge --bridge-all-2to1-topics</syntaxhighlight> |
| | | |
− | === Parameter_bridge === | + | === Advanced === |
− | The <code>parameter_bridge</code> can bridge only selected topics and services by using a YAML file. <br/> | + | ==== Parameter_bridge ==== |
− | For example, only bridge a topic called /chatter | + | The <code>parameter_bridge</code> can bridge only selected topics and services by using a YAML file.<br/> For example, only bridge a topic called /chatter [[File:ROS2 Suite ros1-bridge.png|center|900x600px|ROS2 Suite ros1-bridge]] How to use <code>parameter_bridge</code> can refer to [https://github.com/ros2/ros1_bridge#example-4-bridge-only-selected-topics-and-services parameter_bridge] |
− | [[File:ROS2 Suite ros1-bridge.png|center|900x600px|ROS2 Suite ros1-bridge]] | + | |
− | How to use <code>parameter_bridge</code> can refer to [https://github.com/ros2/ros1_bridge#example-4-bridge-only-selected-topics-and-services parameter_bridge] | + | ==== Quality of Service ==== |
| | | |
− | === Parametrizing Quality of Service ===
| |
| It also can define different Quality of Service(QoS) settings per topic, for instructions on how to do this, please refer to [https://github.com/ros2/ros1_bridge#parametrizing-quality-of-service parametrizing-quality-of-service] | | It also can define different Quality of Service(QoS) settings per topic, for instructions on how to do this, please refer to [https://github.com/ros2/ros1_bridge#parametrizing-quality-of-service parametrizing-quality-of-service] |
| | | |
| = Notice = | | = Notice = |
− | However, using the ROS 1 Bridge can also bring some issues. First, since the message formats of ROS 1 and ROS 2 are different, the ROS 1 Bridge needs to perform message format conversion, which can result in latency and CPU usage. Second, message drops may occur due to the message transmission required by the ROS 1 Bridge.<br/>
| |
| | | |
− | Therefore, when using the ROS 1 Bridge to port ROS 1 to ROS 2, these issues should be taken into account, and optimization and debugging should be carried out according to specific situations to ensure system stability and performance.
| + | <span style="color:#FF0000;"><big> The ROS1 bridge provides a convenient way to achieve data communication between ROS1 and ROS2. However, it is NOT Recommended to use the bridge in high-frequency or large data scenarios. </big></span><span style="color:#FF0000;"><big>In such cases, it is recommended directly porting your ROS1 node to ROS2 node.</big></span> |
| + | |
| + | You must consider these issues when exchanging ROS1 data to ROS2 by the ros1 bridge. |
| + | |
| + | *'''Latency :''' The ROS 1 Bridge will perform message format conversion, which can result in latency |
| + | *'''CPU Usage:''' The ROS 1 Bridge will perform message format conversion, which can result in CPU usage. |
| + | *'''Data Lost:''' It may drops message due to the message transmission required by the ROS 1 Bridge. |
| + | |
| + | Here are some experiences for your reference. |
| | | |
− | * TF and pointcloud delay | + | *[https://github.com/ros2/ros1_bridge/issues/369 TF and pointcloud delay] |
− | :Some users have also mentioned in Github Issues that there are latency issues when using TF or large datasets (such as point clouds).
| |
− | :[https://github.com/ros2/ros1_bridge/issues/369 TF and pointcloud delay]
| |
| | | |
− | * Latency and cpu usage
| + | :Some users have also mentioned in Github Issues that there are latency issues when using TF or large datasets (such as pointcloud and image). |
− | :During the ROSCon'22 speech, it was mentioned that using ros1-bridge can cause issues such as high latency and CPU usage. The following chart compares the differences between using and not using ros1-bridge, which clearly shows the disparity. If interested, please visit the website to watch the speech. [https://vimeo.com/767140113 ROSCon'22-Migrating from ROS1 to ROS2(4:28)] | |
− | :[[File:ROS2 Suite ros1-bridge-latency-cpu.png|ros1-bridge-latency-cpu]]
| |
| | | |
− | <span style="color:#FF0000;">
| + | *Latency and CPU usage: [https://vimeo.com/767140113 ROSCon'22 - Migrating from ROS1 to ROS2(4:28)] |
− | <big>In conclusion, the ROS1 bridge provides a convenient way to achieve data communication between ROS1 and ROS2. However, it is not recommended to use the bridge in high-frequency or large dataset scenarios. In such cases, it is recommended to directly port the ROS1 code to the ROS2 code.</big>
| |
− | </span>
| |
| | | |
− | [[Category:Editor]] | + | :During the ROSCon'22 speech, it was mentioned that using ros1-bridge can cause issues such as high latency and CPU usage. The following chart compares the differences between using and not using ros1-bridge, which clearly shows the difference. For detail please visit the website to watch the speech. |
| + | :[[File:ROS2 Suite ros1-bridge-latency-cpu.png|ros1-bridge-latency-cpu]] |
To port ROS 1 to ROS 2, the ROS 1 Bridge tool can be used. This tool enables message communication between ROS 1 and ROS 2, allowing nodes from ROS 1 to communicate with nodes from ROS 2 and enabling the use of ROS 1 nodes in ROS 2.
Github: ros1-bridge
You can list all ros1_bridge supported data type by following command to confirm that the data format you want to convert to is supported.
can bridge only selected topics and services by using a YAML file.
It also can define different Quality of Service(QoS) settings per topic, for instructions on how to do this, please refer to parametrizing-quality-of-service
You must consider these issues when exchanging ROS1 data to ROS2 by the ros1 bridge.
Here are some experiences for your reference.