Gazebo | Ignition | Community
Ask Your Question
0

How to write ros_ign_bridge in launch file?

asked 2021-02-13 23:35:14 -0500

this post is marked as community wiki

This post is a wiki. Anyone with karma >75 is welcome to improve it.

I use ros2 and ignition to simulate the dynamics of bipedal robot. Thus I need to run bunch of ros_ign_bridge nodes. it is really cumbersome to run those nodes from the terminal. I want to make the launch file to run those nodes. However, I do not know what /TOPIC@ROS_MSG@IGN_MSG is. Probably it is not a parameter neither argument of the node.

Please let me know how to write launch file for the ros_ign_bridge.

ROS2:foxy
ignition: Citadel
OS: Ubuntu 20.04.2 LTS Focal Fossa

Thanks

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2021-02-15 02:57:20 -0500

ahcorde gravatar image

Hi,

To give you an example: /chatter@std_msgs/String@ignition.msgs.StringMsg

  • chatter is the ignition topic name. This topic will be created in the ROS 2 network with the same name
  • std_msgs/String ROS type msgs
  • ignition.msgs.StringMsg: Ignition type msgs

If you want to create a launch file, you have a look to this launch file. The key part:

# Bridge
bridge = Node(
    package='ros_ign_bridge',
    executable='parameter_bridge',
    arguments=['/model/vehicle_blue/cmd_vel@geometry_msgs/msg/Twist@ignition.msgs.Twist',
               '/model/vehicle_blue/battery/linear_battery/state@sensor_msgs/msg/BatteryState@ignition.msgs.BatteryState'],
    output='screen'
)

Hope this help

edit flag offensive delete link more

Comments

If anyone is looking for examples with ros1 xml syntax, see https://github.com/ignitionrobotics/r...

nealtanner gravatar imagenealtanner ( 2021-10-21 11:20:46 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2021-02-13 23:35:14 -0500

Seen: 1,509 times

Last updated: Feb 15 '21