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
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 namespace object_manipulator {
00039
00040 static const std::string IK_SERVICE_SUFFIX = "/constraint_aware_ik";
00041 static const std::string FK_SERVICE_SUFFIX = "/get_fk";
00042 static const std::string INTERPOLATED_IK_SERVICE_SUFFIX = "/interpolated_ik";
00043 static const std::string INTERPOLATED_IK_SET_PARAMS_SERVICE_SUFFIX = "/interpolated_ik_set_params";
00044 static const std::string IK_QUERY_SERVICE_SUFFIX = "/get_ik_solver_info";
00045 static const std::string GRASP_STATUS_SUFFIX = "/grasp_status";
00046
00047 static const std::string CHECK_STATE_VALIDITY_NAME = "environment_server/get_state_validity";
00048 static const std::string NORMALIZE_SERVICE_NAME = "trajectory_filter_unnormalizer/filter_trajectory";
00049
00050 static const std::string REACTIVE_GRASP_ACTION_SUFFIX = "/reactive_grasp";
00051 static const std::string REACTIVE_LIFT_ACTION_SUFFIX = "/reactive_lift";
00052 static const std::string REACTIVE_PLACE_ACTION_SUFFIX = "/reactive_place";
00053 static const std::string MOVE_ARM_ACTION_SUFFIX = "/move_arm";
00054 static const std::string TRAJECTORY_ACTION_SUFFIX = "/joint_trajectory";
00055 static const std::string HAND_POSTURE_ACTION_SUFFIX = "/hand_posture_execution";
00056
00057 static const std::string SWITCH_CONTROLLER_SERVICE_NAME = "/switch_controller";
00058 static const std::string LIST_CONTROLLERS_SERVICE_NAME = "/list_controllers";
00059 static const std::string CARTESIAN_COMMAND_SUFFIX = "/cart/command_pose";
00060
00061 static const std::string MOVE_ARM_PLANNER_ID = "SBLkConfig1";
00062 static const std::string MOVE_ARM_PLANNER_SERVICE_NAME = "ompl_planning/plan_kinematic_path";
00063 static const std::string MOVE_ARM_CONSTRAINED_PLANNER_SERVICE_NAME = "ompl_planning/plan_kinematic_path";
00064
00065 static const std::string ATTACHED_COLLISION_TOPIC="attached_collision_object";
00066
00067 static const std::string POINT_HEAD_ACTION_TOPIC = "/head_traj_controller/point_head_action";
00068
00069 static const double OBJECT_POSITION_TOLERANCE_X = 0.02;
00070 static const double OBJECT_POSITION_TOLERANCE_Y = 0.02;
00071 static const double OBJECT_POSITION_TOLERANCE_Z = 0.02;
00072
00073 MechanismInterface::MechanismInterface() :
00074 root_nh_(""),priv_nh_("~"),
00075
00076
00077 ik_query_client_("", IK_QUERY_SERVICE_SUFFIX, true),
00078 ik_service_client_("", IK_SERVICE_SUFFIX, true),
00079 fk_service_client_("",FK_SERVICE_SUFFIX,true),
00080 interpolated_ik_service_client_("", INTERPOLATED_IK_SERVICE_SUFFIX, true),
00081 interpolated_ik_set_params_client_("", INTERPOLATED_IK_SET_PARAMS_SERVICE_SUFFIX, true),
00082 grasp_status_client_("", GRASP_STATUS_SUFFIX, true),
00083
00084 check_state_validity_client_(CHECK_STATE_VALIDITY_NAME),
00085 joint_trajectory_normalizer_service_(NORMALIZE_SERVICE_NAME),
00086 switch_controller_service_(SWITCH_CONTROLLER_SERVICE_NAME),
00087 list_controllers_service_(LIST_CONTROLLERS_SERVICE_NAME),
00088
00089 reactive_grasp_action_client_("", REACTIVE_GRASP_ACTION_SUFFIX, true, true),
00090 reactive_lift_action_client_("", REACTIVE_LIFT_ACTION_SUFFIX, true, true),
00091 reactive_place_action_client_("", REACTIVE_PLACE_ACTION_SUFFIX, true, true),
00092 move_arm_action_client_("", MOVE_ARM_ACTION_SUFFIX, true, true),
00093 traj_action_client_("", TRAJECTORY_ACTION_SUFFIX, true, true),
00094 hand_posture_client_("", HAND_POSTURE_ACTION_SUFFIX, true, true),
00095
00096 point_head_action_client_(POINT_HEAD_ACTION_TOPIC, true)
00097 {
00098
00099 attached_object_pub_ = root_nh_.advertise<mapping_msgs::AttachedCollisionObject>(ATTACHED_COLLISION_TOPIC, 10);
00100
00101
00102 right_cartesian_pub_ = root_nh_.advertise<geometry_msgs::PoseStamped>(std::string("right_arm")+
00103 CARTESIAN_COMMAND_SUFFIX, 100);
00104 left_cartesian_pub_ = root_nh_.advertise<geometry_msgs::PoseStamped>(std::string("left_arm")+
00105 CARTESIAN_COMMAND_SUFFIX, 100);
00106
00107
00108 priv_nh_.param<std::string>("right_cartesian_controller", right_cartesian_controller_, "r_cart");
00109 priv_nh_.param<std::string>("left_cartesian_controller", left_cartesian_controller_, "l_cart");
00110 priv_nh_.param<std::string>("right_joint_controller", right_joint_controller_, "r_arm_controller");
00111 priv_nh_.param<std::string>("left_joint_controller", left_joint_controller_, "l_arm_controller");
00112 }
00113
00117 std::vector<std::string> MechanismInterface::getJointNames(std::string arm_name)
00118 {
00119 kinematics_msgs::GetKinematicSolverInfo::Request query_request;
00120 kinematics_msgs::GetKinematicSolverInfo::Response query_response;
00121 if ( !ik_query_client_.client(arm_name).call(query_request, query_response) )
00122 {
00123 ROS_ERROR("Failed to call ik information query");
00124 throw MechanismException("Failed to call ik information query");
00125 }
00126 return query_response.kinematic_solver_info.joint_names;
00127 }
00128
00129 void MechanismInterface::attemptTrajectory(std::string arm_name,
00130 const std::vector< std::vector<double> > &positions,
00131 bool unnormalize,
00132 float time_per_segment)
00133 {
00134 trajectory_msgs::JointTrajectory trajectory;
00135 trajectory.header.frame_id = handDescription().robotFrame(arm_name);
00136 trajectory.header.stamp = ros::Time::now() + ros::Duration(1.0);
00137 trajectory.joint_names = getJointNames(arm_name);
00138 float current_time = 0;
00139 for (size_t i=0; i<positions.size(); i++)
00140 {
00141 current_time += time_per_segment;
00142 if (positions[i].size() != trajectory.joint_names.size())
00143 {
00144 ROS_ERROR("Mechanism interface: requested trajectory does not have enough joint values");
00145 throw MechanismException("Mechanism interface: requested trajectory does not have enough joint values");
00146 }
00147 trajectory_msgs::JointTrajectoryPoint point;
00148 point.positions = positions[i];
00149 point.time_from_start = ros::Duration(current_time);
00150 trajectory.points.push_back(point);
00151 }
00152 attemptTrajectory(arm_name, trajectory, unnormalize);
00153 }
00154
00155 void MechanismInterface::attemptTrajectory(std::string arm_name,
00156 const trajectory_msgs::JointTrajectory &trajectory,
00157 bool unnormalize)
00158 {
00159 if (trajectory.points.empty())
00160 {
00161 ROS_ERROR("attemptTrajectory called with empty trajectory");
00162 throw MechanismException("attemptTrajectory called with empty trajectory");
00163 }
00164
00165
00166 if(!checkController(right_joint_controller_) || !checkController(left_joint_controller_))
00167 switchToJoint();
00168
00169 pr2_controllers_msgs::JointTrajectoryGoal goal;
00170 if (unnormalize)
00171 {
00172 motion_planning_msgs::FilterJointTrajectory service_call;
00173 service_call.request.trajectory = trajectory;
00174 service_call.request.allowed_time = ros::Duration(2.0);
00175 if ( !joint_trajectory_normalizer_service_.client().call(service_call) )
00176 {
00177 ROS_ERROR("Mechanism interface: joint trajectory normalizer service call failed");
00178 throw MechanismException("joint trajectory normalizer service call failed");
00179 }
00180 goal.trajectory = service_call.response.trajectory;
00181 }
00182 else
00183 {
00184 goal.trajectory = trajectory;
00185 }
00186
00187 traj_action_client_.client(arm_name);
00188 goal.trajectory.header.stamp = ros::Time::now() + ros::Duration(1.0);
00189
00190
00191 ros::Duration timeout = ros::Duration(1.0) + trajectory.points.back().time_from_start + ros::Duration(5.0);
00192 traj_action_client_.client(arm_name).sendGoal(goal);
00193 if ( !traj_action_client_.client(arm_name).waitForResult(timeout) )
00194 {
00195 ROS_ERROR(" Trajectory timed out");
00196 throw MechanismException("trajectory timed out");
00197 }
00198 }
00199
00200 void MechanismInterface::setInterpolatedIKParams(std::string arm_name, int num_steps,
00201 int collision_check_resolution, bool start_from_end)
00202 {
00203 interpolated_ik_motion_planner::SetInterpolatedIKMotionPlanParams srv;
00204 srv.request.num_steps = num_steps;
00205 srv.request.consistent_angle = M_PI/6;
00206 srv.request.collision_check_resolution = collision_check_resolution;
00207 srv.request.steps_before_abort = 0;
00208 srv.request.pos_spacing = 0.01;
00209 srv.request.rot_spacing = 0.1;
00210 srv.request.collision_aware = true;
00211 srv.request.start_from_end = start_from_end;
00212 if (!interpolated_ik_set_params_client_.client(arm_name).call(srv))
00213 {
00214 ROS_ERROR("Failed to set Interpolated IK server parameters");
00215 throw MechanismException("Failed to set Interpolated IK server parameters");
00216 }
00217 }
00218
00219 bool MechanismInterface::moveArmToPose(std::string arm_name, const geometry_msgs::PoseStamped &desired_pose,
00220 const motion_planning_msgs::OrderedCollisionOperations &collision_operations,
00221 const std::vector<motion_planning_msgs::LinkPadding> &link_padding)
00222 {
00223 kinematics_msgs::GetConstraintAwarePositionIK::Response ik_response;
00224 if(!getIKForPose(arm_name, desired_pose,ik_response, collision_operations, link_padding))
00225 return false;
00226 if(!attemptMoveArmToGoal(arm_name, ik_response.solution.joint_state.position, collision_operations, link_padding))
00227 return false;
00228 return true;
00229 }
00230
00231 bool MechanismInterface::getFK(std::string arm_name,
00232 std::vector<double> positions,
00233 geometry_msgs::PoseStamped &pose_stamped)
00234 {
00235
00236 kinematics_msgs::GetPositionFK::Request fk_request;
00237 kinematics_msgs::GetPositionFK::Response fk_response;
00238 fk_request.header.frame_id = pose_stamped.header.frame_id;
00239 fk_request.header.stamp = pose_stamped.header.stamp;
00240 fk_request.fk_link_names.resize(1);
00241 fk_request.fk_link_names[0] = handDescription().gripperFrame(arm_name);
00242 fk_request.robot_state.joint_state.position = positions;
00243 fk_request.robot_state.joint_state.name = getJointNames(arm_name);
00244 if( !fk_service_client_.client(arm_name).call(fk_request,fk_response) )
00245 {
00246 ROS_ERROR("FK Service Call failed altogether");
00247 throw MechanismException("FK Service Call failed altogether");
00248 }
00249 if (fk_response.error_code.val != fk_response.error_code.SUCCESS)
00250 {
00251 ROS_ERROR("Get FK failed with error code %d", fk_response.error_code.val);
00252 return false;
00253 }
00254 pose_stamped = fk_response.pose_stamped[0];
00255 return true;
00256 }
00257
00258 bool MechanismInterface::getIKForPose(std::string arm_name, const geometry_msgs::PoseStamped &desired_pose,
00259 kinematics_msgs::GetConstraintAwarePositionIK::Response& ik_response,
00260 const motion_planning_msgs::OrderedCollisionOperations &collision_operations,
00261 const std::vector<motion_planning_msgs::LinkPadding> &link_padding)
00262 {
00263
00264 kinematics_msgs::GetConstraintAwarePositionIK::Request ik_request;
00265 ik_request.ik_request.ik_link_name = handDescription().gripperFrame(arm_name);
00266 ik_request.ik_request.pose_stamped.pose = desired_pose.pose;
00267 ik_request.ik_request.pose_stamped.header.stamp = desired_pose.header.stamp;
00268 ik_request.ik_request.pose_stamped.header.frame_id = desired_pose.header.frame_id;
00269 ik_request.ik_request.ik_seed_state.joint_state.name = getJointNames(arm_name);
00270 ik_request.ik_request.ik_seed_state.joint_state.position.resize(7, 0.0);
00271 ik_request.ordered_collision_operations = collision_operations;
00272 ik_request.link_padding = link_padding;
00273 ik_request.timeout = ros::Duration(2.0);
00274 if( !ik_service_client_.client(arm_name).call(ik_request,ik_response) )
00275 {
00276 ROS_ERROR("IK Service Call failed altogether");
00277 throw MechanismException("IK Service Call failed altogether");
00278 }
00279 if (ik_response.error_code.val != ik_response.error_code.SUCCESS)
00280 {
00281 ROS_ERROR("Get IK failed with error code %d", ik_response.error_code.val);
00282 return false;
00283 }
00284 return true;
00285 }
00286
00287 bool MechanismInterface::checkStateValidity(std::string arm_name, const std::vector<double> &joint_values,
00288 const motion_planning_msgs::OrderedCollisionOperations &collision_operations,
00289 const std::vector<motion_planning_msgs::LinkPadding> &link_padding)
00290 {
00291 planning_environment_msgs::GetStateValidity::Request req;
00292 planning_environment_msgs::GetStateValidity::Response res;
00293
00294 req.robot_state.joint_state.name = getJointNames(arm_name);
00295 req.robot_state.joint_state.position = joint_values;
00296 if ( req.robot_state.joint_state.name.size() != joint_values.size() )
00297 {
00298 throw MechanismException("Wrong number of joint values for checkStateValidity");
00299 }
00300 req.robot_state.joint_state.header.stamp = ros::Time::now();
00301 req.check_collisions = true;
00302 req.ordered_collision_operations = collision_operations;
00303 req.link_padding = link_padding;
00304
00305 if(!check_state_validity_client_.client().call(req,res))
00306 {
00307 throw MechanismException("Call to check state validity client failed");
00308 }
00309
00310 if (res.error_code.val == res.error_code.SUCCESS) return true;
00311 return false;
00312 }
00313
00326 int MechanismInterface::getInterpolatedIK(std::string arm_name,
00327 geometry_msgs::PoseStamped start_pose,
00328 geometry_msgs::Vector3Stamped direction,
00329 float desired_trajectory_length,
00330 const std::vector<double> &seed_joint_position,
00331 const sensor_msgs::JointState &joint_state,
00332 const motion_planning_msgs::OrderedCollisionOperations &collision_operations,
00333 const std::vector<motion_planning_msgs::LinkPadding> &link_padding,
00334 bool reverse_trajectory,
00335 trajectory_msgs::JointTrajectory &trajectory,
00336 float &actual_trajectory_length)
00337 {
00338
00339
00340 geometry_msgs::Vector3Stamped direction_norm = direction;
00341 direction_norm.vector = normalize(direction.vector);
00342
00343 desired_trajectory_length = fabs(desired_trajectory_length);
00344 direction_norm.vector.x *= desired_trajectory_length;
00345 direction_norm.vector.y *= desired_trajectory_length;
00346 direction_norm.vector.z *= desired_trajectory_length;
00347 geometry_msgs::PoseStamped end_pose = translateGripperPose(direction_norm, start_pose, arm_name);
00348
00349
00350 float max_step_size = 0.01;
00351 unsigned int collision_check_resolution = 2;
00352
00353
00354 unsigned int num_steps = (unsigned int)ceil(desired_trajectory_length / fabs(max_step_size));
00355 float actual_step_size = desired_trajectory_length / num_steps;
00356
00357 ROS_DEBUG("Trajectory details: length %f, requested num steps: %d, actual step size: %f",
00358 desired_trajectory_length, num_steps, actual_step_size);
00359
00360 if (reverse_trajectory)
00361 {
00362 std::swap(start_pose, end_pose);
00363 }
00364
00365
00366 setInterpolatedIKParams(arm_name, num_steps+1, collision_check_resolution, reverse_trajectory);
00367
00368 motion_planning_msgs::RobotState start_state;
00369 start_state.multi_dof_joint_state.child_frame_ids.push_back(handDescription().gripperFrame(arm_name));
00370 start_state.multi_dof_joint_state.poses.push_back(start_pose.pose);
00371 start_state.multi_dof_joint_state.frame_ids.push_back(start_pose.header.frame_id);
00372 start_state.multi_dof_joint_state.stamp = ros::Time::now();
00373
00374
00375 if (!seed_joint_position.empty())
00376 {
00377
00378 start_state.joint_state.name = getJointNames(arm_name);
00379 if (seed_joint_position.size() != start_state.joint_state.name.size())
00380 {
00381 ROS_ERROR("Interpolated IK request: seed_joint_position does not match joint names");
00382 throw MechanismException("Interpolated IK request: seed_joint_position does not match joint names");
00383 }
00384 start_state.joint_state.position = seed_joint_position;
00385 }
00386
00387
00388 for (size_t i=0; i<joint_state.name.size(); i++)
00389 {
00390 start_state.joint_state.name.push_back(joint_state.name[i]);
00391 start_state.joint_state.position.push_back(joint_state.position[i]);
00392 }
00393
00394 motion_planning_msgs::PositionConstraint position_constraint;
00395 motion_planning_msgs::OrientationConstraint orientation_constraint;
00396 motion_planning_msgs::poseStampedToPositionOrientationConstraints(end_pose, handDescription().gripperFrame(arm_name),
00397 position_constraint,
00398 orientation_constraint);
00399 motion_planning_msgs::Constraints goal_constraints;
00400 goal_constraints.position_constraints.push_back(position_constraint);
00401 goal_constraints.orientation_constraints.push_back(orientation_constraint);
00402
00403 motion_planning_msgs::GetMotionPlan motion_plan;
00404 motion_plan.request.motion_plan_request.start_state = start_state;
00405 motion_plan.request.motion_plan_request.goal_constraints = goal_constraints;
00406 motion_plan.request.motion_plan_request.ordered_collision_operations = collision_operations;
00407
00408
00409 motion_plan.request.motion_plan_request.link_padding = link_padding;
00410
00411 if ( !interpolated_ik_service_client_.client(arm_name).call(motion_plan) )
00412 {
00413 ROS_ERROR(" Call to Interpolated IK service failed");
00414 throw MechanismException("Call to Interpolated IK service failed");
00415 }
00416
00417 trajectory.points.clear();
00418 trajectory.joint_names = motion_plan.response.trajectory.joint_trajectory.joint_names;
00419
00420 if (motion_plan.response.trajectory_error_codes.empty())
00421 {
00422 ROS_ERROR(" Interpolated IK: empty trajectory received");
00423 throw MechanismException("Interpolated IK: empty trajectory received");
00424 }
00425
00426 int error_code = motion_planning_msgs::ArmNavigationErrorCodes::SUCCESS;
00427 if (!reverse_trajectory)
00428 {
00429 for (size_t i=0; i<motion_plan.response.trajectory_error_codes.size(); i++)
00430 {
00431 if ( motion_plan.response.trajectory_error_codes[i].val == motion_plan.response.trajectory_error_codes[i].SUCCESS )
00432 {
00433 trajectory.points.push_back( motion_plan.response.trajectory.joint_trajectory.points[i] );
00434 }
00435 else
00436 {
00437 ROS_DEBUG(" Interpolated IK failed on step %d (forward towards %d) with error code %d",
00438 (int) i,
00439 (int) motion_plan.response.trajectory_error_codes.size() - 1,
00440 motion_plan.response.trajectory_error_codes[i].val);
00441 error_code = motion_plan.response.trajectory_error_codes[i].val;
00442 break;
00443 }
00444 }
00445 }
00446 else
00447 {
00448 size_t first_success = 0;
00449 while ( first_success < motion_plan.response.trajectory_error_codes.size() &&
00450 motion_plan.response.trajectory_error_codes[first_success].val !=
00451 motion_plan.response.trajectory_error_codes[first_success].SUCCESS ) first_success ++;
00452 if (first_success != 0)
00453 {
00454 ROS_DEBUG(" Interpolation failed on step %d (backwards from %d) with error code %d",
00455 (int) first_success - 1,
00456 (int) motion_plan.response.trajectory_error_codes.size() - 1,
00457 motion_plan.response.trajectory_error_codes[first_success - 1].val);
00458 error_code = motion_plan.response.trajectory_error_codes[first_success - 1].val;
00459 }
00460 else
00461 {
00462 ROS_DEBUG(" Interpolation trajectory complete (backwards from %d points)",
00463 (int) motion_plan.response.trajectory_error_codes.size());
00464
00465 }
00466 for (size_t i=first_success; i < motion_plan.response.trajectory_error_codes.size(); i++)
00467 {
00468 if ( motion_plan.response.trajectory_error_codes[i].val == motion_plan.response.trajectory_error_codes[i].SUCCESS )
00469 {
00470 trajectory.points.push_back( motion_plan.response.trajectory.joint_trajectory.points[i] );
00471 }
00472 else
00473 {
00474 ROS_ERROR(" Interpolated IK: unexpected behavior for error codes: step %d has error code %d",
00475 (int) i, motion_plan.response.trajectory_error_codes[i].val);
00476 throw MechanismException("Interpolated IK: unexpected behavior for error codes");
00477 }
00478 }
00479 }
00480
00481 if (!trajectory.points.empty()) actual_trajectory_length = actual_step_size * (trajectory.points.size()-1);
00482 else actual_trajectory_length = 0.0;
00483 return error_code;
00484 }
00485
00486 bool MechanismInterface::attemptMoveArmToGoal(std::string arm_name, const std::vector<double> &desired_joint_values,
00487 const motion_planning_msgs::OrderedCollisionOperations &collision_operations,
00488 const std::vector<motion_planning_msgs::LinkPadding> &link_padding)
00489 {
00490
00491 if(!checkController(right_joint_controller_) || !checkController(left_joint_controller_))
00492 switchToJoint();
00493
00494 int num_tries = 0;
00495 int max_tries = 5;
00496 move_arm_msgs::MoveArmGoal move_arm_goal;
00497
00498 move_arm_goal.motion_plan_request.group_name = handDescription().armGroup(arm_name);
00499 move_arm_goal.motion_plan_request.num_planning_attempts = 1;
00500 move_arm_goal.motion_plan_request.allowed_planning_time = ros::Duration(5.0);
00501 move_arm_goal.motion_plan_request.planner_id = MOVE_ARM_PLANNER_ID;
00502 move_arm_goal.planner_service_name = MOVE_ARM_PLANNER_SERVICE_NAME;
00503
00504 move_arm_goal.motion_plan_request.ordered_collision_operations = collision_operations;
00505 move_arm_goal.motion_plan_request.link_padding = link_padding;
00506
00507 std::vector<std::string> joint_names = getJointNames(arm_name);
00508 move_arm_goal.motion_plan_request.goal_constraints.joint_constraints.resize(joint_names.size());
00509 for(unsigned int i = 0; i < desired_joint_values.size(); i++)
00510 {
00511 move_arm_goal.motion_plan_request.goal_constraints.joint_constraints[i].joint_name = joint_names.at(i);
00512 move_arm_goal.motion_plan_request.goal_constraints.joint_constraints[i].position = desired_joint_values[i];
00513 move_arm_goal.motion_plan_request.goal_constraints.joint_constraints[i].tolerance_below = .08;
00514 move_arm_goal.motion_plan_request.goal_constraints.joint_constraints[i].tolerance_above = .08;
00515 }
00516
00517 bool success = false;
00518 motion_planning_msgs::ArmNavigationErrorCodes error_code;
00519 while(num_tries < max_tries)
00520 {
00521 move_arm_action_client_.client(arm_name).sendGoal(move_arm_goal);
00522 bool withinWait = move_arm_action_client_.client(arm_name).waitForResult(ros::Duration(60.0));
00523 if(!withinWait)
00524 {
00525 move_arm_action_client_.client(arm_name).cancelGoal();
00526 ROS_DEBUG(" Move arm goal could not be achieved by move_arm in the allowed duration");
00527 success = false;
00528 num_tries++;
00529 move_arm_msgs::MoveArmResult move_arm_result = *move_arm_action_client_.client(arm_name).getResult();
00530 error_code.val = error_code.TIMED_OUT;
00531 modifyMoveArmGoal(move_arm_goal,error_code,move_arm_result.contacts);
00532 continue;
00533 }
00534 actionlib::SimpleClientGoalState state = move_arm_action_client_.client(arm_name).getState();
00535 if(state == actionlib::SimpleClientGoalState::SUCCEEDED)
00536 {
00537 ROS_DEBUG(" Move arm: position was successfully achieved");
00538 success = true;
00539 break;
00540 }
00541 else
00542 {
00543 move_arm_msgs::MoveArmResult move_arm_result = *move_arm_action_client_.client(arm_name).getResult();
00544 ROS_DEBUG(" Move arm: non-success state was reached. Reason: %s",
00545 (motion_planning_msgs::armNavigationErrorCodeToString(move_arm_result.error_code)).c_str());
00546 ROS_DEBUG(" num_tries: %d, max_tries: %d",num_tries,max_tries);
00547 success = false;
00548 num_tries++;
00549 error_code = move_arm_result.error_code;
00550 modifyMoveArmGoal(move_arm_goal,error_code,move_arm_result.contacts);
00551 continue;
00552 }
00553 }
00555 if (!success && error_code.val == error_code.START_STATE_IN_COLLISION)
00556 {
00557 throw MoveArmStuckException();
00558 }
00559 return success;
00560 }
00561
00562
00563 void MechanismInterface::modifyMoveArmGoal(move_arm_msgs::MoveArmGoal &move_arm_goal,
00564 motion_planning_msgs::ArmNavigationErrorCodes &error_code,
00565 std::vector<planning_environment_msgs::ContactInformation> &contact_info_)
00566 {
00567 double allowed_penetration_depth = 0.03;
00568 if(error_code.val == error_code.START_STATE_IN_COLLISION)
00569 {
00570 std::vector<motion_planning_msgs::AllowedContactSpecification> allowed_contacts;
00571 for(unsigned int i=0; i < contact_info_.size(); i++)
00572 {
00573 if(contact_info_[i].depth < allowed_penetration_depth)
00574 {
00575 motion_planning_msgs::AllowedContactSpecification allowed_contact_tmp;
00576 allowed_contact_tmp.shape.type = allowed_contact_tmp.shape.BOX;
00577 allowed_contact_tmp.shape.dimensions.resize(3);
00578 allowed_contact_tmp.shape.dimensions[0] = 0.03;
00579 allowed_contact_tmp.shape.dimensions[1] = 0.03;
00580 allowed_contact_tmp.shape.dimensions[2] = 0.03;
00581 allowed_contact_tmp.pose_stamped.pose.position = contact_info_[i].position;
00582 allowed_contact_tmp.pose_stamped.pose.orientation.x = 0.0;
00583 allowed_contact_tmp.pose_stamped.pose.orientation.y = 0.0;
00584 allowed_contact_tmp.pose_stamped.pose.orientation.z = 0.0;
00585 allowed_contact_tmp.pose_stamped.pose.orientation.w = 1.0;
00586 allowed_contact_tmp.pose_stamped.header.stamp = ros::Time::now();
00587 allowed_contact_tmp.pose_stamped.header.frame_id = contact_info_[i].header.frame_id;
00588 allowed_contact_tmp.link_names.push_back(contact_info_[i].contact_body_1);
00589 allowed_contact_tmp.penetration_depth = allowed_penetration_depth;
00590 allowed_contacts.push_back(allowed_contact_tmp);
00591 ROS_DEBUG("Added allowed contact region: %d",i);
00592 ROS_DEBUG("Position : (%f,%f,%f)",contact_info_[i].position.x,
00593 contact_info_[i].position.y,contact_info_[i].position.z);
00594 ROS_DEBUG("Frame id : %s",contact_info_[i].header.frame_id.c_str());
00595 ROS_DEBUG("Depth : %f",allowed_penetration_depth);
00596 ROS_DEBUG("Link : %s",contact_info_[i].contact_body_1.c_str());
00597 ROS_DEBUG(" ");
00598 }
00599 }
00600 ROS_DEBUG("Added %d allowed contact regions",(int)allowed_contacts.size());
00601 move_arm_goal.motion_plan_request.allowed_contacts = allowed_contacts;
00602 }
00603 }
00604
00605
00606 bool MechanismInterface::moveArmConstrained(std::string arm_name, const geometry_msgs::PoseStamped &commanded_pose,
00607 const motion_planning_msgs::OrderedCollisionOperations &collision_operations,
00608 const std::vector<motion_planning_msgs::LinkPadding> &link_padding,
00609 const motion_planning_msgs::Constraints &path_constraints,
00610 const double &redundancy,
00611 const bool &compute_viable_command_pose)
00612 {
00613
00614
00615 if(!checkController(right_joint_controller_) || !checkController(left_joint_controller_))
00616 switchToJoint();
00617
00618 int num_tries = 0;
00619 int max_tries = 1;
00620
00621 move_arm_msgs::MoveArmGoal move_arm_goal;
00622 move_arm_goal.motion_plan_request.group_name = handDescription().armGroup(arm_name)+"_cartesian";
00623 move_arm_goal.motion_plan_request.num_planning_attempts = 1;
00624 move_arm_goal.motion_plan_request.allowed_planning_time = ros::Duration(5.0);
00625 move_arm_goal.motion_plan_request.planner_id = MOVE_ARM_PLANNER_ID;
00626 move_arm_goal.planner_service_name = MOVE_ARM_CONSTRAINED_PLANNER_SERVICE_NAME;
00627 move_arm_goal.motion_plan_request.ordered_collision_operations = collision_operations;
00628 move_arm_goal.motion_plan_request.link_padding = link_padding;
00629
00630 move_arm_goal.motion_plan_request.goal_constraints.position_constraints.resize(1);
00631 move_arm_goal.motion_plan_request.goal_constraints.position_constraints[0].header.frame_id =
00632 commanded_pose.header.frame_id;
00633 move_arm_goal.motion_plan_request.goal_constraints.position_constraints[0].link_name =
00634 handDescription().gripperFrame(arm_name);
00635 move_arm_goal.motion_plan_request.goal_constraints.position_constraints[0].position = commanded_pose.pose.position;
00636 move_arm_goal.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_shape.type =
00637 geometric_shapes_msgs::Shape::BOX;
00638 move_arm_goal.motion_plan_request.goal_constraints.position_constraints[0].
00639 constraint_region_shape.dimensions.push_back(OBJECT_POSITION_TOLERANCE_X);
00640 move_arm_goal.motion_plan_request.goal_constraints.position_constraints[0].
00641 constraint_region_shape.dimensions.push_back(OBJECT_POSITION_TOLERANCE_Y);
00642 move_arm_goal.motion_plan_request.goal_constraints.position_constraints[0].
00643 constraint_region_shape.dimensions.push_back(OBJECT_POSITION_TOLERANCE_Z);
00644 move_arm_goal.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_orientation.w = 1.0;
00645 move_arm_goal.motion_plan_request.goal_constraints.position_constraints[0].weight = 1.0;
00646
00647 move_arm_goal.motion_plan_request.goal_constraints.orientation_constraints.resize(1);
00648 move_arm_goal.motion_plan_request.goal_constraints.orientation_constraints[0] =
00649 path_constraints.orientation_constraints[0];
00650 move_arm_goal.motion_plan_request.goal_constraints.orientation_constraints[0].header.stamp = ros::Time::now();
00651
00652 btQuaternion orientation;
00653 tf::quaternionMsgToTF(commanded_pose.pose.orientation,orientation);
00654 geometry_msgs::PoseStamped desired_pose = commanded_pose;
00655 desired_pose.pose.position = move_arm_goal.motion_plan_request.goal_constraints.position_constraints[0].position;
00656 desired_pose.header.stamp = ros::Time::now();
00657
00658
00659
00660 if(compute_viable_command_pose && path_constraints.orientation_constraints.size())
00661 {
00662 bool get_ik = false;
00663 for(unsigned int i=0; i < 360; i++)
00664 {
00665 double rotation_yaw = i*M_PI/360.0;
00666 ROS_DEBUG("Trying to find suitable goal orientation with yaw rotation: %f",rotation_yaw);
00667 btQuaternion orientation_yaw;
00668 orientation_yaw.setRPY(0.0,0.0,rotation_yaw);
00669 orientation_yaw *= orientation;
00670 geometry_msgs::Quaternion quaternion;
00671 tf::quaternionTFToMsg(orientation_yaw,quaternion);
00672 desired_pose.pose.orientation = quaternion;
00673 desired_pose.header.stamp = ros::Time::now();
00674 kinematics_msgs::GetConstraintAwarePositionIK::Response ik_response;
00675 if(getIKForPose(arm_name,desired_pose,ik_response, collision_operations, link_padding))
00676 {
00677 get_ik = true;
00678 break;
00679 }
00680 }
00681 if(!get_ik)
00682 return false;
00683 }
00684
00685 move_arm_goal.motion_plan_request.path_constraints.orientation_constraints.resize(1);
00686 move_arm_goal.motion_plan_request.path_constraints.orientation_constraints[0] =
00687 move_arm_goal.motion_plan_request.goal_constraints.orientation_constraints[0];
00688 move_arm_goal.disable_ik = true;
00689
00690 move_arm_goal.motion_plan_request.goal_constraints.joint_constraints.resize(1);
00691 move_arm_goal.motion_plan_request.goal_constraints.joint_constraints[0].joint_name = (getJointNames(arm_name))[2];
00692 move_arm_goal.motion_plan_request.goal_constraints.joint_constraints[0].position = redundancy;
00693 move_arm_goal.motion_plan_request.goal_constraints.joint_constraints[0].tolerance_below = M_PI;
00694 move_arm_goal.motion_plan_request.goal_constraints.joint_constraints[0].tolerance_above = M_PI;
00695
00696 bool success = false;
00697 while(num_tries < max_tries)
00698 {
00699 move_arm_action_client_.client(arm_name).sendGoal(move_arm_goal);
00700 bool withinWait = move_arm_action_client_.client(arm_name).waitForResult(ros::Duration(60.0));
00701 if(!withinWait)
00702 {
00703 move_arm_action_client_.client(arm_name).cancelGoal();
00704 ROS_DEBUG(" Move arm goal could not be achieved by move_arm in the allowed duration");
00705 success = false;
00706 num_tries++;
00707 move_arm_msgs::MoveArmResult move_arm_result = *move_arm_action_client_.client(arm_name).getResult();
00708 motion_planning_msgs::ArmNavigationErrorCodes error_code;
00709 error_code.val = error_code.TIMED_OUT;
00710 modifyMoveArmGoal(move_arm_goal,error_code,move_arm_result.contacts);
00711 continue;
00712 }
00713 actionlib::SimpleClientGoalState state = move_arm_action_client_.client(arm_name).getState();
00714 if(state == actionlib::SimpleClientGoalState::SUCCEEDED)
00715 {
00716 ROS_DEBUG(" Move arm: position was successfully achieved");
00717 success = true;
00718 break;
00719 }
00720 else
00721 {
00722 move_arm_msgs::MoveArmResult move_arm_result = *move_arm_action_client_.client(arm_name).getResult();
00723 ROS_DEBUG("Move arm: non-success state was reached. Reason: %s",
00724 (motion_planning_msgs::armNavigationErrorCodeToString(move_arm_result.error_code)).c_str());
00725 ROS_DEBUG("num_tries: %d, max_tries: %d",num_tries,max_tries);
00726 success = false;
00727 num_tries++;
00728 modifyMoveArmGoal(move_arm_goal,move_arm_result.error_code,move_arm_result.contacts);
00729 continue;
00730 }
00731 }
00732 return success;
00733 }
00734
00746 geometry_msgs::PoseStamped MechanismInterface::translateGripperPose(geometry_msgs::Vector3Stamped translation,
00747 geometry_msgs::PoseStamped start_pose,
00748 std::string arm_name)
00749 {
00750 bool pre_multiply;
00751 if (translation.header.frame_id == handDescription().gripperFrame(arm_name))
00752 {
00753 pre_multiply=false;
00754 }
00755 else if (translation.header.frame_id == handDescription().robotFrame(arm_name))
00756 {
00757 pre_multiply=true;
00758 }
00759 else
00760 {
00761 throw MechanismException(std::string("Gripper translations (such as for lift or approach) can only be specified in "
00762 "either the gripper frame or the robot frame. This one was specified in frame ") +
00763 translation.header.frame_id);
00764 }
00765
00766
00767
00768 geometry_msgs::PoseStamped start_pose_robot_frame = transformPose(handDescription().robotFrame(arm_name), start_pose);
00769 tf::StampedTransform start_transform;
00770 tf::poseMsgToTF(start_pose_robot_frame.pose, start_transform);
00771
00772 btVector3 vec;
00773 tf::vector3MsgToTF(translation.vector, vec);
00774 tf::StampedTransform translate_trans;
00775 translate_trans.setIdentity();
00776 translate_trans.setOrigin(vec);
00777
00778
00779 tf::Transform end_transform;
00780 if (pre_multiply) end_transform = translate_trans * start_transform;
00781 else end_transform = start_transform * translate_trans;
00782
00783
00784 geometry_msgs::PoseStamped translated_pose;
00785 tf::poseTFToMsg(end_transform, translated_pose.pose);
00786 translated_pose.header.frame_id = handDescription().robotFrame(arm_name);
00787 translated_pose.header.stamp = ros::Time(0);
00788
00789
00790 translated_pose = transformPose(start_pose.header.frame_id, translated_pose);
00791
00792 return translated_pose;
00793 }
00794
00796 geometry_msgs::PoseStamped MechanismInterface::getGripperPose(std::string arm_name, std::string frame_id)
00797 {
00798 tf::StampedTransform gripper_transform;
00799 try
00800 {
00801 listener_.lookupTransform(frame_id, handDescription().gripperFrame(arm_name), ros::Time(0), gripper_transform);
00802 }
00803 catch (tf::TransformException ex)
00804 {
00805 ROS_ERROR("Mechanism interface: failed to get tf transform for wrist roll link; tf exception %s", ex.what());
00806 throw MechanismException(std::string("failed to get tf transform for wrist roll link; tf exception: ") +
00807 std::string(ex.what()) );
00808 }
00809 geometry_msgs::PoseStamped gripper_pose;
00810 tf::poseTFToMsg(gripper_transform, gripper_pose.pose);
00811 gripper_pose.header.frame_id = frame_id;
00812 gripper_pose.header.stamp = ros::Time::now();
00813 return gripper_pose;
00814 }
00815
00816 void MechanismInterface::transformPointCloud(std::string target_frame,
00817 const sensor_msgs::PointCloud &cloud_in,
00818 sensor_msgs::PointCloud &cloud_out)
00819 {
00820 try
00821 {
00822 listener_.transformPointCloud(target_frame, cloud_in, cloud_out);
00823 }
00824 catch (tf::TransformException ex)
00825 {
00826 ROS_ERROR("Mechanism interface: failed to cloud into %s frame; exception: %s", target_frame.c_str(),
00827 ex.what());
00828 throw MechanismException(std::string("failed to transform cloud into frame ") + target_frame +
00829 std::string("; tf exception: ") + std::string(ex.what()) );
00830 }
00831 }
00832
00833 void MechanismInterface::convertGraspableObjectComponentsToFrame(object_manipulation_msgs::GraspableObject &object,
00834 std::string frame_id)
00835 {
00836 if (!object.cluster.points.empty())
00837 {
00838 transformPointCloud(frame_id, object.cluster, object.cluster);
00839 }
00840 for (size_t i=0; i<object.potential_models.size(); i++)
00841 {
00842 object.potential_models[i].pose = transformPose(frame_id, object.potential_models[i].pose);
00843 }
00844 object.reference_frame_id = frame_id;
00845 }
00846
00847 geometry_msgs::PoseStamped MechanismInterface::transformPose(const std::string target_frame,
00848 const geometry_msgs::PoseStamped &stamped_in)
00849 {
00850 geometry_msgs::PoseStamped stamped_out;
00851 try
00852 {
00853 listener_.transformPose(target_frame, stamped_in, stamped_out);
00854 }
00855 catch (tf::TransformException ex)
00856 {
00857 ROS_ERROR("Mechanism interface: failed to transform pose into %s frame; exception: %s", target_frame.c_str(),
00858 ex.what());
00859 throw MechanismException(std::string("failed to transform pose into frame ") + target_frame +
00860 std::string("; tf exception: ") + std::string(ex.what()) );
00861 }
00862 return stamped_out;
00863 }
00864
00867 bool MechanismInterface::translateGripper(std::string arm_name, const geometry_msgs::Vector3Stamped &direction,
00868 motion_planning_msgs::OrderedCollisionOperations ord,
00869 const std::vector<motion_planning_msgs::LinkPadding> &link_padding,
00870 float requested_distance, float min_distance,
00871 float &actual_distance)
00872 {
00873
00874 geometry_msgs::PoseStamped start_pose_stamped = getGripperPose(arm_name, handDescription().robotFrame(arm_name));
00875
00876
00877 trajectory_msgs::JointTrajectory traj;
00878 std::vector<double> empty;
00879 sensor_msgs::JointState empty_state;
00880 getInterpolatedIK(arm_name,
00881 start_pose_stamped, direction, requested_distance,
00882 empty, empty_state, ord, link_padding, false, traj, actual_distance);
00883
00884 if (min_distance > 0 && actual_distance < min_distance)
00885 {
00886 ROS_DEBUG("Mechanism interface: interpolated IK trajectory covers %f distance, but at least %f requested",
00887 actual_distance, min_distance);
00888 actual_distance = 0;
00889 return false;
00890 }
00891
00892 if (traj.points.empty())
00893 {
00894 ROS_DEBUG("Mechanism interface: translate gripper trajectory is empty");
00895 actual_distance = false;
00896 return false;
00897 }
00898
00899
00900 attemptTrajectory(arm_name, traj, true);
00901 return true;
00902 }
00903
00907 geometry_msgs::PoseStamped MechanismInterface::getObjectPoseForGrasp(std::string arm_name,
00908 const geometry_msgs::Pose &grasp_pose)
00909
00910 {
00911
00912 tf::StampedTransform wrist_transform;
00913 try
00914 {
00915 listener_.lookupTransform("base_link",handDescription().gripperFrame(arm_name),
00916 ros::Time(0), wrist_transform);
00917 }
00918 catch (tf::TransformException ex)
00919 {
00920 ROS_ERROR("Mechanism interface: failed to get tf transform for wrist roll link");
00921 throw MechanismException(std::string("failed to get tf transform for wrist roll link; tf exception: ") +
00922 std::string(ex.what()) );
00923 }
00924
00925
00926 tf::Transform grasp_transform;
00927 tf::poseMsgToTF(grasp_pose, grasp_transform);
00928
00929 tf::Transform object_transform;
00930 object_transform = wrist_transform * grasp_transform.inverse();
00931
00932
00933 geometry_msgs::PoseStamped object_pose;
00934 tf::poseTFToMsg(object_transform, object_pose.pose);
00935 object_pose.header.frame_id = "base_link";
00936 object_pose.header.stamp = ros::Time::now();
00937 return object_pose;
00938 }
00939
00940 void MechanismInterface::attachObjectToGripper(std::string arm_name, std::string collision_object_name)
00941 {
00942 mapping_msgs::AttachedCollisionObject obj;
00943 obj.object.header.stamp = ros::Time::now();
00944 obj.object.header.frame_id = handDescription().robotFrame(arm_name);
00945 obj.object.operation.operation = mapping_msgs::CollisionObjectOperation::ATTACH_AND_REMOVE_AS_OBJECT;
00946 obj.object.id = collision_object_name;
00947 obj.link_name = handDescription().attachLinkName(arm_name);
00948 obj.touch_links = handDescription().gripperTouchLinkNames(arm_name);
00949 attached_object_pub_.publish(obj);
00950 }
00951
00952 void MechanismInterface::detachAndAddBackObjectsAttachedToGripper(std::string arm_name,
00953 std::string collision_object_name)
00954 {
00955 mapping_msgs::AttachedCollisionObject att;
00956 att.object.header.stamp = ros::Time::now();
00957 att.object.header.frame_id = handDescription().robotFrame(arm_name);
00958 att.link_name = handDescription().attachLinkName(arm_name);
00959 att.object.id = collision_object_name;
00960 att.object.operation.operation = mapping_msgs::CollisionObjectOperation::DETACH_AND_ADD_AS_OBJECT;
00961 attached_object_pub_.publish(att);
00962 }
00963
00964 void MechanismInterface::handPostureGraspAction(std::string arm_name,
00965 const object_manipulation_msgs::Grasp &grasp, int goal)
00966 {
00967 object_manipulation_msgs::GraspHandPostureExecutionGoal posture_goal;
00968 posture_goal.grasp = grasp;
00969 posture_goal.goal = goal;
00970 hand_posture_client_.client(arm_name).sendGoal(posture_goal);
00971 bool withinWait = hand_posture_client_.client(arm_name).waitForResult(ros::Duration(10.0));
00972 if(!withinWait)
00973 {
00974 hand_posture_client_.client(arm_name).cancelGoal();
00975 ROS_ERROR("Hand posture controller timed out on goal (%d)", goal);
00976 throw MechanismException("Hand posture controller timed out");
00977 }
00978 actionlib::SimpleClientGoalState state = hand_posture_client_.client(arm_name).getState();
00979 if(state != actionlib::SimpleClientGoalState::SUCCEEDED)
00980 {
00981 ROS_ERROR("Hand posture controller failed on goal (%d)", goal);
00982 throw MechanismException("Hand posture controller failed");
00983 }
00984 ROS_DEBUG("Hand posture controller successfully achieved goal %d", goal);
00985 }
00986
00987 bool MechanismInterface::graspPostureQuery(std::string arm_name)
00988 {
00989 object_manipulation_msgs::GraspStatus query;
00990 if (!grasp_status_client_.client(arm_name).call(query))
00991 {
00992 ROS_ERROR("Grasp posture query call failed");
00993 throw MechanismException("Grasp posture query call failed");
00994 }
00995 return query.response.is_hand_occupied;
00996 }
00997
00998 bool MechanismInterface::pointHeadAction(const geometry_msgs::PointStamped &target, std::string pointing_frame)
00999 {
01000 pr2_controllers_msgs::PointHeadGoal goal;
01001 goal.target = target;
01002 goal.pointing_axis.x = 0;
01003 goal.pointing_axis.y = 0;
01004 goal.pointing_axis.z = 1;
01005 goal.pointing_frame = pointing_frame;
01006 goal.min_duration = ros::Duration(1.0);
01007 goal.max_velocity = 1.0;
01008
01009 point_head_action_client_.client().sendGoal(goal);
01010 point_head_action_client_.client().waitForResult( ros::Duration(3.0) );
01011
01012 if (point_head_action_client_.client().getState() == actionlib::SimpleClientGoalState::SUCCEEDED)
01013 {
01014 ROS_DEBUG("Successfully moved head.");
01015 return true;
01016 }
01017 else
01018 {
01019 ROS_ERROR("Head movement failed or timed out.");
01020 return false;
01021 }
01022
01023 }
01024
01025 bool MechanismInterface::callSwitchControllers(std::vector<std::string> start_controllers,
01026 std::vector<std::string> stop_controllers)
01027 {
01028 pr2_mechanism_msgs::SwitchController srv;
01029 srv.request.start_controllers = start_controllers;
01030 srv.request.stop_controllers = stop_controllers;
01031 srv.request.strictness = srv.request.STRICT;
01032 if ( !switch_controller_service_.client().call(srv) )
01033 {
01034 ROS_ERROR("Mechanism interface: switch controller service call failed");
01035 throw MechanismException("switch controller service call failed");
01036 }
01037 if(!srv.response.ok) return false;
01038 return true;
01039 }
01040
01041 bool MechanismInterface::switchControllers(std::string start_controller, std::string stop_controller)
01042 {
01043 ROS_DEBUG("Switching controller %s for %s", start_controller.c_str(), stop_controller.c_str());
01044 std::vector<std::string> start_controllers;
01045 std::vector<std::string> stop_controllers;
01046 start_controllers.push_back(start_controller);
01047 stop_controllers.push_back(stop_controller);
01048 bool success = callSwitchControllers(start_controllers, stop_controllers);
01049 if(success)
01050 {
01051 bool start_running = checkController(start_controller);
01052 bool stop_running = checkController(stop_controller);
01053 if(start_running && !stop_running) return true;
01054 ROS_ERROR("switching %s to %s failed even though it returned success",
01055 stop_controller.c_str(), start_controller.c_str());
01056 return false;
01057 }
01058 else
01059 {
01060 ROS_ERROR("switching %s to %s failed", stop_controller.c_str(), start_controller.c_str());
01061 return false;
01062 }
01063 }
01064
01065 bool MechanismInterface::checkController(std::string controller)
01066 {
01067 pr2_mechanism_msgs::ListControllers srv;
01068 if( !list_controllers_service_.client().call(srv))
01069 {
01070 ROS_ERROR("Mechanism interface: list controllers service call failed");
01071 throw MechanismException("list controllers service call failed");
01072 }
01073 for(size_t controller_ind=0; controller_ind < srv.response.controllers.size(); controller_ind++)
01074 {
01075 if(controller.compare(srv.response.controllers[controller_ind]) == 0)
01076 {
01077 if(srv.response.state[controller_ind].compare("running") == 0) return true;
01078 return false;
01079 }
01080 }
01081 ROS_WARN("controller %s not found when checking status!", controller.c_str());
01082 return false;
01083 }
01084
01085 bool MechanismInterface::startController(std::string controller)
01086 {
01087 ROS_DEBUG("Starting controller %s", controller.c_str());
01088 std::vector<std::string> start_controllers;
01089 std::vector<std::string> stop_controllers;
01090 start_controllers.push_back(controller);
01091 bool success = callSwitchControllers(start_controllers, stop_controllers);
01092 if(success)
01093 {
01094 bool running = checkController(controller);
01095 if(running) return true;
01096 ROS_ERROR("starting controller %s failed even though it returned success", controller.c_str());
01097 return false;
01098 }
01099 else
01100 {
01101 ROS_ERROR("starting controller %s failed", controller.c_str());
01102 return false;
01103 }
01104 }
01105
01106 bool MechanismInterface::stopController(std::string controller)
01107 {
01108 ROS_DEBUG("Stopping controller %s", controller.c_str());
01109 std::vector<std::string> start_controllers;
01110 std::vector<std::string> stop_controllers;
01111 stop_controllers.push_back(controller);
01112 bool success = callSwitchControllers(start_controllers, stop_controllers);
01113 if(success)
01114 {
01115 bool running = checkController(controller);
01116 if(running)
01117 {
01118 ROS_ERROR("stopping controller %s failed even though it returned success", controller.c_str());
01119 return false;
01120 }
01121 return true;
01122 }
01123 else
01124 {
01125 ROS_ERROR("stopping controller %s failed", controller.c_str());
01126 return false;
01127 }
01128 }
01129
01130 bool MechanismInterface::switchToCartesian()
01131 {
01132 bool result = switchControllers(right_cartesian_controller_, right_joint_controller_);
01133 if(!result) return false;
01134 result = switchControllers(left_cartesian_controller_, left_joint_controller_);
01135 if(!result) return false;
01136 return true;
01137 }
01138
01139 bool MechanismInterface::switchToJoint()
01140 {
01141 bool result = switchControllers(right_joint_controller_, right_cartesian_controller_);
01142 if(!result) return false;
01143 result = switchControllers(left_joint_controller_, left_cartesian_controller_);
01144 if(!result) return false;
01145 return true;
01146 }
01147
01148 geometry_msgs::PoseStamped MechanismInterface::clipDesiredPose(std::string arm_name,
01149 const geometry_msgs::PoseStamped &desired_pose,
01150 double clip_dist, double clip_angle)
01151 {
01152
01153 if(clip_dist == 0 && clip_angle == 0) return desired_pose;
01154
01155
01156 geometry_msgs::PoseStamped current_pose = getGripperPose(arm_name, desired_pose.header.frame_id);
01157
01158
01159 Eigen::eigen2_Transform3d current_trans, desired_trans;
01160 double pos_dist, angle;
01161 Eigen::Vector3d axis, direction;
01162 tf::poseMsgToEigen(current_pose.pose, current_trans);
01163 tf::poseMsgToEigen(desired_pose.pose, desired_trans);
01164 positionAndAngleDist(current_trans, desired_trans, pos_dist, angle, axis, direction);
01165
01166
01167
01168 double pos_fraction, angle_fraction;
01169 double pos_change, angle_change;
01170 pos_fraction = fabs(angle / clip_angle);
01171 angle_fraction = fabs(pos_dist / clip_dist);
01172 if(pos_fraction <=1 && angle_fraction <=1){
01173 return desired_pose;
01174 }
01175 double fraction = pos_fraction;
01176 if(angle_fraction > pos_fraction) fraction = angle_fraction;
01177 pos_change = pos_dist / fraction;
01178 angle_change = angle / fraction;
01179
01180 Eigen::eigen2_Transform3d clipped_trans;
01181 clipped_trans = current_trans;
01182 Eigen::Vector3d scaled_direction;
01183 scaled_direction = direction * pos_change;
01184 Eigen::eigen2_Translation3d translation(scaled_direction);
01185 clipped_trans = clipped_trans * translation;
01186 Eigen::eigen2_AngleAxis<double> angle_axis(angle_change, axis);
01187 clipped_trans = clipped_trans * angle_axis;
01188 geometry_msgs::PoseStamped clipped_pose;
01189 tf::poseEigenToMsg(clipped_trans, clipped_pose.pose);
01190 clipped_pose.header = desired_pose.header;
01191 return clipped_pose;
01192 }
01193
01194 void MechanismInterface::poseDists(geometry_msgs::Pose start, geometry_msgs::Pose end, double &pos_dist, double &angle)
01195 {
01196 Eigen::eigen2_Transform3d start_trans, end_trans;
01197 tf::poseMsgToEigen(start, start_trans);
01198 tf::poseMsgToEigen(end, end_trans);
01199 Eigen::Vector3d axis, direction;
01200 positionAndAngleDist(start_trans, end_trans, pos_dist, angle, axis, direction);
01201 }
01202
01203 void MechanismInterface::positionAndAngleDist(Eigen::eigen2_Transform3d start, Eigen::eigen2_Transform3d end,
01204 double &pos_dist,
01205 double &angle, Eigen::Vector3d &axis, Eigen::Vector3d &direction)
01206 {
01207
01208 Eigen::eigen2_Transform3d trans;
01209 trans = start.inverse() * end;
01210 Eigen::eigen2_AngleAxis<double> angle_axis;
01211 angle_axis = trans.rotation();
01212 angle = angle_axis.angle();
01213 axis = angle_axis.axis();
01214 direction = trans.translation();
01215 pos_dist = sqrt(direction.dot(direction));
01216 if(pos_dist) direction *= 1/pos_dist;
01217 }
01218
01219 int MechanismInterface::translateGripperCartesian(std::string arm_name, const geometry_msgs::Vector3Stamped &direction,
01220 ros::Duration timeout, double dist_tol = .01, double angle_tol = .09,
01221 double clip_dist = .02, double clip_angle = .16, double timestep = 0.1)
01222 {
01223 geometry_msgs::PoseStamped current_pose = getGripperPose(arm_name, direction.header.frame_id);
01224 geometry_msgs::PoseStamped desired_pose = translateGripperPose(direction, current_pose, arm_name);
01225 int result = moveArmToPoseCartesian(arm_name, desired_pose, timeout, dist_tol, angle_tol,
01226 clip_dist, clip_angle, timestep);
01227 return result;
01228 }
01229
01230
01231 int MechanismInterface::moveArmToPoseCartesian(std::string arm_name, const geometry_msgs::PoseStamped &desired_pose,
01232 ros::Duration timeout, double dist_tol = .015, double angle_tol = .09,
01233 double clip_dist = .02, double clip_angle = .16, double timestep = 0.1)
01234 {
01235 bool success = false;
01236
01237
01238 for(int tries=0; tries<3; tries++)
01239 {
01240 success = switchToCartesian();
01241 if(success) break;
01242 ros::Duration(1.0).sleep();
01243 }
01244 if(!success)
01245 {
01246 ROS_ERROR("Tries exceeded when trying to switch to Cartesian control!");
01247 return 0;
01248 }
01249
01250
01251 ros::Time begin = ros::Time::now();
01252 int reached_target = -1;
01253 geometry_msgs::PoseStamped current_pose = getGripperPose(arm_name, desired_pose.header.frame_id);
01254
01255 while(1)
01256 {
01257
01258 if(ros::Time::now() - begin > timeout)
01259 {
01260 ROS_DEBUG("Timed out when moving to desired Cartesian pose");
01261 break;
01262 }
01263
01264
01265 current_pose = getGripperPose(arm_name, desired_pose.header.frame_id);
01266 double pos_dist, angle_dist;
01267 poseDists(current_pose.pose, desired_pose.pose, pos_dist, angle_dist);
01268 if(pos_dist <= dist_tol && angle_dist <= angle_tol)
01269 {
01270 reached_target = 1;
01271 break;
01272 }
01273
01274
01275 sendCartesianPoseCommand(arm_name, desired_pose, clip_dist, clip_angle);
01276
01277
01278 ros::Duration(timestep).sleep();
01279 }
01280
01281
01282 success = false;
01283 for(int tries=0; tries<3; tries++)
01284 {
01285 success = switchToJoint();
01286 if(success) break;
01287 ros::Duration(1.0).sleep();
01288 }
01289 if(!success)
01290 {
01291 ROS_ERROR("Tries exceeding when trying to switch back to joint control!");
01292 return 0;
01293 }
01294 return reached_target;
01295 }
01296
01297 void MechanismInterface::sendCartesianPoseCommand(std::string arm_name, geometry_msgs::PoseStamped desired_pose,
01298 double clip_dist = 0, double clip_angle = 0)
01299 {
01300
01301 geometry_msgs::PoseStamped clipped_pose = clipDesiredPose(arm_name, desired_pose, clip_dist, clip_angle);
01302 if(arm_name.compare("right_arm") == 0)
01303 {
01304 right_cartesian_pub_.publish(clipped_pose);
01305 }
01306 else if(arm_name.compare("left_arm") == 0)
01307 {
01308 left_cartesian_pub_.publish(clipped_pose);
01309 }
01310 else
01311 {
01312 ROS_ERROR("arm_name '%s' not recognized", arm_name.c_str());
01313 }
01314 }
01315
01316 std::vector<motion_planning_msgs::LinkPadding>
01317 MechanismInterface::fingertipPadding(std::string arm_name, double pad)
01318 {
01319 std::vector<motion_planning_msgs::LinkPadding> padding_vec;
01320 motion_planning_msgs::LinkPadding padding;
01321 padding.padding = pad;
01322 std::vector<std::string> links = handDescription().fingertipLinks(arm_name);
01323 for (size_t i=0; i<links.size(); i++)
01324 {
01325 padding.link_name = links[i];
01326 padding_vec.push_back(padding);
01327 }
01328 return padding_vec;
01329 }
01330
01331 std::vector<motion_planning_msgs::LinkPadding>
01332 MechanismInterface::gripperPadding(std::string arm_name, double pad)
01333 {
01334 std::vector<motion_planning_msgs::LinkPadding> padding_vec;
01335 motion_planning_msgs::LinkPadding padding;
01336 padding.padding = pad;
01337 std::vector<std::string> links = handDescription().gripperTouchLinkNames(arm_name);
01338 for (size_t i=0; i<links.size(); i++)
01339 {
01340 padding.link_name = links[i];
01341 padding_vec.push_back(padding);
01342 }
01343 return padding_vec;
01344 }
01345
01346 }