27 #ifndef KATANA_GRIPPER_GRASP_CONTROLLER_H_ 28 #define KATANA_GRIPPER_GRASP_CONTROLLER_H_ 34 #include <control_msgs/GripperCommandAction.h> 35 #include <control_msgs/QueryTrajectoryState.h> 61 void executeCB(
const control_msgs::GripperCommandGoalConstPtr &goal);
63 bool serviceCallback(control_msgs::QueryTrajectoryState::Request &request,
64 control_msgs::QueryTrajectoryState::Response &response);
void executeCB(const control_msgs::GripperCommandGoalConstPtr &goal)
double goal_threshold_
A difference in desired goal angle and actual goal angle above this value indicates that the goal was...
boost::shared_ptr< AbstractKatana > katana_
actionlib::SimpleActionServer< control_msgs::GripperCommandAction > * action_server_
Action server for the grasp posture action.
virtual ~KatanaGripperGraspController()
KatanaGripperGraspController(boost::shared_ptr< AbstractKatana > katana)
ros::ServiceServer query_srv_
Server for the posture query service.
bool serviceCallback(control_msgs::QueryTrajectoryState::Request &request, control_msgs::QueryTrajectoryState::Response &response)