38 #include <pr2_controllers_msgs/Pr2GripperCommandAction.h> 39 #include <pr2_gripper_sensor_msgs/PR2GripperFindContactAction.h> 40 #include <pr2_gripper_sensor_msgs/PR2GripperSlipServoAction.h> 63 gripper_client_ =
new GripperClient(
"r_gripper_sensor_controller/gripper_action",
true);
64 contact_client_ =
new ContactClient(
"r_gripper_sensor_controller/find_contact",
true);
65 slip_client_ =
new SlipClient(
"r_gripper_sensor_controller/slip_servo",
true);
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");
117 ROS_INFO(
"Contact found. Left: %d, Right: %d", contact_client_->
getResult()->data.left_fingertip_pad_contact,
118 contact_client_->
getResult()->data.right_fingertip_pad_contact);
119 ROS_INFO(
"Contact force. Left: %f, Right: %f", contact_client_->
getResult()->data.left_fingertip_pad_force,
120 contact_client_->
getResult()->data.right_fingertip_pad_force);
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){
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
bool waitForResult(const ros::Duration &timeout=ros::Duration(0, 0))
actionlib::SimpleActionClient< pr2_gripper_sensor_msgs::PR2GripperFindContactAction > ContactClient
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
actionlib::SimpleActionClient< pr2_gripper_sensor_msgs::PR2GripperSlipServoAction > SlipClient
ContactClient * contact_client_
actionlib::SimpleActionClient< pr2_controllers_msgs::Pr2GripperCommandAction > GripperClient
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
GripperClient * gripper_client_
SlipClient * slip_client_
SimpleClientGoalState getState() const
ResultConstPtr getResult() const