rapid
A ROS robotics library.
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Pages
arm.h
Go to the documentation of this file.
1 #ifndef _RAPID_MANIPULATION_ARM_H_
2 #define _RAPID_MANIPULATION_ARM_H_
3 
4 #include "boost/shared_ptr.hpp"
5 #include "geometry_msgs/PoseStamped.h"
6 #include "gmock/gmock.h"
7 #include "moveit/move_group_interface/move_group.h"
8 #include "ros/ros.h"
9 
11 
12 namespace rapid {
13 namespace manipulation {
14 // Interface for sending arm navigation goals.
15 //
16 // Sample usage:
17 // MoveGroup group("right_arm");
18 // ArmInterface* right_arm = new MoveItArm(group);
19 // right_arm->MoveToPoseGoal(pose, false);
20 class ArmInterface {
21  public:
22  virtual ~ArmInterface() {}
23 
24  // Sends a goal for the end effector to move to the given pose.
25  // refresh_point_cloud tells trajopt to capture a new point cloud before
26  // planning. Otherwise, it uses a previously captured point cloud. This arg
27  // has not effect on MoveIt.
28  virtual bool MoveToPoseGoal(const geometry_msgs::PoseStamped& pose) const = 0;
29 };
30 
31 // Implements arm navigation using MoveIt.
32 class MoveItArm : public ArmInterface {
33  private:
34  boost::shared_ptr<moveit::planning_interface::MoveGroup> group_;
35 
36  public:
37  MoveItArm(boost::shared_ptr<moveit::planning_interface::MoveGroup> group);
38  MoveItArm(ArmId id);
40  bool MoveToPoseGoal(const geometry_msgs::PoseStamped& pose) const;
41 };
42 
43 class MockArm : public ArmInterface {
44  public:
45  MockArm() {}
47  bool(const geometry_msgs::PoseStamped& pose));
48 };
49 } // namespace manipulation
50 } // namespace rapid
51 
52 #endif // _RAPID_MANIPULATION_ARM_H_
virtual bool MoveToPoseGoal(const geometry_msgs::PoseStamped &pose) const =0
MOCK_CONST_METHOD1(MoveToPoseGoal, bool(const geometry_msgs::PoseStamped &pose))
bool MoveToPoseGoal(const geometry_msgs::PoseStamped &pose) const
MoveItArm(boost::shared_ptr< moveit::planning_interface::MoveGroup > group)