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> 68 void getGains(
double &p,
double &i,
double &
d,
double &i_max,
double &i_min);
85 void executeCB(
const control_msgs::GripperCommandGoalConstPtr &goal);
87 bool serviceCallback(control_msgs::QueryTrajectoryState::Request &request,
88 control_msgs::QueryTrajectoryState::Response &response);
bool hasActiveGoal() const
virtual ~KatanaGripperGraspController()
bool has_new_desired_angle_
GRKAPoint getNextDesiredPoint(ros::Time time)
actionlib::SimpleActionServer< control_msgs::GripperCommandAction > * action_server_
Action server for the grasp posture action.
ros::ServiceServer query_srv_
Server for the posture query service.
void getGains(double &p, double &i, double &d, double &i_max, double &i_min)
void setDesiredAngle(double desired_angle)
void executeCB(const control_msgs::GripperCommandGoalConstPtr &goal)
KatanaGripperGraspController(ros::NodeHandle private_nodehandle)
void setCurrentPoint(GRKAPoint point)
double gripper_object_presence_threshold_
A joint angle below this value indicates there is nothing inside the gripper.
bool serviceCallback(control_msgs::QueryTrajectoryState::Request &request, control_msgs::QueryTrajectoryState::Response &response)