High-level interface for the PR2's head.
More...
#include <head.h>
High-level interface for the PR2's head.
Example:
while (ros::ok() && !head.IsDone()) {
ros::spinOnce();
}
Definition at line 26 of file head.h.
The maximum tilt angle, in radians.
Constructor.
void rapid::pr2::Head::Cancel |
( |
| ) |
|
bool rapid::pr2::Head::IsDone |
( |
| ) |
const |
Returns true if the head is done moving.
bool rapid::pr2::Head::StartPanTilt |
( |
const Radians & |
pan, |
|
|
const Radians & |
tilt |
|
) |
| |
Starts moving the head to the given pan/tilt angle.
The head will move at half the maximum velocity towards the goal. If this method fails to connect to the head action server or read the current head joint values, it will return false.
- Parameters
-
- Returns
- true if head goal was sent successfully, false otherwise.
const double rapid::pr2::Head::kMaxPanDegrees = 168 |
|
static |
The minimum pan angle, in degrees.
Definition at line 29 of file head.h.
const double rapid::pr2::Head::kMaxPanRadians = 168 * M_PI / 180 |
|
static |
The minimum pan angle, in radians.
Definition at line 33 of file head.h.
const double rapid::pr2::Head::kMaxTiltDegrees = 60 |
|
static |
The minimum tilt angle, in degrees.
Definition at line 31 of file head.h.
const double rapid::pr2::Head::kMaxTiltRadians = 60 * M_PI / 180 |
|
static |
The minimum tilt angle, in radians.
Definition at line 35 of file head.h.
const double rapid::pr2::Head::kMinPanDegrees = -168 |
|
static |
const double rapid::pr2::Head::kMinPanRadians = -168 * M_PI / 180 |
|
static |
The maximum tilt angle, in degrees.
Definition at line 32 of file head.h.
const double rapid::pr2::Head::kMinTiltDegrees = -30 |
|
static |
The maximum pan angle, in degrees.
Definition at line 30 of file head.h.
const double rapid::pr2::Head::kMinTiltRadians = -30 * M_PI / 180 |
|
static |
The maximum pan angle, in radians.
Definition at line 34 of file head.h.
The documentation for this class was generated from the following file:
- rapid_pr2/include/rapid_pr2/head.h