Go to the documentation of this file.
38 #include <pr2_controllers_msgs/Pr2GripperCommandAction.h>
39 #include <pr2_gripper_sensor_msgs/PR2GripperReleaseAction.h>
40 #include <pr2_gripper_sensor_msgs/PR2GripperEventDetectorAction.h>
41 #include <std_srvs/Empty.h>
70 ROS_INFO(
"Waiting for the gripper_action action server to come up");
74 ROS_INFO(
"Waiting for the event_detector action server to come up");
84 void open(
double position_open){
86 pr2_controllers_msgs::Pr2GripperCommandGoal
open;
87 open.command.position = position_open;
88 open.command.max_effort = -1.0;
96 void place(
int trigger_conditions,
double acc_trigger,
double slip_trigger){
97 pr2_gripper_sensor_msgs::PR2GripperEventDetectorGoal place_goal;
98 place_goal.command.trigger_conditions = trigger_conditions;
99 place_goal.command.acceleration_trigger_magnitude = acc_trigger;
100 place_goal.command.slip_trigger_magnitude = slip_trigger;
102 ROS_INFO(
"Waiting for object placement contact...");
127 pr2_gripper_sensor_msgs::PR2GripperReleaseFeedback
feedback_;
128 pr2_gripper_sensor_msgs::PR2GripperReleaseResult
result_;
143 void executeCB(
const pr2_gripper_sensor_msgs::PR2GripperReleaseGoalConstPtr &goal)
145 double position_open;
150 bool prempted =
false;
152 gripper.
place(goal->command.event.trigger_conditions, goal->command.event.acceleration_trigger_magnitude, goal->command.event.slip_trigger_magnitude);
166 result_.data.rtstate.realtime_controller_state =
feedback_.data.rtstate.realtime_controller_state;
175 int main(
int argc,
char** argv)
actionlib::SimpleActionClient< pr2_controllers_msgs::Pr2GripperCommandAction > GripperClient
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
pr2_gripper_sensor_msgs::PR2GripperReleaseResult result_
bool getParam(const std::string &key, bool &b) const
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
bool isPreemptRequested()
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
int main(int argc, char **argv)
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
ResultConstPtr getResult() const
EventClient * event_client_
void open(double position_open)
bool waitForResult(const ros::Duration &timeout=ros::Duration(0, 0))
void setPreempted(const Result &result=Result(), const std::string &text=std::string(""))
void place(int trigger_conditions, double acc_trigger, double slip_trigger)
actionlib::SimpleActionServer< pr2_gripper_sensor_msgs::PR2GripperReleaseAction > as_
pr2_gripper_sensor_msgs::PR2GripperReleaseFeedback feedback_
GripperClient * gripper_client_
SimpleClientGoalState getState() const
const std::string & getNamespace() const
PR2GripperReleaseAction(std::string name)
void executeCB(const pr2_gripper_sensor_msgs::PR2GripperReleaseGoalConstPtr &goal)
actionlib::SimpleActionClient< pr2_gripper_sensor_msgs::PR2GripperEventDetectorAction > EventClient
~PR2GripperReleaseAction(void)