$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 #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 <move_arm_msgs/MoveArmAction.h> 00053 00054 #include <motion_planning_msgs/GetMotionPlan.h> 00055 #include <motion_planning_msgs/convert_messages.h> 00056 #include <motion_planning_msgs/FilterJointTrajectory.h> 00057 #include <motion_planning_msgs/OrderedCollisionOperations.h> 00058 00059 #include <pr2_controllers_msgs/JointTrajectoryAction.h> 00060 #include <pr2_controllers_msgs/PointHeadAction.h> 00061 00062 #include <planning_environment_msgs/ContactInformation.h> 00063 #include <planning_environment_msgs/GetStateValidity.h> 00064 00065 #include <interpolated_ik_motion_planner/SetInterpolatedIKMotionPlanParams.h> 00066 00067 #include <mapping_msgs/AttachedCollisionObject.h> 00068 00069 #include <object_manipulation_msgs/ReactiveGraspAction.h> 00070 #include <object_manipulation_msgs/ReactiveLiftAction.h> 00071 #include <object_manipulation_msgs/ReactivePlaceAction.h> 00072 #include <object_manipulation_msgs/GraspHandPostureExecutionAction.h> 00073 #include <object_manipulation_msgs/GraspStatus.h> 00074 00075 #include <pr2_mechanism_msgs/SwitchController.h> 00076 #include <pr2_mechanism_msgs/ListControllers.h> 00077 00078 #include "object_manipulator/tools/exceptions.h" 00079 #include "object_manipulator/tools/service_action_wrappers.h" 00080 00081 00082 namespace object_manipulator { 00083 00085 class MechanismInterface 00086 { 00087 private: 00089 ros::NodeHandle root_nh_; 00090 00092 ros::NodeHandle priv_nh_; 00093 00095 tf::TransformListener listener_; 00096 00098 ros::Publisher attached_object_pub_; 00099 00101 std::vector<std::string> getJointNames(std::string arm_name); 00102 00104 void setInterpolatedIKParams(std::string arm_name, int num_steps, 00105 int collision_check_resolution, bool start_from_end); 00106 00108 bool callSwitchControllers(std::vector<std::string> start_controllers, std::vector<std::string> stop_controllers); 00109 00111 std::string right_cartesian_controller_; 00112 std::string left_cartesian_controller_; 00113 std::string right_joint_controller_; 00114 std::string left_joint_controller_; 00115 00116 public: 00117 00118 //----------------------------- Service clients ------------------------------- 00119 00121 MultiArmServiceWrapper<kinematics_msgs::GetKinematicSolverInfo> ik_query_client_; 00122 00124 MultiArmServiceWrapper<kinematics_msgs::GetConstraintAwarePositionIK> ik_service_client_; 00125 00127 MultiArmServiceWrapper<kinematics_msgs::GetPositionFK> fk_service_client_; 00128 00130 MultiArmServiceWrapper<motion_planning_msgs::GetMotionPlan> interpolated_ik_service_client_; 00131 00133 MultiArmServiceWrapper<interpolated_ik_motion_planner::SetInterpolatedIKMotionPlanParams> 00134 interpolated_ik_set_params_client_; 00135 00137 MultiArmServiceWrapper<object_manipulation_msgs::GraspStatus> grasp_status_client_; 00138 00140 ServiceWrapper<planning_environment_msgs::GetStateValidity> check_state_validity_client_; 00141 00143 ServiceWrapper<motion_planning_msgs::FilterJointTrajectory> joint_trajectory_normalizer_service_; 00144 00146 ServiceWrapper<pr2_mechanism_msgs::SwitchController> switch_controller_service_; 00147 00149 ServiceWrapper<pr2_mechanism_msgs::ListControllers> list_controllers_service_; 00150 00151 //------------------------------ Action clients ------------------------------- 00152 00154 MultiArmActionWrapper<object_manipulation_msgs::ReactiveGraspAction> reactive_grasp_action_client_; 00155 00157 MultiArmActionWrapper<object_manipulation_msgs::ReactiveLiftAction> reactive_lift_action_client_; 00158 00160 MultiArmActionWrapper<object_manipulation_msgs::ReactivePlaceAction> reactive_place_action_client_; 00161 00163 MultiArmActionWrapper<move_arm_msgs::MoveArmAction> move_arm_action_client_; 00164 00166 MultiArmActionWrapper<pr2_controllers_msgs::JointTrajectoryAction> traj_action_client_; 00167 00169 MultiArmActionWrapper<object_manipulation_msgs::GraspHandPostureExecutionAction> hand_posture_client_; 00170 00172 ActionWrapper<pr2_controllers_msgs::PointHeadAction> point_head_action_client_; 00173 00174 //------------------------------ Publishers ---------------------------------- 00175 00177 ros::Publisher right_cartesian_pub_; 00178 ros::Publisher left_cartesian_pub_; 00179 00180 //------------------------------ Functionality ------------------------------- 00181 00183 MechanismInterface(); 00184 00185 //------------- IK ------------- 00186 00188 bool checkStateValidity(std::string arm_name, const std::vector<double> &joint_values, 00189 const motion_planning_msgs::OrderedCollisionOperations &collision_operations, 00190 const std::vector<motion_planning_msgs::LinkPadding> &link_padding); 00191 00193 bool checkStateValidity(std::string arm_name, const std::vector<double> &joint_values) 00194 { 00195 motion_planning_msgs::OrderedCollisionOperations empty; 00196 std::vector<motion_planning_msgs::LinkPadding> also_empty; 00197 return checkStateValidity(arm_name, joint_values, empty, also_empty); 00198 } 00199 00201 bool getIKForPose(std::string arm_name, const geometry_msgs::PoseStamped &desired_pose, 00202 kinematics_msgs::GetConstraintAwarePositionIK::Response& ik_response, 00203 const motion_planning_msgs::OrderedCollisionOperations &collision_operations, 00204 const std::vector<motion_planning_msgs::LinkPadding> &link_padding); 00205 00207 bool getFK(std::string arm_name, 00208 std::vector<double> positions, 00209 geometry_msgs::PoseStamped &pose_stamped); 00210 00211 00213 int getInterpolatedIK(std::string arm_name, 00214 geometry_msgs::PoseStamped start_pose, 00215 geometry_msgs::Vector3Stamped direction, 00216 float desired_trajectory_length, 00217 const std::vector<double> &seed_joint_position, 00218 const sensor_msgs::JointState &joint_state, 00219 const motion_planning_msgs::OrderedCollisionOperations &collision_operations, 00220 const std::vector<motion_planning_msgs::LinkPadding> &link_padding, 00221 bool reverse_trajectory, 00222 trajectory_msgs::JointTrajectory &trajectory, 00223 float &actual_trajectory_length); 00224 00225 //------ traj controller ------ 00226 00228 void attemptTrajectory(std::string arm_name, const trajectory_msgs::JointTrajectory &trajectory, bool unnormalize); 00229 00232 void attemptTrajectory(std::string arm_name, const std::vector< std::vector<double> > &positions, 00233 bool unnormalize, float time_per_segment); 00234 00235 //---------- move arm ---------- 00236 00238 bool attemptMoveArmToGoal(std::string arm_name, const std::vector<double> &desired_joint_values, 00239 const motion_planning_msgs::OrderedCollisionOperations &collision_operations, 00240 const std::vector<motion_planning_msgs::LinkPadding> &link_padding); 00241 00242 void modifyMoveArmGoal(move_arm_msgs::MoveArmGoal &move_arm_goal, 00243 motion_planning_msgs::ArmNavigationErrorCodes &error_code, 00244 std::vector<planning_environment_msgs::ContactInformation> &contact_info_); 00245 00247 bool moveArmToPose(std::string arm_name, const geometry_msgs::PoseStamped &desired_pose, 00248 const motion_planning_msgs::OrderedCollisionOperations &collision_operations, 00249 const std::vector<motion_planning_msgs::LinkPadding> &link_padding); 00250 00252 bool moveArmConstrained(std::string arm_name, const geometry_msgs::PoseStamped &commanded_pose, 00253 const motion_planning_msgs::OrderedCollisionOperations &collision_operations, 00254 const std::vector<motion_planning_msgs::LinkPadding> &link_padding, 00255 const motion_planning_msgs::Constraints &path_constraints, 00256 const double &redundancy = 0.0, 00257 const bool &compute_viable_pose = true); 00258 00259 //---------- gripper ---------- 00260 00262 void handPostureGraspAction(std::string arm_name, const object_manipulation_msgs::Grasp &grasp, int goal); 00263 00265 bool graspPostureQuery(std::string arm_name); 00266 00267 //---------- head ---------- 00268 00270 bool pointHeadAction(const geometry_msgs::PointStamped &target, std::string pointing_frame="/narrow_stereo_optical_frame"); 00271 00272 //------------- tf ------------- 00273 00275 geometry_msgs::PoseStamped getGripperPose(std::string arm_name, std::string frame_id); 00276 00278 geometry_msgs::PoseStamped translateGripperPose(geometry_msgs::Vector3Stamped translation, 00279 geometry_msgs::PoseStamped start_pose, 00280 std::string arm_id); 00281 00283 geometry_msgs::PoseStamped transformPose(const std::string target_frame, 00284 const geometry_msgs::PoseStamped &stamped_in); 00285 00287 void transformPointCloud(std::string target_frame, 00288 const sensor_msgs::PointCloud &cloud_in, 00289 sensor_msgs::PointCloud &cloud_out); 00290 00292 geometry_msgs::PoseStamped getObjectPoseForGrasp(std::string arm_name, 00293 const geometry_msgs::Pose &grasp_pose); 00294 00298 void convertGraspableObjectComponentsToFrame(object_manipulation_msgs::GraspableObject &object, 00299 std::string frame_id); 00300 00302 float vectorLen(const geometry_msgs::Vector3 &vec) 00303 { 00304 btVector3 v; 00305 tf::vector3MsgToTF(vec, v); 00306 return v.length(); 00307 } 00308 00310 geometry_msgs::Vector3 normalize(const geometry_msgs::Vector3 &vec) 00311 { 00312 btVector3 v; 00313 tf::vector3MsgToTF(vec, v); 00314 v.normalize(); 00315 geometry_msgs::Vector3 vr; 00316 tf::vector3TFToMsg(v, vr); 00317 return vr; 00318 } 00319 00320 geometry_msgs::Vector3 negate(const geometry_msgs::Vector3 &vec) 00321 { 00322 geometry_msgs::Vector3 v; 00323 v.x = - vec.x; 00324 v.y = - vec.y; 00325 v.z = - vec.z; 00326 return v; 00327 } 00328 00329 //------------ controller switching ------------ 00330 00332 bool checkController(std::string controller); 00333 00335 bool switchControllers(std::string start_controller, std::string stop_controller); 00336 00338 bool startController(std::string controller); 00339 00341 bool stopController(std::string controller); 00342 00344 bool switchToCartesian(); 00345 00347 bool switchToJoint(); 00348 00349 //------------ Cartesian movement and related helper functions ------------ 00350 00352 void sendCartesianPoseCommand(std::string arm_name, geometry_msgs::PoseStamped desired_pose, 00353 double clip_dist, double clip_angle); 00354 00356 // (to within tolerances) or times out (returns 0 for error, 1 for got there, -1 for timed out) 00357 int moveArmToPoseCartesian(std::string arm_name, const geometry_msgs::PoseStamped &desired_pose, 00358 ros::Duration timeout, double dist_tol, double angle_tol, 00359 double clip_dist, double clip_angle, double timestep); 00360 00362 int translateGripperCartesian(std::string arm_name, const geometry_msgs::Vector3Stamped &direction, 00363 ros::Duration timeout, double dist_tol, double angle_tol, 00364 double clip_dist, double clip_angle, double timestep); 00365 00367 void poseDists(geometry_msgs::Pose start, geometry_msgs::Pose end, double &pos_dist, double &angle); 00368 00370 void positionAndAngleDist(Eigen::eigen2_Transform3d start, Eigen::eigen2_Transform3d end, double &pos_dist, 00371 double &angle, Eigen::Vector3d &axis, Eigen::Vector3d &direction); 00372 00374 geometry_msgs::PoseStamped clipDesiredPose(std::string arm_name, const geometry_msgs::PoseStamped &desired_pose, 00375 double clip_dist, double clip_angle); 00376 00377 //------------ misc ------------ 00378 00380 bool translateGripper(std::string arm_name, const geometry_msgs::Vector3Stamped &direction, 00381 motion_planning_msgs::OrderedCollisionOperations ord, 00382 const std::vector<motion_planning_msgs::LinkPadding> &link_padding, 00383 float requested_distance, float min_distance, 00384 float &actual_distance); 00385 00387 static std::vector<motion_planning_msgs::LinkPadding> fingertipPadding(std::string arm_name, double pad); 00388 00390 static std::vector<motion_planning_msgs::LinkPadding> gripperPadding(std::string arm_name, double pad); 00391 00392 //------------ attached objects (collision space) ------------ 00393 00395 void attachObjectToGripper(std::string arm_name, std::string object_collision_name); 00396 00398 void detachAndAddBackObjectsAttachedToGripper(std::string arm_name, std::string object_collision_name); 00399 00400 }; 00401 00403 00408 inline MechanismInterface& mechInterface() 00409 { 00410 static MechanismInterface mech_interface; 00411 return mech_interface; 00412 } 00413 00414 } //namespace object_manipulator 00415 00416 #endif