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 #ifndef _MECHANISM_INTERFACE_H_
00034 #define _MECHANISM_INTERFACE_H_
00035
00036 #include <ros/ros.h>
00037
00038 #include <actionlib/client/simple_action_client.h>
00039
00040 #include <tf/transform_listener.h>
00041
00042 #include <eigen_conversions/eigen_msg.h>
00043 #include <Eigen/Core>
00044 #include <Eigen/Geometry>
00045
00046 #include <geometry_msgs/Vector3.h>
00047
00048 #include <kinematics_msgs/GetKinematicSolverInfo.h>
00049 #include <kinematics_msgs/GetConstraintAwarePositionIK.h>
00050 #include <kinematics_msgs/GetPositionFK.h>
00051
00052 #include <arm_navigation_msgs/MoveArmAction.h>
00053
00054 #include <arm_navigation_msgs/GetMotionPlan.h>
00055 #include <arm_navigation_msgs/convert_messages.h>
00056 #include <arm_navigation_msgs/FilterJointTrajectory.h>
00057 #include <arm_navigation_msgs/OrderedCollisionOperations.h>
00058
00059 #include <pr2_controllers_msgs/JointTrajectoryAction.h>
00060 #include <pr2_controllers_msgs/PointHeadAction.h>
00061
00062 #include <arm_navigation_msgs/ContactInformation.h>
00063 #include <arm_navigation_msgs/GetStateValidity.h>
00064 #include <arm_navigation_msgs/SetPlanningSceneDiff.h>
00065 #include <arm_navigation_msgs/GetRobotState.h>
00066
00067 #include <std_srvs/Empty.h>
00068
00069 #include <interpolated_ik_motion_planner/SetInterpolatedIKMotionPlanParams.h>
00070
00071 #include <arm_navigation_msgs/AttachedCollisionObject.h>
00072
00073 #include <object_manipulation_msgs/ReactiveGraspAction.h>
00074 #include <object_manipulation_msgs/ReactiveLiftAction.h>
00075 #include <object_manipulation_msgs/ReactivePlaceAction.h>
00076 #include <object_manipulation_msgs/GraspHandPostureExecutionAction.h>
00077 #include <object_manipulation_msgs/GraspStatus.h>
00078
00079 #include <pr2_mechanism_msgs/SwitchController.h>
00080 #include <pr2_mechanism_msgs/ListControllers.h>
00081
00082 #include "object_manipulator/tools/exceptions.h"
00083 #include "object_manipulator/tools/service_action_wrappers.h"
00084
00085
00086 namespace object_manipulator {
00087
00089 class MechanismInterface
00090 {
00091 private:
00093 ros::NodeHandle root_nh_;
00094
00096 ros::NodeHandle priv_nh_;
00097
00099 tf::TransformListener listener_;
00100
00102 ros::Publisher attached_object_pub_;
00103
00105 std::string joint_states_topic_;
00106
00109 std::map<std::string, std::string> joint_controller_names_;
00110
00113 std::map<std::string, std::string> cartesian_controller_names_;
00114
00116 arm_navigation_msgs::OrderedCollisionOperations collision_operations_cache_;
00117
00119 std::vector<arm_navigation_msgs::LinkPadding> link_padding_cache_;
00120
00122 bool planning_scene_cache_empty_;
00123
00125 bool cache_planning_scene_;
00126
00128 void setInterpolatedIKParams(std::string arm_name, int num_steps,
00129 int collision_check_resolution, bool start_from_end);
00130
00132 bool callSwitchControllers(std::vector<std::string> start_controllers, std::vector<std::string> stop_controllers);
00133
00135
00136 bool cachePlanningScene(const arm_navigation_msgs::OrderedCollisionOperations& collision_operations,
00137 const std::vector<arm_navigation_msgs::LinkPadding> &link_padding);
00138
00139 public:
00140
00141
00142
00144 MultiArmServiceWrapper<kinematics_msgs::GetKinematicSolverInfo> ik_query_client_;
00145
00147 MultiArmServiceWrapper<kinematics_msgs::GetConstraintAwarePositionIK> ik_service_client_;
00148
00150 MultiArmServiceWrapper<kinematics_msgs::GetPositionFK> fk_service_client_;
00151
00153 MultiArmServiceWrapper<arm_navigation_msgs::GetMotionPlan> interpolated_ik_service_client_;
00154
00156 MultiArmServiceWrapper<interpolated_ik_motion_planner::SetInterpolatedIKMotionPlanParams>
00157 interpolated_ik_set_params_client_;
00158
00160 MultiArmServiceWrapper<object_manipulation_msgs::GraspStatus> grasp_status_client_;
00161
00163 ServiceWrapper<arm_navigation_msgs::GetStateValidity> check_state_validity_client_;
00164
00166 ServiceWrapper<arm_navigation_msgs::FilterJointTrajectory> joint_trajectory_normalizer_service_;
00167
00169 ServiceWrapper<pr2_mechanism_msgs::SwitchController> switch_controller_service_;
00170
00172 ServiceWrapper<pr2_mechanism_msgs::ListControllers> list_controllers_service_;
00173
00175 ServiceWrapper<arm_navigation_msgs::GetRobotState> get_robot_state_client_;
00176
00178 ServiceWrapper<arm_navigation_msgs::SetPlanningSceneDiff> set_planning_scene_diff_service_;
00179
00181 ServiceWrapper<std_srvs::Empty> reset_collision_map_service_;
00182
00183
00184
00186 MultiArmActionWrapper<object_manipulation_msgs::ReactiveGraspAction> reactive_grasp_action_client_;
00187
00189 MultiArmActionWrapper<object_manipulation_msgs::ReactiveLiftAction> reactive_lift_action_client_;
00190
00192 MultiArmActionWrapper<object_manipulation_msgs::ReactivePlaceAction> reactive_place_action_client_;
00193
00195 MultiArmActionWrapper<arm_navigation_msgs::MoveArmAction> move_arm_action_client_;
00196
00198 MultiArmActionWrapper<pr2_controllers_msgs::JointTrajectoryAction> traj_action_client_;
00199
00201 MultiArmActionWrapper<object_manipulation_msgs::GraspHandPostureExecutionAction> hand_posture_client_;
00202
00204 ActionWrapper<pr2_controllers_msgs::PointHeadAction> point_head_action_client_;
00205
00206
00207
00209 MultiArmTopicWrapper<geometry_msgs::PoseStamped> cartesian_pub_;
00210
00212 MultiArmTopicWrapper<std_msgs::Float64MultiArray> cartesian_posture_pub_;
00213
00215
00216
00217
00218
00219
00221 MechanismInterface();
00222
00223
00224
00226 void getRobotState(arm_navigation_msgs::RobotState& state);
00227
00230 void getPlanningScene(const arm_navigation_msgs::OrderedCollisionOperations& collision_operations,
00231 const std::vector<arm_navigation_msgs::LinkPadding> &link_padding);
00232
00234 bool checkStateValidity(std::string arm_name, const std::vector<double> &joint_values,
00235 const arm_navigation_msgs::OrderedCollisionOperations &collision_operations,
00236 const std::vector<arm_navigation_msgs::LinkPadding> &link_padding);
00237
00239 bool checkStateValidity(std::string arm_name, const std::vector<double> &joint_values)
00240 {
00241 arm_navigation_msgs::OrderedCollisionOperations empty;
00242 std::vector<arm_navigation_msgs::LinkPadding> also_empty;
00243 return checkStateValidity(arm_name, joint_values, empty, also_empty);
00244 }
00245
00247 bool getIKForPose(std::string arm_name, const geometry_msgs::PoseStamped &desired_pose,
00248 kinematics_msgs::GetConstraintAwarePositionIK::Response& ik_response,
00249 const arm_navigation_msgs::OrderedCollisionOperations &collision_operations,
00250 const std::vector<arm_navigation_msgs::LinkPadding> &link_padding);
00251
00253 bool getFK(std::string arm_name,
00254 std::vector<double> positions,
00255 geometry_msgs::PoseStamped &pose_stamped);
00256
00257
00259 int getInterpolatedIK(std::string arm_name,
00260 geometry_msgs::PoseStamped start_pose,
00261 geometry_msgs::Vector3Stamped direction,
00262 float desired_trajectory_length,
00263 const std::vector<double> &seed_joint_position,
00264 const sensor_msgs::JointState &joint_state,
00265 const arm_navigation_msgs::OrderedCollisionOperations &collision_operations,
00266 const std::vector<arm_navigation_msgs::LinkPadding> &link_padding,
00267 bool reverse_trajectory,
00268 trajectory_msgs::JointTrajectory &trajectory,
00269 float &actual_trajectory_length);
00270
00271
00272
00274 void attemptTrajectory(std::string arm_name, const trajectory_msgs::JointTrajectory &trajectory, bool unnormalize);
00275
00278 void attemptTrajectory(std::string arm_name, const std::vector< std::vector<double> > &positions,
00279 bool unnormalize, float time_per_segment);
00280
00282 trajectory_msgs::JointTrajectory assembleJointTrajectory(std::string arm_name,
00283 const std::vector< std::vector<double> > &positions,
00284 float time_per_segment);
00285
00287 void unnormalizeTrajectory(std::string arm_name, const trajectory_msgs::JointTrajectory &input_trajectory,
00288 trajectory_msgs::JointTrajectory &normalized_trajectory);
00289
00290
00291
00293 bool attemptMoveArmToGoal(std::string arm_name, const std::vector<double> &desired_joint_values,
00294 const arm_navigation_msgs::OrderedCollisionOperations &collision_operations,
00295 const std::vector<arm_navigation_msgs::LinkPadding> &link_padding);
00296
00297 void modifyMoveArmGoal(arm_navigation_msgs::MoveArmGoal &move_arm_goal,
00298 arm_navigation_msgs::ArmNavigationErrorCodes &error_code,
00299 std::vector<arm_navigation_msgs::ContactInformation> &contact_info_);
00300
00302 bool moveArmToPose(std::string arm_name, const geometry_msgs::PoseStamped &desired_pose,
00303 const arm_navigation_msgs::OrderedCollisionOperations &collision_operations,
00304 const std::vector<arm_navigation_msgs::LinkPadding> &link_padding);
00305
00307 bool moveArmConstrained(std::string arm_name, const geometry_msgs::PoseStamped &commanded_pose,
00308 const arm_navigation_msgs::OrderedCollisionOperations &collision_operations,
00309 const std::vector<arm_navigation_msgs::LinkPadding> &link_padding,
00310 const arm_navigation_msgs::Constraints &path_constraints,
00311 const double &redundancy = 0.0,
00312 const bool &compute_viable_pose = true);
00313
00314
00315
00317 void handPostureGraspAction(std::string arm_name, const object_manipulation_msgs::Grasp &grasp, int goal, float max_contact_force);
00318
00320 bool graspPostureQuery(std::string arm_name, const object_manipulation_msgs::Grasp grasp);
00321
00322
00323
00325 bool pointHeadAction(const geometry_msgs::PointStamped &target,
00326 std::string pointing_frame="/narrow_stereo_optical_frame", bool wait_for_result = true);
00327
00328
00329
00331 geometry_msgs::PoseStamped getGripperPose(std::string arm_name, std::string frame_id);
00332
00334 geometry_msgs::PoseStamped translateGripperPose(geometry_msgs::Vector3Stamped translation,
00335 geometry_msgs::PoseStamped start_pose,
00336 std::string arm_id);
00337
00339 geometry_msgs::PoseStamped transformPose(const std::string target_frame,
00340 const geometry_msgs::PoseStamped &stamped_in);
00341
00343 void transformPointCloud(std::string target_frame,
00344 const sensor_msgs::PointCloud &cloud_in,
00345 sensor_msgs::PointCloud &cloud_out);
00346
00348 geometry_msgs::PoseStamped getObjectPoseForGrasp(std::string arm_name,
00349 const geometry_msgs::Pose &grasp_pose);
00350
00354 void convertGraspableObjectComponentsToFrame(object_manipulation_msgs::GraspableObject &object,
00355 std::string frame_id);
00356
00358 float vectorLen(const geometry_msgs::Vector3 &vec)
00359 {
00360 btVector3 v;
00361 tf::vector3MsgToTF(vec, v);
00362 return v.length();
00363 }
00364
00366 geometry_msgs::Vector3 normalize(const geometry_msgs::Vector3 &vec)
00367 {
00368 btVector3 v;
00369 tf::vector3MsgToTF(vec, v);
00370 v.normalize();
00371 geometry_msgs::Vector3 vr;
00372 tf::vector3TFToMsg(v, vr);
00373 return vr;
00374 }
00375
00376 geometry_msgs::Vector3 negate(const geometry_msgs::Vector3 &vec)
00377 {
00378 geometry_msgs::Vector3 v;
00379 v.x = - vec.x;
00380 v.y = - vec.y;
00381 v.z = - vec.z;
00382 return v;
00383 }
00384
00385
00386
00388 bool checkController(std::string controller);
00389
00391 bool switchControllers(std::string start_controller, std::string stop_controller);
00392
00394 bool startController(std::string controller);
00395
00397 bool stopController(std::string controller);
00398
00400 bool switchToCartesian(std::string arm_name);
00401
00403 bool switchToJoint(std::string arm_name);
00404
00406 std::string cartesianControllerName(std::string arm_name);
00407
00409 std::string jointControllerName(std::string arm_name);
00410
00411
00412
00414 void sendCartesianPoseCommand(std::string arm_name, geometry_msgs::PoseStamped desired_pose);
00415
00417 void sendCartesianPostureCommand(std::string arm_name, std::vector<double> arm_angles);
00418
00419
00421
00422
00423
00425 void setCartesianPostureGoalToCurrentAngles(std::string arm_name);
00426
00428
00429 int moveArmToPoseCartesian(std::string arm_name, const geometry_msgs::PoseStamped &desired_pose,
00430 ros::Duration timeout, double dist_tol = 0.001, double angle_tol = 0.05,
00431 double clip_dist = .02, double clip_angle = .16,
00432 double overshoot_dist = .005, double overshoot_angle = .087,
00433 double timestep = 0.1,
00434 const std::vector<double> &goal_posture_suggestion = std::vector<double>());
00435
00437 int translateGripperCartesian(std::string arm_name, const geometry_msgs::Vector3Stamped &direction,
00438 ros::Duration timeout, double dist_tol = .001, double angle_tol = .05,
00439 double clip_dist = .02, double clip_angle = .16,
00440 double overshoot_dist = 0.005, double overshoot_angle = 0.087, double timestep = 0.1);
00441
00443 void poseDists(geometry_msgs::Pose start, geometry_msgs::Pose end, double &pos_dist, double &angle);
00444
00446 void positionAndAngleDist(Eigen::Affine3d start, Eigen::Affine3d end, double &pos_dist,
00447 double &angle, Eigen::Vector3d &axis, Eigen::Vector3d &direction);
00448
00450 geometry_msgs::PoseStamped clipDesiredPose(const geometry_msgs::PoseStamped ¤t_pose,
00451 const geometry_msgs::PoseStamped &desired_pose,
00452 double clip_dist, double clip_angle,
00453 double &resulting_clip_fraction);
00454
00456 geometry_msgs::PoseStamped clipDesiredPose(std::string arm_name, const geometry_msgs::PoseStamped &desired_pose,
00457 double clip_dist, double clip_angle, double &resulting_clip_fraction);
00458
00460
00461 geometry_msgs::PoseStamped clipDesiredPose(std::string arm_name, const geometry_msgs::PoseStamped &desired_pose,
00462 double clip_dist, double clip_angle, double &resulting_clip_fraction,
00463 const std::vector<double> &goal_posture_suggestion,
00464 std::vector<double> &clipped_posture_goal);
00465
00467 geometry_msgs::PoseStamped overshootDesiredPose(std::string arm_name,
00468 const geometry_msgs::PoseStamped &desired_pose,
00469 double overshoot_dist, double overshoot_angle,
00470 double dist_tol, double angle_tol);
00471
00473 std::vector<std::string> getJointNames(std::string arm_name);
00474
00476 bool getArmAngles(std::string arm_name, std::vector<double> &arm_angles);
00477
00478
00479
00481 bool translateGripper(std::string arm_name, const geometry_msgs::Vector3Stamped &direction,
00482 arm_navigation_msgs::OrderedCollisionOperations ord,
00483 const std::vector<arm_navigation_msgs::LinkPadding> &link_padding,
00484 float requested_distance, float min_distance,
00485 float &actual_distance);
00486
00488 static std::vector<arm_navigation_msgs::LinkPadding> fingertipPadding(std::string arm_name, double pad);
00489
00491 static std::vector<arm_navigation_msgs::LinkPadding> gripperPadding(std::string arm_name, double pad);
00492
00493
00494
00496 void attachObjectToGripper(std::string arm_name, std::string object_collision_name);
00497
00499 void detachAndAddBackObjectsAttachedToGripper(std::string arm_name, std::string object_collision_name);
00500
00502 void detachAllObjectsFromGripper(std::string arm_name);
00503 };
00504
00506
00511 inline MechanismInterface& mechInterface()
00512 {
00513 static MechanismInterface mech_interface;
00514 return mech_interface;
00515 }
00516
00517 }
00518
00519 #endif