rapid
A ROS robotics library.
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Pages
torso.h
Go to the documentation of this file.
1 #ifndef _RAPID_PR2_TORSO_H_
2 #define _RAPID_PR2_TORSO_H_
3 
4 #include "actionlib/client/simple_action_client.h"
5 #include "control_msgs/FollowJointTrajectoryAction.h"
7 
8 namespace rapid {
9 namespace pr2 {
25 class Torso {
26  public:
27  static const double kMinHeight;
28  static const double kMaxHeight;
29 
31  explicit Torso(const rapid::JointStateReader& js_reader);
32 
43  bool StartMoving(double height);
44 
46  bool IsDone() const;
47 
49  void Cancel();
50 
51  private:
52  static const double kMaxVel;
53  static const char kTorsoJoint[];
54  actionlib::SimpleActionClient<control_msgs::FollowJointTrajectoryAction>
55  client_;
56  const rapid::JointStateReader& js_reader_;
57 };
58 
59 static const char kTorsoAction[] = "/torso_controller/follow_joint_trajectory";
60 const double Torso::kMinHeight = 0;
61 const double Torso::kMaxHeight = 0.31;
62 const double Torso::kMaxVel = 0.013;
63 const char Torso::kTorsoJoint[] = "torso_lift_joint";
64 } // namespace pr2
65 } // namespace rapid
66 
67 #endif // _RAPID_PR2_TORSO_H_
static const char kTorsoAction[]
Definition: torso.h:59
bool IsDone() const
Returns true if the torso is done moving.
void Cancel()
Stops moving the torso.
static const double kMinHeight
Definition: torso.h:27
High-level interface for the PR2's torso.
Definition: torso.h:25
static const double kMaxHeight
The minimum torso height.
Definition: torso.h:28
Tracks the latest joint states.
bool StartMoving(double height)
Starts moving the torso.
Torso(const rapid::JointStateReader &js_reader)
The maximum torso height.