TEMAS ToF Camera Node

The TEMAS Time-of-Flight camera node streams distance frames as ROS2 sensor_msgs/Image, and publishes camera connection status and info messages. See the Python API reference (autodoc below) for parameters, topics, and usage.

class TemasCameraTofNode(*args, **kwargs)[source]

Bases: Node

ROS2 node for streaming a TEMAS Time-of-Flight (ToF) camera.

This node connects to a TEMAS ToF camera, continuously publishes frames as ROS2 images, and provides camera status and info topics.

Parameters:
  • ip_address (str): IP address of the TEMAS device (default: ‘192.168.4.4’)

    Example:

    ros2 run temas_ros2 camera_tof --ros-args -p ip_address:=192.168.4.4

Published Topics:
  • temas/camera_tof/image_raw (sensor_msgs.msg.Image) – live camera frames

    Example:

    ros2 topic echo /temas/camera_tof/image_raw

  • temas/camera_tof/status (std_msgs.msg.Bool) – frame status (True if frame received)

    ros2 topic echo /temas/camera_tof/status

  • temas/camera_tof/info (std_msgs.msg.String) – connection info messages

    ros2 topic echo /temas/camera_tof/info

Usage Example:

Start the node with default parameters:

ros2 run temas_ros2 camera_tof

Check if the camera is streaming:

ros2 topic echo /temas/camera_tof/status

View live images:

ros2 run rqt_image_view rqt_image_view

Then select topic /temas/camera_tof/image_raw.

Notes:
  • The camera automatically starts a streaming thread.

  • Node publishes status True when frames are received; False if no frame is available.

try_connect()[source]

Attempt to connect to the TEMAS ToF camera.

This method establishes the connection, starts the camera streaming thread, and publishes initial info and status messages.

stream_camera()[source]

Continuously read frames from the camera and publish them as ROS2 Image messages.

Also publishes a status boolean indicating whether a frame was successfully received.

destroy_node()[source]

Gracefully stop the camera thread and shut down the node.

Stops the camera thread if active and ensures proper ROS2 shutdown.

main(args=None)[source]

Main entry point for the TEMAS ToF Camera Node.

Initializes ROS2, spins the node, and handles shutdown on keyboard interrupt.