1 #ifndef _RAPID_PR2_TORSO_H_
2 #define _RAPID_PR2_TORSO_H_
4 #include "actionlib/client/simple_action_client.h"
5 #include "control_msgs/FollowJointTrajectoryAction.h"
52 static const double kMaxVel;
53 static const char kTorsoJoint[];
54 actionlib::SimpleActionClient<control_msgs::FollowJointTrajectoryAction>
59 static const char kTorsoAction[] =
"/torso_controller/follow_joint_trajectory";
62 const double Torso::kMaxVel = 0.013;
63 const char Torso::kTorsoJoint[] =
"torso_lift_joint";
67 #endif // _RAPID_PR2_TORSO_H_
static const char kTorsoAction[]
bool IsDone() const
Returns true if the torso is done moving.
void Cancel()
Stops moving the torso.
static const double kMinHeight
High-level interface for the PR2's torso.
static const double kMaxHeight
The minimum torso height.
Tracks the latest joint states.
bool StartMoving(double height)
Starts moving the torso.
Torso(const rapid::JointStateReader &js_reader)
The maximum torso height.