1 #ifndef _RAPID_MANIPULATION_ARM_H_
2 #define _RAPID_MANIPULATION_ARM_H_
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"
13 namespace manipulation {
28 virtual bool MoveToPoseGoal(
const geometry_msgs::PoseStamped& pose)
const = 0;
34 boost::shared_ptr<moveit::planning_interface::MoveGroup> group_;
37 MoveItArm(boost::shared_ptr<moveit::planning_interface::MoveGroup> group);
47 bool(
const geometry_msgs::PoseStamped& pose));
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)