Controls panning and tilting of CARL's cameras. More...
#include <servo_pan_tilt.h>
Public Member Functions | |
| servoPanTilt () | |
| Constructor. | |
Private Member Functions | |
| void | backJointStateCallback (const sensor_msgs::JointState::ConstPtr &msg) |
| float | calculateLookAngle (float x, float z) |
| Determine the servo command angle to look at a given point with the Asus servo. | |
| void | frontJointStateCallback (const sensor_msgs::JointState::ConstPtr &msg) |
| bool | lookAtFrame (carl_dynamixel::LookAtFrame::Request &req, carl_dynamixel::LookAtFrame::Response &res) |
| Callback for pointing the servo at a point. | |
| bool | lookAtPoint (carl_dynamixel::LookAtPoint::Request &req, carl_dynamixel::LookAtPoint::Response &res) |
| Callback for pointing the servo at a point. | |
| void | panCallback (const std_msgs::Float64::ConstPtr &msg) |
| void | tiltCallback (const std_msgs::Float64::ConstPtr &msg) |
Private Attributes | |
| ros::Publisher | asusServoControllerPublisher |
| ros::Subscriber | backJointStateSubscriber |
| float | backServoPos |
| ros::Publisher | creativeServoControllerPublisher |
| ros::Subscriber | frontJointStateSubscriber |
| float | frontServoPos |
| ros::ServiceServer | lookAtFrameServer |
| ros::ServiceServer | lookAtPointServer |
| ros::NodeHandle | node |
| ros::Subscriber | panCommandSubscriber |
| tf::TransformListener | tfListener |
| ros::Subscriber | tiltCommandSubscriber |
Controls panning and tilting of CARL's cameras.
servoPanTilt creates a ROS node that allows pan and tilt control of the servos that CARL's cameras are mounted on.
Definition at line 32 of file servo_pan_tilt.h.
Constructor.
Definition at line 5 of file servo_pan_tilt.cpp.
| void servoPanTilt::backJointStateCallback | ( | const sensor_msgs::JointState::ConstPtr & | msg | ) | [private] |
Back servo joint state callback.
| msg | servo joint states |
Definition at line 23 of file servo_pan_tilt.cpp.
| float servoPanTilt::calculateLookAngle | ( | float | x, |
| float | z | ||
| ) | [private] |
Determine the servo command angle to look at a given point with the Asus servo.
| x | forward distance from camera |
| z | height distance from camera |
Definition at line 78 of file servo_pan_tilt.cpp.
| void servoPanTilt::frontJointStateCallback | ( | const sensor_msgs::JointState::ConstPtr & | msg | ) | [private] |
Front servo joint state callback.
| msg | servo joint states |
Definition at line 28 of file servo_pan_tilt.cpp.
| bool servoPanTilt::lookAtFrame | ( | carl_dynamixel::LookAtFrame::Request & | req, |
| carl_dynamixel::LookAtFrame::Response & | res | ||
| ) | [private] |
Callback for pointing the servo at a point.
| req | service request |
| res | empty service response |
Definition at line 66 of file servo_pan_tilt.cpp.
| bool servoPanTilt::lookAtPoint | ( | carl_dynamixel::LookAtPoint::Request & | req, |
| carl_dynamixel::LookAtPoint::Response & | res | ||
| ) | [private] |
Callback for pointing the servo at a point.
| req | service request |
| res | empty service response |
Definition at line 53 of file servo_pan_tilt.cpp.
| void servoPanTilt::panCallback | ( | const std_msgs::Float64::ConstPtr & | msg | ) | [private] |
Servo pan command callback
| msg | message denoting the desired pan velocity (rad/s) |
Definition at line 43 of file servo_pan_tilt.cpp.
| void servoPanTilt::tiltCallback | ( | const std_msgs::Float64::ConstPtr & | msg | ) | [private] |
Servo tilt command callback
| msg | message denoting the desired tilt velocity (rad/s) |
Definition at line 33 of file servo_pan_tilt.cpp.
position command for the asus servo
Definition at line 93 of file servo_pan_tilt.h.
back (asus) servo joint state subscrbier
Definition at line 97 of file servo_pan_tilt.h.
float servoPanTilt::backServoPos [private] |
the current position of the back servo
Definition at line 105 of file servo_pan_tilt.h.
position command for the creative camera servo
Definition at line 94 of file servo_pan_tilt.h.
front (creative) servo joint state subscrbier
Definition at line 98 of file servo_pan_tilt.h.
float servoPanTilt::frontServoPos [private] |
the current position of the front servo
Definition at line 106 of file servo_pan_tilt.h.
Definition at line 101 of file servo_pan_tilt.h.
Definition at line 100 of file servo_pan_tilt.h.
ros::NodeHandle servoPanTilt::node [private] |
a handle for this ROS node
Definition at line 91 of file servo_pan_tilt.h.
subscriber for camera pan commands
Definition at line 96 of file servo_pan_tilt.h.
Definition at line 103 of file servo_pan_tilt.h.
subscriber for camera tilt commands
Definition at line 95 of file servo_pan_tilt.h.