ROSTopic.publish#
- ROSTopic.publish(msg: dict | Image | PointCloud, timestamp_ns: int | None = None) None[source]#
Publish a message on the configured ROS topic.
- Parameters:
msg (dict,
Image, orPointCloud) – ROS payload as a message dictionary,Image, orPointCloudtimestamp_ns (int or None) – optional timestamp in nanoseconds since Unix epoch; used for generated ROS headers. If None, message/object timestamp is used when present, otherwise current wall-clock time is used.
Dictionary payloads are forwarded directly and must match the configured ROS message type.
If
msgis anImage, it is serialised according to the configured topic message type:sensor_msgs/Imageorsensor_msgs/msg/Imagefor raw image datasensor_msgs/CompressedImageorsensor_msgs/msg/CompressedImagefor JPEG-compressed image data
Colour plane order is encoded in the ROS
encodingfield for raw images, and in the compressed-messageformatstring for compressed images.If
msgis aPointCloud, it is published assensor_msgs/PointCloud2withx,y,zfields and anrgbfield when colour data is present.Example publishing a
std_msgs/Stringmessage:pub = ROSTopic("/cmd_text", message="std_msgs/String", subscribe=False) pub.publish({"data": "hello"}) pub.release()
Example publishing a
geometry_msgs/Twistmessage:pub = ROSTopic("/cmd_vel", message="geometry_msgs/Twist", subscribe=False) pub.publish( { "linear": {"x": 0.2, "y": 0.0, "z": 0.0}, "angular": {"x": 0.0, "y": 0.0, "z": 0.5}, } ) pub.release()
Example publishing an
Imagewith an explicit timestamp:img = Image(np.zeros((240, 320, 3), dtype=np.uint8), colororder="RGB") pub = ROSTopic("/camera/image_raw", message="sensor_msgs/Image", subscribe=False) pub.publish(img, timestamp_ns=1_700_000_000_123_456_789) pub.release()
Example publishing a
PointCloudwith an explicit timestamp:points = np.array([[0.0, 1.0], [0.0, 0.2], [1.0, 1.2]], dtype=np.float32) pc = PointCloud(points) pub = ROSTopic("/cloud", message="sensor_msgs/PointCloud2", subscribe=False) pub.publish(pc, timestamp_ns=1_700_000_000_223_456_789) pub.release()
The topic is advertised lazily on first publish.