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

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

#include <torso.h>

Public Member Functions

 Torso (const rapid::JointStateReader &js_reader)
 The maximum torso height. More...
 
bool StartMoving (double height)
 Starts moving the torso. More...
 
bool IsDone () const
 Returns true if the torso is done moving. More...
 
void Cancel ()
 Stops moving the torso. More...
 

Static Public Attributes

static const double kMinHeight = 0
 
static const double kMaxHeight = 0.31
 The minimum torso height. More...
 

Detailed Description

High-level interface for the PR2's torso.

Example:

js_reader.Start();
rapid::pr2::Torso torso(js_reader);
torso.StartMoving(0.31);
while (ros::ok() && !torso.IsDone()) {
ros::spinOnce();
}

Definition at line 25 of file torso.h.

Constructor & Destructor Documentation

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

The maximum torso height.

Constructor.

Member Function Documentation

void rapid::pr2::Torso::Cancel ( )

Stops moving the torso.

bool rapid::pr2::Torso::IsDone ( ) const

Returns true if the torso is done moving.

bool rapid::pr2::Torso::StartMoving ( double  height)

Starts moving the torso.

The torso will move at its maximum velocity (1.3 cm/s) towards the goal. If this method fails to connect to the torso action server or read the current torso joint value, it will return false.

Parameters
[in]heightThe height move to. The value will be clamped between Torso::kMinHeight and Torso::kMaxHeight.
Returns
true if torso goal was sent successfully, false otherwise.

Member Data Documentation

const double rapid::pr2::Torso::kMaxHeight = 0.31
static

The minimum torso height.

Definition at line 28 of file torso.h.

const double rapid::pr2::Torso::kMinHeight = 0
static

Definition at line 27 of file torso.h.


The documentation for this class was generated from the following file: