45 desired_angle_(0.0), current_angle_(0.0), has_new_desired_angle_(false)
51 std::string query_service_name = root_nh.
resolveName(
"gripper_grasp_status");
53 ROS_INFO_STREAM(
"katana gripper grasp query service started on topic " << query_service_name);
55 std::string gripper_grasp_posture_controller = root_nh.
resolveName(
"gripper_grasp_posture_controller");
59 ROS_INFO_STREAM(
"katana gripper grasp hand posture action server started on topic " << gripper_grasp_posture_controller);
69 ROS_INFO(
"Moving gripper to position: %f", goal->command.position);
71 control_msgs::GripperCommandResult result;
73 result.reached_goal =
false;
74 result.stalled =
false;
76 if(goal->command.position < GRIPPER_CLOSED_ANGLE || goal->command.position > GRIPPER_OPEN_ANGLE)
78 ROS_WARN(
"Goal position (%f) outside gripper range. Or some other stuff happened.", goal->command.position);
88 result.stalled =
true;
93 result.reached_goal =
true;
101 control_msgs::QueryTrajectoryState::Response &response)
103 response.position.resize(1);
virtual ~KatanaGripperGraspController()
std::string resolveName(const std::string &name, bool remap=true) const
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
static const double GRIPPER_OPENING_CLOSING_DURATION
The maximum time it takes to open or close the gripper.
static const double GRIPPER_OPEN_ANGLE
Constants for gripper fully open or fully closed (should be equal to the value in the urdf descriptio...
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)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void setDesiredAngle(double desired_angle)
void executeCB(const control_msgs::GripperCommandGoalConstPtr &goal)
void setAborted(const Result &result=Result(), const std::string &text=std::string(""))
static const double GRIPPER_CLOSED_ANGLE
Constants for gripper fully open or fully closed (should be equal to the value in the urdf descriptio...
#define ROS_INFO_STREAM(args)
KatanaGripperGraspController(ros::NodeHandle private_nodehandle)
bool serviceCallback(control_msgs::QueryTrajectoryState::Request &request, control_msgs::QueryTrajectoryState::Response &response)