00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033 #include <string>
00034 #include <boost/bind.hpp>
00035
00036 #include <pr2_mechanism_msgs/SwitchController.h>
00037 #include <geometry_msgs/Twist.h>
00038 #include <trajectory_msgs/JointTrajectory.h>
00039 #include <kinematics_msgs/GetKinematicSolverInfo.h>
00040 #include <kinematics_msgs/GetPositionFK.h>
00041 #include <kinematics_msgs/GetPositionIK.h>
00042 #include <polled_camera/GetPolledImage.h>
00043
00044 #include "pr2_teleop_general/pr2_teleop_general_commander.h"
00045
00046 static const std::string LEFT_HAND_LINK_TO_TRACK = "l_gripper_palm_link";
00047 static const std::string RIGHT_HAND_LINK_TO_TRACK = "r_gripper_palm_link";
00048
00049 static const double MAX_HEAD_TRACK_SPEED = 2.0;
00050
00051 static const double GRIPPER_CLOSE_POSITION = 0.000;
00052 static const double GRIPPER_CLOSE_MAX_EFFORT = 10000.0;
00053
00054 static const double GRIPPER_OPEN_POSITION = 0.086;
00055 static const double GRIPPER_OPEN_MAX_EFFORT = 10000.0;
00056
00057 static const std::string RIGHT_ARM_MANNEQUIN_CONTROLLER = "r_arm_controller_loose";
00058 static const std::string LEFT_ARM_MANNEQUIN_CONTROLLER = "l_arm_controller_loose";
00059
00060 static const std::string HEAD_MANNEQUIN_CONTROLLER = "head_traj_controller_loose";
00061 static const std::string HEAD_POSITION_CONTROLLER = "head_traj_controller";
00062
00063 static const unsigned int WALK_BUFFER = 10;
00064
00065 GeneralCommander::GeneralCommander(bool control_body,
00066 bool control_head,
00067 bool control_rarm,
00068 bool control_larm,
00069 bool control_prosilica,
00070 std::string arm_controller_name)
00071 : n_(),
00072 control_body_(control_body),
00073 control_head_(control_head),
00074 control_rarm_(control_rarm),
00075 control_larm_(control_larm),
00076 control_prosilica_(control_prosilica)
00077 {
00078
00079 r_arm_controller_name_ = "r_"+arm_controller_name;
00080 l_arm_controller_name_ = "l_"+arm_controller_name;
00081
00082 head_control_mode_ = HEAD_JOYSTICK;
00083
00084 std::string urdf_xml,full_urdf_xml;
00085 n_.param("urdf_xml", urdf_xml, std::string("robot_description"));
00086 if(!n_.getParam(urdf_xml,full_urdf_xml))
00087 {
00088 ROS_ERROR("Could not load the xml from parameter server: %s\n", urdf_xml.c_str());
00089 robot_model_initialized_ = false;
00090 }
00091 else
00092 {
00093 robot_model_.initString(full_urdf_xml);
00094 robot_model_initialized_ = true;
00095 }
00096
00097
00098 switch_controllers_service_ = n_.serviceClient<pr2_mechanism_msgs::SwitchController>("pr2_controller_manager/switch_controller");
00099 joint_state_sub_ = n_.subscribe("joint_states", 1, &GeneralCommander::jointStateCallback, this);
00100 power_board_sub_ = n_.subscribe<pr2_msgs::PowerBoardState>("power_board/state", 1, &GeneralCommander::powerBoardCallback, this);
00101
00102 if(control_head_) {
00103 tilt_laser_service_ = n_.serviceClient<pr2_msgs::SetPeriodicCmd>("laser_tilt_controller/set_periodic_cmd");
00104 head_pub_ = n_.advertise<trajectory_msgs::JointTrajectory>("head_traj_controller/command", 1);
00105 head_track_hand_client_ = new actionlib::SimpleActionClient<pr2_controllers_msgs::PointHeadAction>("/head_traj_controller/point_head_action", true);
00106 while(!head_track_hand_client_->waitForServer(ros::Duration(5.0))){
00107 ROS_INFO("Waiting for the point_head_action server to come up");
00108 }
00109
00110 head_track_hand_client_->cancelAllGoals();
00111 } else {
00112 head_track_hand_client_ = NULL;
00113 }
00114 if(control_body_) {
00115 torso_pub_ = n_.advertise<trajectory_msgs::JointTrajectory>("torso_controller/command", 1);
00116 base_pub_ = n_.advertise<geometry_msgs::Twist>("base_controller/command", 1);
00117 }
00118 if(control_rarm_) {
00119 right_gripper_client_ = new actionlib::SimpleActionClient<pr2_controllers_msgs::Pr2GripperCommandAction>("r_gripper_controller/gripper_action", true);
00120 right_arm_trajectory_client_ = new actionlib::SimpleActionClient<pr2_controllers_msgs::JointTrajectoryAction>(r_arm_controller_name_+"/joint_trajectory_action", true);
00121 right_arm_traj_pub_ = n_.advertise<trajectory_msgs::JointTrajectory>(r_arm_controller_name_+"/command", 1);
00122 while(!right_gripper_client_->waitForServer(ros::Duration(5.0))){
00123 ROS_INFO("Waiting for the right gripper action server to come up");
00124 }
00125 while(!right_arm_trajectory_client_->waitForServer(ros::Duration(5.0))){
00126 ROS_INFO_STREAM("Waiting for the right arm trajectory action server to come up" << r_arm_controller_name_+"/joint_trajectory_action");
00127 }
00128 } else {
00129 right_gripper_client_ = NULL;
00130 right_arm_trajectory_client_ = NULL;
00131 }
00132 if(control_larm_) {
00133 left_gripper_client_ = new actionlib::SimpleActionClient<pr2_controllers_msgs::Pr2GripperCommandAction>("l_gripper_controller/gripper_action", true);
00134 left_arm_trajectory_client_ = new actionlib::SimpleActionClient<pr2_controllers_msgs::JointTrajectoryAction>(l_arm_controller_name_+"/joint_trajectory_action", true);
00135 left_arm_traj_pub_ = n_.advertise<trajectory_msgs::JointTrajectory>(l_arm_controller_name_+"/command", 1);
00136 while(!left_gripper_client_->waitForServer(ros::Duration(5.0))){
00137 ROS_INFO("Waiting for the right gripper action server to come up");
00138 }
00139 while(!left_arm_trajectory_client_->waitForServer(ros::Duration(5.0))){
00140 ROS_INFO_STREAM("Waiting for the left arm trajectory action server to come up");
00141 }
00142 } else {
00143 left_gripper_client_ = NULL;
00144 left_arm_trajectory_client_ = NULL;
00145 }
00146 if(control_larm_ || control_rarm_) {
00147 tuck_arms_client_ = new actionlib::SimpleActionClient<pr2_common_action_msgs::TuckArmsAction>("tuck_arms", true);
00148 } else {
00149 tuck_arms_client_ = NULL;
00150 }
00151
00152 if(control_rarm_) {
00153 ROS_INFO("Waiting for right arm kinematics servers");
00154 ros::service::waitForService("pr2_right_arm_kinematics/get_fk_solver_info");
00155 ros::service::waitForService("pr2_right_arm_kinematics/get_fk");
00156 ros::service::waitForService("pr2_right_arm_kinematics/get_ik");
00157 right_arm_kinematics_solver_client_ = n_.serviceClient<kinematics_msgs::GetKinematicSolverInfo>("pr2_right_arm_kinematics/get_fk_solver_info", true);
00158 right_arm_kinematics_forward_client_ = n_.serviceClient<kinematics_msgs::GetPositionFK>("pr2_right_arm_kinematics/get_fk", true);
00159 right_arm_kinematics_inverse_client_ = n_.serviceClient<kinematics_msgs::GetPositionIK>("pr2_right_arm_kinematics/get_ik", true);
00160 }
00161
00162 if(control_larm_) {
00163 ROS_INFO("Waiting for left arm kinematics servers");
00164 ros::service::waitForService("pr2_left_arm_kinematics/get_fk");
00165 ros::service::waitForService("pr2_left_arm_kinematics/get_fk_solver_info");
00166 ros::service::waitForService("pr2_left_arm_kinematics/get_ik");
00167 left_arm_kinematics_solver_client_ = n_.serviceClient<kinematics_msgs::GetKinematicSolverInfo>("pr2_left_arm_kinematics/get_fk_solver_info", true);
00168 left_arm_kinematics_forward_client_ = n_.serviceClient<kinematics_msgs::GetPositionFK>("pr2_left_arm_kinematics/get_fk", true);
00169 left_arm_kinematics_inverse_client_ = n_.serviceClient<kinematics_msgs::GetPositionIK>("pr2_left_arm_kinematics/get_ik", true);
00170 }
00171
00172
00173 if(control_prosilica_) {
00174 ros::service::waitForService("prosilica/request_image");
00175 prosilica_polling_client_ = n_.serviceClient<polled_camera::GetPolledImage>("prosilica/request_image", true);
00176 }
00177
00178 right_walk_along_pose_.push_back(.049);
00179 right_walk_along_pose_.push_back(-.116);
00180 right_walk_along_pose_.push_back(.036);
00181 right_walk_along_pose_.push_back(-1.272);
00182 right_walk_along_pose_.push_back(-.084);
00183 right_walk_along_pose_.push_back(-.148);
00184 right_walk_along_pose_.push_back(-0.027);
00185
00186 left_walk_along_pose_.push_back(0.0);
00187 left_walk_along_pose_.push_back(-.149);
00188 left_walk_along_pose_.push_back(.085);
00189 left_walk_along_pose_.push_back(-1.234);
00190 left_walk_along_pose_.push_back(0.030);
00191 left_walk_along_pose_.push_back(-.141);
00192 left_walk_along_pose_.push_back(3.114);
00193
00194 head_nod_traj_.joint_names.push_back("head_pan_joint");
00195 head_nod_traj_.joint_names.push_back("head_tilt_joint");
00196 head_nod_traj_.points.resize(3);
00197 head_nod_traj_.points[0].positions.push_back(0.0);
00198 head_nod_traj_.points[0].positions.push_back(-0.2);
00199 head_nod_traj_.points[0].velocities.push_back(0.0);
00200 head_nod_traj_.points[0].velocities.push_back(0.0);
00201 head_nod_traj_.points[0].time_from_start = ros::Duration(0.5);
00202
00203 head_nod_traj_.points[1].positions.push_back(0.0);
00204 head_nod_traj_.points[1].positions.push_back(0.2);
00205 head_nod_traj_.points[1].velocities.push_back(0.0);
00206 head_nod_traj_.points[1].velocities.push_back(0.0);
00207 head_nod_traj_.points[1].time_from_start = ros::Duration(1.0);
00208
00209 head_nod_traj_.points[2].positions.push_back(0.0);
00210 head_nod_traj_.points[2].positions.push_back(0.0);
00211 head_nod_traj_.points[2].velocities.push_back(0.0);
00212 head_nod_traj_.points[2].velocities.push_back(0.0);
00213 head_nod_traj_.points[2].time_from_start = ros::Duration(1.5);
00214
00215 head_shake_traj_.joint_names.push_back("head_pan_joint");
00216 head_shake_traj_.joint_names.push_back("head_tilt_joint");
00217 head_shake_traj_.points.resize(3);
00218 head_shake_traj_.points[0].positions.push_back(.62);
00219 head_shake_traj_.points[0].positions.push_back(0.0);
00220 head_shake_traj_.points[0].velocities.push_back(0.0);
00221 head_shake_traj_.points[0].velocities.push_back(0.0);
00222 head_shake_traj_.points[0].time_from_start = ros::Duration(0.5);
00223
00224 head_shake_traj_.points[1].positions.push_back(-.62);
00225 head_shake_traj_.points[1].positions.push_back(0.0);
00226 head_shake_traj_.points[1].velocities.push_back(0.0);
00227 head_shake_traj_.points[1].velocities.push_back(0.0);
00228 head_shake_traj_.points[1].time_from_start = ros::Duration(1.0);
00229
00230 head_shake_traj_.points[2].positions.push_back(0.0);
00231 head_shake_traj_.points[2].positions.push_back(0.0);
00232 head_shake_traj_.points[2].velocities.push_back(0.0);
00233 head_shake_traj_.points[2].velocities.push_back(0.0);
00234 head_shake_traj_.points[2].time_from_start = ros::Duration(1.5);
00235
00236
00237 right_arm_control_mode_ = ARM_MANNEQUIN_MODE;
00238 left_arm_control_mode_ = ARM_MANNEQUIN_MODE;
00239 setArmMode(ARMS_BOTH, ARM_POSITION_CONTROL);
00240 head_control_mode_ = HEAD_MANNEQUIN;
00241 if(control_head_) {
00242 setHeadMode(HEAD_JOYSTICK);
00243 laser_control_mode_ = LASER_TILT_OFF;
00244 }
00245
00246
00247 laser_slow_period_ = 10;
00248 laser_slow_amplitude_ = .75;
00249 laser_slow_offset_ = .25;
00250
00251
00252 laser_fast_period_ = 2;
00253 laser_fast_amplitude_ = .78;
00254 laser_fast_offset_ = .3;
00255
00256 last_right_wrist_goal_stamp_ = ros::Time::now();
00257 last_left_wrist_goal_stamp_ = ros::Time::now();
00258
00259 last_torso_vel_ = 0.0;
00260 walk_along_ok_ = false;
00261 }
00262
00263 GeneralCommander::~GeneralCommander() {
00264 if(head_track_hand_client_) {
00265 head_track_hand_client_->cancelAllGoals();
00266 delete head_track_hand_client_;
00267 }
00268 if(right_gripper_client_) {
00269 delete right_gripper_client_;
00270 }
00271 if(left_gripper_client_) {
00272 delete left_gripper_client_;
00273 }
00274 if(right_arm_trajectory_client_) {
00275 delete right_arm_trajectory_client_;
00276 }
00277 if(left_arm_trajectory_client_) {
00278 delete left_arm_trajectory_client_;
00279 }
00280 if(tuck_arms_client_) {
00281 delete tuck_arms_client_;
00282 }
00283 }
00284
00285 void GeneralCommander::jointStateCallback(const sensor_msgs::JointStateConstPtr &jointState)
00286 {
00287 for(unsigned int i = 0; i < jointState->name.size(); i++) {
00288 joint_state_position_map_[jointState->name[i]] = jointState->position[i];
00289 joint_state_velocity_map_[jointState->name[i]] = jointState->velocity[i];
00290
00291
00292
00293 }
00294 }
00295
00296 bool GeneralCommander::getJointPosition(const std::string& name, double& pos) const {
00297 if(joint_state_position_map_.find(name) == joint_state_position_map_.end()) {
00298 return false;
00299 }
00300 pos = joint_state_position_map_.find(name)->second;
00301 return true;
00302 }
00303
00304 bool GeneralCommander::getJointVelocity(const std::string& name, double& vel) const {
00305 if(joint_state_velocity_map_.find(name) == joint_state_velocity_map_.end()) {
00306 return false;
00307 }
00308 vel = joint_state_velocity_map_.find(name)->second;
00309 return true;
00310 }
00311
00312 GeneralCommander::LaserControlMode GeneralCommander::getLaserMode() {
00313 return laser_control_mode_;
00314 }
00315
00316 GeneralCommander::HeadControlMode GeneralCommander::getHeadMode() {
00317 return head_control_mode_;
00318 }
00319
00320 GeneralCommander::ArmControlMode GeneralCommander::getArmMode(WhichArm arm) {
00321 if(arm == ARMS_RIGHT || arm == ARMS_BOTH) {
00322 return right_arm_control_mode_;
00323 } else {
00324 return left_arm_control_mode_;
00325 }
00326 }
00327
00328 void GeneralCommander::sendProjectorStartStop(bool start) {
00329
00330 if(!control_head_) return;
00331
00332 if(start) {
00333 int ok = system("rosrun dynamic_reconfigure dynparam set camera_synchronizer_node narrow_stereo_trig_mode 3");
00334 ROS_DEBUG("Trying to send projector on");
00335 if(ok < 0) {
00336 ROS_WARN("Dynamic reconfigure for setting trigger mode ON failed");
00337 }
00338 } else {
00339 int ok = system("rosrun dynamic_reconfigure dynparam set camera_synchronizer_node narrow_stereo_trig_mode 4");
00340 ROS_DEBUG("Trying to send trigger off");
00341 if(ok < 0) {
00342 ROS_WARN("Dynamic reconfigure for setting trigger mode OFF failed");
00343 }
00344 }
00345 }
00346
00347 void GeneralCommander::setLaserMode(LaserControlMode mode) {
00348 if(!control_head_) return;
00349
00350 if(laser_control_mode_ == mode) return;
00351
00352 pr2_msgs::SetPeriodicCmd::Request req;
00353 pr2_msgs::SetPeriodicCmd::Response res;
00354
00355 req.command.profile = "linear";
00356 if(mode == LASER_TILT_SLOW) {
00357 ROS_DEBUG("Sending slow");
00358 req.command.period = laser_slow_period_;
00359 req.command.amplitude = laser_slow_period_;
00360 req.command.offset = laser_slow_offset_;
00361 } else if(mode == LASER_TILT_FAST) {
00362 ROS_DEBUG("Sending fast");
00363 req.command.period = laser_fast_period_;
00364 req.command.amplitude = laser_fast_period_;
00365 req.command.offset = laser_fast_offset_;
00366 } else {
00367 ROS_DEBUG("Sending off");
00368 req.command.period = 1.0;
00369 req.command.amplitude = 0;
00370 req.command.offset = laser_slow_offset_;
00371 }
00372
00373 if(tilt_laser_service_.call(req,res)) {
00374
00375 } else {
00376 ROS_ERROR("Tilt laser service call failed.\n");
00377 }
00378 laser_control_mode_ = mode;
00379 }
00380
00381 void GeneralCommander::setHeadMode(HeadControlMode mode) {
00382 if(!control_head_) return;
00383 if(mode == head_control_mode_) return;
00384 if(mode == HEAD_TRACK_LEFT_HAND) {
00385 ROS_DEBUG("Setting head to track left hand");
00386 } else if(mode == HEAD_TRACK_RIGHT_HAND) {
00387 ROS_DEBUG("Setting head to track right hand");
00388 }
00389 std::vector<std::string> start_controllers;
00390 std::vector<std::string> stop_controllers;
00391 if(mode == HEAD_MANNEQUIN) {
00392 start_controllers.push_back(HEAD_MANNEQUIN_CONTROLLER);
00393 stop_controllers.push_back(HEAD_POSITION_CONTROLLER);
00394 } else if(head_control_mode_ == HEAD_MANNEQUIN) {
00395 start_controllers.push_back(HEAD_POSITION_CONTROLLER);
00396 stop_controllers.push_back(HEAD_MANNEQUIN_CONTROLLER);
00397 }
00398 if(!start_controllers.empty() || !stop_controllers.empty()) {
00399 switchControllers(start_controllers, stop_controllers);
00400 }
00401 head_control_mode_ = mode;
00402 }
00403
00404 void GeneralCommander::setArmMode(WhichArm arm, ArmControlMode mode) {
00405 if(!control_rarm_ && !control_larm_) return;
00406 if(!control_rarm_ && arm == ARMS_RIGHT) return;
00407 if(!control_larm_ && arm == ARMS_LEFT) return;
00408
00409 if(arm == ARMS_LEFT) {
00410 if(mode == left_arm_control_mode_) return;
00411 } else if(arm == ARMS_RIGHT) {
00412 if(mode == right_arm_control_mode_) return;
00413 } else {
00414 if(mode == left_arm_control_mode_ && mode == right_arm_control_mode_) return;
00415 }
00416
00417 std::string left_running_controller;
00418 std::string right_running_controller;
00419
00420 if(left_arm_control_mode_ == ARM_MANNEQUIN_MODE) {
00421 left_running_controller = LEFT_ARM_MANNEQUIN_CONTROLLER;
00422 } else if(left_arm_control_mode_ == ARM_POSITION_CONTROL) {
00423 left_running_controller = l_arm_controller_name_;
00424 }
00425
00426 if(right_arm_control_mode_ == ARM_MANNEQUIN_MODE) {
00427 right_running_controller = RIGHT_ARM_MANNEQUIN_CONTROLLER;
00428 } else if(right_arm_control_mode_ == ARM_POSITION_CONTROL) {
00429 right_running_controller = r_arm_controller_name_;
00430 }
00431
00432 std::vector<std::string> start_controllers;
00433 std::vector<std::string> stop_controllers;
00434
00435 if(mode == ARM_NO_CONTROLLER) {
00436 if(arm == ARMS_LEFT || arm == ARMS_BOTH) {
00437 stop_controllers.push_back(left_running_controller);
00438 }
00439 if(arm == ARMS_RIGHT || arm == ARMS_BOTH) {
00440 stop_controllers.push_back(right_running_controller);
00441 }
00442 } else if(mode == ARM_MANNEQUIN_MODE) {
00443 if(arm == ARMS_LEFT || arm == ARMS_BOTH) {
00444 if(!left_running_controller.empty()) {
00445 stop_controllers.push_back(left_running_controller);
00446 }
00447 start_controllers.push_back(LEFT_ARM_MANNEQUIN_CONTROLLER);
00448 }
00449 if(arm == ARMS_RIGHT || arm == ARMS_BOTH) {
00450 if(!right_running_controller.empty()) {
00451 stop_controllers.push_back(right_running_controller);
00452 }
00453 start_controllers.push_back(RIGHT_ARM_MANNEQUIN_CONTROLLER);
00454 }
00455 } else if(mode == ARM_POSITION_CONTROL) {
00456 if(arm == ARMS_LEFT || arm == ARMS_BOTH) {
00457 if(!left_running_controller.empty()) {
00458 stop_controllers.push_back(left_running_controller);
00459 }
00460 start_controllers.push_back(l_arm_controller_name_);
00461 }
00462 if(arm == ARMS_RIGHT || arm == ARMS_BOTH) {
00463 if(!right_running_controller.empty()) {
00464 stop_controllers.push_back(right_running_controller);
00465 }
00466 start_controllers.push_back(r_arm_controller_name_);
00467 }
00468 }
00469 switchControllers(start_controllers, stop_controllers);
00470 if(arm == ARMS_LEFT || arm == ARMS_BOTH) {
00471 left_arm_control_mode_ = mode;
00472 }
00473 if(arm == ARMS_RIGHT || arm == ARMS_BOTH) {
00474 right_arm_control_mode_ = mode;
00475 }
00476 }
00477
00478 void GeneralCommander::sendHeadCommand(double req_pan, double req_tilt) {
00479 if(!control_head_) return;
00480 if(head_control_mode_ != HEAD_JOYSTICK) {
00481 return;
00482 }
00483
00484 trajectory_msgs::JointTrajectory traj;
00485 traj.header.stamp = ros::Time::now() + ros::Duration(0.01);
00486 traj.joint_names.push_back("head_pan_joint");
00487 traj.joint_names.push_back("head_tilt_joint");
00488 traj.points.resize(1);
00489 traj.points[0].positions.push_back(req_pan);
00490 traj.points[0].velocities.push_back(0.0);
00491 traj.points[0].positions.push_back(req_tilt);
00492 traj.points[0].velocities.push_back(0.0);
00493 traj.points[0].time_from_start = ros::Duration(0.1);
00494
00495 head_pub_.publish(traj);
00496 }
00497
00498 void GeneralCommander::sendHeadTrackCommand() {
00499 if(!control_head_) return;
00500 if(head_control_mode_ != HEAD_TRACK_LEFT_HAND &&
00501 head_control_mode_ != HEAD_TRACK_RIGHT_HAND) {
00502 return;
00503 }
00504
00505
00506 pr2_controllers_msgs::PointHeadGoal goal;
00507
00508
00509 geometry_msgs::PointStamped point;
00510 if(head_control_mode_ == HEAD_TRACK_LEFT_HAND) {
00511 point.header.frame_id = LEFT_HAND_LINK_TO_TRACK;
00512 } else {
00513 point.header.frame_id = RIGHT_HAND_LINK_TO_TRACK;
00514 }
00515 point.point.x = 0.0;
00516 point.point.y = 0.0;
00517 point.point.z = 0.0;
00518 goal.target = point;
00519
00520
00521
00522 goal.pointing_frame = "high_def_frame";
00523
00524
00525 goal.min_duration = ros::Duration(0.1);
00526
00527
00528 goal.max_velocity = MAX_HEAD_TRACK_SPEED;
00529
00530
00531 head_track_hand_client_->sendGoal(goal);
00532
00533
00534
00535 }
00536
00537 void GeneralCommander::sendGripperCommand(WhichArm which, bool close) {
00538 if(!control_rarm_ && !control_larm_) return;
00539 if(!control_rarm_ && which == ARMS_RIGHT) return;
00540 if(!control_larm_ && which == ARMS_LEFT) return;
00541 if(which == ARMS_RIGHT || which == ARMS_BOTH) {
00542 pr2_controllers_msgs::Pr2GripperCommandGoal com;
00543 if(close) {
00544 com.command.position = GRIPPER_CLOSE_POSITION;
00545 com.command.max_effort = GRIPPER_CLOSE_MAX_EFFORT;
00546 } else {
00547 com.command.position = GRIPPER_OPEN_POSITION;
00548 com.command.max_effort = GRIPPER_OPEN_MAX_EFFORT;
00549 }
00550 right_gripper_client_->sendGoal(com);
00551 right_gripper_client_->waitForResult(ros::Duration(5.0));
00552 if(right_gripper_client_->getState() == actionlib::SimpleClientGoalState::SUCCEEDED)
00553 ROS_DEBUG("Right gripper command succeeded");
00554 else
00555 ROS_WARN("Right gripper command failed");
00556 }
00557 if(which == ARMS_LEFT || which == ARMS_BOTH) {
00558 pr2_controllers_msgs::Pr2GripperCommandGoal com;
00559 if(close) {
00560 com.command.position = GRIPPER_CLOSE_POSITION;
00561 com.command.max_effort = GRIPPER_CLOSE_MAX_EFFORT;
00562 } else {
00563 com.command.position = GRIPPER_OPEN_POSITION;
00564 com.command.max_effort = GRIPPER_OPEN_MAX_EFFORT;
00565 }
00566 left_gripper_client_->sendGoal(com);
00567 left_gripper_client_->waitForResult(ros::Duration(5.0));
00568 if(left_gripper_client_->getState() == actionlib::SimpleClientGoalState::SUCCEEDED)
00569 ROS_DEBUG("Left gripper command succeeded");
00570 else
00571 ROS_WARN("Left gripper command failed");
00572 }
00573
00574 }
00575
00576 void GeneralCommander::sendTorsoCommand(double pos, double vel) {
00577 if(!control_body_) return;
00578
00579 if(fabs(vel) < .0001 && fabs(last_torso_vel_ < .0001)) {
00580
00581 }
00582 last_torso_vel_ = vel;
00583
00584 trajectory_msgs::JointTrajectory traj;
00585 traj.header.stamp = ros::Time::now() + ros::Duration(0.01);
00586 traj.joint_names.push_back("torso_lift_joint");
00587 traj.points.resize(1);
00588 traj.points[0].positions.push_back(pos);
00589 traj.points[0].velocities.push_back(vel);
00590 traj.points[0].time_from_start = ros::Duration(0.25);
00591 torso_pub_.publish(traj);
00592 }
00593
00594 void GeneralCommander::sendBaseCommand(double vx, double vy, double vw) {
00595 if(!control_body_) return;
00596 geometry_msgs::Twist cmd;
00597
00598 cmd.linear.x = vx;
00599 cmd.linear.y = vy;
00600 cmd.angular.z = vw;
00601 base_pub_.publish(cmd);
00602 }
00603
00604 void GeneralCommander::switchControllers(const std::vector<std::string>& start_controllers, const std::vector<std::string>& stop_controllers) {
00605 pr2_mechanism_msgs::SwitchController::Request req;
00606 pr2_mechanism_msgs::SwitchController::Response res;
00607 req.start_controllers = start_controllers;
00608 req.stop_controllers = stop_controllers;
00609 for(std::vector<std::string>::const_iterator it = start_controllers.begin();
00610 it != start_controllers.end();
00611 it++) {
00612 ROS_DEBUG_STREAM("Trying to start controller " << (*it));
00613 }
00614 for(std::vector<std::string>::const_iterator it = stop_controllers.begin();
00615 it != stop_controllers.end();
00616 it++) {
00617 ROS_DEBUG_STREAM("Trying to stop controller " << (*it));
00618 }
00619 req.strictness = pr2_mechanism_msgs::SwitchController::Request::BEST_EFFORT;
00620 if(!switch_controllers_service_.call(req,res)) {
00621 ROS_WARN("Call to switch controllers failed entirely");
00622 }
00623 if(res.ok != true) {
00624 ROS_WARN("Call to switch controllers reports not ok");
00625 }
00626 }
00627
00628 void GeneralCommander::sendWristVelCommands(double right_wrist_vel, double left_wrist_vel, double hz) {
00629
00630 clampDesiredArmPositionsToActual(.05);
00631
00632 if(control_rarm_) {
00633 if(abs(right_wrist_vel) > .01) {
00634 if((ros::Time::now()-last_right_wrist_goal_stamp_).toSec() > .5) {
00635 clampDesiredArmPositionsToActual(0.0);
00636 }
00637 last_right_wrist_goal_stamp_ = ros::Time::now();
00638
00639
00640 pr2_controllers_msgs::JointTrajectoryGoal right_goal;
00641 composeWristRotGoal("r", right_goal, right_des_joint_states_ ,right_wrist_vel, hz);
00642 right_arm_traj_pub_.publish(right_goal.trajectory);
00643
00644 }
00645 }
00646 if(control_larm_) {
00647 if(abs(left_wrist_vel) > .01) {
00648 if((ros::Time::now()-last_left_wrist_goal_stamp_).toSec() > .5) {
00649 clampDesiredArmPositionsToActual(0.0);
00650 }
00651 last_left_wrist_goal_stamp_ = ros::Time::now();
00652
00653 pr2_controllers_msgs::JointTrajectoryGoal left_goal;
00654 composeWristRotGoal("l", left_goal, left_des_joint_states_, left_wrist_vel, hz);
00655 left_arm_traj_pub_.publish(left_goal.trajectory);
00656
00657 }
00658 }
00659 }
00660
00661 void GeneralCommander::composeWristRotGoal(const std::string pref, pr2_controllers_msgs::JointTrajectoryGoal& goal,
00662 std::vector<double>& des_joints,
00663 double des_vel, double hz) const {
00664
00665 double trajectory_duration = .2;
00666
00667 std::vector<std::string> joint_names;
00668
00669
00670 joint_names.push_back(pref+"_"+"shoulder_pan_joint");
00671 joint_names.push_back(pref+"_"+"shoulder_lift_joint");
00672 joint_names.push_back(pref+"_"+"upper_arm_roll_joint");
00673 joint_names.push_back(pref+"_"+"elbow_flex_joint");
00674 joint_names.push_back(pref+"_"+"forearm_roll_joint");
00675 joint_names.push_back(pref+"_"+"wrist_flex_joint");
00676 joint_names.push_back(pref+"_"+"wrist_roll_joint");
00677
00678 double end_pos_diff = (trajectory_duration)*des_vel;
00679 double cur_pos_diff = (1.0/hz)*des_vel;
00680
00681 goal.trajectory.joint_names=joint_names;
00682 goal.trajectory.points.resize(1);
00683 goal.trajectory.points[0].positions = des_joints;
00684
00685 goal.trajectory.points[0].velocities.resize(7,0.0);
00686
00687
00688 goal.trajectory.points[0].positions[6] += end_pos_diff;
00689 des_joints[6] += cur_pos_diff;
00690
00691
00692 goal.trajectory.header.stamp = ros::Time::now()+ros::Duration(0.030);
00693 goal.trajectory.points[0].time_from_start = ros::Duration(trajectory_duration);
00694 }
00695
00696 void GeneralCommander::updateCurrentWristPositions() {
00697
00698 if(control_rarm_) {
00699 kinematics_msgs::GetKinematicSolverInfo::Request right_request;
00700 kinematics_msgs::GetKinematicSolverInfo::Response right_response;
00701
00702 kinematics_msgs::GetPositionFK::Request right_fk_request;
00703 kinematics_msgs::GetPositionFK::Response right_fk_response;
00704
00705 right_arm_kinematics_solver_client_.call(right_request, right_response);
00706
00707 right_fk_request.header.frame_id = "base_link";
00708 right_fk_request.fk_link_names.push_back("r_wrist_roll_link");
00709 right_fk_request.robot_state.joint_state.position.resize(right_response.kinematic_solver_info.joint_names.size());
00710 right_fk_request.robot_state.joint_state.name = right_response.kinematic_solver_info.joint_names;
00711 for(unsigned int i = 0; i < right_fk_request.robot_state.joint_state.name.size(); i++) {
00712 bool ok = getJointPosition(right_fk_request.robot_state.joint_state.name[i], right_fk_request.robot_state.joint_state.position[i]);
00713 if(!ok) {
00714 ROS_WARN_STREAM("No joint state yet for " << right_fk_request.robot_state.joint_state.name[i]);
00715 return;
00716 }
00717 }
00718 if(right_arm_kinematics_forward_client_.call(right_fk_request, right_fk_response)) {
00719 if(right_fk_response.error_code.val == right_fk_response.error_code.SUCCESS) {
00720 right_wrist_roll_pose_ = right_fk_response.pose_stamped[0].pose;
00721 } else {
00722 ROS_DEBUG("Right fk not a success");
00723 }
00724 } else {
00725 ROS_WARN("Right fk call failed all together");
00726 }
00727 }
00728
00729 if(control_larm_) {
00730 kinematics_msgs::GetKinematicSolverInfo::Request left_request;
00731 kinematics_msgs::GetKinematicSolverInfo::Response left_response;
00732
00733 kinematics_msgs::GetPositionFK::Request left_fk_request;
00734 kinematics_msgs::GetPositionFK::Response left_fk_response;
00735
00736 left_arm_kinematics_solver_client_.call(left_request, left_response);
00737
00738 left_fk_request.header.frame_id = "base_link";
00739 left_fk_request.fk_link_names.push_back("l_wrist_roll_link");
00740 left_fk_request.robot_state.joint_state.position.resize(left_response.kinematic_solver_info.joint_names.size());
00741 left_fk_request.robot_state.joint_state.name = left_response.kinematic_solver_info.joint_names;
00742 for(unsigned int i = 0; i < left_fk_request.robot_state.joint_state.name.size(); i++) {
00743 bool ok = getJointPosition(left_fk_request.robot_state.joint_state.name[i], left_fk_request.robot_state.joint_state.position[i]);
00744 if(!ok) {
00745 ROS_WARN_STREAM("No joint state yet for " << left_fk_request.robot_state.joint_state.name[i]);
00746 return;
00747 }
00748 }
00749 if(left_arm_kinematics_forward_client_.call(left_fk_request, left_fk_response)) {
00750 if(left_fk_response.error_code.val == left_fk_response.error_code.SUCCESS) {
00751 left_wrist_roll_pose_ = left_fk_response.pose_stamped[0].pose;
00752 } else {
00753 ROS_DEBUG("Left fk not a success");
00754 }
00755 } else {
00756 ROS_WARN("Left fk call failed all together");
00757 }
00758
00759
00760 }
00761 }
00762
00763 void GeneralCommander::clampDesiredArmPositionsToActual(double max_dist) {
00764
00765 updateCurrentWristPositions();
00766
00767 double tot_distance;
00768 if(control_rarm_) {
00769 tot_distance = sqrt(pow(des_r_wrist_roll_pose_.position.x-right_wrist_roll_pose_.position.x,2.0)+
00770 pow(des_r_wrist_roll_pose_.position.y-right_wrist_roll_pose_.position.y,2.0)+
00771 pow(des_r_wrist_roll_pose_.position.z-right_wrist_roll_pose_.position.z,2.0));
00772
00773
00774
00775
00776
00777
00778 if(tot_distance > max_dist) {
00779 des_r_wrist_roll_pose_ = right_wrist_roll_pose_;
00780
00781 std::vector<std::string> joint_names;
00782 std::string pref = "r";
00783
00784 joint_names.push_back(pref+"_"+"shoulder_pan_joint");
00785 joint_names.push_back(pref+"_"+"shoulder_lift_joint");
00786 joint_names.push_back(pref+"_"+"upper_arm_roll_joint");
00787 joint_names.push_back(pref+"_"+"elbow_flex_joint");
00788 joint_names.push_back(pref+"_"+"forearm_roll_joint");
00789 joint_names.push_back(pref+"_"+"wrist_flex_joint");
00790 joint_names.push_back(pref+"_"+"wrist_roll_joint");
00791 right_des_joint_states_.clear();
00792 for(unsigned int i = 0; i < joint_names.size(); i++) {
00793 double cur_pos;
00794 getJointPosition(joint_names[i], cur_pos);
00795 right_des_joint_states_.push_back(cur_pos);
00796 }
00797
00798 }
00799 }
00800
00801 if(control_larm_) {
00802 tot_distance = sqrt(pow(des_l_wrist_roll_pose_.position.x-left_wrist_roll_pose_.position.x,2.0)+
00803 pow(des_l_wrist_roll_pose_.position.y-left_wrist_roll_pose_.position.y,2.0)+
00804 pow(des_l_wrist_roll_pose_.position.z-left_wrist_roll_pose_.position.z,2.0));
00805
00806 if(tot_distance > max_dist) {
00807 des_l_wrist_roll_pose_ = left_wrist_roll_pose_;
00808 std::vector<std::string> joint_names;
00809 std::string pref = "l";
00810
00811 joint_names.push_back(pref+"_"+"shoulder_pan_joint");
00812 joint_names.push_back(pref+"_"+"shoulder_lift_joint");
00813 joint_names.push_back(pref+"_"+"upper_arm_roll_joint");
00814 joint_names.push_back(pref+"_"+"elbow_flex_joint");
00815 joint_names.push_back(pref+"_"+"forearm_roll_joint");
00816 joint_names.push_back(pref+"_"+"wrist_flex_joint");
00817 joint_names.push_back(pref+"_"+"wrist_roll_joint");
00818 left_des_joint_states_.clear();
00819 for(unsigned int i = 0; i < joint_names.size(); i++) {
00820 double cur_pos;
00821 getJointPosition(joint_names[i], cur_pos);
00822 left_des_joint_states_.push_back(cur_pos);
00823 }
00824
00825 }
00826 }
00827 }
00828
00829 void GeneralCommander::unnormalizeTrajectory(trajectory_msgs::JointTrajectory& traj) const {
00830
00831 std::vector<double> current_values;
00832 std::vector<bool> wraparound;
00833 trajectory_msgs::JointTrajectory input_trajectory = traj;
00834
00835 for (size_t i=0; i<input_trajectory.joint_names.size(); i++)
00836 {
00837 std::string name = input_trajectory.joint_names[i];
00838
00839 double pos;
00840 if(!getJointPosition(name, pos)) {
00841 ROS_WARN_STREAM("Can't unnormalize as no current joint state for " << name);
00842 return;
00843 }
00844
00845
00846 current_values.push_back(pos);
00847
00848 boost::shared_ptr<const urdf::Joint> joint = robot_model_.getJoint(name);
00849 if (joint.get() == NULL)
00850 {
00851 ROS_ERROR("Joint name %s not found in urdf model", name.c_str());
00852 return;
00853 }
00854 if (joint->type == urdf::Joint::CONTINUOUS) {
00855 wraparound.push_back(true);
00856 } else {
00857 wraparound.push_back(false);
00858 }
00859 }
00860
00861 trajectory_msgs::JointTrajectory unnormalized_trajectory = input_trajectory;
00862 for (size_t i=0; i<unnormalized_trajectory.points.size(); i++)
00863 {
00864 for (size_t j=0; j<unnormalized_trajectory.points[i].positions.size(); j++)
00865 {
00866 if(!wraparound[j]){
00867 continue;
00868 }
00869 double current = current_values[j];
00870 double traj = unnormalized_trajectory.points[i].positions[j];
00871 while ( current - traj > M_PI ) traj += 2*M_PI;
00872 while ( traj - current > M_PI ) traj -= 2*M_PI;
00873 ROS_DEBUG("Normalizing joint %s from %f to %f", unnormalized_trajectory.joint_names.at(j).c_str(),
00874 unnormalized_trajectory.points[i].positions[j], traj);
00875 unnormalized_trajectory.points[i].positions[j] = traj;
00876
00877 current_values[j] = traj;
00878 }
00879 }
00880 traj = unnormalized_trajectory;
00881 }
00882
00883 void GeneralCommander::sendArmVelCommands(double r_x_vel, double r_y_vel, double r_z_vel, double r_yaw_vel,
00884 double l_x_vel, double l_y_vel, double l_z_vel, double l_yaw_vel,
00885 double hz) {
00886
00887
00888 ros::Time beforeCall = ros::Time::now();
00889
00890 double trajectory_duration = .2;
00891
00892
00893
00894 clampDesiredArmPositionsToActual(.1);
00895
00896 if(control_rarm_) {
00897
00898 if(fabs(r_x_vel) > .001 || fabs(r_y_vel) > .001 || fabs(r_z_vel) > .001) {
00899
00900 geometry_msgs::Pose right_trajectory_endpoint = des_r_wrist_roll_pose_;
00901
00902 kinematics_msgs::GetKinematicSolverInfo::Request right_request;
00903 kinematics_msgs::GetKinematicSolverInfo::Response right_response;
00904
00905 right_arm_kinematics_solver_client_.call(right_request, right_response);
00906
00907 double pos_diff_x = r_x_vel*(1.0/hz);
00908 double pos_diff_y = r_y_vel*(1.0/hz);
00909 double pos_diff_z = r_z_vel*(1.0/hz);
00910
00911
00912 right_trajectory_endpoint.position.x += r_x_vel*trajectory_duration;
00913 right_trajectory_endpoint.position.y += r_y_vel*trajectory_duration;
00914 right_trajectory_endpoint.position.z += r_z_vel*trajectory_duration;
00915
00916 des_r_wrist_roll_pose_.position.x += pos_diff_x;
00917 des_r_wrist_roll_pose_.position.y += pos_diff_y;
00918 des_r_wrist_roll_pose_.position.z += pos_diff_z;
00919
00920
00921
00922
00923
00924
00925
00926 kinematics_msgs::GetPositionIK::Request ik_req;
00927 kinematics_msgs::GetPositionIK::Response ik_res;
00928
00929 ik_req.timeout = ros::Duration(0.05);
00930 ik_req.ik_request.ik_link_name = "r_wrist_roll_link";
00931 ik_req.ik_request.pose_stamped.header.frame_id = "base_link";
00932 ik_req.ik_request.pose_stamped.header.stamp = ros::Time::now();
00933 ik_req.ik_request.pose_stamped.pose = right_trajectory_endpoint;
00934
00935 ik_req.ik_request.ik_seed_state.joint_state.position.resize(right_response.kinematic_solver_info.joint_names.size());
00936 ik_req.ik_request.ik_seed_state.joint_state.name = right_response.kinematic_solver_info.joint_names;
00937 for(unsigned int i = 0; i < ik_req.ik_request.ik_seed_state.joint_state.name.size(); i++) {
00938 bool ok = getJointPosition(ik_req.ik_request.ik_seed_state.joint_state.name[i], ik_req.ik_request.ik_seed_state.joint_state.position[i]);
00939 if(!ok) {
00940 ROS_WARN_STREAM("No joint state yet for " << ik_req.ik_request.ik_seed_state.joint_state.name[i]);
00941 return;
00942 } else {
00943
00944
00945 }
00946 }
00947
00948
00949
00950 if(right_arm_kinematics_inverse_client_.call(ik_req, ik_res) && ik_res.error_code.val == ik_res.error_code.SUCCESS) {
00951
00952 pr2_controllers_msgs::JointTrajectoryGoal goal;
00953
00954 std::vector<std::string> joint_names;
00955 std::string pref = "r";
00956
00957
00958 joint_names.push_back(pref+"_"+"shoulder_pan_joint");
00959 joint_names.push_back(pref+"_"+"shoulder_lift_joint");
00960 joint_names.push_back(pref+"_"+"upper_arm_roll_joint");
00961 joint_names.push_back(pref+"_"+"elbow_flex_joint");
00962 joint_names.push_back(pref+"_"+"forearm_roll_joint");
00963 joint_names.push_back(pref+"_"+"wrist_flex_joint");
00964 joint_names.push_back(pref+"_"+"wrist_roll_joint");
00965
00966 goal.trajectory.joint_names = joint_names;
00967
00968
00969 goal.trajectory.points.resize(1);
00970
00971 for(unsigned int i = 0; i < goal.trajectory.joint_names.size(); i++) {
00972 goal.trajectory.points[0].positions.push_back(ik_res.solution.joint_state.position[i]);
00973 goal.trajectory.points[0].velocities.push_back(0.0);
00974 }
00975 goal.trajectory.header.stamp = ros::Time::now()+ros::Duration(0.200);
00976 goal.trajectory.points[0].time_from_start = ros::Duration(trajectory_duration);
00977
00978 unnormalizeTrajectory(goal.trajectory);
00979 right_arm_traj_pub_.publish(goal.trajectory);
00980 } else {
00981 ROS_DEBUG_STREAM("Ik failed with response " << ik_res.error_code.val);
00982 }
00983 }
00984
00985 ros::Time afterCall = ros::Time::now();
00986 }
00987 if(control_larm_) {
00988 if(fabs(l_x_vel) > .001 || fabs(l_y_vel) > .001 || fabs(l_z_vel) > .001) {
00989
00990 geometry_msgs::Pose left_trajectory_endpoint = des_l_wrist_roll_pose_;
00991
00992 kinematics_msgs::GetKinematicSolverInfo::Request left_request;
00993 kinematics_msgs::GetKinematicSolverInfo::Response left_response;
00994
00995 left_arm_kinematics_solver_client_.call(left_request, left_response);
00996
00997 double pos_diff_x = l_x_vel*(1.0/hz);
00998 double pos_diff_y = l_y_vel*(1.0/hz);
00999 double pos_diff_z = l_z_vel*(1.0/hz);
01000
01001
01002 left_trajectory_endpoint.position.x += l_x_vel*trajectory_duration;
01003 left_trajectory_endpoint.position.y += l_y_vel*trajectory_duration;
01004 left_trajectory_endpoint.position.z += l_z_vel*trajectory_duration;
01005
01006 des_l_wrist_roll_pose_.position.x += pos_diff_x;
01007 des_l_wrist_roll_pose_.position.y += pos_diff_y;
01008 des_l_wrist_roll_pose_.position.z += pos_diff_z;
01009
01010
01011
01012
01013 kinematics_msgs::GetPositionIK::Request ik_req;
01014 kinematics_msgs::GetPositionIK::Response ik_res;
01015
01016 ik_req.timeout = ros::Duration(0.05);
01017 ik_req.ik_request.ik_link_name = "l_wrist_roll_link";
01018 ik_req.ik_request.pose_stamped.header.frame_id = "base_link";
01019 ik_req.ik_request.pose_stamped.header.stamp = ros::Time::now();
01020 ik_req.ik_request.pose_stamped.pose = left_trajectory_endpoint;
01021
01022 ik_req.ik_request.ik_seed_state.joint_state.position.resize(left_response.kinematic_solver_info.joint_names.size());
01023 ik_req.ik_request.ik_seed_state.joint_state.name = left_response.kinematic_solver_info.joint_names;
01024 for(unsigned int i = 0; i < ik_req.ik_request.ik_seed_state.joint_state.name.size(); i++) {
01025 bool ok = getJointPosition(ik_req.ik_request.ik_seed_state.joint_state.name[i], ik_req.ik_request.ik_seed_state.joint_state.position[i]);
01026 if(!ok) {
01027 ROS_WARN_STREAM("No joint state yet for " << ik_req.ik_request.ik_seed_state.joint_state.name[i]);
01028 return;
01029 } else {
01030
01031
01032 }
01033 }
01034
01035
01036
01037 if(left_arm_kinematics_inverse_client_.call(ik_req, ik_res) && ik_res.error_code.val == ik_res.error_code.SUCCESS) {
01038
01039 pr2_controllers_msgs::JointTrajectoryGoal goal;
01040
01041 std::vector<std::string> joint_names;
01042 std::string pref = "l";
01043
01044
01045 joint_names.push_back(pref+"_"+"shoulder_pan_joint");
01046 joint_names.push_back(pref+"_"+"shoulder_lift_joint");
01047 joint_names.push_back(pref+"_"+"upper_arm_roll_joint");
01048 joint_names.push_back(pref+"_"+"elbow_flex_joint");
01049 joint_names.push_back(pref+"_"+"forearm_roll_joint");
01050 joint_names.push_back(pref+"_"+"wrist_flex_joint");
01051 joint_names.push_back(pref+"_"+"wrist_roll_joint");
01052
01053 goal.trajectory.joint_names = joint_names;
01054
01055
01056 goal.trajectory.points.resize(1);
01057
01058 for(unsigned int i = 0; i < goal.trajectory.joint_names.size(); i++) {
01059 goal.trajectory.points[0].positions.push_back(ik_res.solution.joint_state.position[i]);
01060 goal.trajectory.points[0].velocities.push_back(0.0);
01061 }
01062 goal.trajectory.header.stamp = ros::Time::now()+ros::Duration(0.200);
01063 goal.trajectory.points[0].time_from_start = ros::Duration(trajectory_duration);
01064
01065 unnormalizeTrajectory(goal.trajectory);
01066 left_arm_traj_pub_.publish(goal.trajectory);
01067 } else {
01068 ROS_DEBUG_STREAM("Ik failed with response " << ik_res.error_code.val);
01069 }
01070 }
01071 }
01072 }
01073
01074 bool GeneralCommander::moveToWalkAlongArmPose() {
01075
01076
01077 if(!control_rarm_ || !control_larm_) {
01078 return false;
01079 }
01080
01081 updateCurrentWristPositions();
01082
01083 ROS_DEBUG("Attempting to set arms to walk along pose");
01084
01085 std::vector<std::string> joint_names;
01086 std::string pref;
01087 pr2_controllers_msgs::JointTrajectoryGoal goal;
01088
01089 pref = "r";
01090
01091
01092 joint_names.push_back(pref+"_"+"shoulder_pan_joint");
01093 joint_names.push_back(pref+"_"+"shoulder_lift_joint");
01094 joint_names.push_back(pref+"_"+"upper_arm_roll_joint");
01095 joint_names.push_back(pref+"_"+"elbow_flex_joint");
01096 joint_names.push_back(pref+"_"+"forearm_roll_joint");
01097 joint_names.push_back(pref+"_"+"wrist_flex_joint");
01098 joint_names.push_back(pref+"_"+"wrist_roll_joint");
01099
01100 goal.trajectory.joint_names = joint_names;
01101
01102
01103 goal.trajectory.points.resize(1);
01104 goal.trajectory.points[0].positions = right_walk_along_pose_;
01105
01106 for(unsigned int i = 0; i < goal.trajectory.joint_names.size(); i++) {
01107 goal.trajectory.points[0].velocities.push_back(0.0);
01108 }
01109
01110 geometry_msgs::Pose right_walk_pose = getPositionFromJointsPose(right_arm_kinematics_forward_client_,
01111 "r_wrist_roll_link",
01112 joint_names,
01113 right_walk_along_pose_);
01114 double tot_distance = sqrt(pow(right_walk_pose.position.x-right_wrist_roll_pose_.position.x,2.0)+
01115 pow(right_walk_pose.position.y-right_wrist_roll_pose_.position.y,2.0)+
01116 pow(right_walk_pose.position.z-right_wrist_roll_pose_.position.z,2.0));
01117 ROS_DEBUG_STREAM("Right dist is " << tot_distance);
01118
01119 if(tot_distance > .02) {
01120
01121 goal.trajectory.header.stamp = ros::Time::now()+ros::Duration(0.030);
01122 goal.trajectory.points[0].time_from_start = ros::Duration(3.0);
01123
01124 unnormalizeTrajectory(goal.trajectory);
01125
01126 ROS_DEBUG("Sending right arm goal");
01127
01128 right_arm_trajectory_client_->sendGoal(goal);
01129 bool finished_before_timeout = right_arm_trajectory_client_->waitForResult(ros::Duration(5.0));
01130
01131 actionlib::SimpleClientGoalState state = right_arm_trajectory_client_->getState();
01132
01133 if(!finished_before_timeout || state != actionlib::SimpleClientGoalState::SUCCEEDED) {
01134 right_arm_trajectory_client_->sendGoal(goal);
01135 finished_before_timeout = right_arm_trajectory_client_->waitForResult(ros::Duration(5.0));
01136 state = right_arm_trajectory_client_->getState();
01137 if(!finished_before_timeout || state != actionlib::SimpleClientGoalState::SUCCEEDED) {
01138 ROS_WARN("Not in walk along pose");
01139 return false;
01140 }
01141 } else {
01142 ROS_DEBUG("Right arm goal successful");
01143 }
01144 } else {
01145 ROS_DEBUG("No need for right arm goal");
01146 }
01147 joint_names.clear();
01148 pref = "l";
01149
01150
01151 joint_names.push_back(pref+"_"+"shoulder_pan_joint");
01152 joint_names.push_back(pref+"_"+"shoulder_lift_joint");
01153 joint_names.push_back(pref+"_"+"upper_arm_roll_joint");
01154 joint_names.push_back(pref+"_"+"elbow_flex_joint");
01155 joint_names.push_back(pref+"_"+"forearm_roll_joint");
01156 joint_names.push_back(pref+"_"+"wrist_flex_joint");
01157 joint_names.push_back(pref+"_"+"wrist_roll_joint");
01158
01159 goal.trajectory.joint_names = joint_names;
01160 goal.trajectory.points[0].positions = left_walk_along_pose_;
01161 goal.trajectory.points[0].velocities.clear();
01162 for(unsigned int i = 0; i < goal.trajectory.joint_names.size(); i++) {
01163 goal.trajectory.points[0].velocities.push_back(0.0);
01164 }
01165
01166 geometry_msgs::Pose left_walk_pose = getPositionFromJointsPose(left_arm_kinematics_forward_client_,
01167 "l_wrist_roll_link",
01168 joint_names,
01169 left_walk_along_pose_);
01170 tot_distance = sqrt(pow(left_walk_pose.position.x-left_wrist_roll_pose_.position.x,2.0)+
01171 pow(left_walk_pose.position.y-left_wrist_roll_pose_.position.y,2.0)+
01172 pow(left_walk_pose.position.z-left_wrist_roll_pose_.position.z,2.0));
01173 ROS_DEBUG_STREAM("Left dist is " << tot_distance);
01174
01175 if(tot_distance > .02) {
01176
01177
01178
01179 goal.trajectory.header.stamp = ros::Time::now()+ros::Duration(0.030);
01180 goal.trajectory.points[0].time_from_start = ros::Duration(3.0);
01181
01182 unnormalizeTrajectory(goal.trajectory);
01183
01184 ROS_DEBUG("Sending left arm goal");
01185
01186 left_arm_trajectory_client_->sendGoal(goal);
01187 bool finished_before_timeout = left_arm_trajectory_client_->waitForResult(ros::Duration(5.0));
01188
01189 actionlib::SimpleClientGoalState state = left_arm_trajectory_client_->getState();
01190
01191 if(!finished_before_timeout || state != actionlib::SimpleClientGoalState::SUCCEEDED) {
01192 left_arm_trajectory_client_->sendGoal(goal);
01193 finished_before_timeout = left_arm_trajectory_client_->waitForResult(ros::Duration(5.0));
01194 state = left_arm_trajectory_client_->getState();
01195 if(!finished_before_timeout || state != actionlib::SimpleClientGoalState::SUCCEEDED) {
01196 ROS_WARN("Not in walk along pose");
01197 return false;
01198 }
01199 } else {
01200 ROS_DEBUG("Left arm goal successful");
01201 }
01202 } else {
01203 ROS_DEBUG("No need for arm goal");
01204 }
01205
01206
01207
01208 updateCurrentWristPositions();
01209 walk_along_right_des_pose_ = right_wrist_roll_pose_;
01210 walk_along_left_des_pose_ = left_wrist_roll_pose_;
01211
01212
01213
01214 walk_rdx_vals_.clear();
01215 walk_rdy_vals_.clear();
01216 walk_ldx_vals_.clear();
01217 walk_ldy_vals_.clear();
01218
01219 return true;
01220 }
01221
01222 bool GeneralCommander::initWalkAlong() {
01223
01224
01225 if(!control_rarm_ || !control_larm_) {
01226 return false;
01227 }
01228
01229 updateCurrentWristPositions();
01230
01231 std::vector<std::string> joint_names;
01232 std::string pref = "r";
01233
01234
01235 joint_names.push_back(pref+"_"+"shoulder_pan_joint");
01236 joint_names.push_back(pref+"_"+"shoulder_lift_joint");
01237 joint_names.push_back(pref+"_"+"upper_arm_roll_joint");
01238 joint_names.push_back(pref+"_"+"elbow_flex_joint");
01239 joint_names.push_back(pref+"_"+"forearm_roll_joint");
01240 joint_names.push_back(pref+"_"+"wrist_flex_joint");
01241 joint_names.push_back(pref+"_"+"wrist_roll_joint");
01242
01243 geometry_msgs::Pose right_walk_pose = getPositionFromJointsPose(right_arm_kinematics_forward_client_,
01244 "r_wrist_roll_link",
01245 joint_names,
01246 right_walk_along_pose_);
01247 double tot_distance = sqrt(pow(right_walk_pose.position.x-right_wrist_roll_pose_.position.x,2.0)+
01248 pow(right_walk_pose.position.y-right_wrist_roll_pose_.position.y,2.0)+
01249 pow(right_walk_pose.position.z-right_wrist_roll_pose_.position.z,2.0));
01250 ROS_DEBUG_STREAM("Right dist is " << tot_distance);
01251
01252 if(tot_distance > .02) {
01253 walk_along_ok_ = false;
01254 return false;
01255 }
01256
01257 joint_names.clear();
01258 pref = "l";
01259
01260
01261 joint_names.push_back(pref+"_"+"shoulder_pan_joint");
01262 joint_names.push_back(pref+"_"+"shoulder_lift_joint");
01263 joint_names.push_back(pref+"_"+"upper_arm_roll_joint");
01264 joint_names.push_back(pref+"_"+"elbow_flex_joint");
01265 joint_names.push_back(pref+"_"+"forearm_roll_joint");
01266 joint_names.push_back(pref+"_"+"wrist_flex_joint");
01267 joint_names.push_back(pref+"_"+"wrist_roll_joint");
01268 geometry_msgs::Pose left_walk_pose = getPositionFromJointsPose(left_arm_kinematics_forward_client_,
01269 "l_wrist_roll_link",
01270 joint_names,
01271 left_walk_along_pose_);
01272 tot_distance = sqrt(pow(left_walk_pose.position.x-left_wrist_roll_pose_.position.x,2.0)+
01273 pow(left_walk_pose.position.y-left_wrist_roll_pose_.position.y,2.0)+
01274 pow(left_walk_pose.position.z-left_wrist_roll_pose_.position.z,2.0));
01275 ROS_DEBUG_STREAM("Left dist is " << tot_distance);
01276
01277 if(tot_distance > .02) {
01278 walk_along_ok_ = false;
01279 return false;
01280 }
01281 walk_along_ok_ = true;
01282 return true;
01283 }
01284
01285 void GeneralCommander::updateWalkAlongAverages() {
01286
01287
01288 if(!control_rarm_ || !control_larm_) {
01289 return;
01290 }
01291
01292 if(walk_rdx_vals_.size() > WALK_BUFFER) {
01293 walk_rdx_vals_.pop_front();
01294 }
01295 if(walk_rdy_vals_.size() > WALK_BUFFER) {
01296 walk_rdy_vals_.pop_front();
01297 }
01298 if(walk_ldx_vals_.size() > WALK_BUFFER) {
01299 walk_ldx_vals_.pop_front();
01300 }
01301 if(walk_ldy_vals_.size() > WALK_BUFFER) {
01302 walk_ldy_vals_.pop_front();
01303 }
01304
01305 updateCurrentWristPositions();
01306
01307
01308
01309
01310 double rdx = right_wrist_roll_pose_.position.x-walk_along_right_des_pose_.position.x;
01311 double rdy = right_wrist_roll_pose_.position.y-walk_along_right_des_pose_.position.y;
01312
01313 double ldx = left_wrist_roll_pose_.position.x-walk_along_left_des_pose_.position.x;
01314 double ldy = left_wrist_roll_pose_.position.y-walk_along_left_des_pose_.position.y;
01315
01316
01317
01318 walk_rdx_vals_.push_back(rdx);
01319 walk_rdy_vals_.push_back(rdy);
01320 walk_ldx_vals_.push_back(ldx);
01321 walk_ldy_vals_.push_back(ldy);
01322
01323 }
01324
01325 void GeneralCommander::sendWalkAlongCommand(double thresh,
01326 double x_dist_max, double x_speed_scale,
01327 double y_dist_max, double y_speed_scale,
01328 double rot_speed_scale) {
01329
01330 if(!control_rarm_ || !control_larm_) {
01331 return;
01332 }
01333
01334 if(!walk_along_ok_) {
01335 return;
01336 }
01337
01338 updateWalkAlongAverages();
01339
01340 double av_rdx = calcAverage(walk_rdx_vals_);
01341 double av_rdy = calcAverage(walk_rdy_vals_);
01342 double av_ldx = calcAverage(walk_ldx_vals_);
01343 double av_ldy = calcAverage(walk_ldy_vals_);
01344
01345
01346
01347 if(fabs(av_rdx) < thresh) {
01348 av_rdx = 0.0;
01349 }
01350 if(fabs(av_rdy) < thresh) {
01351 av_rdy = 0.0;
01352 }
01353 if(fabs(av_ldx) < thresh) {
01354 av_ldx = 0.0;
01355 }
01356 if(fabs(av_ldy) < thresh) {
01357 av_ldy = 0.0;
01358 }
01359
01360 double vx = 0.0;
01361 double vy = 0.0;
01362 double vw = 0.0;
01363
01364
01365
01366
01367
01368
01369
01370
01371
01372
01373
01374
01375
01376
01377 double av_x = av_rdx/2.0+av_ldx/2.0;
01378 double per_x = fabs(av_x)/x_dist_max;
01379 per_x = std::min(per_x, 1.0);
01380 vx = (per_x*per_x)*x_speed_scale*((av_x > 0) ? 1 : -1);
01381
01382 double per_y = fabs(av_ldy/2.0)/y_dist_max;
01383 per_y = std::min(per_y, 1.0);
01384 vy = (per_y*per_y)*y_speed_scale*((av_ldy > 0) ? 1 : -1);
01385
01386
01387
01388 double per_rot = fabs(av_rdy/2.0)/y_dist_max;
01389 per_rot = std::min(per_rot, 1.0);
01390 vw = (per_rot*per_rot)*rot_speed_scale*((av_rdy > 0) ? 1 : -1);;
01391
01392
01393
01394 sendBaseCommand(vx, vy, vw);
01395
01396
01397
01398
01399
01400
01401 }
01402
01403 double GeneralCommander::calcAverage(const std::list<double>& av_list) const {
01404 double av = 0.0;
01405 for(std::list<double>::const_iterator it = av_list.begin();
01406 it != av_list.end();
01407 it++) {
01408 av += (*it);
01409 }
01410 av /= av_list.size();
01411 return av;
01412 }
01413
01414 geometry_msgs::Pose GeneralCommander::getPositionFromJointsPose(ros::ServiceClient& service_client,
01415 std::string fk_link,
01416 const std::vector<std::string>& joint_names, const std::vector<double>& joint_pos) {
01417 kinematics_msgs::GetPositionFK::Request fk_request;
01418 kinematics_msgs::GetPositionFK::Response fk_response;
01419
01420 geometry_msgs::Pose ret_pose;
01421
01422 fk_request.header.frame_id = "base_link";
01423 fk_request.fk_link_names.push_back(fk_link);
01424 fk_request.robot_state.joint_state.position.resize(joint_names.size());
01425 fk_request.robot_state.joint_state.name = joint_names;
01426 fk_request.robot_state.joint_state.position = joint_pos;
01427 if(service_client.call(fk_request, fk_response)) {
01428 if(fk_response.error_code.val == fk_response.error_code.SUCCESS) {
01429 ret_pose = fk_response.pose_stamped[0].pose;
01430 } else {
01431 ROS_DEBUG("fk not a success");
01432 }
01433 } else {
01434 ROS_WARN("fk call failed all together");
01435 }
01436 return ret_pose;
01437 }
01438
01439 void GeneralCommander::sendHeadSequence(HeadSequence seq) {
01440
01441 if(!control_head_) return;
01442
01443 setHeadMode(HEAD_JOYSTICK);
01444
01445 trajectory_msgs::JointTrajectory traj;
01446
01447 if(seq == HEAD_NOD) {
01448 traj = head_nod_traj_;
01449 } else if(seq == HEAD_SHAKE){
01450 traj = head_shake_traj_;
01451 }
01452 traj.header.stamp = ros::Time::now() + ros::Duration(0.01);
01453 head_pub_.publish(traj);
01454 }
01455
01456 void GeneralCommander::powerBoardCallback(const pr2_msgs::PowerBoardStateConstPtr &powerBoardState) {
01457 if(walk_along_ok_) {
01458 if(!powerBoardState->run_stop || !powerBoardState->wireless_stop) {
01459 ROS_DEBUG("Killing walk along due to stop");
01460 walk_along_ok_ = false;
01461 }
01462 }
01463 }
01464
01465 void GeneralCommander::requestProsilicaImage(std::string ns) {
01466 if(!control_prosilica_) return;
01467 polled_camera::GetPolledImage::Request gpi_req;
01468 polled_camera::GetPolledImage::Response gpi_res;
01469 gpi_req.response_namespace = ns;
01470 if(!prosilica_polling_client_.call(gpi_req, gpi_res)) {
01471 ROS_WARN("Prosilica polling request failed");
01472 }
01473 }
01474
01475 void GeneralCommander::tuckArms(WhichArm arm) {
01476
01477
01478 if(!control_rarm_ || !control_larm_) {
01479 return;
01480 }
01481
01482 setArmMode(arm, ARM_POSITION_CONTROL);
01483
01484 pr2_common_action_msgs::TuckArmsGoal tuck_arm_goal;
01485
01486 if(arm == ARMS_BOTH) {
01487 tuck_arm_goal.tuck_right = true;
01488 tuck_arm_goal.tuck_left = true;
01489 } else {
01490 ROS_DEBUG("Tucking one arm not supported");
01491 }
01492
01493 ROS_DEBUG("Sending tuck arms");
01494
01495 tuck_arms_client_->sendGoalAndWait(tuck_arm_goal, ros::Duration(10.0), ros::Duration(5.0));
01496 }
01497
01498 void GeneralCommander::untuckArms(WhichArm arm) {
01499
01500
01501 if(!control_rarm_ || !control_larm_) {
01502 return;
01503 }
01504
01505 setArmMode(arm, ARM_POSITION_CONTROL);
01506
01507 pr2_common_action_msgs::TuckArmsGoal tuck_arm_goal;
01508
01509 if(arm == ARMS_BOTH) {
01510 tuck_arm_goal.tuck_right = false;
01511 tuck_arm_goal.tuck_left = false;
01512 } else {
01513 ROS_DEBUG("Untucking one arm not supported");
01514 }
01515
01516 ROS_DEBUG("Sending untuck arms");
01517
01518 tuck_arms_client_->sendGoalAndWait(tuck_arm_goal, ros::Duration(10.0), ros::Duration(5.0));
01519
01520 }