NOTE: This tutorial is several years out of date and the specific commands for installing software and using ROS have changed since then. An up-to-date version of this tutorial can be found in the book ROS By Example Volume 2: Packages and Programs for Advanced Robot Behaviors, available as a downloadable PDF and in paperback on Lulu.com.
When working with reference frames, keep in mind that ROS uses a right-hand convention for orienting the
coordinate axes as shown on left. Similarly, the direction of rotations about an axis is defined by the right hand rule shown on the right: if you point your thumb in the positive direction of any axis, your fingers curl in the direction of a positive rotation. For a mobile robot using ROS, the z-axis points upward, the x-axis points forward, and the y-axis points to the left. Under the right-hand rule, a positive rotation of the robot about the z-axis is counterclockwise while a negative rotation is clockwise.$ svn co http://pi-robot-ros-pkg.googlecode.com/svn/trunk/pi_tutorials/pi_head_tracking_3d_part1
$ more pi_head_tracking_3d_part1/manifest.xml
<package>
<description brief="pi_head_tracking_3d_part1">
Head Tracking in 3D Part 1
</description>
<author>Patrick Goebel</author>
<license>BSD</license>
<review status="unreviewed" notes=""/>
<url>https://pirobot.org/blog/0018</url>
<depend package="roscpp"/>
<depend package="rospy"/>
<depend package="std_msgs"/>
<depend package="geometry_msgs"/>
<depend package="tf"/>
<depend package="rviz"/>
<depend package="robot_state_publisher"/>
<depend package="joint_state_publisher"/>
<depend package="dynamixel_driver"/>
<depend package="dynamixel_msgs"/>
<depend package="dynamixel_controllers"/>
</package>
Note the dependency on the third-party packages joint_state_publisher as well as dynamixel_driver, dynamixel_msgs and dynamixel_controllers. Let's download and install these packages now so we can build the main head tracking project.
$ svn co https://wu-ros-pkg.svn.sourceforge.net/svnroot/wu-ros-pkg/stacks/urdf_tools/trunk urdf_tools
$ cd urdf_tools
$ rosmake --rosdep-install
$ sudo apt-get install ros-diamondback-dynamixel-motor
$ sudo apt-get install ros-electric-dynamixel-motor
$ rosmake --rosdep-install pi_head_tracking_3d_part1
$ roscd pi_head_tracking_3d_part1/urdf
$ more kinectbot.urdf.xacro
$ rosrun xacro xacro.py kinectbot.urdf.xacro > tmp.urdf
$ rosrun urdf check_urdf tmp.urdf
$ rosrun urdf_parser check_urdf tmp.urdf
robot name is: kinectbot
---------- Successfully Parsed XML ---------------
root Link: base_link has 1 child(ren)
child(1): torso_link
child(1): head_pan_link
child(1): pan_tilt_bracket
child(1): head_tilt_link
child(1): neck_link
child(1): head_base_link
child(1): head_post_link
child(1): head_link
child(1): hair_link
child(2): left_eye_link
child(3): right_eye_link
<launch>
<!-- Load the URDF/Xacro model of our robot -->
<param name="robot_description" command="$(find xacro)/xacro.py '$(find pi_head_tracking_3d_part1)/urdf/kinectbot.urdf.xacro'" />
<!-- Provide simulated control of the robot joint angles -->
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" />
<param name="/use_gui" value="True" />
<!-- Publish the robot state -->
<node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher">
<param name="publish_frequency" value="20.0"/>
</node>
<!-- Publish a static transform between the robot base and the world frame -->
<node pkg="tf" type="static_transform_publisher" name="world_base_broadcaster" args="0 0 0.0325 0 0 0 /world /base_link 100" />
</launch>
$ roslaunch pi_head_tracking_3d_part1 test_urdf.launch
SUMMARY
========
PARAMETERS
* /rosversion
* /use_gui
* /rosdistro
* /robot_description
* /robot_state_publisher/publish_frequency
NODES
/
joint_state_publisher (joint_state_publisher/joint_state_publisher)
robot_state_publisher (robot_state_publisher/state_publisher)
world_base_broadcaster (tf/static_transform_publisher)
ROS_MASTER_URI=http://localhost:11311
core service [/rosout] found
process[joint_state_publisher-1]: started with pid [11991]
process[robot_state_publisher-2]: started with pid [11992]
process[world_base_broadcaster-3]: started with pid [11993]

$ roscd pi_head_tracking_3d_part1
$ rosrun rviz rviz -d tutorial.vcg

<launch>
<arg name="dynamixel_namespace" value="dynamixel_controller" />
<!-- Load the URDF/Xacro model of our robot -->
<param name="robot_description" command="$(find xacro)/xacro.py '$(find pi_head_tracking_3d_part1)/urdf/kinectbot.urdf.xacro'" />
<!-- Publish the robot state -->
<node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher">
<param name="publish_frequency" value="20.0"/>
</node>
<!-- Start the Dynamixel low-level driver manager with parameters -->
<node ns="$(arg dynamixel_namespace)" name="dynamixel_manager" pkg="dynamixel_controllers"
type="controller_manager.py" required="true" output="screen">
<rosparam>
namespace: pi_dynamixel_manager
serial_ports:
dynamixel_ax12:
port_name: "/dev/ttyUSB0"
baud_rate: 1000000
min_motor_id: 1
max_motor_id: 2
update_rate: 20
</rosparam>
</node>
<!-- Load joint controller configuration from YAML file to parameter server -->
<rosparam ns="$(arg dynamixel_namespace)" file="$(find pi_head_tracking_3d_part1)/params/dynamixel_params.yaml" command="load"/>
<!-- Start the head pan and tilt controllers -->
<node ns="$(arg dynamixel_namespace)" name="dynamixel_controller_spawner_ax12" pkg="dynamixel_controllers"
type="controller_spawner.py"
args="--manager=pi_dynamixel_manager
--port=dynamixel_ax12
--type=simple
head_pan_controller
head_tilt_controller"
output="screen" />
<!-- Start the Dynamixel Joint States Publisher -->
<node ns="$(arg dynamixel_namespace)" name="dynamixel_joint_states_publisher" pkg="pi_head_tracking_3d_part1" type="dynamixel_joint_state_publisher.py" output="screen" />
<!-- Start all Dynamixels in the relaxed state -->
<node pkg="pi_head_tracking_3d_part1" type="relax_all_servos.py" name="relax_all_servos" />
<!-- Publish a static transform between the robot base and the world frame -->
<node pkg="tf" type="static_transform_publisher" name="world_base_broadcaster" args="0 0 0.0325 0 0 0 /world /base_link 100" />
</launch>
dynamixels: ['head_pan', 'head_tilt']
head_pan_controller:
controller:
package: dynamixel_controllers
module: joint_position_controller
type: JointPositionController
joint_name: head_pan_joint
joint_speed: 2.0
motor:
id: 1
init: 512
min: 0
max: 1024
head_tilt_controller:
controller:
package: dynamixel_controllers
module: joint_position_controller
type: JointPositionController
joint_name: head_tilt_joint
joint_speed: 2.0
motor:
id: 2
init: 512
min: 300
max: 800
$ ls /dev/ttyUSB*
$ roslaunch pi_head_tracking_3d_part1 dynamixels.launch
$ rostopic pub -1 /dynamixel_controller/head_pan_controller/command std_msgs/Float64 -- 1.0
$ rostopic pub -1 /dynamixel_controller/head_pan_controller/command std_msgs/Float64 -- 0.0
$ rostopic pub -1 /dynamixel_controller/head_tilt_controller/command std_msgs/Float64 -- 0.5
$ rostopic pub -1 /dynamixel_controller/head_tilt_controller/command std_msgs/Float64 -- 0.0
$ rosservice call /dynamixel_controller/head_pan_controller/set_speed 1.0
$ rostopic pub -1 /dynamixel_controller/head_pan_controller/command std_msgs/Float64 -- 1.0
$ rosservice call /dynamixel_controller/head_pan_controller/torque_enable False
#! /usr/bin/env pythonNow let's focus on some of the more important parts of the script beginning near the top:
import roslib; roslib.load_manifest('pi_head_tracking_3d_part1')
import rospy
import tf
from geometry_msgs.msg import PointStamped
from std_msgs.msg import Float64
import math
class PointHeadNode():
def __init__(self):
# Initialize new node
rospy.init_node('point_head_node', anonymous=True)
dynamixel_namespace = rospy.get_namespace()
rate = rospy.get_param('~rate', 1)
r = rospy.Rate(rate)
# Initialize the target point
self.target_point = PointStamped()
self.last_target_point = PointStamped()
# Subscribe to the target_point topic
rospy.Subscriber('/target_point', PointStamped, self.update_target_point)
# Initialize publisher for the pan servo
self.head_pan_frame = 'head_pan_link'
self.head_pan_pub = rospy.Publisher(dynamixel_namespace + 'head_pan_controller/command', Float64)
# Initialize publisher for the tilt servo
self.head_tilt_frame = 'head_tilt_link'
self.head_tilt_pub = rospy.Publisher(dynamixel_namespace + 'head_tilt_controller/command', Float64)
# Initialize tf listener
self.tf = tf.TransformListener()
# Make sure we can see at least the pan and tilt frames
self.tf.waitForTransform(self.head_pan_frame, self.head_tilt_frame, rospy.Time(), \
rospy.Duration(5.0))
# Reset the head position to neutral
rospy.sleep(1)
self.reset_head_position()
rospy.loginfo("Ready to accept target point")
while not rospy.is_shutdown():
rospy.wait_for_message('/target_point', PointStamped)
if self.target_point == self.last_target_point:
continue
try:
target_angles = self.transform_target_point(self.target_point)
except (tf.Exception, tf.ConnectivityException, tf.LookupException):
rospy.loginfo("tf Failure")
continue
self.head_pan_pub.publish(target_angles[0])
self.head_tilt_pub.publish(target_angles[1])
self.last_target_point = self.target_point
rospy.loginfo("Setting Target Point:\n" + str(self.target_point))
r.sleep()
def update_target_point(self, msg):
self.target_point = msg
def reset_head_position(self):
self.head_pan_pub.publish(0.0)
self.head_tilt_pub.publish(0.0)
rospy.sleep(3)
def transform_target_point(self, target):
# Set the pan and tilt reference frames to the head_pan_frame and head_tilt_frame defined above
pan_ref_frame = self.head_pan_frame
tilt_ref_frame = self.head_tilt_frame
# Wait for tf info (time-out in 5 seconds)
self.tf.waitForTransform(pan_ref_frame, target.header.frame_id, rospy.Time(), \
rospy.Duration(5.0))
self.tf.waitForTransform(tilt_ref_frame, target.header.frame_id, rospy.Time(), \
rospy.Duration(5.0))
# Transform target point to pan reference frame & retrieve the pan angle
pan_target = self.tf.transformPoint(pan_ref_frame, target)
pan_angle = math.atan2(pan_target.point.y, pan_target.point.x)
# Transform target point to tilt reference frame & retrieve the tilt angle
tilt_target = self.tf.transformPoint(tilt_ref_frame, target)
tilt_angle = math.atan2(tilt_target.point.z,
math.sqrt(math.pow(tilt_target.point.x, 2) + math.pow(tilt_target.point.y, 2)))
return [pan_angle, tilt_angle]
if __name__ == '__main__':
try:
point_head = PointHeadNode()
rospy.spin()
except rospy.ROSInterruptException:
pass
import tfSince the name of the game is frame transformations, we import the tf package. The PointStamped message type glues together a Point message type (x, y, z coordinates) with a Header message type (seq, stamp, frame_id) which therefore attaches the point to a particular frame of reference. Remember that you can always display the fields of a given message type using the rosmsg command:
from geometry_msgs.msg import PointStamped
$ rosmsg show geometry_msgs/PointStamped
Header header
uint32 seq
time stamp
string frame_id
geometry_msgs/Point point
float64 x
float64 y
float64 z
self.target_point = PointStamped()Next we subscribe to the /target_point topic on which we will publish PointStamped target locations:
self.last_target_point = PointStamped()
rospy.Subscriber('/target_point', PointStamped, self.update_target_point)The callback function update_target_point simply sets the local target_point variable to the published value:
def update_target_point(self, msg):We use a pair of publishers to update the positions of the pan and tilt servos. We also select the two reference frames, head_pan_link and head_tilt_link, that will be used in transforming the target location into appropriate motions:
self.target_point = msg
# Initialize publisher for the pan servoNext we initialize the tf listener and make sure that at least the pan and tilt frames are up and visible:
self.head_pan_frame = 'head_pan_link'
self.head_pan_pub = rospy.Publisher(dynamixel_namespace + 'head_pan_controller/command', Float64)
# Initialize publisher for the tilt servo
self.head_tilt_frame = 'head_tilt_link'
self.head_tilt_pub = rospy.Publisher(dynamixel_namespace + 'head_tilt_controller/command', Float64)
self.tf = tf.TransformListener()Now we enter the main processing loop:
self.tf.waitForTransform(self.head_pan_frame, self.head_tilt_frame, rospy.Time(), \
rospy.Duration(5.0))
while not rospy.is_shutdown():First we wait on the /target_point topic to make sure we get a target message. If the current target is the same as the last, we skip the rest of the loop since there is nothing to do. Otherwise, we transform the target location into the pan and tilt link frames and get back the angles needed to rotate the head to point at the target:
rospy.wait_for_message('/target_point', PointStamped)
if self.target_point == self.last_target_point:
continue
try:The function transform_target_point will be described shortly. Once we have our pan and tilt angles, we publish them to the dynamixel controllers to move the head:
target_angles = self.transform_target_point(self.target_point)
except (tf.Exception, tf.ConnectivityException, tf.LookupException):
rospy.loginfo("tf Failure")
continue
self.head_pan_pub.publish(target_angles[0])The real work is done by the transform_target_point function which, as mentioned earlier, is taken from the UA wubble head action script. Let's see how it works:
self.head_tilt_pub.publish(target_angles[1])
def transform_target_point(self, target):The input to the function is the PointStamped target location. First we set our reference frames to the head_pan_frame and head_tilt_frame defined in the main script, namely /head_pan_link and /head_tilt_link. Since these are the frames in which head motion takes place, we have to transform the target's coordinates into these frames. It's a good idea to wait for tf to see both the reference frames (pan and tilt) and the target frame, so we do that next:
# Set the pan and tilt reference frames to the head_pan_frame and head_tilt_frame defined above
pan_ref_frame = self.head_pan_frame
tilt_ref_frame = self.head_tilt_frame
# Wait for tf info (time-out in 5 seconds)Finally, we put tf to work by using the the transformPoint method to map the target point from its own frame into the pan and tilt frames. First the pan frame:
self.tf.waitForTransform(pan_ref_frame, target.header.frame_id, rospy.Time(), \
rospy.Duration(5.0))
self.tf.waitForTransform(tilt_ref_frame, target.header.frame_id, rospy.Time(), \
rospy.Duration(5.0))
pan_target = self.tf.transformPoint(pan_ref_frame, target)In the first line above, pan_target is assigned the (x, y, z) coordinates of the target in the reference frame attached to the head_pan_link. The corresponding pan angle is then computed in the second line from the projection of these coordinates in the horizontal x-y plane. In a similar fashion, the next two lines compute the tilt angle as follows:
pan_angle = math.atan2(pan_target.point.y, pan_target.point.x)
tilt_target = self.tf.transformPoint(tilt_ref_frame, target)With both angles computed, we return them to our main loop:
tilt_angle = math.atan2(tilt_target.point.z,
math.sqrt(math.pow(tilt_target.point.x, 2) + math.pow(tilt_target.point.y, 2)))
return [pan_angle, tilt_angle]This completes the point_head node. Once launched, the node will listen on the /target_point topic and when a target message is received, it will move the pan and tilt servos to point the head in the appropriate direction. To test the node, first make sure you have launched the dynamixel controllers if they are not already running:
$ roslaunch pi_head_tracking_3d_part1 dynamixels.launch
$ roslaunch pi_head_tracking_3d_part1 point_head.launch
process[ax12_controller/point_head_node-1]: started with pid [870]
[INFO] [WallTime: 1298908182.741524] Ready to accept target point
$ rostopic pub -1 /target_point geometry_msgs/PointStamped '{ header: {frame_id: base_link }, point: {x: 1.0, y: 1.0, z: 0.0} }'
$ rostopic pub -1 /target_point geometry_msgs/PointStamped '{ header: {frame_id: torso_link }, point: {x: 1.0, y: 1.0, z: 0.0} }'
$ rostopic pub -1 /target_point geometry_msgs/PointStamped '{ header: {frame_id: head_pan_link }, point: {x: 100.0, y: 0.0, z: 0.0} }'
$ rostopic pub -r 1 /target_point geometry_msgs/PointStamped '{ header: {frame_id: head_link }, point: {x: 5.0, y: 0.0, z: 0.01} }'
$ rosrun pi_head_tracking_3d_part1 head_pointer_gui.py
