$search
00001 /********************************************************************* 00002 * 00003 * Software License Agreement (BSD License) 00004 * 00005 * Copyright (c) 2008, Robert Bosch LLC. 00006 * All rights reserved. 00007 * 00008 * Redistribution and use in source and binary forms, with or without 00009 * modification, are permitted provided that the following conditions 00010 * are met: 00011 * 00012 * * Redistributions of source code must retain the above copyright 00013 * notice, this list of conditions and the following disclaimer. 00014 * * Redistributions in binary form must reproduce the above 00015 * copyright notice, this list of conditions and the following 00016 * disclaimer in the documentation and/or other materials provided 00017 * with the distribution. 00018 * * Neither the name of the Robert Bosch nor the names of its 00019 * contributors may be used to endorse or promote products derived 00020 * from this software without specific prior written permission. 00021 * 00022 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00023 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00024 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00025 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00026 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00027 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00028 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00029 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00030 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00031 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00032 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00033 * POSSIBILITY OF SUCH DAMAGE. 00034 * 00035 *********************************************************************/ 00036 00037 /* 00038 * arm_control.h 00039 * 00040 * Created on: Jun 30, 2010 00041 * Author: christian 00042 */ 00043 00044 #ifndef ARM_CONTROL_H_ 00045 #define ARM_CONTROL_H_ 00046 00047 #include <string> 00048 #include <cmath> 00049 00050 #include <ros/ros.h> 00051 #include <geometry_msgs/PoseStamped.h> 00052 #include <pr2_controllers_msgs/JointTrajectoryAction.h> 00053 #include <actionlib/client/simple_action_client.h> 00054 #include <tf/transform_datatypes.h> 00055 #include <arm_navigation_msgs/MoveArmAction.h> 00056 #include <kinematics_msgs/GetPositionIK.h> 00057 00058 00059 00060 00061 00062 00063 00064 namespace simple_robot_control{ 00065 00066 00067 using ::std::string; 00068 using ::std::vector; 00069 00070 00071 class Arm{ 00072 private: 00073 const static double wrist_speed_ = 2.0; //2 seconds per revolution 00074 const static double gripperlength = 0.18; 00075 00076 00077 00078 vector<string> joint_names; 00079 string armside_str; 00080 string group_name; 00081 actionlib::SimpleActionClient<arm_navigation_msgs::MoveArmAction>* move_arm_client_; 00082 actionlib::SimpleActionClient< pr2_controllers_msgs::JointTrajectoryAction > traj_client_; 00083 00084 ros::ServiceClient ik_service_client_; 00085 ros::NodeHandle nh_; 00086 00087 00088 vector<double> current_joint_angles_; 00089 00090 public: 00091 00092 00096 Arm(char arm_side, bool collision_checking = true); 00097 00098 00099 ~Arm(); 00100 00102 //joint angle control 00104 00108 bool goToJointPos (const vector<double>& positions , double max_time = 3.0, bool wait = true ); 00109 00110 00114 bool goToJointPosWithCollisionChecking (const vector<double>& positions, double max_time = 3.0, bool wait = true ); 00115 00116 00120 bool rotateWrist(double radians, double wrist_speed = wrist_speed_ ,bool wait = true); 00121 00122 00123 00125 //euclidian position control 00127 00130 bool getIK(const geometry_msgs::PoseStamped& pose, vector<double>& joint_angles, vector<double>* ik_seed_pos = NULL); 00131 00132 00136 vector<double> getCurrentJointAngles(); 00137 00138 00139 00140 enum approach_direction_t { FRONTAL, FROM_BELOW, FROM_ABOVE, FROM_RIGHT_SIDEWAYS, FROM_RIGHT_UPRIGHT, FROM_LEFT_UPRIGHT, FROM_LEFT_SIDEWAYS}; 00144 bool moveGripperToPosition(const tf::Vector3& position, string frame_id, approach_direction_t approach = FRONTAL, double max_time =5.0, bool wait=true, vector<double>* ik_seed_pos = 0 ); 00145 00146 00150 bool moveGrippertoPositionWithCollisionChecking(const tf::Vector3& position, string frame_id, approach_direction_t approach = FRONTAL, double max_time =5.0, bool wait=true, std::string planner = "ompl" ); 00151 00152 00156 bool moveGrippertoPose(const tf::StampedTransform& pose, double max_time =5.0, bool wait=true, vector<double>* ik_seed_pos = 0 ); 00157 00161 bool moveGrippertoPoseWithCollisionChecking(const tf::StampedTransform& pose, double max_time =5.0, bool wait=true, std::string planner = "ompl" ); 00162 00163 00167 bool moveGrippertoPoseWithOrientationConstraints(const tf::StampedTransform& tf, bool keep_roll, bool keep_pitch, bool keep_yaw, double max_time =5.0, bool wait=true, double tolerance = 0.2); 00168 00169 00170 00171 00172 00173 00177 bool moveWristRollLinktoPose(const tf::StampedTransform& pose, double max_time =5.0, bool wait=true, vector<double>* ik_seed_pos = 0 ); 00178 00182 bool moveWristRollLinktoPose(const geometry_msgs::PoseStamped& pose, double max_time =5.0, bool wait=true, vector<double>* ik_seed_pos = 0 ); 00183 00187 bool moveWristRollLinktoPoseWithCollisionChecking(const geometry_msgs::PoseStamped& pose, double max_time =5.0, bool wait=true, std::string planner = "ompl" ); 00188 00189 00193 bool moveWristRollLinktoPoseWithCollisionChecking(const tf::StampedTransform& pose, double max_time =5.0, bool wait=true, std::string planner = "ompl" ); 00194 00195 00199 bool moveWristRollLinktoPoseWithOrientationConstraints(const tf::StampedTransform& pose, bool keep_roll, bool keep_pitch, bool keep_yaw, double max_time =5.0, bool wait=true, double tolerance = 0.2); 00200 00201 00205 bool moveWristRollLinktoPoseWithOrientationConstraints(const geometry_msgs::PoseStamped& pose, bool keep_roll, bool keep_pitch, bool keep_yaw, double max_time =5.0, bool wait=true, double tolerance = 0.2 ); 00206 00207 00211 bool goToJointPos (const double* positions , int num_positions, double max_time = 3.0, bool wait = true ); 00212 00216 bool updateJointStatePos(); 00217 00218 00222 bool isAtPos(const std::vector<double>& pos_vec); 00223 00227 bool tuck(); 00228 00232 bool stretch(); 00233 00234 00235 00236 00237 private: 00238 tf::StampedTransform gripperToWrist(const tf::StampedTransform& pose); 00239 tf::StampedTransform wristToGripper(const tf::StampedTransform& pose); 00240 tf::StampedTransform makePose(const tf::Vector3& position, string frame_id, approach_direction_t approach); 00241 00242 00243 00244 00245 00246 }; 00247 } 00248 00249 #endif /* ARM_CONTROL_H_ */