ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question

Revision history [back]

Here's an example with the Bash multiline syntax:

rostopic pub /test geometry_msgs/PoseArray "header:
  seq: 0
  stamp:
    secs: 0
    nsecs: 0
  frame_id: ''
poses:
- position:
    x: 1.0
    y: 2.0
    z: 3.0
  orientation:
    x: 0.0
    y: 0.0
    z: 0.0
    w: 0.0
- position:
    x: 4.0
    y: 5.0
    z: 6.0
  orientation:
    x: 0.0
    y: 0.0
    z: 0.0
    w: 0.0"

Here's an example using the YAML command line dictionary syntax:

rostopic pub /test geometry_msgs/PoseArray "{header: auto, poses: [{position: [1,2,3]}, {position: [4,5,6]}]}"

Here's an example with the Bash multiline syntax:

rostopic pub /test geometry_msgs/PoseArray "header:
  seq: 0
  stamp:
    secs: 0
    nsecs: 0
  frame_id: ''
poses:
- position:
    x: 1.0
    y: 2.0
    z: 3.0
  orientation:
    x: 0.0
    y: 0.0
    z: 0.0
    w: 0.0
- position:
    x: 4.0
    y: 5.0
    z: 6.0
  orientation:
    x: 0.0
    y: 0.0
    z: 0.0
    w: 0.0"

Here's an example using the YAML command line dictionary syntax:

rostopic pub /test geometry_msgs/PoseArray "{header: auto, poses: [{position: [1,2,3]}, {position: [4,5,6]}]}"

Personally when the messages get this complicated, I generally just write a short Python script to publish the desired message at whatever rate I want to avoid having to mess with this complicated syntax at the command line.

Here's an example with the Bash multiline syntax:

rostopic pub /test geometry_msgs/PoseArray "header:
  seq: 0
  stamp:
    secs: 0
    nsecs: 0
  frame_id: ''
poses:
- position:
    x: 1.0
    y: 2.0
    z: 3.0
  orientation:
    x: 0.0
    y: 0.0
    z: 0.0
    w: 0.0
- position:
    x: 4.0
    y: 5.0
    z: 6.0
  orientation:
    x: 0.0
    y: 0.0
    z: 0.0
    w: 0.0"

Here's an example using the YAML command line dictionary syntax:

rostopic pub /test geometry_msgs/PoseArray "{header: auto, poses: [{position: [1,2,3]}, {position: [4,5,6]}]}"
[4,5,6]}]}"\

You can also use the -f option to read the message contents from a YAML file. For example, imagine tmp.yaml had the following contents:

poses:
- position:
    x: 1.0
    y: 2.0
    z: 3.0
  orientation:
    x: 0.0
    y: 0.0
    z: 0.0
    w: 0.0
- position:
    x: 4.0
    y: 5.0
    z: 6.0
  orientation:
    x: 0.0
    y: 0.0
    z: 0.0
    w: 0.0

This could be published using

rostopic pub /test geometry_msgs/PoseArray -f tmp.yaml

Note that when reading from a file if you would like to publish the message continuously at a set rate, you need to have multiple messages in the file separated by --- lines.

Personally when the messages get this complicated, I generally just write a short Python script to publish the desired message at whatever rate I want to avoid having to mess with this complicated syntax at the command line.