rapid
A ROS robotics library.
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Pages
rapid::pr2::Head Class Reference

High-level interface for the PR2's head. More...

#include <head.h>

Public Member Functions

 Head (const rapid::JointStateReader &js_reader)
 The maximum tilt angle, in radians. More...
 
bool StartPanTilt (const Radians &pan, const Radians &tilt)
 Starts moving the head to the given pan/tilt angle. More...
 
bool IsDone () const
 Returns true if the head is done moving. More...
 
void Cancel ()
 Stops moving the head. More...
 

Static Public Attributes

static const double kMinPanDegrees = -168
 
static const double kMaxPanDegrees = 168
 The minimum pan angle, in degrees. More...
 
static const double kMinTiltDegrees = -30
 The maximum pan angle, in degrees. More...
 
static const double kMaxTiltDegrees = 60
 The minimum tilt angle, in degrees. More...
 
static const double kMinPanRadians = -168 * M_PI / 180
 The maximum tilt angle, in degrees. More...
 
static const double kMaxPanRadians = 168 * M_PI / 180
 The minimum pan angle, in radians. More...
 
static const double kMinTiltRadians = -30 * M_PI / 180
 The maximum pan angle, in radians. More...
 
static const double kMaxTiltRadians = 60 * M_PI / 180
 The minimum tilt angle, in radians. More...
 

Detailed Description

High-level interface for the PR2's head.

Example:

#include "rapid_pr2/head.h"
js_reader.Start();
rapid::pr2::Head head(js_reader);
head.StartPanTilt(rapid::Degrees(0), rapid::Degrees(45));
while (ros::ok() && !head.IsDone()) {
ros::spinOnce();
}

Definition at line 26 of file head.h.

Constructor & Destructor Documentation

rapid::pr2::Head::Head ( const rapid::JointStateReader js_reader)
explicit

The maximum tilt angle, in radians.

Constructor.

Member Function Documentation

void rapid::pr2::Head::Cancel ( )

Stops moving the head.

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
[in]panThe pan angle, given as rapid::Degrees or rapid::Radians.
[in]tiltThe tilt angle, given as rapid::Degrees or rapid::Radians.
Returns
true if head goal was sent successfully, false otherwise.

Member Data Documentation

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

Definition at line 28 of file head.h.

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: