38 #include <pr2_controllers_msgs/Pr2GripperCommandAction.h> 39 #include <pr2_gripper_sensor_msgs/PR2GripperFindContactAction.h> 40 #include <pr2_gripper_sensor_msgs/PR2GripperForceServoAction.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 force_client_ =
new ForceClient(
"r_gripper_sensor_controller/force_servo",
true);
69 ROS_INFO(
"Waiting for the r_gripper_sensor_controller/gripper_action action server to come up");
73 ROS_INFO(
"Waiting for the r_gripper_sensor_controller/find_contact action server to come up");
77 ROS_INFO(
"Waiting for the r_gripper_sensor_controller/force_servo action server to come up");
89 pr2_controllers_msgs::Pr2GripperCommandGoal
open;
90 open.command.position = 0.08;
91 open.command.max_effort = -1.0;
99 ROS_INFO(
"The gripper failed to open.");
104 pr2_controllers_msgs::Pr2GripperCommandGoal squeeze;
105 squeeze.command.position = 0.0;
106 squeeze.command.max_effort = -1.0;
114 ROS_INFO(
"The gripper failed to close.");
121 pr2_gripper_sensor_msgs::PR2GripperForceServoGoal squeeze;
122 squeeze.command.fingertip_force = holdForce;
128 ROS_INFO(
"Stable force was achieved");
130 ROS_INFO(
"Stable force was NOT achieved");
136 pr2_gripper_sensor_msgs::PR2GripperFindContactGoal findTwo;
137 findTwo.command.contact_conditions = findTwo.command.BOTH;
138 findTwo.command.zero_fingertip_sensors =
true;
141 ROS_INFO(
"Sending find 2 contact goal");
146 ROS_INFO(
"Contact found. Left: %d, Right: %d", contact_client_->
getResult()->data.left_fingertip_pad_contact,
147 contact_client_->
getResult()->data.right_fingertip_pad_contact);
148 ROS_INFO(
"Contact force. Left: %f, Right: %f", contact_client_->
getResult()->data.left_fingertip_pad_force,
149 contact_client_->
getResult()->data.right_fingertip_pad_force);
152 ROS_INFO(
"The gripper did not find a contact or could not maintain contact force.");
156 int main(
int argc,
char** argv){
actionlib::SimpleActionClient< pr2_gripper_sensor_msgs::PR2GripperForceServoAction > ForceClient
actionlib::SimpleActionClient< pr2_gripper_sensor_msgs::PR2GripperFindContactAction > ContactClient
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)
actionlib::SimpleActionClient< pr2_controllers_msgs::Pr2GripperCommandAction > GripperClient
ContactClient * contact_client_
ForceClient * force_client_
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
GripperClient * gripper_client_
int main(int argc, char **argv)
void hold(double holdForce)
SimpleClientGoalState getState() const
ResultConstPtr getResult() const