Only released in EOL distros:
rwi_ros: b21_description | b21_teleop | ptu46 | ptu_control | rflex
Package Summary
Released
Documented
Actionlib interface for PTUs which listen for JointState messages (such as PTU46)
- Maintainer status: maintained
- Maintainer: David V. Lu!! <davidvlu AT gmail DOT com>
- Author: Dan Lazewatsky
- License: BSD
- Source: git https://github.com/DLu/rwi_ros.git (branch: hydro)
Contents
Overview
This package defines an actionlib interface for controlling PTUs. This interface allows PTUs to be controlled by specifing either absolute pan/tilt angles, or pan/tilt velocities (if supported in hardware).
An actionlib server using this interface is also provided for controlling and tracking the Logitech Orbit AF camera.
Python Action Client Example
The following code reads pan and tilt angles from the command line, starts an action client, sends the desired pan/tilt angles, and waits for any feedback.
1 #!/usr/env/bin python
2 import roslib; roslib.load_manifest('ptu_control')
3 import rospy
4 import ptu_control.msg
5 import actionlib
6 import sys
7
8 def ptu_action_test():
9 client = actionlib.SimpleActionClient('SetPTUState', ptu_control.msg.PtuGotoAction)
10 client.wait_for_server()
11 goal = ptu_control.msg.PtuGotoGoal(pan=float(sys.argv[1]), tilt=float(sys.argv[2]))
12 client.send_goal(goal)
13 client.wait_for_result()
14 return client.get_result()
15
16 if __name__ == '__main__':
17 rospy.init_node('action_test')
18 result = ptu_action_test()
19 print result