Go to the documentation of this file.
38 #include <pr2_controllers_msgs/Pr2GripperCommandAction.h>
39 #include <pr2_gripper_sensor_msgs/PR2GripperFindContactAction.h>
40 #include <pr2_gripper_sensor_msgs/PR2GripperSlipServoAction.h>
70 ROS_INFO(
"Waiting for the r_gripper_sensor_controller/gripper_action action server to come up");
74 ROS_INFO(
"Waiting for the r_gripper_sensor_controller/find_contact action server to come up");
78 ROS_INFO(
"Waiting for the r_gripper_sensor_controller/slip_servo action server to come up");
91 pr2_controllers_msgs::Pr2GripperCommandGoal
open;
92 open.command.position = 0.09;
100 ROS_INFO(
"The gripper failed to open.");
108 pr2_gripper_sensor_msgs::PR2GripperFindContactGoal findTwo;
109 findTwo.command.contact_conditions = findTwo.command.BOTH;
110 findTwo.command.zero_fingertip_sensors =
true;
112 ROS_INFO(
"Sending find 2 contact goal");
123 ROS_INFO(
"The gripper did not find a contact.");
129 pr2_gripper_sensor_msgs::PR2GripperSlipServoGoal slip_goal;
137 ROS_INFO(
"The gripper did not find a contact or could not maintain contact force.");
141 int main(
int argc,
char** argv){
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
actionlib::SimpleActionClient< pr2_controllers_msgs::Pr2GripperCommandAction > GripperClient
SlipClient * slip_client_
actionlib::SimpleActionClient< pr2_gripper_sensor_msgs::PR2GripperSlipServoAction > SlipClient
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
ResultConstPtr getResult() const
int main(int argc, char **argv)
bool waitForResult(const ros::Duration &timeout=ros::Duration(0, 0))
ContactClient * contact_client_
GripperClient * gripper_client_
SimpleClientGoalState getState() const
actionlib::SimpleActionClient< pr2_gripper_sensor_msgs::PR2GripperFindContactAction > ContactClient