TEMAS Control Node

The control node sends movement commands (pan/tilt), controls scanning, and publishes live telemetry such as distance, mean distance, current head position, and scan progress.

It also subscribes to command topics that let you: - move to a position, - go to home, - start/stop point cloud scans, - save point clouds, - reset scan flags.

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

Bases: Node

ROS2 node for controlling the TEMAS device.

This node allows moving the device, starting/stopping point cloud scans, and publishing control-related data such as distance, position, and scan progress.

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

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

Published Topics:
  • temas/control/distance (std_msgs.msg.Float32) – current distance

    ros2 topic echo /temas/control/distance --once

  • temas/control/mean_distance (std_msgs.msg.Float32) – mean distance

    ros2 topic echo /temas/control/mean_distance --once

  • temas/control/position (std_msgs.msg.String) – current position

    ros2 topic echo /temas/control/position --once

  • temas/control/scan_progress (std_msgs.msg.Float32) – point cloud scan progress [%]

    ros2 topic echo /temas/control/scan_progress --once

Subscribed Topics (Commands):
  • temas/control/move_pos (example_interfaces.msg.Float32MultiArray) – move to [phi, theta]

    ros2 topic pub /temas/control/move_pos example_interfaces/msg/Float32MultiArray "{data: [30.0, 45.0]}" --once

  • temas/control/move_home (std_msgs.msg.Bool) – move to home position

    ros2 topic pub /temas/control/move_home std_msgs/msg/Bool "{data: true}" --once

  • distance_request (std_msgs.msg.Float32) – current distance

    ros2 topic pub /distance_request

  • mean_distance_request (std_msgs.msg.Float32) – mean distance

    ros2 topic pub /mean_distance_request

  • temas/control/start_scan (example_interfaces.msg.Float32MultiArray) – start point cloud scan with optional args [min_theta, max_theta, min_phi, max_phi, color_mode]

    ros2 topic pub /temas/control/start_scan example_interfaces/msg/Float32MultiArray "{data: [-30.0, 90.0, -60.0, 60.0, 0]}" --once

  • temas/control/stop_scan (std_msgs.msg.Bool) – stop point cloud scan

    ros2 topic pub /temas/control/stop_scan std_msgs/msg/Bool "{data: true}" --once

  • temas/control/reset_commands (std_msgs.msg.Bool) – reset start scan flag

    ros2 topic pub /temas/control/reset_commands std_msgs/msg/Bool "{data: true}" --once

  • temas/control/save_pcl (std_msgs.msg.String) – save point cloud to specified path

    ros2 topic pub /temas/control/save_pcl std_msgs/msg/String "{data: '/home/user/'}" --once

Notes:
  • Start scan can only be executed once until reset.

  • All commands are executed in background threads to avoid blocking.

  • Node continuously publishes sensor/control data at ~10 Hz.

publish_loop()[source]

Continuously publishes TEMAS data.

This method runs in a background thread and publishes:
  • Distance

  • Mean distance

  • Pan/Tilt position

  • Scan progress

at a fixed rate (10 Hz).

move_pos_cb(msg)[source]

Move the TEMAS device to a specified position.

Parameters:

msg (Float32MultiArray) – Array containing [phi, theta] angles.

move_home_cb(msg)[source]

Move the TEMAS device to the home position.

Parameters:

msg (Bool) – Boolean trigger

start_scan_cb(msg)[source]

Start a point cloud scan (only once until reset).

Parameters:

msg (Float32MultiArray) – Optional array [theta1, theta2, phi1, phi2, color] - theta1: min elevation (-30 to 90°, step 0.5°) - theta2: max elevation (-30 to 90°, step 0.5°) - phi1: min azimuth (-60 to 60°, step 0.5°) - phi2: max azimuth (-60 to 60°, step 0.5°) - color: 0=black-white, 1=color (default=0)

Returns:

Status message indicating success. Returns ‘True’ if successful.

Return type:

str

stop_scan_cb(msg)[source]

Stop an ongoing point cloud scan.

Parameters:

msg (Bool) – Boolean trigger

Returns:

Status message. Returns ‘True’ if successful.

Return type:

str

save_pcl_cb(msg)[source]

Save the latest point cloud to the specified path.

Parameters:

msg (String) – File path

Returns:

Status message. Returns ‘True’ if successful.

Return type:

str

reset_commands_cb(msg)[source]

Reset internal command flags to allow starting a new scan.

Parameters:

msg (Bool) – Boolean trigger

destroy_node()[source]

Cleanly stop background threads and destroy the node.

main(args=None)[source]

Main function to initialize ROS2 and spin the TEMAS control node.

Parameters:

args – Optional command line arguments