rapid
A ROS robotics library.
|
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... | |
High-level interface for the PR2's torso.
Example:
|
explicit |
The maximum torso height.
Constructor.
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.
[in] | height | The height move to. The value will be clamped between Torso::kMinHeight and Torso::kMaxHeight. |
|
static |