$search
00001 /********************************************************************* 00002 * 00003 * Copyright (c) 2009, Willow Garage, Inc. 00004 * All rights reserved. 00005 * 00006 * Redistribution and use in source and binary forms, with or without 00007 * modification, are permitted provided that the following conditions 00008 * are met: 00009 * 00010 * * Redistributions of source code must retain the above copyright 00011 * notice, this list of conditions and the following disclaimer. 00012 * * Redistributions in binary form must reproduce the above 00013 * copyright notice, this list of conditions and the following 00014 * disclaimer in the documentation and/or other materials provided 00015 * with the distribution. 00016 * * Neither the name of the Willow Garage nor the names of its 00017 * contributors may be used to endorse or promote products derived 00018 * from this software without specific prior written permission. 00019 * 00020 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00021 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00022 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00023 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00024 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00025 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00026 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00027 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00028 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00029 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00030 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00031 * POSSIBILITY OF SUCH DAMAGE. 00032 *********************************************************************/ 00033 00034 #include "object_manipulator/tools/mechanism_interface.h" 00035 #include "object_manipulator/tools/hand_description.h" 00036 #include "object_manipulator/tools/exceptions.h" 00037 00038 //#define PROF_ENABLED 00039 //#include <profiling/profiling.h> 00040 //PROF_DECLARE(INTERPOLATED_IK); 00041 //PROF_DECLARE(SET_PLANNING_SCENE); 00042 00043 namespace object_manipulator { 00044 00045 static const std::string IK_SERVICE_SUFFIX = "/constraint_aware_ik"; 00046 static const std::string FK_SERVICE_SUFFIX = "/get_fk"; 00047 static const std::string INTERPOLATED_IK_SERVICE_SUFFIX = "/interpolated_ik"; 00048 static const std::string INTERPOLATED_IK_SET_PARAMS_SERVICE_SUFFIX = "/interpolated_ik_set_params"; 00049 static const std::string IK_QUERY_SERVICE_SUFFIX = "/get_ik_solver_info"; 00050 static const std::string GRASP_STATUS_SUFFIX = "/grasp_status"; 00051 00052 static const std::string SET_PLANNING_SCENE_DIFF_NAME = "environment_server/set_planning_scene_diff"; 00053 static const std::string CHECK_STATE_VALIDITY_NAME = "planning_scene_validity_server/get_state_validity"; 00054 static const std::string GET_ROBOT_STATE_NAME = "environment_server/get_robot_state"; 00055 static const std::string NORMALIZE_SERVICE_NAME = "trajectory_filter_unnormalizer/filter_trajectory"; 00056 static const std::string RESET_COLLISION_MAP_SERVICE_NAME = "collider_node/reset"; 00057 00058 static const std::string REACTIVE_GRASP_ACTION_SUFFIX = "/reactive_grasp"; 00059 static const std::string REACTIVE_LIFT_ACTION_SUFFIX = "/reactive_lift"; 00060 static const std::string REACTIVE_PLACE_ACTION_SUFFIX = "/reactive_place"; 00061 static const std::string MOVE_ARM_ACTION_SUFFIX = "/move_arm"; 00062 static const std::string TRAJECTORY_ACTION_SUFFIX = "/joint_trajectory"; 00063 static const std::string HAND_POSTURE_ACTION_SUFFIX = "/hand_posture_execution"; 00064 00065 static const std::string SWITCH_CONTROLLER_SERVICE_NAME = "/switch_controller"; 00066 static const std::string LIST_CONTROLLERS_SERVICE_NAME = "/list_controllers"; 00067 static const std::string CARTESIAN_COMMAND_SUFFIX = "/cart/command_pose"; 00068 static const std::string CARTESIAN_POSTURE_SUFFIX = "/cart/command_posture"; 00069 //static const std::string CARTESIAN_GAINS_SUFFIX = "/cart/gains"; 00070 00071 static const std::string MOVE_ARM_PLANNER_ID = "SBLkConfig1"; 00072 static const std::string MOVE_ARM_PLANNER_SERVICE_NAME = "ompl_planning/plan_kinematic_path"; 00073 static const std::string MOVE_ARM_CONSTRAINED_PLANNER_SERVICE_NAME = "ompl_planning/plan_kinematic_path"; 00074 00075 static const std::string ATTACHED_COLLISION_TOPIC="attached_collision_object"; 00076 00077 static const std::string POINT_HEAD_ACTION_TOPIC = "/head_traj_controller/point_head_action"; 00078 00079 static const double OBJECT_POSITION_TOLERANCE_X = 0.02; 00080 static const double OBJECT_POSITION_TOLERANCE_Y = 0.02; 00081 static const double OBJECT_POSITION_TOLERANCE_Z = 0.02; 00082 00083 MechanismInterface::MechanismInterface() : 00084 root_nh_(""),priv_nh_("~"), 00085 planning_scene_cache_empty_(true), 00086 cache_planning_scene_(false), 00087 //------------------- multi arm service clients ----------------------- 00088 ik_query_client_("", IK_QUERY_SERVICE_SUFFIX, true), 00089 ik_service_client_("", IK_SERVICE_SUFFIX, true), 00090 fk_service_client_("",FK_SERVICE_SUFFIX,true), 00091 interpolated_ik_service_client_("", INTERPOLATED_IK_SERVICE_SUFFIX, true), 00092 interpolated_ik_set_params_client_("", INTERPOLATED_IK_SET_PARAMS_SERVICE_SUFFIX, true), 00093 grasp_status_client_("", GRASP_STATUS_SUFFIX, true), 00094 //------------------- simple service clients ----------------------- 00095 check_state_validity_client_(CHECK_STATE_VALIDITY_NAME), 00096 joint_trajectory_normalizer_service_(NORMALIZE_SERVICE_NAME), 00097 switch_controller_service_(SWITCH_CONTROLLER_SERVICE_NAME), 00098 list_controllers_service_(LIST_CONTROLLERS_SERVICE_NAME), 00099 get_robot_state_client_(GET_ROBOT_STATE_NAME), 00100 set_planning_scene_diff_service_(SET_PLANNING_SCENE_DIFF_NAME), 00101 reset_collision_map_service_(RESET_COLLISION_MAP_SERVICE_NAME), 00102 //-------------------- multi arm action clients ----------------------- 00103 reactive_grasp_action_client_("", REACTIVE_GRASP_ACTION_SUFFIX, true, true), 00104 reactive_lift_action_client_("", REACTIVE_LIFT_ACTION_SUFFIX, true, true), 00105 reactive_place_action_client_("", REACTIVE_PLACE_ACTION_SUFFIX, true, true), 00106 move_arm_action_client_("", MOVE_ARM_ACTION_SUFFIX, true, true), 00107 traj_action_client_("", TRAJECTORY_ACTION_SUFFIX, true, true), 00108 hand_posture_client_("", HAND_POSTURE_ACTION_SUFFIX, true, true), 00109 //-------------------- head action client ----------------------- 00110 point_head_action_client_(POINT_HEAD_ACTION_TOPIC, true), 00111 //-------------------- multi arm topic publishers --------------------- 00112 cartesian_pub_("", CARTESIAN_COMMAND_SUFFIX, true), 00113 cartesian_posture_pub_("", CARTESIAN_POSTURE_SUFFIX, true) 00114 //cartesian_gains_pub_("", CARTESIAN_GAINS_SUFFIX, true) 00115 { 00116 //attached object publishing topic 00117 attached_object_pub_ = root_nh_.advertise<arm_navigation_msgs::AttachedCollisionObject>(ATTACHED_COLLISION_TOPIC, 10); 00118 00119 //JointStates topic for current arm angles 00120 priv_nh_.param<std::string>("joint_states_topic", joint_states_topic_, "joint_states"); 00121 00122 } 00123 00127 std::vector<std::string> MechanismInterface::getJointNames(std::string arm_name) 00128 { 00129 kinematics_msgs::GetKinematicSolverInfo::Request query_request; 00130 kinematics_msgs::GetKinematicSolverInfo::Response query_response; 00131 if ( !ik_query_client_.client(arm_name).call(query_request, query_response) ) 00132 { 00133 ROS_ERROR("Failed to call ik information query"); 00134 throw MechanismException("Failed to call ik information query"); 00135 } 00136 return query_response.kinematic_solver_info.joint_names; 00137 } 00138 00139 void MechanismInterface::getRobotState(arm_navigation_msgs::RobotState& robot_state) 00140 { 00141 arm_navigation_msgs::GetRobotState::Request req; 00142 arm_navigation_msgs::GetRobotState::Response res; 00143 if(!get_robot_state_client_.client().call(req,res)) 00144 { 00145 ROS_ERROR("Mechanism interface: can't get current robot state"); 00146 throw MechanismException("Mechanism interface: can't get current robot state"); 00147 } 00148 robot_state = res.robot_state; 00149 } 00150 00151 bool compareOrderedCollisionOperations(const arm_navigation_msgs::OrderedCollisionOperations& c1, 00152 const arm_navigation_msgs::OrderedCollisionOperations& c2) 00153 { 00154 if (c1.collision_operations.size() != c2.collision_operations.size()) return false; 00155 for (size_t i=0; i<c1.collision_operations.size(); i++) 00156 { 00157 if (c1.collision_operations[i].object1 != c2.collision_operations[i].object1 ) return false; 00158 if (c1.collision_operations[i].object2 != c2.collision_operations[i].object2 ) return false; 00159 if (c1.collision_operations[i].penetration_distance != 00160 c2.collision_operations[i].penetration_distance ) return false; 00161 if (c1.collision_operations[i].operation != c2.collision_operations[i].operation ) return false; 00162 } 00163 return true; 00164 } 00165 00166 bool compareLinkPadding(const std::vector<arm_navigation_msgs::LinkPadding> &l1, 00167 const std::vector<arm_navigation_msgs::LinkPadding> &l2) 00168 { 00169 if (l1.size() != l2.size()) return false; 00170 for (size_t i=0; i<l1.size(); i++) 00171 { 00172 if (l1[i].link_name != l2[i].link_name) return false; 00173 if (l1[i].padding != l2[i].padding) return false; 00174 } 00175 return true; 00176 } 00177 00178 bool MechanismInterface::cachePlanningScene(const arm_navigation_msgs::OrderedCollisionOperations& collision_operations, 00179 const std::vector<arm_navigation_msgs::LinkPadding> &link_padding) 00180 { 00181 static int cache_hits = 0; 00182 static int total_hits = 0; 00183 total_hits++; 00184 if (!cache_planning_scene_) 00185 { 00186 ROS_DEBUG_NAMED("manipulation","Planning scene caching disabled"); 00187 collision_operations_cache_ = collision_operations; 00188 link_padding_cache_ = link_padding; 00189 return false; 00190 } 00191 if (planning_scene_cache_empty_) 00192 { 00193 ROS_DEBUG_NAMED("manipulation","Planning scene cache empty."); 00194 collision_operations_cache_ = collision_operations; 00195 link_padding_cache_ = link_padding; 00196 planning_scene_cache_empty_ = false; 00197 return false; 00198 } 00199 if (!compareOrderedCollisionOperations(collision_operations, collision_operations_cache_)) 00200 { 00201 ROS_DEBUG_NAMED("manipulation","Planning scene cache miss - collisions (hits: %d/%d).", cache_hits, total_hits); 00202 collision_operations_cache_ = collision_operations; 00203 link_padding_cache_ = link_padding; 00204 return false; 00205 } 00206 if (!compareLinkPadding(link_padding, link_padding_cache_)) 00207 { 00208 ROS_DEBUG_NAMED("manipulation","Planning scene cache miss - padding (hits: %d/%d).", cache_hits, total_hits); 00209 collision_operations_cache_ = collision_operations; 00210 link_padding_cache_ = link_padding; 00211 return false; 00212 } 00213 cache_hits++; 00214 ROS_DEBUG_NAMED("manipulation", "Planning scene cache hit (hits: %d/%d).", cache_hits, total_hits); 00215 return true; 00216 } 00217 00218 void MechanismInterface::getPlanningScene(const arm_navigation_msgs::OrderedCollisionOperations& collision_operations, 00219 const std::vector<arm_navigation_msgs::LinkPadding> &link_padding) 00220 { 00221 if (cachePlanningScene(collision_operations, link_padding)) return; 00222 arm_navigation_msgs::SetPlanningSceneDiff::Request planning_scene_req; 00223 planning_scene_req.planning_scene_diff.link_padding = link_padding; 00224 planning_scene_req.operations = collision_operations; 00225 arm_navigation_msgs::SetPlanningSceneDiff::Response planning_scene_res; 00226 //PROF_COUNT(SET_PLANNING_SCENE); 00227 //PROF_START_TIMER(SET_PLANNING_SCENE); 00228 if(!set_planning_scene_diff_service_.client().call(planning_scene_req, planning_scene_res)) 00229 { 00230 ROS_ERROR("Failed to set planning scene diff"); 00231 throw MechanismException("Failed to set planning scene diff"); 00232 } 00233 //PROF_STOP_TIMER(SET_PLANNING_SCENE); 00234 } 00235 00236 trajectory_msgs::JointTrajectory MechanismInterface::assembleJointTrajectory(std::string arm_name, 00237 const std::vector< std::vector<double> > &positions, 00238 float time_per_segment) 00239 { 00240 trajectory_msgs::JointTrajectory trajectory; 00241 trajectory.header.frame_id = handDescription().robotFrame(arm_name); 00242 trajectory.header.stamp = ros::Time::now() + ros::Duration(1.0); 00243 trajectory.joint_names = getJointNames(arm_name); 00244 float current_time = 0; 00245 for (size_t i=0; i<positions.size(); i++) 00246 { 00247 current_time += time_per_segment; 00248 if (positions[i].size() != trajectory.joint_names.size()) 00249 { 00250 ROS_ERROR("Mechanism interface: requested trajectory does not have enough joint values"); 00251 throw MechanismException("Mechanism interface: requested trajectory does not have enough joint values"); 00252 } 00253 trajectory_msgs::JointTrajectoryPoint point; 00254 point.positions = positions[i]; 00255 point.time_from_start = ros::Duration(current_time); 00256 trajectory.points.push_back(point); 00257 } 00258 return trajectory; 00259 } 00260 00261 void MechanismInterface::attemptTrajectory(std::string arm_name, 00262 const std::vector< std::vector<double> > &positions, 00263 bool unnormalize, 00264 float time_per_segment) 00265 { 00266 attemptTrajectory(arm_name, assembleJointTrajectory(arm_name, positions, time_per_segment), unnormalize); 00267 } 00268 00269 00270 void MechanismInterface::unnormalizeTrajectory(std::string arm_name, 00271 const trajectory_msgs::JointTrajectory &input_trajectory, 00272 trajectory_msgs::JointTrajectory &normalized_trajectory) 00273 { 00274 arm_navigation_msgs::FilterJointTrajectory service_call; 00275 getRobotState(service_call.request.start_state); 00276 service_call.request.trajectory = input_trajectory; 00277 service_call.request.allowed_time = ros::Duration(2.0); 00278 if ( !joint_trajectory_normalizer_service_.client().call(service_call) ) 00279 { 00280 ROS_ERROR("Mechanism interface: joint trajectory normalizer service call failed"); 00281 throw MechanismException("joint trajectory normalizer service call failed"); 00282 } 00283 normalized_trajectory = service_call.response.trajectory; 00284 } 00285 00286 00287 void MechanismInterface::attemptTrajectory(std::string arm_name, 00288 const trajectory_msgs::JointTrajectory &trajectory, 00289 bool unnormalize) 00290 { 00291 if (trajectory.points.empty()) 00292 { 00293 ROS_ERROR("attemptTrajectory called with empty trajectory"); 00294 throw MechanismException("attemptTrajectory called with empty trajectory"); 00295 } 00296 00297 //make sure joint controllers are running 00298 if(!checkController(jointControllerName(arm_name))) 00299 switchToJoint(arm_name); 00300 00301 pr2_controllers_msgs::JointTrajectoryGoal goal; 00302 if (unnormalize) 00303 { 00304 unnormalizeTrajectory(arm_name, trajectory, goal.trajectory); 00305 } 00306 else 00307 { 00308 goal.trajectory = trajectory; 00309 } 00310 //force it to wait for client here, so that the duration below is not wasted 00311 traj_action_client_.client(arm_name); 00312 goal.trajectory.header.stamp = ros::Time::now() + ros::Duration(1.0); 00313 00314 //wait 5 seconds more that the whole trajectory is supposed to take 00315 ros::Duration timeout = ros::Duration(1.0) + trajectory.points.back().time_from_start + ros::Duration(5.0); 00316 traj_action_client_.client(arm_name).sendGoal(goal); 00317 if ( !traj_action_client_.client(arm_name).waitForResult(timeout) ) 00318 { 00319 ROS_ERROR(" Trajectory timed out"); 00320 throw MechanismException("trajectory timed out"); 00321 } 00322 } 00323 00324 void MechanismInterface::setInterpolatedIKParams(std::string arm_name, int num_steps, 00325 int collision_check_resolution, bool start_from_end) 00326 { 00327 interpolated_ik_motion_planner::SetInterpolatedIKMotionPlanParams srv; 00328 srv.request.num_steps = num_steps; 00329 srv.request.consistent_angle = M_PI/6; 00330 srv.request.collision_check_resolution = collision_check_resolution; 00331 srv.request.steps_before_abort = 0; 00332 srv.request.pos_spacing = 0.01; //ignored if num_steps !=0 00333 srv.request.rot_spacing = 0.1; //ignored if num_steps !=0 00334 srv.request.collision_aware = true; 00335 srv.request.start_from_end = start_from_end; 00336 if (!interpolated_ik_set_params_client_.client(arm_name).call(srv)) 00337 { 00338 ROS_ERROR("Failed to set Interpolated IK server parameters"); 00339 throw MechanismException("Failed to set Interpolated IK server parameters"); 00340 } 00341 } 00342 00343 bool MechanismInterface::moveArmToPose(std::string arm_name, const geometry_msgs::PoseStamped &desired_pose, 00344 const arm_navigation_msgs::OrderedCollisionOperations &collision_operations, 00345 const std::vector<arm_navigation_msgs::LinkPadding> &link_padding) 00346 { 00347 kinematics_msgs::GetConstraintAwarePositionIK::Response ik_response; 00348 if(!getIKForPose(arm_name, desired_pose,ik_response, collision_operations, link_padding)) return false; 00349 if(!attemptMoveArmToGoal(arm_name, ik_response.solution.joint_state.position, collision_operations, link_padding)) 00350 return false; 00351 return true; 00352 } 00353 00354 bool MechanismInterface::getFK(std::string arm_name, 00355 std::vector<double> positions, 00356 geometry_msgs::PoseStamped &pose_stamped) 00357 { 00358 // define the service messages 00359 kinematics_msgs::GetPositionFK::Request fk_request; 00360 kinematics_msgs::GetPositionFK::Response fk_response; 00361 fk_request.header.frame_id = pose_stamped.header.frame_id; 00362 fk_request.header.stamp = pose_stamped.header.stamp; 00363 fk_request.fk_link_names.resize(1); 00364 fk_request.fk_link_names[0] = handDescription().gripperFrame(arm_name); 00365 fk_request.robot_state.joint_state.position = positions; 00366 fk_request.robot_state.joint_state.name = getJointNames(arm_name); 00367 if( !fk_service_client_.client(arm_name).call(fk_request,fk_response) ) 00368 { 00369 ROS_ERROR("FK Service Call failed altogether"); 00370 throw MechanismException("FK Service Call failed altogether"); 00371 } 00372 if (fk_response.error_code.val != fk_response.error_code.SUCCESS) 00373 { 00374 ROS_ERROR("Get FK failed with error code %d", fk_response.error_code.val); 00375 return false; 00376 } 00377 pose_stamped = fk_response.pose_stamped[0]; 00378 return true; 00379 } 00380 00381 bool MechanismInterface::getIKForPose(std::string arm_name, const geometry_msgs::PoseStamped &desired_pose, 00382 kinematics_msgs::GetConstraintAwarePositionIK::Response& ik_response, 00383 const arm_navigation_msgs::OrderedCollisionOperations &collision_operations, 00384 const std::vector<arm_navigation_msgs::LinkPadding> &link_padding) 00385 { 00386 //prepare the planning scene 00387 getPlanningScene(collision_operations, link_padding); 00388 //call collision-aware ik 00389 kinematics_msgs::GetConstraintAwarePositionIK::Request ik_request; 00390 ik_request.ik_request.ik_link_name = handDescription().gripperFrame(arm_name); 00391 ik_request.ik_request.pose_stamped.pose = desired_pose.pose; 00392 ik_request.ik_request.pose_stamped.header.stamp = desired_pose.header.stamp; 00393 ik_request.ik_request.pose_stamped.header.frame_id = desired_pose.header.frame_id; 00394 ik_request.ik_request.ik_seed_state.joint_state.name = getJointNames(arm_name); 00395 ik_request.ik_request.ik_seed_state.joint_state.position.resize(7, 0.0); 00396 ik_request.timeout = ros::Duration(2.0); 00397 if( !ik_service_client_.client(arm_name).call(ik_request,ik_response) ) 00398 { 00399 ROS_ERROR("IK Service Call failed altogether"); 00400 throw MechanismException("IK Service Call failed altogether"); 00401 } 00402 if (ik_response.error_code.val != ik_response.error_code.SUCCESS) 00403 { 00404 ROS_ERROR("Get IK failed with error code %d", ik_response.error_code.val); 00405 return false; 00406 } 00407 return true; 00408 } 00409 00410 bool MechanismInterface::checkStateValidity(std::string arm_name, const std::vector<double> &joint_values, 00411 const arm_navigation_msgs::OrderedCollisionOperations &collision_operations, 00412 const std::vector<arm_navigation_msgs::LinkPadding> &link_padding) 00413 { 00414 //prepare the planning scene 00415 getPlanningScene(collision_operations, link_padding); 00416 //call check state validity 00417 arm_navigation_msgs::GetStateValidity::Request req; 00418 arm_navigation_msgs::GetStateValidity::Response res; 00419 req.group_name = handDescription().armGroup(arm_name); 00420 if (!joint_values.empty()) 00421 { 00422 req.robot_state.joint_state.name = getJointNames(arm_name); 00423 req.robot_state.joint_state.position = joint_values; 00424 if ( req.robot_state.joint_state.name.size() != joint_values.size() ) 00425 { 00426 throw MechanismException("Wrong number of joint values for checkStateValidity"); 00427 } 00428 req.robot_state.joint_state.header.stamp = ros::Time::now(); 00429 } 00430 req.check_collisions = true; 00431 if(!check_state_validity_client_.client().call(req,res)) 00432 { 00433 throw MechanismException("Call to check state validity client failed"); 00434 } 00435 00436 if (res.error_code.val == res.error_code.SUCCESS) return true; 00437 return false; 00438 } 00439 00441 double getJointPosition( std::string name, const arm_navigation_msgs::RobotState& robot_state) 00442 { 00443 for (size_t i=0; i<robot_state.joint_state.name.size(); i++) 00444 { 00445 if (robot_state.joint_state.name[i] == name) 00446 { 00447 ROS_ASSERT(robot_state.joint_state.position.size() > i); 00448 return robot_state.joint_state.position[i]; 00449 } 00450 } 00451 ROS_ERROR_STREAM("Joint " << name << " not found in robot state"); 00452 return 0.0; 00453 } 00454 00467 int MechanismInterface::getInterpolatedIK(std::string arm_name, 00468 geometry_msgs::PoseStamped start_pose, 00469 geometry_msgs::Vector3Stamped direction, 00470 float desired_trajectory_length, 00471 const std::vector<double> &seed_joint_position, 00472 const sensor_msgs::JointState &joint_state, 00473 const arm_navigation_msgs::OrderedCollisionOperations &collision_operations, 00474 const std::vector<arm_navigation_msgs::LinkPadding> &link_padding, 00475 bool reverse_trajectory, 00476 trajectory_msgs::JointTrajectory &trajectory, 00477 float &actual_trajectory_length) 00478 { 00479 //first compute the desired end pose 00480 //make sure the input is normalized 00481 geometry_msgs::Vector3Stamped direction_norm = direction; 00482 direction_norm.vector = normalize(direction.vector); 00483 //multiply by the length 00484 desired_trajectory_length = fabs(desired_trajectory_length); 00485 direction_norm.vector.x *= desired_trajectory_length; 00486 direction_norm.vector.y *= desired_trajectory_length; 00487 direction_norm.vector.z *= desired_trajectory_length; 00488 geometry_msgs::PoseStamped end_pose = translateGripperPose(direction_norm, start_pose, arm_name); 00489 00490 //hard-coded for now 00491 float max_step_size = 0.01; 00492 unsigned int collision_check_resolution = 2; 00493 00494 //compute the number of steps 00495 unsigned int num_steps = (unsigned int)ceil(desired_trajectory_length / fabs(max_step_size)); 00496 float actual_step_size = desired_trajectory_length / num_steps; 00497 00498 ROS_DEBUG_NAMED("manipulation","Trajectory details: length %f, requested num steps: %d, actual step size: %f", 00499 desired_trajectory_length, num_steps, actual_step_size); 00500 00501 if (reverse_trajectory) 00502 { 00503 std::swap(start_pose, end_pose); 00504 } 00505 00506 //recall that here we setting the number of points in trajectory, which is steps+1 00507 setInterpolatedIKParams(arm_name, num_steps+1, collision_check_resolution, reverse_trajectory); 00508 00509 arm_navigation_msgs::RobotState start_state; 00510 start_state.multi_dof_joint_state.child_frame_ids.push_back(handDescription().gripperFrame(arm_name)); 00511 start_state.multi_dof_joint_state.poses.push_back(start_pose.pose); 00512 start_state.multi_dof_joint_state.frame_ids.push_back(start_pose.header.frame_id); 00513 start_state.multi_dof_joint_state.stamp = ros::Time::now(); 00514 00515 //pass the seeds for the IK 00516 if (!seed_joint_position.empty()) 00517 { 00518 //the caller has provided seeds for planned joints 00519 //we are silently assuming that the values passed in match our joint names for IK 00520 start_state.joint_state.name = getJointNames(arm_name); 00521 if (seed_joint_position.size() != start_state.joint_state.name.size()) 00522 { 00523 ROS_ERROR("Interpolated IK request: seed_joint_position does not match joint names"); 00524 throw MechanismException("Interpolated IK request: seed_joint_position does not match joint names"); 00525 } 00526 start_state.joint_state.position = seed_joint_position; 00527 } 00528 else 00529 { 00530 //no seeds have been passed in, use current robot state 00531 //grab the latest JointState message and read in joint positions 00532 arm_navigation_msgs::RobotState robot_state; 00533 getRobotState(robot_state); 00534 start_state.joint_state.name = getJointNames(arm_name); 00535 for (size_t i=0; i<start_state.joint_state.name.size(); i++) 00536 { 00537 start_state.joint_state.position.push_back( getJointPosition(start_state.joint_state.name[i], robot_state) ); 00538 } 00539 } 00540 00541 //pass the desired values of non-planned joints, if any 00542 for (size_t i=0; i<joint_state.name.size(); i++) 00543 { 00544 start_state.joint_state.name.push_back(joint_state.name[i]); 00545 start_state.joint_state.position.push_back(joint_state.position[i]); 00546 } 00547 00548 arm_navigation_msgs::PositionConstraint position_constraint; 00549 arm_navigation_msgs::OrientationConstraint orientation_constraint; 00550 arm_navigation_msgs::poseStampedToPositionOrientationConstraints(end_pose, handDescription().gripperFrame(arm_name), 00551 position_constraint, 00552 orientation_constraint); 00553 arm_navigation_msgs::Constraints goal_constraints; 00554 goal_constraints.position_constraints.push_back(position_constraint); 00555 goal_constraints.orientation_constraints.push_back(orientation_constraint); 00556 00557 arm_navigation_msgs::GetMotionPlan motion_plan; 00558 motion_plan.request.motion_plan_request.start_state = start_state; 00559 motion_plan.request.motion_plan_request.goal_constraints = goal_constraints; 00560 00561 //prepare the planning scene 00562 getPlanningScene(collision_operations, link_padding); 00563 00564 //PROF_COUNT(INTERPOLATED_IK); 00565 //PROF_START_TIMER(INTERPOLATED_IK); 00566 if ( !interpolated_ik_service_client_.client(arm_name).call(motion_plan) ) 00567 { 00568 ROS_ERROR(" Call to Interpolated IK service failed"); 00569 throw MechanismException("Call to Interpolated IK service failed"); 00570 } 00571 //PROF_STOP_TIMER(INTERPOLATED_IK); 00572 00573 trajectory.points.clear(); 00574 trajectory.joint_names = motion_plan.response.trajectory.joint_trajectory.joint_names; 00575 00576 if (motion_plan.response.trajectory_error_codes.empty()) 00577 { 00578 ROS_ERROR(" Interpolated IK: empty trajectory received"); 00579 throw MechanismException("Interpolated IK: empty trajectory received"); 00580 } 00581 00582 int error_code = arm_navigation_msgs::ArmNavigationErrorCodes::SUCCESS; 00583 if (!reverse_trajectory) 00584 { 00585 for (size_t i=0; i<motion_plan.response.trajectory_error_codes.size(); i++) 00586 { 00587 if ( motion_plan.response.trajectory_error_codes[i].val == motion_plan.response.trajectory_error_codes[i].SUCCESS ) 00588 { 00589 trajectory.points.push_back( motion_plan.response.trajectory.joint_trajectory.points[i] ); 00590 } 00591 else 00592 { 00593 ROS_DEBUG_NAMED("manipulation"," Interpolated IK failed on step %d (forward towards %d) with error code %d", 00594 (int) i, 00595 (int) motion_plan.response.trajectory_error_codes.size() - 1, 00596 motion_plan.response.trajectory_error_codes[i].val); 00597 error_code = motion_plan.response.trajectory_error_codes[i].val; 00598 break; 00599 } 00600 } 00601 } 00602 else 00603 { 00604 size_t first_success = 0; 00605 while ( first_success < motion_plan.response.trajectory_error_codes.size() && 00606 motion_plan.response.trajectory_error_codes[first_success].val != 00607 motion_plan.response.trajectory_error_codes[first_success].SUCCESS ) first_success ++; 00608 if (first_success != 0) 00609 { 00610 ROS_DEBUG_NAMED("manipulation"," Interpolation failed on step %d (backwards from %d) with error code %d", 00611 (int) first_success - 1, 00612 (int) motion_plan.response.trajectory_error_codes.size() - 1, 00613 motion_plan.response.trajectory_error_codes[first_success - 1].val); 00614 error_code = motion_plan.response.trajectory_error_codes[first_success - 1].val; 00615 } 00616 else 00617 { 00618 ROS_DEBUG_NAMED("manipulation"," Interpolation trajectory complete (backwards from %d points)", 00619 (int) motion_plan.response.trajectory_error_codes.size()); 00620 00621 } 00622 for (size_t i=first_success; i < motion_plan.response.trajectory_error_codes.size(); i++) 00623 { 00624 if ( motion_plan.response.trajectory_error_codes[i].val == motion_plan.response.trajectory_error_codes[i].SUCCESS ) 00625 { 00626 trajectory.points.push_back( motion_plan.response.trajectory.joint_trajectory.points[i] ); 00627 } 00628 else 00629 { 00630 ROS_ERROR(" Interpolated IK: unexpected behavior for error codes: step %d has error code %d", 00631 (int) i, motion_plan.response.trajectory_error_codes[i].val); 00632 throw MechanismException("Interpolated IK: unexpected behavior for error codes"); 00633 } 00634 } 00635 } 00636 00637 if (!trajectory.points.empty()) actual_trajectory_length = actual_step_size * (trajectory.points.size()-1); 00638 else actual_trajectory_length = 0.0; 00639 return error_code; 00640 } 00641 00642 bool MechanismInterface::attemptMoveArmToGoal(std::string arm_name, const std::vector<double> &desired_joint_values, 00643 const arm_navigation_msgs::OrderedCollisionOperations &collision_operations, 00644 const std::vector<arm_navigation_msgs::LinkPadding> &link_padding) 00645 { 00646 //make sure joint controllers are running 00647 if(!checkController(jointControllerName(arm_name))) 00648 switchToJoint(arm_name); 00649 00650 int num_tries = 0; 00651 int max_tries = 5; 00652 arm_navigation_msgs::MoveArmGoal move_arm_goal; 00653 // no need to set the planning scene as move arm does not use that; instead 00654 // we'll set collision ops and link padding in move arm call 00655 move_arm_goal.planning_scene_diff.link_padding = link_padding; 00656 move_arm_goal.operations = collision_operations; 00657 00658 move_arm_goal.motion_plan_request.group_name = handDescription().armGroup(arm_name); 00659 move_arm_goal.motion_plan_request.num_planning_attempts = 1; 00660 move_arm_goal.motion_plan_request.allowed_planning_time = ros::Duration(5.0); 00661 move_arm_goal.motion_plan_request.planner_id = MOVE_ARM_PLANNER_ID; 00662 move_arm_goal.planner_service_name = MOVE_ARM_PLANNER_SERVICE_NAME; 00663 00664 00665 std::vector<std::string> joint_names = getJointNames(arm_name); 00666 move_arm_goal.motion_plan_request.goal_constraints.joint_constraints.resize(joint_names.size()); 00667 for(unsigned int i = 0; i < desired_joint_values.size(); i++) 00668 { 00669 move_arm_goal.motion_plan_request.goal_constraints.joint_constraints[i].joint_name = joint_names.at(i); 00670 move_arm_goal.motion_plan_request.goal_constraints.joint_constraints[i].position = desired_joint_values[i]; 00671 move_arm_goal.motion_plan_request.goal_constraints.joint_constraints[i].tolerance_below = .08; 00672 move_arm_goal.motion_plan_request.goal_constraints.joint_constraints[i].tolerance_above = .08; 00673 } 00674 00675 bool success = false; 00676 arm_navigation_msgs::ArmNavigationErrorCodes error_code; 00677 while(num_tries < max_tries) 00678 { 00679 move_arm_action_client_.client(arm_name).sendGoal(move_arm_goal); 00680 bool withinWait = move_arm_action_client_.client(arm_name).waitForResult(ros::Duration(60.0)); 00681 if(!withinWait) 00682 { 00683 move_arm_action_client_.client(arm_name).cancelGoal(); 00684 ROS_DEBUG_NAMED("manipulation"," Move arm goal could not be achieved by move_arm in the allowed duration"); 00685 success = false; 00686 num_tries++; 00687 arm_navigation_msgs::MoveArmResult move_arm_result = *move_arm_action_client_.client(arm_name).getResult(); 00688 error_code.val = error_code.TIMED_OUT; 00689 modifyMoveArmGoal(move_arm_goal,error_code,move_arm_result.contacts); 00690 continue; 00691 } 00692 actionlib::SimpleClientGoalState state = move_arm_action_client_.client(arm_name).getState(); 00693 if(state == actionlib::SimpleClientGoalState::SUCCEEDED) 00694 { 00695 ROS_DEBUG_NAMED("manipulation"," Move arm: position was successfully achieved"); 00696 success = true; 00697 break; 00698 } 00699 else 00700 { 00701 arm_navigation_msgs::MoveArmResult move_arm_result = *move_arm_action_client_.client(arm_name).getResult(); 00702 ROS_DEBUG_NAMED("manipulation"," Move arm: non-success state was reached. Reason: %s", 00703 (arm_navigation_msgs::armNavigationErrorCodeToString(move_arm_result.error_code)).c_str()); 00704 ROS_DEBUG_NAMED("manipulation"," num_tries: %d, max_tries: %d",num_tries,max_tries); 00705 success = false; 00706 num_tries++; 00707 error_code = move_arm_result.error_code; 00708 00709 //reset the collision map and wait to repopulate it before trying again 00710 if(error_code.val == error_code.START_STATE_IN_COLLISION) 00711 { 00712 std_srvs::Empty srv; 00713 if ( !reset_collision_map_service_.client().call(srv) ) 00714 { 00715 ROS_ERROR("Mechanism interface: reset collision map service call failed"); 00716 } 00717 //tried to reset and repopulate twice already; just reset and try again right away 00718 if(num_tries <=2){ 00719 ros::Duration(5.0).sleep(); 00720 ROS_INFO("move arm is stuck! Resetting the collision map and repopulating!"); 00721 } 00722 else{ 00723 ROS_ERROR("move arm is still stuck! Resetting the collision map and NOT repopulating"); 00724 } 00725 } 00726 //modifyMoveArmGoal(move_arm_goal,error_code,move_arm_result.contacts); 00727 continue; 00728 } 00729 } 00731 if (!success && error_code.val == error_code.START_STATE_IN_COLLISION) 00732 { 00733 throw MoveArmStuckException(); 00734 } 00735 return success; 00736 } 00737 00738 00739 void MechanismInterface::modifyMoveArmGoal(arm_navigation_msgs::MoveArmGoal &move_arm_goal, 00740 arm_navigation_msgs::ArmNavigationErrorCodes &error_code, 00741 std::vector<arm_navigation_msgs::ContactInformation> &contact_info_) 00742 { 00743 double allowed_penetration_depth = 0.03; 00744 if(error_code.val == error_code.START_STATE_IN_COLLISION) 00745 { 00746 std::vector<arm_navigation_msgs::AllowedContactSpecification> allowed_contacts; 00747 for(unsigned int i=0; i < contact_info_.size(); i++) 00748 { 00749 if(contact_info_[i].depth < allowed_penetration_depth) 00750 { 00751 arm_navigation_msgs::AllowedContactSpecification allowed_contact_tmp; 00752 allowed_contact_tmp.shape.type = allowed_contact_tmp.shape.BOX; 00753 allowed_contact_tmp.shape.dimensions.resize(3); 00754 allowed_contact_tmp.shape.dimensions[0] = 0.03; 00755 allowed_contact_tmp.shape.dimensions[1] = 0.03; 00756 allowed_contact_tmp.shape.dimensions[2] = 0.03; 00757 allowed_contact_tmp.pose_stamped.pose.position = contact_info_[i].position; 00758 allowed_contact_tmp.pose_stamped.pose.orientation.x = 0.0; 00759 allowed_contact_tmp.pose_stamped.pose.orientation.y = 0.0; 00760 allowed_contact_tmp.pose_stamped.pose.orientation.z = 0.0; 00761 allowed_contact_tmp.pose_stamped.pose.orientation.w = 1.0; 00762 allowed_contact_tmp.pose_stamped.header.stamp = ros::Time::now(); 00763 allowed_contact_tmp.pose_stamped.header.frame_id = contact_info_[i].header.frame_id; 00764 allowed_contact_tmp.link_names.push_back(contact_info_[i].contact_body_1); 00765 allowed_contact_tmp.penetration_depth = allowed_penetration_depth; 00766 allowed_contacts.push_back(allowed_contact_tmp); 00767 ROS_DEBUG_NAMED("manipulation","Added allowed contact region: %d",i); 00768 ROS_DEBUG_NAMED("manipulation","Position : (%f,%f,%f)",contact_info_[i].position.x, 00769 contact_info_[i].position.y,contact_info_[i].position.z); 00770 ROS_DEBUG_NAMED("manipulation","Frame id : %s",contact_info_[i].header.frame_id.c_str()); 00771 ROS_DEBUG_NAMED("manipulation","Depth : %f",allowed_penetration_depth); 00772 ROS_DEBUG_NAMED("manipulation","Link : %s",contact_info_[i].contact_body_1.c_str()); 00773 ROS_DEBUG_NAMED("manipulation"," "); 00774 } 00775 } 00776 ROS_DEBUG_NAMED("manipulation","Added %d allowed contact regions",(int)allowed_contacts.size()); 00777 move_arm_goal.planning_scene_diff.allowed_contacts = allowed_contacts; 00778 } 00779 } 00780 00781 00782 bool MechanismInterface::moveArmConstrained(std::string arm_name, const geometry_msgs::PoseStamped &commanded_pose, 00783 const arm_navigation_msgs::OrderedCollisionOperations &collision_operations, 00784 const std::vector<arm_navigation_msgs::LinkPadding> &link_padding, 00785 const arm_navigation_msgs::Constraints &path_constraints, 00786 const double &redundancy, 00787 const bool &compute_viable_command_pose) 00788 { 00789 //make sure joint controllers are running 00790 if(!checkController(jointControllerName(arm_name))) 00791 switchToJoint(arm_name); 00792 00793 int num_tries = 0; 00794 int max_tries = 1; 00795 00796 arm_navigation_msgs::MoveArmGoal move_arm_goal; 00797 // no need to set the planning scene as move arm does not use that; instead 00798 // we'll set collision ops and link padding in move arm call 00799 move_arm_goal.planning_scene_diff.link_padding = link_padding; 00800 move_arm_goal.operations = collision_operations; 00801 00802 move_arm_goal.motion_plan_request.group_name = handDescription().armGroup(arm_name)+"_cartesian"; 00803 move_arm_goal.motion_plan_request.num_planning_attempts = 1; 00804 move_arm_goal.motion_plan_request.allowed_planning_time = ros::Duration(5.0); 00805 move_arm_goal.motion_plan_request.planner_id = MOVE_ARM_PLANNER_ID; 00806 move_arm_goal.planner_service_name = MOVE_ARM_CONSTRAINED_PLANNER_SERVICE_NAME; 00807 00808 move_arm_goal.motion_plan_request.goal_constraints.position_constraints.resize(1); 00809 move_arm_goal.motion_plan_request.goal_constraints.position_constraints[0].header.frame_id = 00810 commanded_pose.header.frame_id; 00811 move_arm_goal.motion_plan_request.goal_constraints.position_constraints[0].link_name = 00812 handDescription().gripperFrame(arm_name); 00813 move_arm_goal.motion_plan_request.goal_constraints.position_constraints[0].position = commanded_pose.pose.position; 00814 move_arm_goal.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_shape.type = 00815 arm_navigation_msgs::Shape::BOX; 00816 move_arm_goal.motion_plan_request.goal_constraints.position_constraints[0]. 00817 constraint_region_shape.dimensions.push_back(OBJECT_POSITION_TOLERANCE_X); 00818 move_arm_goal.motion_plan_request.goal_constraints.position_constraints[0]. 00819 constraint_region_shape.dimensions.push_back(OBJECT_POSITION_TOLERANCE_Y); 00820 move_arm_goal.motion_plan_request.goal_constraints.position_constraints[0]. 00821 constraint_region_shape.dimensions.push_back(OBJECT_POSITION_TOLERANCE_Z); 00822 move_arm_goal.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_orientation.w = 1.0; 00823 move_arm_goal.motion_plan_request.goal_constraints.position_constraints[0].weight = 1.0; 00824 00825 move_arm_goal.motion_plan_request.goal_constraints.orientation_constraints.resize(1); 00826 move_arm_goal.motion_plan_request.goal_constraints.orientation_constraints[0] = 00827 path_constraints.orientation_constraints[0]; 00828 move_arm_goal.motion_plan_request.goal_constraints.orientation_constraints[0].header.stamp = ros::Time::now(); 00829 00830 btQuaternion orientation; 00831 tf::quaternionMsgToTF(commanded_pose.pose.orientation,orientation); 00832 geometry_msgs::PoseStamped desired_pose = commanded_pose; 00833 desired_pose.pose.position = move_arm_goal.motion_plan_request.goal_constraints.position_constraints[0].position; 00834 desired_pose.header.stamp = ros::Time::now(); 00835 00836 // TODO - this should really happen through the constraint 00837 // Currently its hard-coded for keeping objects level 00838 if(compute_viable_command_pose && path_constraints.orientation_constraints.size()) 00839 { 00840 bool get_ik = false; 00841 for(unsigned int i=0; i < 360; i++) 00842 { 00843 double rotation_yaw = i*M_PI/360.0; 00844 ROS_DEBUG_NAMED("manipulation","Trying to find suitable goal orientation with yaw rotation: %f",rotation_yaw); 00845 btQuaternion orientation_yaw; 00846 orientation_yaw.setRPY(0.0,0.0,rotation_yaw); 00847 orientation_yaw *= orientation; 00848 geometry_msgs::Quaternion quaternion; 00849 tf::quaternionTFToMsg(orientation_yaw,quaternion); 00850 desired_pose.pose.orientation = quaternion; 00851 desired_pose.header.stamp = ros::Time::now(); 00852 kinematics_msgs::GetConstraintAwarePositionIK::Response ik_response; 00853 if(getIKForPose(arm_name,desired_pose,ik_response, collision_operations, link_padding)) 00854 { 00855 get_ik = true; 00856 break; 00857 } 00858 } 00859 if(!get_ik) 00860 return false; 00861 } 00862 00863 move_arm_goal.motion_plan_request.path_constraints.orientation_constraints.resize(1); 00864 move_arm_goal.motion_plan_request.path_constraints.orientation_constraints[0] = 00865 move_arm_goal.motion_plan_request.goal_constraints.orientation_constraints[0]; 00866 move_arm_goal.disable_ik = true; 00867 00868 move_arm_goal.motion_plan_request.goal_constraints.joint_constraints.resize(1); 00869 move_arm_goal.motion_plan_request.goal_constraints.joint_constraints[0].joint_name = (getJointNames(arm_name))[2]; 00870 move_arm_goal.motion_plan_request.goal_constraints.joint_constraints[0].position = redundancy; 00871 move_arm_goal.motion_plan_request.goal_constraints.joint_constraints[0].tolerance_below = M_PI; 00872 move_arm_goal.motion_plan_request.goal_constraints.joint_constraints[0].tolerance_above = M_PI; 00873 00874 bool success = false; 00875 while(num_tries < max_tries) 00876 { 00877 move_arm_action_client_.client(arm_name).sendGoal(move_arm_goal); 00878 bool withinWait = move_arm_action_client_.client(arm_name).waitForResult(ros::Duration(60.0)); 00879 if(!withinWait) 00880 { 00881 move_arm_action_client_.client(arm_name).cancelGoal(); 00882 ROS_DEBUG_NAMED("manipulation"," Move arm goal could not be achieved by move_arm in the allowed duration"); 00883 success = false; 00884 num_tries++; 00885 arm_navigation_msgs::MoveArmResult move_arm_result = *move_arm_action_client_.client(arm_name).getResult(); 00886 arm_navigation_msgs::ArmNavigationErrorCodes error_code; 00887 error_code.val = error_code.TIMED_OUT; 00888 modifyMoveArmGoal(move_arm_goal,error_code,move_arm_result.contacts); 00889 continue; 00890 } 00891 actionlib::SimpleClientGoalState state = move_arm_action_client_.client(arm_name).getState(); 00892 if(state == actionlib::SimpleClientGoalState::SUCCEEDED) 00893 { 00894 ROS_DEBUG_NAMED("manipulation"," Move arm: position was successfully achieved"); 00895 success = true; 00896 break; 00897 } 00898 else 00899 { 00900 arm_navigation_msgs::MoveArmResult move_arm_result = *move_arm_action_client_.client(arm_name).getResult(); 00901 ROS_DEBUG_NAMED("manipulation","Move arm: non-success state was reached. Reason: %s", 00902 (arm_navigation_msgs::armNavigationErrorCodeToString(move_arm_result.error_code)).c_str()); 00903 ROS_DEBUG_NAMED("manipulation","num_tries: %d, max_tries: %d",num_tries,max_tries); 00904 success = false; 00905 num_tries++; 00906 modifyMoveArmGoal(move_arm_goal,move_arm_result.error_code,move_arm_result.contacts); 00907 continue; 00908 } 00909 } 00910 return success; 00911 } 00912 00924 geometry_msgs::PoseStamped MechanismInterface::translateGripperPose(geometry_msgs::Vector3Stamped translation, 00925 geometry_msgs::PoseStamped start_pose, 00926 std::string arm_name) 00927 { 00928 bool pre_multiply; 00929 if (translation.header.frame_id == handDescription().gripperFrame(arm_name)) 00930 { 00931 pre_multiply=false; 00932 } 00933 else if (translation.header.frame_id == handDescription().robotFrame(arm_name)) 00934 { 00935 pre_multiply=true; 00936 } 00937 else 00938 { 00939 throw MechanismException(std::string("Gripper translations (such as for lift or approach) can only be specified in " 00940 "either the gripper frame or the robot frame. This one was specified in frame ") + 00941 translation.header.frame_id); 00942 } 00943 00944 00945 //go to robot frame first 00946 geometry_msgs::PoseStamped start_pose_robot_frame = transformPose(handDescription().robotFrame(arm_name), start_pose); 00947 tf::StampedTransform start_transform; 00948 tf::poseMsgToTF(start_pose_robot_frame.pose, start_transform); 00949 00950 btVector3 vec; 00951 tf::vector3MsgToTF(translation.vector, vec); 00952 tf::StampedTransform translate_trans; 00953 translate_trans.setIdentity(); 00954 translate_trans.setOrigin(vec); 00955 00956 //compute the translated pose 00957 tf::Transform end_transform; 00958 if (pre_multiply) end_transform = translate_trans * start_transform; 00959 else end_transform = start_transform * translate_trans; 00960 00961 //prepare the results 00962 geometry_msgs::PoseStamped translated_pose; 00963 tf::poseTFToMsg(end_transform, translated_pose.pose); 00964 translated_pose.header.frame_id = handDescription().robotFrame(arm_name); 00965 translated_pose.header.stamp = ros::Time(0); 00966 00967 //return the result in the requested frame 00968 translated_pose = transformPose(start_pose.header.frame_id, translated_pose); 00969 00970 return translated_pose; 00971 } 00972 00974 geometry_msgs::PoseStamped MechanismInterface::getGripperPose(std::string arm_name, std::string frame_id) 00975 { 00976 tf::StampedTransform gripper_transform; 00977 try 00978 { 00979 listener_.lookupTransform(frame_id, handDescription().gripperFrame(arm_name), ros::Time(0), gripper_transform); 00980 } 00981 catch (tf::TransformException ex) 00982 { 00983 //sometimes fails the first time but succeeds the second. Don't ask me why. 00984 ROS_ERROR("failed to get tf transform for wrist roll link, trying a second time"); 00985 try 00986 { 00987 listener_.lookupTransform(frame_id, handDescription().gripperFrame(arm_name), ros::Time(0), gripper_transform); 00988 } 00989 catch (tf::TransformException ex) 00990 { 00991 ROS_ERROR("Mechanism interface: failed to get tf transform for wrist roll link; tf exception %s", ex.what()); 00992 throw MechanismException(std::string("failed to get tf transform for wrist roll link; tf exception: ") + 00993 std::string(ex.what()) ); 00994 } 00995 } 00996 geometry_msgs::PoseStamped gripper_pose; 00997 tf::poseTFToMsg(gripper_transform, gripper_pose.pose); 00998 gripper_pose.header.frame_id = frame_id; 00999 gripper_pose.header.stamp = ros::Time::now(); 01000 return gripper_pose; 01001 } 01002 01003 void MechanismInterface::transformPointCloud(std::string target_frame, 01004 const sensor_msgs::PointCloud &cloud_in, 01005 sensor_msgs::PointCloud &cloud_out) 01006 { 01007 try 01008 { 01009 listener_.transformPointCloud(target_frame, cloud_in, cloud_out); 01010 } 01011 catch (tf::TransformException ex) 01012 { 01013 ROS_ERROR("Mechanism interface: failed to cloud into %s frame; exception: %s", target_frame.c_str(), 01014 ex.what()); 01015 throw MechanismException(std::string("failed to transform cloud into frame ") + target_frame + 01016 std::string("; tf exception: ") + std::string(ex.what()) ); 01017 } 01018 } 01019 01020 void MechanismInterface::convertGraspableObjectComponentsToFrame(object_manipulation_msgs::GraspableObject &object, 01021 std::string frame_id) 01022 { 01023 if (!object.cluster.points.empty()) 01024 { 01025 transformPointCloud(frame_id, object.cluster, object.cluster); 01026 } 01027 for (size_t i=0; i<object.potential_models.size(); i++) 01028 { 01029 object.potential_models[i].pose = transformPose(frame_id, object.potential_models[i].pose); 01030 } 01031 object.reference_frame_id = frame_id; 01032 } 01033 01034 geometry_msgs::PoseStamped MechanismInterface::transformPose(const std::string target_frame, 01035 const geometry_msgs::PoseStamped &stamped_in) 01036 { 01037 geometry_msgs::PoseStamped stamped_out; 01038 try 01039 { 01040 listener_.transformPose(target_frame, stamped_in, stamped_out); 01041 } 01042 catch (tf::TransformException ex) 01043 { 01044 ROS_ERROR("Mechanism interface: failed to transform pose into %s frame; exception: %s", target_frame.c_str(), 01045 ex.what()); 01046 throw MechanismException(std::string("failed to transform pose into frame ") + target_frame + 01047 std::string("; tf exception: ") + std::string(ex.what()) ); 01048 } 01049 return stamped_out; 01050 } 01051 01054 bool MechanismInterface::translateGripper(std::string arm_name, const geometry_msgs::Vector3Stamped &direction, 01055 arm_navigation_msgs::OrderedCollisionOperations ord, 01056 const std::vector<arm_navigation_msgs::LinkPadding> &link_padding, 01057 float requested_distance, float min_distance, 01058 float &actual_distance) 01059 { 01060 //get the current gripper pose in the robot frame 01061 geometry_msgs::PoseStamped start_pose_stamped = getGripperPose(arm_name, handDescription().robotFrame(arm_name)); 01062 01063 //compute the interpolated trajectory 01064 trajectory_msgs::JointTrajectory traj; 01065 std::vector<double> empty; 01066 sensor_msgs::JointState empty_state; 01067 getInterpolatedIK(arm_name, 01068 start_pose_stamped, direction, requested_distance, 01069 empty, empty_state, ord, link_padding, false, traj, actual_distance); 01070 01071 if (min_distance > 0 && actual_distance < min_distance) 01072 { 01073 ROS_DEBUG_NAMED("manipulation","Mechanism interface: interpolated IK trajectory covers %f distance, but at least %f requested", 01074 actual_distance, min_distance); 01075 actual_distance = 0; 01076 return false; 01077 } 01078 01079 if (traj.points.empty()) 01080 { 01081 ROS_DEBUG_NAMED("manipulation","Mechanism interface: translate gripper trajectory is empty"); 01082 actual_distance = false; 01083 return false; 01084 } 01085 01086 //execute the normalized interpolated trajectory 01087 attemptTrajectory(arm_name, traj, true); 01088 return true; 01089 } 01090 01094 geometry_msgs::PoseStamped MechanismInterface::getObjectPoseForGrasp(std::string arm_name, 01095 const geometry_msgs::Pose &grasp_pose) 01096 01097 { 01098 //get the current pose of the gripper in base link coordinate frame 01099 tf::StampedTransform wrist_transform; 01100 try 01101 { 01102 listener_.lookupTransform("base_link",handDescription().gripperFrame(arm_name), 01103 ros::Time(0), wrist_transform); 01104 } 01105 catch (tf::TransformException ex) 01106 { 01107 ROS_ERROR("Mechanism interface: failed to get tf transform for wrist roll link"); 01108 throw MechanismException(std::string("failed to get tf transform for wrist roll link; tf exception: ") + 01109 std::string(ex.what()) ); 01110 } 01111 01112 //multiply by inverse of grasp pose 01113 tf::Transform grasp_transform; 01114 tf::poseMsgToTF(grasp_pose, grasp_transform); 01115 01116 tf::Transform object_transform; 01117 object_transform = wrist_transform * grasp_transform.inverse(); 01118 01119 //prepare the result 01120 geometry_msgs::PoseStamped object_pose; 01121 tf::poseTFToMsg(object_transform, object_pose.pose); 01122 object_pose.header.frame_id = "base_link"; 01123 object_pose.header.stamp = ros::Time::now(); 01124 return object_pose; 01125 } 01126 01127 void MechanismInterface::attachObjectToGripper(std::string arm_name, std::string collision_object_name) 01128 { 01129 arm_navigation_msgs::AttachedCollisionObject obj; 01130 obj.object.header.stamp = ros::Time::now(); 01131 obj.object.header.frame_id = handDescription().robotFrame(arm_name); 01132 obj.object.operation.operation = arm_navigation_msgs::CollisionObjectOperation::ATTACH_AND_REMOVE_AS_OBJECT; 01133 obj.object.id = collision_object_name; 01134 obj.link_name = handDescription().attachLinkName(arm_name); 01135 obj.touch_links = handDescription().gripperTouchLinkNames(arm_name); 01136 attached_object_pub_.publish(obj); 01137 } 01138 01139 void MechanismInterface::detachAndAddBackObjectsAttachedToGripper(std::string arm_name, 01140 std::string collision_object_name) 01141 { 01142 arm_navigation_msgs::AttachedCollisionObject att; 01143 att.object.header.stamp = ros::Time::now(); 01144 att.object.header.frame_id = handDescription().robotFrame(arm_name); 01145 att.link_name = handDescription().attachLinkName(arm_name); 01146 att.object.id = collision_object_name; 01147 att.object.operation.operation = arm_navigation_msgs::CollisionObjectOperation::DETACH_AND_ADD_AS_OBJECT; 01148 attached_object_pub_.publish(att); 01149 } 01150 01151 void MechanismInterface::detachAllObjectsFromGripper(std::string arm_name) 01152 { 01153 arm_navigation_msgs::AttachedCollisionObject att; 01154 att.object.header.stamp = ros::Time::now(); 01155 att.object.header.frame_id = handDescription().robotFrame(arm_name); 01156 att.link_name = handDescription().attachLinkName(arm_name); 01157 att.object.operation.operation = arm_navigation_msgs::CollisionObjectOperation::REMOVE; 01158 attached_object_pub_.publish(att); 01159 } 01160 01161 void MechanismInterface::handPostureGraspAction(std::string arm_name, 01162 const object_manipulation_msgs::Grasp &grasp, int goal, float max_contact_force) 01163 { 01164 object_manipulation_msgs::GraspHandPostureExecutionGoal posture_goal; 01165 posture_goal.grasp = grasp; 01166 posture_goal.goal = goal; 01167 posture_goal.max_contact_force = max_contact_force; 01168 hand_posture_client_.client(arm_name).sendGoal(posture_goal); 01169 bool withinWait = hand_posture_client_.client(arm_name).waitForResult(ros::Duration(10.0)); 01170 if(!withinWait) 01171 { 01172 hand_posture_client_.client(arm_name).cancelGoal(); 01173 ROS_ERROR("Hand posture controller timed out on goal (%d)", goal); 01174 throw MechanismException("Hand posture controller timed out"); 01175 } 01176 actionlib::SimpleClientGoalState state = hand_posture_client_.client(arm_name).getState(); 01177 if(state != actionlib::SimpleClientGoalState::SUCCEEDED) 01178 { 01179 ROS_ERROR("Hand posture controller failed on goal (%d)", goal); 01180 throw MechanismException("Hand posture controller failed"); 01181 } 01182 ROS_DEBUG_NAMED("manipulation","Hand posture controller successfully achieved goal %d", goal); 01183 } 01184 01185 bool MechanismInterface::graspPostureQuery(std::string arm_name, const object_manipulation_msgs::Grasp grasp) 01186 { 01187 object_manipulation_msgs::GraspStatus query; 01188 query.request.grasp = grasp; 01189 if (!grasp_status_client_.client(arm_name).call(query)) 01190 { 01191 ROS_ERROR("Grasp posture query call failed"); 01192 throw MechanismException("Grasp posture query call failed"); 01193 } 01194 return query.response.is_hand_occupied; 01195 } 01196 01197 bool MechanismInterface::pointHeadAction(const geometry_msgs::PointStamped &target, std::string pointing_frame, bool wait_for_result) 01198 { 01199 pr2_controllers_msgs::PointHeadGoal goal; 01200 goal.target = target; 01201 goal.pointing_axis.x = 0; 01202 goal.pointing_axis.y = 0; 01203 goal.pointing_axis.z = 1; 01204 goal.pointing_frame = pointing_frame; 01205 goal.min_duration = ros::Duration(0.05); 01206 goal.max_velocity = 1.0; 01207 01208 point_head_action_client_.client().sendGoal(goal); 01209 01210 if(wait_for_result) 01211 { 01212 point_head_action_client_.client().waitForResult( ros::Duration(3.0) ); 01213 01214 if (point_head_action_client_.client().getState() == actionlib::SimpleClientGoalState::SUCCEEDED) 01215 { 01216 ROS_DEBUG_NAMED("manipulation","Successfully moved head."); 01217 return true; 01218 } 01219 else 01220 { 01221 ROS_ERROR("Head movement failed or timed out."); 01222 return false; 01223 } 01224 } 01225 return true; 01226 } 01227 01228 bool MechanismInterface::callSwitchControllers(std::vector<std::string> start_controllers, 01229 std::vector<std::string> stop_controllers) 01230 { 01231 pr2_mechanism_msgs::SwitchController srv; 01232 srv.request.start_controllers = start_controllers; 01233 srv.request.stop_controllers = stop_controllers; 01234 srv.request.strictness = srv.request.STRICT; 01235 if ( !switch_controller_service_.client().call(srv) ) 01236 { 01237 ROS_ERROR("Mechanism interface: switch controller service call failed"); 01238 throw MechanismException("switch controller service call failed"); 01239 } 01240 if(!srv.response.ok) return false; 01241 return true; 01242 } 01243 01244 bool MechanismInterface::switchControllers(std::string start_controller, std::string stop_controller) 01245 { 01246 ROS_DEBUG_NAMED("manipulation","Switching controller %s for %s", start_controller.c_str(), stop_controller.c_str()); 01247 std::vector<std::string> start_controllers; 01248 std::vector<std::string> stop_controllers; 01249 start_controllers.push_back(start_controller); 01250 stop_controllers.push_back(stop_controller); 01251 bool success = callSwitchControllers(start_controllers, stop_controllers); 01252 if(success) 01253 { 01254 bool start_running = checkController(start_controller); 01255 bool stop_running = checkController(stop_controller); 01256 if(start_running && !stop_running) return true; 01257 ROS_ERROR("switching %s to %s failed even though it returned success", 01258 stop_controller.c_str(), start_controller.c_str()); 01259 return false; 01260 } 01261 else 01262 { 01263 ROS_ERROR("switching %s to %s failed", stop_controller.c_str(), start_controller.c_str()); 01264 return false; 01265 } 01266 } 01267 01268 bool MechanismInterface::checkController(std::string controller) 01269 { 01270 pr2_mechanism_msgs::ListControllers srv; 01271 if( !list_controllers_service_.client().call(srv)) 01272 { 01273 ROS_ERROR("Mechanism interface: list controllers service call failed"); 01274 throw MechanismException("list controllers service call failed"); 01275 } 01276 for(size_t controller_ind=0; controller_ind < srv.response.controllers.size(); controller_ind++) 01277 { 01278 if(controller.compare(srv.response.controllers[controller_ind]) == 0) 01279 { 01280 if(srv.response.state[controller_ind].compare("running") == 0) return true; 01281 return false; 01282 } 01283 } 01284 ROS_WARN("controller %s not found when checking status!", controller.c_str()); 01285 return false; 01286 } 01287 01288 bool MechanismInterface::startController(std::string controller) 01289 { 01290 ROS_DEBUG_NAMED("manipulation","Starting controller %s", controller.c_str()); 01291 std::vector<std::string> start_controllers; 01292 std::vector<std::string> stop_controllers; 01293 start_controllers.push_back(controller); 01294 bool success = callSwitchControllers(start_controllers, stop_controllers); 01295 if(success) 01296 { 01297 bool running = checkController(controller); 01298 if(running) return true; 01299 ROS_ERROR("starting controller %s failed even though it returned success", controller.c_str()); 01300 return false; 01301 } 01302 else 01303 { 01304 ROS_ERROR("starting controller %s failed", controller.c_str()); 01305 return false; 01306 } 01307 } 01308 01309 bool MechanismInterface::stopController(std::string controller) 01310 { 01311 ROS_DEBUG_NAMED("manipulation","Stopping controller %s", controller.c_str()); 01312 std::vector<std::string> start_controllers; 01313 std::vector<std::string> stop_controllers; 01314 stop_controllers.push_back(controller); 01315 bool success = callSwitchControllers(start_controllers, stop_controllers); 01316 if(success) 01317 { 01318 bool running = checkController(controller); 01319 if(running) 01320 { 01321 ROS_ERROR("stopping controller %s failed even though it returned success", controller.c_str()); 01322 return false; 01323 } 01324 return true; 01325 } 01326 else 01327 { 01328 ROS_ERROR("stopping controller %s failed", controller.c_str()); 01329 return false; 01330 } 01331 } 01332 01333 bool MechanismInterface::getArmAngles(std::string arm_name, std::vector<double> &arm_angles) 01334 { 01335 std::vector<std::string> arm_joints = handDescription().armJointNames(arm_name); 01336 if(arm_joints.size() == 0) 01337 { 01338 ROS_ERROR("mechanism interface: armJointNames was empty!"); 01339 return false; 01340 } 01341 arm_angles.resize(arm_joints.size()); 01342 01343 //grab the latest JointState message 01344 arm_navigation_msgs::RobotState robot_state; 01345 getRobotState(robot_state); 01346 //find each joint and its current position in the JointState message 01347 for (size_t joint_num = 0; joint_num < arm_joints.size(); joint_num++) 01348 { 01349 std::string joint_name = arm_joints[joint_num]; 01350 size_t i; 01351 for (i=0; i<robot_state.joint_state.name.size(); i++) 01352 { 01353 if (robot_state.joint_state.name[i] == joint_name) break; 01354 } 01355 if (i==robot_state.joint_state.name.size()) 01356 { 01357 ROS_ERROR("mechanism interface: arm joint %s not found in joint state", joint_name.c_str()); 01358 return false; 01359 } 01360 if (robot_state.joint_state.position.size() <= i) 01361 { 01362 ROS_ERROR("mechanism interface: malformed joint state message received"); 01363 return false; 01364 } 01365 arm_angles[joint_num] = robot_state.joint_state.position[i]; 01366 } 01367 ROS_DEBUG_NAMED("manipulation","%s arm_angles: %.2f %.2f %.2f %.2f %.2f %.2f %.2f", 01368 arm_name.c_str(), arm_angles[0], arm_angles[1], arm_angles[2], 01369 arm_angles[3], arm_angles[4], arm_angles[5], arm_angles[6]); 01370 return true; 01371 } 01372 01373 bool MechanismInterface::switchToCartesian(std::string arm_name) 01374 { 01375 //set the desired posture to the current joint angles first 01376 setCartesianPostureGoalToCurrentAngles(arm_name); 01377 01378 //switch controllers 01379 bool result = switchControllers(cartesianControllerName(arm_name), jointControllerName(arm_name)); 01380 if(!result) return false; 01381 return true; 01382 } 01383 01384 bool MechanismInterface::switchToJoint(std::string arm_name) 01385 { 01386 bool result = switchControllers(jointControllerName(arm_name), cartesianControllerName(arm_name)); 01387 if(!result) return false; 01388 return true; 01389 } 01390 01391 std::string MechanismInterface::jointControllerName(std::string arm_name) 01392 { 01393 std::map<std::string, std::string>::iterator it = joint_controller_names_.find(arm_name); 01394 if ( it != joint_controller_names_.end() ) 01395 { 01396 return it->second; 01397 } 01398 std::string controller_name; 01399 priv_nh_.param<std::string>(arm_name+std::string("_joint_controller"), controller_name, ""); 01400 if(controller_name == "") 01401 { 01402 ROS_WARN("joint controller name for arm %s not found!", arm_name.c_str()); 01403 } 01404 else 01405 { 01406 joint_controller_names_.insert(std::pair<std::string, std::string>(arm_name, controller_name)); 01407 ROS_INFO("added controller name %s to joint controller map", controller_name.c_str()); 01408 } 01409 return controller_name; 01410 } 01411 01412 std::string MechanismInterface::cartesianControllerName(std::string arm_name) 01413 { 01414 std::map<std::string, std::string>::iterator it = cartesian_controller_names_.find(arm_name); 01415 if ( it != cartesian_controller_names_.end() ) 01416 { 01417 return it->second; 01418 } 01419 std::string controller_name; 01420 priv_nh_.param<std::string>(arm_name+std::string("_cartesian_controller"), controller_name, ""); 01421 if(controller_name == "") 01422 { 01423 ROS_WARN("Cartesian controller name for arm %s not found!", arm_name.c_str()); 01424 } 01425 else 01426 { 01427 cartesian_controller_names_.insert(std::pair<std::string, std::string>(arm_name, controller_name)); 01428 ROS_INFO("added controller name %s to Cartesian controller map", controller_name.c_str()); 01429 } 01430 return controller_name; 01431 } 01432 01433 geometry_msgs::PoseStamped MechanismInterface::clipDesiredPose(std::string arm_name, 01434 const geometry_msgs::PoseStamped &desired_pose, 01435 double clip_dist, double clip_angle, 01436 double &resulting_clip_fraction) 01437 { 01438 //no clipping desired 01439 if(clip_dist == 0 && clip_angle == 0) return desired_pose; 01440 01441 //Get the current gripper pose 01442 geometry_msgs::PoseStamped current_pose = getGripperPose(arm_name, desired_pose.header.frame_id); 01443 01444 return clipDesiredPose(current_pose, desired_pose, clip_dist, clip_angle, resulting_clip_fraction); 01445 } 01446 01447 geometry_msgs::PoseStamped MechanismInterface::clipDesiredPose(const geometry_msgs::PoseStamped ¤t_pose, 01448 const geometry_msgs::PoseStamped &desired_pose, 01449 double clip_dist, double clip_angle, 01450 double &resulting_clip_fraction) 01451 { 01452 //no clipping desired 01453 if(clip_dist == 0 && clip_angle == 0) return desired_pose; 01454 01455 //Get the position and angle dists between current and desired 01456 Eigen::Affine3d current_trans, desired_trans; 01457 double pos_dist, angle; 01458 Eigen::Vector3d axis, direction; 01459 tf::poseMsgToEigen(current_pose.pose, current_trans); 01460 tf::poseMsgToEigen(desired_pose.pose, desired_trans); 01461 positionAndAngleDist(current_trans, desired_trans, pos_dist, angle, axis, direction); 01462 01463 //Clip the desired pose to be at most clip_dist and the desired angle to be at most clip_angle (proportional) 01464 //from the current 01465 double pos_mult, angle_mult; 01466 double pos_change, angle_change; 01467 angle_mult = fabs(angle / clip_angle); 01468 pos_mult = fabs(pos_dist / clip_dist); 01469 if(pos_mult <=1 && angle_mult <=1){ 01470 return desired_pose; 01471 } 01472 double mult = pos_mult; 01473 if(angle_mult > pos_mult) mult = angle_mult; 01474 pos_change = pos_dist / mult; 01475 angle_change = angle / mult; 01476 resulting_clip_fraction = 1 / mult; 01477 01478 Eigen::Affine3d clipped_trans; 01479 clipped_trans = current_trans; 01480 Eigen::Vector3d scaled_direction; 01481 scaled_direction = direction * pos_change; 01482 Eigen::Translation3d translation(scaled_direction); 01483 clipped_trans = clipped_trans * translation; 01484 Eigen::AngleAxis<double> angle_axis(angle_change, axis); 01485 clipped_trans = clipped_trans * angle_axis; 01486 geometry_msgs::PoseStamped clipped_pose; 01487 tf::poseEigenToMsg(clipped_trans, clipped_pose.pose); 01488 clipped_pose.header = desired_pose.header; 01489 return clipped_pose; 01490 } 01491 01492 01493 geometry_msgs::PoseStamped MechanismInterface::overshootDesiredPose(std::string arm_name, 01494 const geometry_msgs::PoseStamped &desired_pose, 01495 double overshoot_dist, double overshoot_angle, 01496 double dist_tol, double angle_tol) 01497 { 01498 //Get the current gripper pose 01499 geometry_msgs::PoseStamped current_pose = getGripperPose(arm_name, desired_pose.header.frame_id); 01500 01501 //Get the position and angle dists between current and desired 01502 Eigen::Affine3d current_trans, desired_trans; 01503 double pos_dist, angle; 01504 Eigen::Vector3d axis, direction; 01505 tf::poseMsgToEigen(current_pose.pose, current_trans); 01506 tf::poseMsgToEigen(desired_pose.pose, desired_trans); 01507 positionAndAngleDist(current_trans, desired_trans, pos_dist, angle, axis, direction); 01508 01509 //Add overshoot_dist in length to the pos difference vector, and overshoot_angle to the angle difference 01510 double pos_change = 0; 01511 double angle_change = 0; 01512 if(angle > angle_tol) angle_change = angle + overshoot_angle; 01513 double pos_sign = pos_dist / fabs(pos_dist); 01514 if(fabs(pos_dist) > dist_tol) pos_change = pos_dist + pos_sign*overshoot_dist; 01515 //std::cout << "pos_change: " << pos_change << "angle_change: " << angle_change; 01516 01517 Eigen::Affine3d overshoot_trans; 01518 overshoot_trans = current_trans; 01519 Eigen::Vector3d scaled_direction; 01520 scaled_direction = direction * pos_change; 01521 Eigen::Translation3d translation(scaled_direction); 01522 overshoot_trans = overshoot_trans * translation; 01523 Eigen::AngleAxis<double> angle_axis(angle_change, axis); 01524 overshoot_trans = overshoot_trans * angle_axis; 01525 geometry_msgs::PoseStamped overshoot_pose; 01526 tf::poseEigenToMsg(overshoot_trans, overshoot_pose.pose); 01527 overshoot_pose.header = desired_pose.header; 01528 01529 return overshoot_pose; 01530 } 01531 01532 01533 geometry_msgs::PoseStamped MechanismInterface::clipDesiredPose(std::string arm_name, 01534 const geometry_msgs::PoseStamped &desired_pose, 01535 double clip_dist, double clip_angle, 01536 double &resulting_clip_fraction, 01537 const std::vector<double> &goal_posture_suggestion, 01538 std::vector<double> &clipped_posture_goal) 01539 { 01540 double clip_fraction; 01541 geometry_msgs::PoseStamped clipped_pose = clipDesiredPose(arm_name, desired_pose, clip_dist, clip_angle, clip_fraction); 01542 01543 //If there's a goal posture suggestion, clip it as well 01544 if(goal_posture_suggestion.size() > 0 && (clip_dist != 0 || clip_angle != 0)) 01545 { 01546 //Get the current arm angles 01547 std::vector<double> current_arm_angles; 01548 getArmAngles(arm_name, current_arm_angles); 01549 01550 if(goal_posture_suggestion.size() != current_arm_angles.size()) 01551 { 01552 ROS_ERROR("goal posture suggestion length not consistent with length of current arm angles!"); 01553 return clipped_pose; 01554 } 01555 01556 //Unnormalize the goal arm angles 01557 std::vector<std::vector<double> > goal_positions; 01558 goal_positions.push_back(goal_posture_suggestion); 01559 trajectory_msgs::JointTrajectory goal_trajectory = assembleJointTrajectory(arm_name, goal_positions, 5.0); 01560 goal_trajectory.header.stamp = ros::Time(0); 01561 trajectory_msgs::JointTrajectory unnormalized_goal; 01562 unnormalizeTrajectory(arm_name, goal_trajectory, unnormalized_goal); 01563 01564 //Clip the posture goal by the same amount the pose got clipped 01565 clipped_posture_goal.resize(current_arm_angles.size()); 01566 for(size_t i=0; i<current_arm_angles.size(); i++) 01567 { 01568 clipped_posture_goal[i] = 01569 (unnormalized_goal.points[0].positions[i] - current_arm_angles[i]) * clip_fraction + current_arm_angles[i]; 01570 } 01571 } 01572 01573 return clipped_pose; 01574 } 01575 01576 void MechanismInterface::poseDists(geometry_msgs::Pose start, geometry_msgs::Pose end, double &pos_dist, double &angle) 01577 { 01578 Eigen::Affine3d start_trans, end_trans; 01579 tf::poseMsgToEigen(start, start_trans); 01580 tf::poseMsgToEigen(end, end_trans); 01581 Eigen::Vector3d axis, direction; 01582 positionAndAngleDist(start_trans, end_trans, pos_dist, angle, axis, direction); 01583 } 01584 01585 void MechanismInterface::positionAndAngleDist(Eigen::Affine3d start, Eigen::Affine3d end, 01586 double &pos_dist, 01587 double &angle, Eigen::Vector3d &axis, Eigen::Vector3d &direction) 01588 { 01589 //trans = end to start = global to start * end to global 01590 Eigen::Affine3d trans; 01591 trans = start.inverse() * end; 01592 Eigen::AngleAxis<double> angle_axis; 01593 angle_axis = trans.rotation(); 01594 angle = angle_axis.angle(); 01595 axis = angle_axis.axis(); 01596 if(angle > M_PI) 01597 { 01598 angle = -(angle - 2*M_PI); 01599 axis = -axis; 01600 } 01601 direction = trans.translation(); 01602 pos_dist = sqrt(direction.dot(direction)); 01603 if(pos_dist) direction *= 1/pos_dist; 01604 } 01605 01606 int MechanismInterface::translateGripperCartesian(std::string arm_name, const geometry_msgs::Vector3Stamped &direction, 01607 ros::Duration timeout, double dist_tol, double angle_tol, 01608 double clip_dist, double clip_angle, 01609 double overshoot_dist, double overshoot_angle, double timestep) 01610 { 01611 geometry_msgs::PoseStamped current_pose = getGripperPose(arm_name, direction.header.frame_id); 01612 geometry_msgs::PoseStamped desired_pose = translateGripperPose(direction, current_pose, arm_name); 01613 int result = moveArmToPoseCartesian(arm_name, desired_pose, timeout, dist_tol, angle_tol, 01614 clip_dist, clip_angle, overshoot_dist, overshoot_angle, timestep); 01615 return result; 01616 } 01617 01618 //returns 0 if an error occurred, 1 if it got there, -1 if it timed out 01619 int MechanismInterface::moveArmToPoseCartesian(std::string arm_name, const geometry_msgs::PoseStamped &desired_pose, 01620 ros::Duration timeout, double dist_tol, double angle_tol, 01621 double clip_dist, double clip_angle, 01622 double overshoot_dist, double overshoot_angle, 01623 double timestep, 01624 const std::vector<double> &goal_posture_suggestion) 01625 { 01626 bool success = false; 01627 01628 //Switch to Cartesian controllers 01629 for(int tries=0; tries<3; tries++) 01630 { 01631 success = switchToCartesian(arm_name); 01632 if(success) break; 01633 ros::Duration(1.0).sleep(); 01634 } 01635 if(!success) 01636 { 01637 ROS_ERROR("Tries exceeded when trying to switch to Cartesian control!"); 01638 return 0; 01639 } 01640 01641 //Move towards the desired pose until we get there within our tolerance or until time runs out 01642 ros::Time begin = ros::Time::now(); 01643 int reached_target = -1; 01644 geometry_msgs::PoseStamped current_pose = getGripperPose(arm_name, desired_pose.header.frame_id); 01645 geometry_msgs::PoseStamped last_pose = current_pose; 01646 01647 //Compute a new desired_pose with the desired overshoot 01648 geometry_msgs::PoseStamped overshoot_pose = overshootDesiredPose(arm_name, desired_pose, overshoot_dist, overshoot_angle, dist_tol, angle_tol); 01649 01650 while(ros::ok()) 01651 { 01652 //stop if we're out of time 01653 if(ros::Time::now() - begin > timeout) 01654 { 01655 ROS_DEBUG_NAMED("manipulation","Timed out when moving to desired Cartesian pose"); 01656 break; 01657 } 01658 01659 //stop if we're within our tolerances 01660 current_pose = getGripperPose(arm_name, desired_pose.header.frame_id); 01661 01662 double pos_dist, angle_dist; 01663 poseDists(current_pose.pose, overshoot_pose.pose, pos_dist, angle_dist); 01664 if(pos_dist <= dist_tol+overshoot_dist && angle_dist <= angle_tol+overshoot_angle) 01665 { 01666 //send the original desired pose out 01667 sendCartesianPoseCommand(arm_name, desired_pose); 01668 01669 //ROS_INFO("moveArmToPoseCartesian reached target"); 01670 reached_target = 1; 01671 break; 01672 } 01673 01674 //also stop if we're not moving 01675 double pos_change, angle_change; 01676 poseDists(current_pose.pose, last_pose.pose, pos_change, angle_change); 01677 if(ros::Time::now() - begin > ros::Duration(2.0) && pos_change <= .005*timestep && angle_change <= .001*timestep) 01678 { 01679 ROS_INFO("moveArmToPoseCartesian is stuck! Returning"); 01680 break; 01681 } 01682 01683 //clip the desired pose and posture suggestion and send it out 01684 double resulting_clip_fraction; 01685 std::vector<double> clipped_posture_suggestion; 01686 geometry_msgs::PoseStamped clipped_pose = clipDesiredPose(arm_name, overshoot_pose, clip_dist, clip_angle, 01687 resulting_clip_fraction, goal_posture_suggestion, clipped_posture_suggestion); 01688 sendCartesianPoseCommand(arm_name, clipped_pose); 01689 01690 if(clipped_posture_suggestion.size() > 0) 01691 { 01692 sendCartesianPostureCommand(arm_name, clipped_posture_suggestion); 01693 } 01694 01695 last_pose = current_pose; 01696 01697 //sleep until the next timestep 01698 ros::Duration(timestep).sleep(); 01699 } 01700 01701 //Switch back to joint control 01702 success = false; 01703 for(int tries=0; tries<3; tries++) 01704 { 01705 success = switchToJoint(arm_name); 01706 if(success) break; 01707 ros::Duration(1.0).sleep(); 01708 } 01709 if(!success) 01710 { 01711 ROS_ERROR("Tries exceeding when trying to switch back to joint control!"); 01712 return 0; 01713 } 01714 return reached_target; 01715 } 01716 01717 void MechanismInterface::sendCartesianPoseCommand(std::string arm_name, geometry_msgs::PoseStamped desired_pose) 01718 { 01719 desired_pose.header.stamp = ros::Time(0); 01720 cartesian_pub_.publisher(arm_name).publish(desired_pose); 01721 } 01722 01723 void MechanismInterface::sendCartesianPostureCommand(std::string arm_name, std::vector<double> arm_angles) 01724 { 01725 std_msgs::Float64MultiArray angles; 01726 for(size_t i=0; i<arm_angles.size(); i++) 01727 { 01728 angles.data.push_back(arm_angles[i]); 01729 } 01730 cartesian_posture_pub_.publisher(arm_name).publish(angles); 01731 } 01732 01733 /* 01734 void MechanismInterface::sendCartesianGainsCommand(std::string arm_name, std::vector<double> gains) 01735 { 01736 std_msgs::Float64MultiArray new_gains; 01737 new_gains.data = gains; 01738 cartesian_gains_pub_.publisher(arm_name).publish(new_gains); 01739 }*/ 01740 /* 01741 void MechanismInterface::sendCartesianGainsCommand(std::string arm_name, std::vector<double> gains, std::string frame_id, std::vector<double> fixed_frame) 01742 { 01743 object_manipulation_msgs::CartesianGains new_gains; 01744 new_gains.gains = gains; 01745 new_gains.fixed_frame = fixed_frame; 01746 new_gains.header.frame_id = frame_id; 01747 cartesian_gains_pub_.publisher(arm_name).publish(new_gains); 01748 }*/ 01749 01750 void MechanismInterface::setCartesianPostureGoalToCurrentAngles(std::string arm_name) 01751 { 01752 std::vector<double> arm_angles; 01753 getArmAngles(arm_name, arm_angles); 01754 sendCartesianPostureCommand(arm_name, arm_angles); 01755 } 01756 01757 std::vector<arm_navigation_msgs::LinkPadding> 01758 MechanismInterface::fingertipPadding(std::string arm_name, double pad) 01759 { 01760 std::vector<arm_navigation_msgs::LinkPadding> padding_vec; 01761 arm_navigation_msgs::LinkPadding padding; 01762 padding.padding = pad; 01763 std::vector<std::string> links = handDescription().fingertipLinks(arm_name); 01764 for (size_t i=0; i<links.size(); i++) 01765 { 01766 padding.link_name = links[i]; 01767 padding_vec.push_back(padding); 01768 } 01769 return padding_vec; 01770 } 01771 01772 std::vector<arm_navigation_msgs::LinkPadding> 01773 MechanismInterface::gripperPadding(std::string arm_name, double pad) 01774 { 01775 std::vector<arm_navigation_msgs::LinkPadding> padding_vec; 01776 arm_navigation_msgs::LinkPadding padding; 01777 padding.padding = pad; 01778 std::vector<std::string> links = handDescription().gripperTouchLinkNames(arm_name); 01779 for (size_t i=0; i<links.size(); i++) 01780 { 01781 padding.link_name = links[i]; 01782 padding_vec.push_back(padding); 01783 } 01784 return padding_vec; 01785 } 01786 01787 } //namespace object_manipulator