1 #ifndef _RAPID_PR2_HEAD_H_
2 #define _RAPID_PR2_HEAD_H_
4 #include "actionlib/client/simple_action_client.h"
5 #include "control_msgs/FollowJointTrajectoryAction.h"
59 static const char kPanTiltAction[];
60 static const char kPanJoint[];
61 static const char kTiltJoint[];
62 static const double kMaxPanVel;
63 static const double kMaxTiltVel;
64 actionlib::SimpleActionClient<control_msgs::FollowJointTrajectoryAction>
78 const char Head::kPanTiltAction[] =
79 "/head_traj_controller/follow_joint_trajectory";
80 const char Head::kPanJoint[] =
"head_pan_joint";
81 const char Head::kTiltJoint[] =
"head_tilt_joint";
82 const double Head::kMaxPanVel = 6;
83 const double Head::kMaxTiltVel = 5;
87 #endif // _RAPID_PR2_HEAD_H_
Type for angles measured in radians.
static const double kMaxTiltRadians
The minimum tilt angle, in radians.
static const double kMinPanDegrees
static const double kMaxPanRadians
The minimum pan angle, in radians.
static const double kMaxTiltDegrees
The minimum tilt angle, in degrees.
static const double kMaxPanDegrees
The minimum pan angle, in degrees.
static const double kMinTiltDegrees
The maximum pan angle, in degrees.
Head(const rapid::JointStateReader &js_reader)
The maximum tilt angle, in radians.
void Cancel()
Stops moving the head.
High-level interface for the PR2's head.
static const double kMinTiltRadians
The maximum pan angle, in radians.
Tracks the latest joint states.
static const double kMinPanRadians
The maximum tilt angle, in degrees.
bool StartPanTilt(const Radians &pan, const Radians &tilt)
Starts moving the head to the given pan/tilt angle.
bool IsDone() const
Returns true if the head is done moving.