38 #include <pr2_controllers_msgs/Pr2GripperCommandAction.h> 39 #include <pr2_gripper_sensor_msgs/PR2GripperFindContactAction.h> 59 gripper_client_ =
new GripperClient(
"r_gripper_sensor_controller/gripper_action",
true);
60 contact_client_ =
new ContactClient(
"r_gripper_sensor_controller/find_contact",
true);
64 ROS_INFO(
"Waiting for the r_gripper_sensor_controller/gripper_action action server to come up");
68 ROS_INFO(
"Waiting for the r_gripper_sensor_controller/find_contact action server to come up");
79 pr2_controllers_msgs::Pr2GripperCommandGoal
open;
80 open.command.position = 0.08;
81 open.command.max_effort = -1.0;
89 ROS_INFO(
"The gripper failed to open.");
94 pr2_gripper_sensor_msgs::PR2GripperFindContactGoal findOne;
95 findOne.command.contact_conditions = findOne.command.EITHER;
96 findOne.command.zero_fingertip_sensors =
true;
99 ROS_INFO(
"Sending find 1 contact goal");
104 ROS_INFO(
"Contact found. Left: %d, Right: %d", contact_client_->
getResult()->data.left_fingertip_pad_contact,
105 contact_client_->
getResult()->data.right_fingertip_pad_contact);
106 ROS_INFO(
"Contact force. Left: %f, Right: %f", contact_client_->
getResult()->data.left_fingertip_pad_force,
107 contact_client_->
getResult()->data.right_fingertip_pad_force);
110 ROS_INFO(
"The gripper did not find a contact.");
117 pr2_gripper_sensor_msgs::PR2GripperFindContactGoal findTwo;
118 findTwo.command.contact_conditions = findTwo.command.BOTH;
119 findTwo.command.zero_fingertip_sensors =
true;
122 ROS_INFO(
"Sending find 2 contact goal");
127 ROS_INFO(
"Contact found. Left: %d, Right: %d", contact_client_->
getResult()->data.left_fingertip_pad_contact,
128 contact_client_->
getResult()->data.right_fingertip_pad_contact);
129 ROS_INFO(
"Contact force. Left: %f, Right: %f", contact_client_->
getResult()->data.left_fingertip_pad_force,
130 contact_client_->
getResult()->data.right_fingertip_pad_force);
133 ROS_INFO(
"The gripper did not find a contact or could not maintain contact force.");
137 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))
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ContactClient * contact_client_
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
GripperClient * gripper_client_
SimpleClientGoalState getState() const
ResultConstPtr getResult() const