rapid
A ROS robotics library.
All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Pages
head.h
Go to the documentation of this file.
1 #ifndef _RAPID_PR2_HEAD_H_
2 #define _RAPID_PR2_HEAD_H_
3 
4 #include "actionlib/client/simple_action_client.h"
5 #include "control_msgs/FollowJointTrajectoryAction.h"
7 #include "rapid_utils/deg_rad.h"
8 
9 namespace rapid {
10 namespace pr2 {
26 class Head {
27  public:
28  static const double kMinPanDegrees;
29  static const double kMaxPanDegrees;
30  static const double kMinTiltDegrees;
31  static const double kMaxTiltDegrees;
32  static const double kMinPanRadians;
33  static const double kMaxPanRadians;
34  static const double kMinTiltRadians;
35  static const double kMaxTiltRadians;
36 
38  explicit Head(const rapid::JointStateReader& js_reader);
39 
50  bool StartPanTilt(const Radians& pan, const Radians& tilt);
51 
53  bool IsDone() const;
54 
56  void Cancel();
57 
58  private:
59  static const char kPanTiltAction[];
60  static const char kPanJoint[];
61  static const char kTiltJoint[];
62  static const double kMaxPanVel; // In radians/s
63  static const double kMaxTiltVel; // In radians/s
64  actionlib::SimpleActionClient<control_msgs::FollowJointTrajectoryAction>
65  client_;
66  const rapid::JointStateReader& js_reader_;
67 };
68 
69 const double Head::kMinPanDegrees = -168;
70 const double Head::kMaxPanDegrees = 168;
71 const double Head::kMinTiltDegrees = -30;
72 const double Head::kMaxTiltDegrees = 60;
73 const double Head::kMinPanRadians = -168 * M_PI / 180;
74 const double Head::kMaxPanRadians = 168 * M_PI / 180;
75 const double Head::kMinTiltRadians = -30 * M_PI / 180;
76 const double Head::kMaxTiltRadians = 60 * M_PI / 180;
77 
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;
84 } // namespace pr2
85 } // namespace rapid
86 
87 #endif // _RAPID_PR2_HEAD_H_
Type for angles measured in radians.
Definition: deg_rad.h:43
static const double kMaxTiltRadians
The minimum tilt angle, in radians.
Definition: head.h:35
static const double kMinPanDegrees
Definition: head.h:28
static const double kMaxPanRadians
The minimum pan angle, in radians.
Definition: head.h:33
static const double kMaxTiltDegrees
The minimum tilt angle, in degrees.
Definition: head.h:31
static const double kMaxPanDegrees
The minimum pan angle, in degrees.
Definition: head.h:29
static const double kMinTiltDegrees
The maximum pan angle, in degrees.
Definition: head.h:30
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.
Definition: head.h:26
static const double kMinTiltRadians
The maximum pan angle, in radians.
Definition: head.h:34
Tracks the latest joint states.
static const double kMinPanRadians
The maximum tilt angle, in degrees.
Definition: head.h:32
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.