Skeleton Tracker Teleoperation Package for Mobile Robot
Description: Skeleton Tracker ROS Package for Teleoperating a Mobile RobotSubmitted By: Patrick Goebel
Keywords: skeleton tracking, kinect, depth camera, teleoperation, pi robot, robotis, dynamixel, ax-12+, serializer, differential drive, mobile robot
Contents
Overview
The pi_tracker ROS package consists of four interrelated but independent ROS nodes that communicate over ROS topics and services:
skeleton_tracker for talking to the OpenNI skeleton tracking API and publishing the joint configuration and tf frames. Publishes joint names, positions, orientations and confidence values to the /skeleton topic. Based on Taylor Veltrop's teleop_kinect.cpp source at veltrobot_teleop.
tracker_command for detecting gesture commands and connecting to services that control the robot. Subscribes to the /skeleton topic and makes calls to services on other nodes. New gestures and commands can be added easily by defining simple functions over the joint configurations.
tracker_base_controller for controlling the movements of a wheeled robot base (either holonomic or non-holonomic). Subscribes to /skeleton and publishes to /cmd_vel.
tracker_joint_controller for teleoperating the joints of the robot including arms, torso and head. Subscribes to /skeleton and publishes to /cmd_joints.
Features
- Automatically scales gestures to operator's body dimensions.
- Easily add new gestures and commands by way of simple Python functions over the joint configurations.
- Works with holonomic as well as non-holonomic robots. (Though my Rovio broke in the middle of testing so YMMV...)
- Highly configurable YAML file allows customization for different robots.
Should work with any robot that can consume sensor_msgs/JointState messages to move the joints and geometry_msgs/Twist messages to move the base.
- Can use either the feet or the hands to drive the base. (Demonstration video shows using the feet.)
Video
How to Reproduce Your Entry
Code to Checkout
Install ros-cturtle-base
Install ni
Install the serializer package
Install the robotis package
Install the pi_lib package
Install the pi_tracker package
Configuration and Launching
Edit the included launch files and configuration files to match your robot. See the pi_tracker package for descriptions of all the parameters.
In the current version of the pi_tracker package, two launch files are used:
skeleton.launch brings up the skeleton_tracker node (which includes a viewer) as well as the kinect frames nodes and the robot_state_publisher.
tracker.launch brings up the three other pi_tracker nodes: tracker_command, tracker_base_controller and tracker_joint_controller. If you are only controlling a base (such as when using with the Rovio), then you do not need the tracker_joint_controller, and vice versa.
$ roslaunch pi_tracker skeleton.launch $ roslaunch pi_tracker tracker.launch
You will then need to launch the controllers for your base hardware and servos. For example:
$ roslaunch pi_tracker serializer.launch $ roslaunch pi_tracker robotis.launch
Hardware Used for this Demonstration
- Microsoft Kinect RGB-D camera
- Dynamixel AX-12+ servos
- USB2Dynamixel controller
- Serializer microcontroller