Go to the documentation of this file.00001 #include <ros/ros.h>
00002 #include <pr2_controllers_msgs/JointTrajectoryAction.h>
00003 #include <actionlib/client/simple_action_client.h>
00004 #include <pr2_controllers_msgs/Pr2GripperCommandAction.h>
00005 #include <gazebo_msgs/BodyRequest.h>
00006 #include <gazebo_msgs/ApplyBodyWrench.h>
00007 #include <gazebo_msgs/SetModelConfiguration.h>
00008 #include <std_srvs/Empty.h>
00009 #include <pr2_mechanism_msgs/SwitchController.h>
00010
00011 typedef actionlib::SimpleActionClient< pr2_controllers_msgs::JointTrajectoryAction > TrajClient;
00012
00013 class RobotArm
00014 {
00015 private:
00016
00017
00018 TrajClient* traj_client_;
00019
00020 public:
00022 RobotArm()
00023 {
00024
00025 traj_client_ = new TrajClient("r_arm_controller/joint_trajectory_action", true);
00026
00027
00028 while(!traj_client_->waitForServer(ros::Duration(5.0))){
00029 ROS_INFO("Waiting for the joint_trajectory_action server");
00030 }
00031 }
00032
00034 ~RobotArm()
00035 {
00036 delete traj_client_;
00037 }
00038
00040 void startTrajectory(pr2_controllers_msgs::JointTrajectoryGoal goal)
00041 {
00042
00043
00044 ros::Duration wait_time(20.0);
00045 actionlib::SimpleClientGoalState state = traj_client_->sendGoalAndWait(goal,wait_time,wait_time);
00046 if (state == actionlib::SimpleClientGoalState::SUCCEEDED)
00047 ROS_INFO("The arm traj finished with state [%s]",state.toString().c_str());
00048 else
00049 ROS_INFO("The arm traj failed with state [%s]",state.toString().c_str());
00050 }
00051
00053
00058 pr2_controllers_msgs::JointTrajectoryGoal armExtensionTrajectory()
00059 {
00060
00061 pr2_controllers_msgs::JointTrajectoryGoal goal;
00062
00063
00064 goal.trajectory.joint_names.push_back("r_shoulder_pan_joint");
00065 goal.trajectory.joint_names.push_back("r_shoulder_lift_joint");
00066 goal.trajectory.joint_names.push_back("r_upper_arm_roll_joint");
00067 goal.trajectory.joint_names.push_back("r_elbow_flex_joint");
00068 goal.trajectory.joint_names.push_back("r_forearm_roll_joint");
00069 goal.trajectory.joint_names.push_back("r_wrist_flex_joint");
00070 goal.trajectory.joint_names.push_back("r_wrist_roll_joint");
00071
00072
00073 goal.trajectory.points.resize(2);
00074
00075
00076
00077 int ind = 0;
00078 goal.trajectory.points[ind].positions.resize(7);
00079 goal.trajectory.points[ind].positions[0] = 0.0;
00080 goal.trajectory.points[ind].positions[1] = 0.0;
00081 goal.trajectory.points[ind].positions[2] = 0.0;
00082 goal.trajectory.points[ind].positions[3] = 0.0;
00083 goal.trajectory.points[ind].positions[4] = 0.0;
00084 goal.trajectory.points[ind].positions[5] = 0.0;
00085 goal.trajectory.points[ind].positions[6] = 0.0;
00086
00087 goal.trajectory.points[ind].time_from_start = ros::Duration(3.0);
00088
00089
00090
00091 ind += 1;
00092 goal.trajectory.points[ind].positions.resize(7);
00093 goal.trajectory.points[ind].positions[0] = 0.0;
00094 goal.trajectory.points[ind].positions[1] = 0.25;
00095 goal.trajectory.points[ind].positions[2] = 0.0;
00096 goal.trajectory.points[ind].positions[3] = 0.0;
00097 goal.trajectory.points[ind].positions[4] = 0.0;
00098 goal.trajectory.points[ind].positions[5] = 0.0;
00099 goal.trajectory.points[ind].positions[6] = 0.0;
00100
00101 goal.trajectory.points[ind].time_from_start = ros::Duration(6.0);
00102
00103
00104 return goal;
00105 }
00106
00108 actionlib::SimpleClientGoalState getState()
00109 {
00110 return traj_client_->getState();
00111 }
00112
00113 };
00114
00115
00116 typedef actionlib::SimpleActionClient<pr2_controllers_msgs::Pr2GripperCommandAction> GripperClient;
00117
00118 class Gripper{
00119 private:
00120 GripperClient* gripper_client_;
00121
00122 public:
00123
00124 Gripper(){
00125
00126
00127
00128 gripper_client_ = new GripperClient("r_gripper_controller/gripper_action", true);
00129
00130
00131 while(!gripper_client_->waitForServer(ros::Duration(30.0))){
00132 ROS_INFO("Waiting for the r_gripper_controller/gripper_action action server to come up");
00133 }
00134 }
00135
00136 ~Gripper(){
00137 delete gripper_client_;
00138 }
00139
00140
00141 void open(){
00142 pr2_controllers_msgs::Pr2GripperCommandGoal open;
00143 open.command.position = 0.08;
00144 open.command.max_effort = 100.0;
00145
00146 ROS_INFO("Sending open goal");
00147 if (gripper_client_->sendGoalAndWait(open,ros::Duration(10.0),ros::Duration(5.0)) == actionlib::SimpleClientGoalState::SUCCEEDED)
00148 ROS_INFO("The gripper opened!");
00149 else
00150 ROS_INFO("The gripper failed to open.");
00151 }
00152
00153
00154 void close(){
00155 pr2_controllers_msgs::Pr2GripperCommandGoal squeeze;
00156 squeeze.command.position = 0.0;
00157 squeeze.command.max_effort = 200.0;
00158
00159 ROS_INFO("Sending squeeze goal");
00160 if (gripper_client_->sendGoalAndWait(squeeze,ros::Duration(5.0),ros::Duration(3.0)) == actionlib::SimpleClientGoalState::SUCCEEDED)
00161 ROS_INFO("The gripper closed!");
00162 else
00163 ROS_INFO("The gripper failed to close.");
00164 gripper_client_->sendGoal(squeeze);
00165 }
00166 };
00167
00168 int main(int argc, char** argv)
00169 {
00170
00171 ros::init(argc, argv, "robot_driver");
00172 ros::NodeHandle rh("");
00173 ros::Duration(1e-9).sleep();
00174
00175
00176 ros::service::waitForService("/gazebo/clear_body_wrenches");
00177 ros::ServiceClient clear_client = rh.serviceClient<gazebo_msgs::BodyRequest>("/gazebo/clear_body_wrenches");
00178 gazebo_msgs::BodyRequest body_request;
00179 body_request.request.body_name = "object_1::coke_can";
00180 clear_client.call(body_request);
00181
00182
00183 std::string switch_controller_srv_name = "/pr2_controller_manager/switch_controller";
00184 ros::service::waitForService(switch_controller_srv_name);
00185 ros::ServiceClient switch_controller_client = rh.serviceClient<pr2_mechanism_msgs::SwitchController>(switch_controller_srv_name);
00186 pr2_mechanism_msgs::SwitchController switch_controller;
00187 switch_controller.request.start_controllers.clear();
00188 switch_controller.request.stop_controllers.push_back("r_arm_controller");
00189 switch_controller.request.strictness = pr2_mechanism_msgs::SwitchControllerRequest::STRICT;
00190 switch_controller_client.call(switch_controller);
00191
00192
00193
00194
00195 std::string psn = "/gazebo/pause_physics";
00196 ros::service::waitForService(psn);
00197 ros::ServiceClient ps_client = rh.serviceClient<std_srvs::Empty>(psn);
00198 std_srvs::Empty ps;
00199 ps_client.call(ps);
00200
00201
00202 std::string smcn = "/gazebo/set_model_configuration";
00203 ros::service::waitForService(smcn);
00204 ros::ServiceClient smc_client = rh.serviceClient<gazebo_msgs::SetModelConfiguration>(smcn);
00205 gazebo_msgs::SetModelConfiguration smc;
00206 smc.request.model_name = "r_arm";
00207 smc.request.urdf_param_name = "robot_description";
00208 smc.request.joint_names.push_back("r_upper_arm_roll_joint");
00209 smc.request.joint_names.push_back("r_shoulder_pan_joint");
00210 smc.request.joint_names.push_back("r_shoulder_lift_joint");
00211 smc.request.joint_names.push_back("r_forearm_roll_joint");
00212 smc.request.joint_names.push_back("r_elbow_flex_joint");
00213 smc.request.joint_names.push_back("r_wrist_flex_joint");
00214 smc.request.joint_names.push_back("r_wrist_roll_joint");
00215 smc.request.joint_positions.push_back(0);
00216 smc.request.joint_positions.push_back(0);
00217 smc.request.joint_positions.push_back(-0.3);
00218 smc.request.joint_positions.push_back(0);
00219 smc.request.joint_positions.push_back(-0.5);
00220 smc.request.joint_positions.push_back(-0.3);
00221 smc.request.joint_positions.push_back(0);
00222 smc_client.call(smc);
00223
00224
00225
00226
00227
00228 std::string upsn = "/gazebo/unpause_physics";
00229 ros::service::waitForService(upsn);
00230 ros::ServiceClient ups_client = rh.serviceClient<std_srvs::Empty>(upsn);
00231 std_srvs::Empty ups;
00232 ups_client.call(ups);
00233
00234 gazebo_msgs::SetModelConfiguration smc1;
00235 smc1.request.model_name = "r_arm";
00236 smc1.request.urdf_param_name = "robot_description";
00237 smc1.request.joint_names.push_back("r_upper_arm_roll_joint");
00238 smc1.request.joint_names.push_back("r_shoulder_pan_joint");
00239 smc1.request.joint_names.push_back("r_shoulder_lift_joint");
00240 smc1.request.joint_names.push_back("r_forearm_roll_joint");
00241 smc1.request.joint_names.push_back("r_elbow_flex_joint");
00242 smc1.request.joint_names.push_back("r_wrist_flex_joint");
00243 smc1.request.joint_names.push_back("r_wrist_roll_joint");
00244 smc1.request.joint_positions.push_back(0);
00245 smc1.request.joint_positions.push_back(0);
00246 smc1.request.joint_positions.push_back(-0.2);
00247 smc1.request.joint_positions.push_back(0);
00248 smc1.request.joint_positions.push_back(-0.3);
00249 smc1.request.joint_positions.push_back(-0.1);
00250 smc1.request.joint_positions.push_back(0);
00251 smc_client.call(smc1);
00252
00253 smc_client.call(smc);
00254
00255 smc_client.call(smc1);
00256
00257 smc_client.call(smc);
00258
00259
00260
00261 switch_controller.request.start_controllers.push_back("r_arm_controller");
00262 switch_controller.request.stop_controllers.clear();
00263 switch_controller_client.call(switch_controller);
00264
00265
00266
00267
00268 std::string rsn = "/gazebo/reset_simulation";
00269 ros::service::waitForService(rsn);
00270 ros::ServiceClient rs_client = rh.serviceClient<std_srvs::Empty>(rsn);
00271 std_srvs::Empty rs;
00272 rs_client.call(rs);
00273
00274 Gripper gripper;
00275 RobotArm arm;
00276
00277
00278 gripper.open();
00279
00280
00281 arm.startTrajectory(arm.armExtensionTrajectory());
00282
00283
00284
00285
00286 gripper.close();
00287
00288
00289 ros::ServiceClient wrench_client = rh.serviceClient<gazebo_msgs::ApplyBodyWrench>("/gazebo/apply_body_wrench");
00290 gazebo_msgs::ApplyBodyWrench wrench;
00291
00292
00293 wrench.request.body_name = "object_1::coke_can";
00294 wrench.request.reference_frame = "world";
00295 wrench.request.wrench.force.z = -20.0;
00296 wrench.request.start_time = ros::Time(0.0);
00297 wrench.request.duration = ros::Duration(-1.0);
00298 wrench_client.call(wrench);
00299
00300
00301
00302 }
00303