rapid
A ROS robotics library.
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Pages
gripper.h
Go to the documentation of this file.
1 #ifndef _RAPID_PR2_GRIPPER_H_
2 #define _RAPID_PR2_GRIPPER_H_
3 
4 #include "actionlib/client/simple_action_client.h"
5 #include "boost/shared_ptr.hpp"
6 #include "pr2_controllers_msgs/Pr2GripperCommandAction.h"
7 
8 namespace rapid {
9 namespace pr2 {
10 static const char kLeftGripperAction[] = "/l_gripper_controller/gripper_action";
11 static const char kRightGripperAction[] =
12  "/r_gripper_controller/gripper_action";
13 
24 class Gripper {
25  public:
27  static Gripper Left();
28 
30  static Gripper Right();
31 
35  bool StartOpening();
36 
40  bool StartClosing();
41 
47  bool StartClosing(double max_effort);
48 
50  bool IsDone() const;
51 
53  void Cancel();
54 
55  private:
56  explicit Gripper(bool is_left);
57 
58  boost::shared_ptr<actionlib::SimpleActionClient<
59  pr2_controllers_msgs::Pr2GripperCommandAction> >
60  client_;
61 };
62 } // namespace pr2
63 } // namespace rapid
64 
65 #endif // _RAPID_PR2_GRIPPER_H_
static Gripper Left()
Returns a Gripper object for the PR2's left gripper.
void Cancel()
Stops the gripper's opening or closing movement.
static const char kLeftGripperAction[]
Definition: gripper.h:10
static const char kRightGripperAction[]
Definition: gripper.h:11
bool StartOpening()
Starts opening the gripper.
bool IsDone() const
Returns true if the gripper is done opening or closing.
static Gripper Right()
Returns a Gripper object for the PR2's right gripper.
bool StartClosing()
Starts closing the gripper.
High-level interface for a PR2's gripper.
Definition: gripper.h:24