This project aims to create an open, maker-friendly robotics platform that delivers real-time, fully on-device hand detection and tracking with a pan-tilt camera, all powered entirely by edge computing. It runs an Edge Impulse's optimized YOLO-Pro object detection model on the device’s built-in neural processing unit, delivering low-latency inference at over 60 FPS with extremely low power consumption. ROS 2 serves as the real-time orchestration backbone, cleanly separating perception, control, and actuation nodes, which makes the system highly extensible for applications like gesture recognition, teleoperation, or collaborative robotics.
HardwareWe are using a Rubik Pi 3 with Qualcomm Dragonwing QCM6490 SoC. The Dragonwing QCM6490 features an octa-core Qualcomm Kryo CPU, a Qualcomm Adreno 643 GPU, and a Qualcomm Hexagon 770 DSP containing an AI accelerator capable of delivering 12 TOPS.
For actuation, the robot uses servo motors driven by a SparkFun Servo pHAT, which provides convenient control for multiple servos over an I2C connection.
For pan and tilt motion, the robot uses two DFRobot DSS-P05 standard servo motors: one dedicated to pan and the other to tilt.
The pan-tilt mechanism is built using DFRobot pan-tilt brackets for easy and sturdy assembly.
We'll be using an Elecom 5MP webcam.
We have 3D-printed a mounting bracket to firmly attach the robot to the base plate, ensuring stable and secure movement.
The fully assembled system is shown below.
To install the optimized Ubuntu 24.04 image on your RUBIK Pi 3, please follow the setup guide here:
Once completed, SSH access to the device over WiFi should be fully enabled and operational.
ROS 2 Jazzy InstallationFollow the instructions below to install the essential packages.
Set locale
$ sudo apt update
$ sudo apt install locales
$ sudo locale-gen en_US en_US.UTF-8
$ sudo update-locale LC_ALL=en_US.UTF-8 LANG=en_US.UTF-8
$ export LANG=en_US.UTF-8Set the ROS 2 Apt Repository
$ sudo apt install software-properties-common
$ sudo add-apt-repository universe
$ sudo apt update && sudo apt install curl -y
$ curl -L -o ros2-apt-source.deb https://github.com/ros-infrastructure/ros-apt-source/releases/download/1.1.0/ros2-apt-source_1.1.0.noble_all.deb
$ sudo dpkg -i ros2-apt-source.debInstall development tools
$ sudo apt update && sudo apt install ros-dev-toolsInstall ROS 2 base packages
Since we will be using the Rubik Pi 3 in headless mode, run the following commands to install the bare-bones ROS 2 base packages without any GUI tools.
$ sudo apt update && sudo apt upgrade
$ sudo apt install ros-jazzy-ros-baseURDFAn accurate Unified Robot Description Format (URDF) for the pan-tilt camera mechanism is essential to guarantee precise and reliable coordinate transformations between the camera, pan, and tilt frames. We have carefully hand-crafted this URDF to meet those requirements.
<?xml version="1.0"?>
<robot name="ptcam_robot" xmlns:xacro="http://www.ros.org/wiki/xacro">
<link name="base_link">
<visual>
<geometry>
<mesh filename="package://ptcam_robot/meshes/base.stl" scale="0.001 0.001 0.001"/>
</geometry>
<origin xyz="0 0 0" rpy="1.57 0 0"/>
<material name="gray"/>
</visual>
</link>
<link name="pan_link">
<visual>
<geometry>
<mesh filename="package://ptcam_robot/meshes/dss-p05_servo.stl" scale="0.001 0.001 0.001"/>
</geometry>
<origin xyz="-0.0377 -0.0101 -0.018" rpy="1.5708 0 1.5708"/>
<material name="gray"/>
</visual>
</link>
<link name="tilt_link">
<visual>
<geometry>
<mesh filename="package://ptcam_robot/meshes/dss-p05_servo.stl" scale="0.001 0.001 0.001"/>
</geometry>
<origin xyz="0.0175 0.023 0.0145" rpy="3.1416 1.5708 0"/>
<material name="gray"/>
</visual>
</link>
<link name="u_bracket_link">
<visual>
<geometry>
<mesh filename="package://ptcam_robot/meshes/u_bracket.stl" scale="0.001 0.001 0.001"/>
</geometry>
<origin xyz="0 0 0.030" rpy="-1.5708 0 1.5708"/>
<material name="gray"/>
</visual>
</link>
<link name="multi_bracket_link">
<visual>
<geometry>
<mesh filename="package://ptcam_robot/meshes/multi_bracket.stl" scale="0.001 0.001 0.001"/>
</geometry>
<origin xyz="-0.010 0.0255 -0.001" rpy="1.5708 0 0"/>
<material name="gray"/>
</visual>
</link>
<joint name="base_joint" type="fixed">
<parent link="base_link"/>
<child link="pan_link"/>
<origin xyz="0.010 -0.012 0" rpy="0 0 0"/>
</joint>
<joint name="pan_joint" type="revolute">
<parent link="pan_link"/>
<child link="multi_bracket_link"/>
<origin xyz="0.0 0.0 0.025" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<limit lower="0" upper="3.1416" effort="0.5" velocity="1.0"/>
<dynamics damping="0.1" friction="0.1"/>
</joint>
<joint name="multi_bracket_joint" type="fixed">
<parent link="multi_bracket_link"/>
<child link="tilt_link"/>
<origin xyz="0 0 0.010" rpy="0 0 0"/>
</joint>
<joint name="tilt_joint" type="revolute">
<parent link="tilt_link"/>
<child link="u_bracket_link"/>
<origin xyz="-0.020 0.005 0.0045" rpy="0 1.5708 0"/>
<axis xyz="0 -1 0"/>
<limit lower="1.0472" upper="2.0944" effort="0.5" velocity="1.0"/>
<dynamics damping="0.1" friction="0.1"/>
</joint>
<link name="camera_link">
<visual>
<geometry>
<box size="0.060 0.025 0.020"/>
</geometry>
<origin xyz="0 0 0" rpy="0 0 0"/>
<material name="gray"/>
</visual>
</link>
<link name="camera_lens_link">
<visual>
<geometry>
<cylinder length="0.020" radius="0.010"/>
</geometry>
<origin xyz="0 0 0" rpy="0 0 0"/>
<material name="gray_trans"/>
</visual>
</link>
<joint name="camera_joint" type="fixed">
<parent link="u_bracket_link"/>
<child link="camera_link"/>
<origin xyz="0 0 0.0415" rpy="0 0 1.5708"/>
</joint>
<joint name="camera_lens_joint" type="fixed">
<parent link="camera_link"/>
<child link="camera_lens_link"/>
<origin xyz="0.014 -0.010 0" rpy="0 1.5708 1.5708"/>
</joint>
<material name="gray">
<color rgba="0.5 0.5 0.5 1.0"/>
</material>
<material name="gray_trans">
<color rgba="0.37 0.38 0.47 1.0"/>
</material>
</robot>The robot model can be visualized and validated manually in RViz2 using the Joint State Publisher gui. The launch script is available in the GitHub repository referenced in the Code section.
We need to sign up an account at the Edge Impulse Studio and create a new project. We need to install the Edge Impulse CLI tool by following the instructions at https://docs.edgeimpulse.com/tools/clis/edge-impulse-cli/installation.
Run the command below and follow the onscreen instructions to connect the device to Edge Impulse Studio for data collection.
$ edge-impulse-linuxWe captured 357 images with different distances and lighting settings and labeled them using the Labeling Queue tab in Edge Impulse Studio’s Data Acquisition page.
For model development, we need to create an impulse, a custom pipeline integrating image processing and machine learning models. Navigate to the Impulse Design > Create Impulse page, select Add a processing block, and choose Image to preprocess and normalize image data. On the same page, select Add a learning block and choose Object Detection (Images). We are using a 224x224 image size. Then, click the Save Impulse button.
Next, go to the Impulse > Image page set the Color depth parameter as RGB.
Click on the Save parameters button which redirects to another page where we should click on the Generate Feature button.
To train the model, navigate to the Impulse > ObjectDetection page. The Object detection settings we selected are displayed below.
We opted for the basic spatial and color space augmentations in the Advanced training settings.
We selected the latest YOLO-Pro model, ideal for detecting hands of varying sizes due to different distances from the camera, and capable of running efficiently on the Qualcomm AI Accelerator. Click on the Save & train button to begin training.
Once training is finished, the training performance is shown as follows. The quantized (int8) model attained a 94.4% precision score on the training data.
To evaluate the model’s performance on the test datasets, navigate to the Model testing page and click the Classify All button. The model shows improved performance on unseen datasets with a 97.1% accuracy.
We can test the model inferencing in the Impulse > Live classification page.
As the model will run inference using the Qualcomm AI Accelerator on the Rubik Pi 3, we chose the Linux (AARCH64 with Qualcomm QNN) option on the Deployment page.
Select the Quantized (int8) option for Model Optimizations, since the Qualcomm AI Accelerator is incompatible with float32 models.
Click the Build button to compile and download the EIM (Edge Impulse Model) binary.
Application DevelopmentThe application is built as distributed ROS 2 nodes, adhering to the separation of concerns principle. It captures images from a camera, processes them to detect and track the hand with PID control. The results are streamed over HTTP for real-time monitoring. This modular design ensures clear division of tasks, enhancing efficiency and maintainability. Each node handles a specific function, from image capture to pan tilt actuation, while seamlessly integrating to achieve the application's objectives.
Edge Impulse Linux SDK for Python
We utilize the Edge Impulse Linux SDK for on-device model inference, which can be installed by running the commands listed below.
$ sudo apt install python3-pip
$ pip3 install edge_impulse_linux --break-system-packagesQualcomm AI Runtime
The Qualcomm AI runtime and its required dependencies can be installed by running the command below.
$ sudo apt install libqnn-devHere is the code for the object_detection node.
import rclpy
import cv2
import os
from rclpy.node import Node
from sensor_msgs.msg import Image
from std_msgs.msg import Header
from vision_msgs.msg import Detection2DArray, Detection2D, ObjectHypothesisWithPose
from cv_bridge import CvBridge
from rclpy.qos import QoSProfile, ReliabilityPolicy, HistoryPolicy
from edge_impulse_linux.image import ImageImpulseRunner
class ObjectDetectionNode(Node):
def __init__(self):
super().__init__("object_detection_node")
self.declare_parameter("resource_path", "")
resource_path = (
self.get_parameter("resource_path").get_parameter_value().string_value
)
model_file = os.path.join(resource_path, "hands-linux-aarch64-qnn-v9.eim")
self.cvbridge = CvBridge()
best_effort_qos_profile = QoSProfile(
reliability=ReliabilityPolicy.BEST_EFFORT,
history=HistoryPolicy.KEEP_LAST,
depth=1,
)
self.sub = self.create_subscription(
Image, "/camera/image_raw", self.image_callback, 10
)
self.pub_dets = self.create_publisher(
Detection2DArray, "/edge_impulse/detections", 10
)
self.runner = ImageImpulseRunner(model_file)
model_info = self.runner.init()
self.get_logger().info("Object detection node Started")
def image_callback(self, msg):
img = self.cvbridge.imgmsg_to_cv2(msg, "rgb8")
features, cropped = self.runner.get_features_from_image_auto_studio_settings(
img
)
res = self.runner.classify(features)
vision_msg_dets = Detection2DArray()
vision_msg_dets.header = msg.header
for bb in res["result"]["bounding_boxes"]:
det2D = Detection2D()
objHyp = ObjectHypothesisWithPose()
det2D.bbox.center.position.x = float(bb["x"] + bb["width"] / 2)
det2D.bbox.center.position.y = float(bb["y"] + bb["height"] / 2)
det2D.bbox.size_x = float(bb["width"])
det2D.bbox.size_y = float(bb["height"])
objHyp.hypothesis.class_id = str(bb["label"])
objHyp.hypothesis.score = float(bb["value"])
det2D.results.append(objHyp)
vision_msg_dets.detections.append(det2D)
self.pub_dets.publish(vision_msg_dets)
def destroy_node(self):
if self.runner:
self.runner.stop()
if rclpy.ok():
self.get_logger().info("Object detection node shut down.")
super().destroy_node()
def main(args=None):
rclpy.init(args=args)
object_detection_node = ObjectDetectionNode()
try:
rclpy.spin(object_detection_node)
except KeyboardInterrupt:
pass
finally:
object_detection_node.destroy_node()
if rclpy.ok():
rclpy.shutdown()
if __name__ == "__main__":
main()Here is the code for the hand_tracker node.
import rclpy
import cv2
import numpy as np
from cv_bridge import CvBridge
from rclpy.node import Node
from sensor_msgs.msg import Image
from vision_msgs.msg import Detection2DArray
from std_msgs.msg import Float64MultiArray
from hand_tracker.pid import PID
class HandTrackerNode(Node):
def __init__(self):
super().__init__("hand_tracker_node")
self.image_size = 224, 224
self.pan_pid = PID(kp=0.07, ki=0.0, kd=0.005, setpoint=self.image_size[0] / 2)
self.tilt_pid = PID(kp=0.07, ki=0.0, kd=0.005, setpoint=self.image_size[0] / 2)
self.current_pan = 90.0
self.current_tilt = 90.0
self.last_time = None
self.max_speed = 80.0
self.pub = self.create_publisher(
Float64MultiArray, "/ptcam_robot_controller/commands", 10
)
self.sub = self.create_subscription(
Detection2DArray, "/edge_impulse/detections", self.detections_callback, 10
)
self.get_logger().info("Hand Tracker Node Started")
def detections_callback(self, detections_msg):
bbox_center = None
for det2D in detections_msg.detections:
bbox_center = det2D.bbox.center.position
if abs(bbox_center.x - self.image_size[0] / 2) < 10:
bbox_center.x = self.image_size[0] / 2
if abs(bbox_center.y - self.image_size[0] / 2) < 10:
bbox_center.y = self.image_size[0] / 2
current_time = self.get_clock().now().nanoseconds / 1e9
if bbox_center is not None:
pan_control = self.pan_pid.compute(bbox_center.x, current_time)
tilt_control = self.tilt_pid.compute(bbox_center.y, current_time)
if self.last_time is None:
self.last_time = current_time
dt = max((current_time - self.last_time), 0.001)
self.last_time = current_time
max_delta = self.max_speed * dt
pan_delta = np.clip(pan_control, -max_delta, max_delta)
tilt_delta = np.clip(tilt_control, -max_delta, max_delta)
self.current_pan += pan_delta
self.current_tilt += tilt_delta
# Clamp to servo limits
self.current_pan = np.clip(self.current_pan, 0.0, 180.0)
self.current_tilt = np.clip(self.current_tilt, 45.0, 150.0)
commands = Float64MultiArray()
commands.data = [
np.deg2rad(self.current_pan),
np.deg2rad(self.current_tilt),
]
self.pub.publish(commands)
else:
self.pan_pid.reset()
self.tilt_pid.reset()
def main(args=None):
rclpy.init(args=args)
try:
hand_tracker_node = HandTrackerNode()
rclpy.spin(hand_tracker_node)
except KeyboardInterrupt:
pass
finally:
hand_tracker_node.destroy_node()
if rclpy.ok():
rclpy.shutdown()
if __name__ == "__main__":
main()We employed the ros2_control framework to provide real-time control and seamlessly interface with the robot's hardware.
Here is the controller manager configuration file.
controller_manager:
ros__parameters:
update_rate: 50
joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster
ptcam_robot_controller:
type: position_controllers/JointGroupPositionController
ptcam_robot_controller:
ros__parameters:
joints:
- pan_joint
- tilt_jointHere is the hardware interface code. The hardware interface is written in C++ to ensure low-latency performance and maximum efficiency.
#include <string>
#include <sstream>
#include <cmath>
#include <iostream>
#include <algorithm>
#include <PiPCA9685/PCA9685.h>
#include "rclcpp/rclcpp.hpp"
#include "ptcam_robot/ptcam_robot_system.hpp"
namespace ptcam_robot {
hardware_interface::CallbackReturn PTCamSystemHardware::on_init(const hardware_interface::HardwareInfo & info) {
if (hardware_interface::SystemInterface::on_init(info) != hardware_interface::CallbackReturn::SUCCESS) {
return hardware_interface::CallbackReturn::ERROR;
}
// Get configuration parameters
std::string i2c_bus = info_.hardware_parameters["i2c_bus"];
int i2c_address = std::stoi(info_.hardware_parameters["i2c_address"], 0, 16);
RCLCPP_INFO(rclcpp::get_logger("PTCamSystemHardware"), "Configured for I2C Bus: %s and Address: 0x%X", i2c_bus.c_str(), i2c_address);
// Initialize the dedicated driver
driver_ = std::make_unique < PiPCA9685::PCA9685 > ();
driver_ -> set_pwm_freq(50.0);
// Size the command and state arrays
num_servos_ = info_.joints.size();
hw_commands_.resize(num_servos_, std::numeric_limits < double > ::quiet_NaN());
hw_states_.resize(num_servos_, std::numeric_limits < double > ::quiet_NaN());
servo_configs_.resize(num_servos_);
// Validate joint configuration and load servo limits (pulse width in us)
for (size_t i = 0; i < num_servos_; ++i) {
const auto & joint = info_.joints[i];
// Check for command/state interfaces (same logic as before)
if (joint.command_interfaces.size() != 1 || joint.command_interfaces[0].name != hardware_interface::HW_IF_POSITION || joint.state_interfaces.size() != 1 || joint.state_interfaces[0].name != hardware_interface::HW_IF_POSITION) {
RCLCPP_FATAL(rclcpp::get_logger("PTCamSystemHardware"),
"Joint '%s' interfaces must be exactly one 'position' for command and state.", joint.name.c_str());
return hardware_interface::CallbackReturn::ERROR;
}
// Load specific servo parameters
try {
servo_configs_[i].channel = std::stoi(joint.parameters.at("channel"));
servo_configs_[i].min_us = std::stod(joint.parameters.at("min_pulse_us"));
servo_configs_[i].max_us = std::stod(joint.parameters.at("max_pulse_us"));
RCLCPP_INFO(rclcpp::get_logger("PTCamSystemHardware"), "Joint '%s' configured: Channel %d, min_us %.1f, max_us %.1f",
joint.name.c_str(), servo_configs_[i].channel, servo_configs_[i].min_us, servo_configs_[i].max_us);
} catch (const std::out_of_range & e) {
RCLCPP_FATAL(rclcpp::get_logger("PTCamSystemHardware"),
"Missing required joint parameter (channel, min_pulse_us, max_pulse_us) for joint '%s'.", joint.name.c_str());
return hardware_interface::CallbackReturn::ERROR;
}
}
return hardware_interface::CallbackReturn::SUCCESS;
}
// --- State and Command Interface Exports (Unchanged) ---
std::vector < hardware_interface::StateInterface > PTCamSystemHardware::export_state_interfaces() {
std::vector < hardware_interface::StateInterface > state_interfaces;
for (size_t i = 0; i < num_servos_; ++i) {
state_interfaces.emplace_back(hardware_interface::StateInterface(
info_.joints[i].name, hardware_interface::HW_IF_POSITION, & hw_states_[i]));
}
return state_interfaces;
}
std::vector < hardware_interface::CommandInterface > PTCamSystemHardware::export_command_interfaces() {
std::vector < hardware_interface::CommandInterface > command_interfaces;
for (size_t i = 0; i < num_servos_; ++i) {
command_interfaces.emplace_back(hardware_interface::CommandInterface(
info_.joints[i].name, hardware_interface::HW_IF_POSITION, & hw_commands_[i]));
}
return command_interfaces;
}
/**
* @brief Method to activate the hardware interface.
*/
hardware_interface::CallbackReturn PTCamSystemHardware::on_activate(const rclcpp_lifecycle::State & /*previous_state*/ ) {
RCLCPP_INFO(rclcpp::get_logger("PTCamSystemHardware"), "Activating hardware interface...");
// Initialize command and state buffers
for (size_t i = 0; i < num_servos_; ++i) {
// Set the initial command to a neutral position (0.0 rad)
hw_commands_[i] = 0.0;
hw_states_[i] = 0.0;
const auto & config = servo_configs_[i];
driver_ -> set_pwm_ms(config.channel, 1.5 f); // set initial position to 90 degrees (1500us)
}
RCLCPP_INFO(rclcpp::get_logger("PTCamSystemHardware"), "Hardware interface successfully activated!");
return hardware_interface::CallbackReturn::SUCCESS;
}
/**
* @brief Method to deactivate the hardware interface.
*/
hardware_interface::CallbackReturn PTCamSystemHardware::on_deactivate(const rclcpp_lifecycle::State & /*previous_state*/ ) {
RCLCPP_INFO(rclcpp::get_logger("PTCamSystemHardware"), "Deactivating hardware interface...");
// Driver destructor handles closing the file descriptor.
RCLCPP_INFO(rclcpp::get_logger("PTCamSystemHardware"), "Hardware interface successfully deactivated.");
return hardware_interface::CallbackReturn::SUCCESS;
}
/**
* @brief Reads state data from the hardware.
*/
hardware_interface::return_type PTCamSystemHardware::read(const rclcpp::Time & /*time*/ ,
const rclcpp::Duration & /*period*/ ) {
for (size_t i = 0; i < num_servos_; ++i) {
hw_states_[i] = hw_commands_[i];
}
return hardware_interface::return_type::OK;
}
/**
* @brief Writes command data to the hardware using the dedicated driver.
*/
hardware_interface::return_type PTCamSystemHardware::write(const rclcpp::Time & /*time*/ ,
const rclcpp::Duration & /*period*/ ) {
for (size_t i = 0; i < num_servos_; ++i) {
double target_rad = hw_commands_[i];
const auto & config = servo_configs_[i];
if (hw_commands_[i] == hw_states_[i]) {
continue;
}
RCLCPP_INFO(get_logger(), "i=%ld, target_rad=%f", i, target_rad);
// Radians to Pulse Width (us) Mapping
// Assuming +/- M_PI/2 radians maps to min/max pulse widths
//constexpr double min_rad = -M_PI_2; // -90 degrees
constexpr double min_rad = 0;
constexpr double max_rad = M_PI;
// Clamp target_rad
target_rad = std::max(min_rad, std::min(max_rad, target_rad));
// Linear interpolation:
double normalized = (target_rad - min_rad) / (max_rad - min_rad);
double pulse_us = config.min_us + normalized * (config.max_us - config.min_us);
driver_ -> set_pwm_ms(config.channel, pulse_us / 1000.0 f);
}
return hardware_interface::return_type::OK;
}
} // namespace
// This macro exports the hardware interface class to be used by the ROS 2 Control manager.
#include "pluginlib/class_list_macros.hpp"
PLUGINLIB_EXPORT_CLASS(
ptcam_robot::PTCamSystemHardware,
hardware_interface::SystemInterface)Launch the applicationExecute following commands to setup ROS 2 workspace environment.
$ source /opt/ros/jazzy/setup.bash
$ source /home/ubuntu/ws_pt_cam/install/setup.bashHere is the launch file script.
from launch import LaunchDescription
from launch.conditions import IfCondition
from launch.event_handlers import OnProcessExit
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare
from launch.actions import DeclareLaunchArgument, RegisterEventHandler, IncludeLaunchDescription
from launch.substitutions import Command, FindExecutable, PathJoinSubstitution, LaunchConfiguration
def generate_launch_description():
hand_tracker_launch_path = PathJoinSubstitution(
[FindPackageShare("hand_tracker"), "launch", "hand_tracker_node.launch.py"]
)
hand_tracker_launch = IncludeLaunchDescription(
launch_description_source=hand_tracker_launch_path
)
robot_description_content = Command(
[
PathJoinSubstitution([FindExecutable(name="xacro")]),
" ",
PathJoinSubstitution(
[FindPackageShare("ptcam_robot"), "urdf", "ptcam_robot.urdf.xacro"]
),
]
)
robot_description = {"robot_description": robot_description_content}
robot_controllers = PathJoinSubstitution(
[
FindPackageShare("ptcam_robot"),
"config",
"controllers.yaml",
]
)
control_node = Node(
package="controller_manager",
executable="ros2_control_node",
parameters=[robot_description, robot_controllers],
# arguments=['--ros-args', '--log-level', 'debug'],
output="both",
)
robot_state_pub_node = Node(
package="robot_state_publisher",
executable="robot_state_publisher",
output="both",
parameters=[robot_description],
)
joint_state_broadcaster_spawner = Node(
package="controller_manager",
executable="spawner",
arguments=["joint_state_broadcaster"],
)
robot_controller_spawner = Node(
package="controller_manager",
executable="spawner",
arguments=[
"ptcam_robot_controller",
"--controller-manager",
"/controller_manager",
],
)
# Delay start of joint_state_broadcaster after `robot_controller`
delay_joint_state_broadcaster_after_robot_controller_spawner = RegisterEventHandler(
event_handler=OnProcessExit(
target_action=robot_controller_spawner,
on_exit=[joint_state_broadcaster_spawner],
)
)
return LaunchDescription(
[
control_node,
robot_state_pub_node,
robot_controller_spawner,
delay_joint_state_broadcaster_after_robot_controller_spawner,
hand_tracker_launch,
]
)Execute the following command to launch the application.
$ ros2 launch ptcam_robot ptcam_robot.launch.pyDemoConclusionThis project successfully demonstrates that sophisticated real-time hand tracking can be achieved on low-cost, open-source hardware without reliance on cloud services or high-power GPUs, setting a new benchmark for accessible edge AI in robotics. By combining an optimized YOLO-Pro model, ROS 2 modularity, and efficient pan-tilt servoing, the platform provides a solid foundation for responsive human–robot interaction in resource-constrained environments.













_3u05Tpwasz.png?auto=compress%2Cformat&w=40&h=40&fit=fillmax&bg=fff&dpr=2)

Comments