$search
00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2009, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of the Willow Garage nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 *********************************************************************/ 00034 00037 #ifndef CHOMP_ROBOT_MODEL_H_ 00038 #define CHOMP_ROBOT_MODEL_H_ 00039 00040 #include <planning_environment/models/collision_models.h> 00041 #include <collision_proximity_planner/treefksolverjointposaxis.hpp> 00042 #include <collision_proximity_planner/treefksolverjointposaxis_partial.hpp> 00043 #include <ros/ros.h> 00044 #include <kdl/tree.hpp> 00045 #include <kdl/chain.hpp> 00046 #include <boost/shared_ptr.hpp> 00047 00048 #include <sensor_msgs/JointState.h> 00049 00050 #include <map> 00051 #include <vector> 00052 #include <string> 00053 #include <Eigen/Core> 00054 #include <cstdlib> 00055 00056 namespace chomp 00057 { 00058 00066 class ChompRobotModel 00067 { 00068 public: 00069 00073 struct ChompJoint 00074 { 00075 const KDL::Joint* kdl_joint_; 00076 int kdl_joint_index_; 00077 int chomp_joint_index_; 00078 std::string joint_name_; 00079 std::string link_name_; 00080 bool wrap_around_; 00081 bool has_joint_limits_; 00082 double joint_limit_min_; 00083 double joint_limit_max_; 00084 double joint_update_limit_; 00085 }; 00086 00090 struct ChompPlanningGroup 00091 { 00092 std::string name_; 00093 int num_joints_; 00094 std::vector<ChompJoint> chomp_joints_; 00095 std::vector<std::string> link_names_; 00096 boost::shared_ptr<KDL::TreeFkSolverJointPosAxisPartial> fk_solver_; 00101 template <typename Derived> 00102 void getRandomState(Eigen::MatrixBase<Derived>& state_vec) const; 00103 00104 }; 00105 00106 ChompRobotModel(); 00107 virtual ~ChompRobotModel(); 00108 00114 bool init(const planning_environment::CollisionModels* model); 00115 00119 const ChompPlanningGroup* getPlanningGroup(const std::string& group_name) const; 00120 00124 int getNumKDLJoints() const; 00125 00129 const KDL::Tree* getKDLTree() const; 00130 00136 int urdfNameToKdlNumber(const std::string& urdf_name) const; 00137 00143 const std::string kdlNumberToUrdfName(int kdl_number) const; 00144 00145 const KDL::TreeFkSolverJointPosAxis* getForwardKinematicsSolver() const; 00146 00147 const std::string& getReferenceFrame() const; 00148 00157 template<typename T> 00158 void jointMsgToArray(T& msg_vector, Eigen::MatrixXd::RowXpr joint_array); 00159 00168 template<typename T> 00169 void jointMsgToArray(T& msg_vector, KDL::JntArray& joint_array); 00170 00171 void jointStateToArray(const sensor_msgs::JointState &joint_state, KDL::JntArray& joint_array); 00172 00173 void jointStateToArray(const sensor_msgs::JointState &joint_state, Eigen::MatrixXd::RowXpr joint_array); 00174 00175 void publishCollisionPoints(ros::Publisher& vis_marker); 00176 void getActiveJointInformation(const std::string &link_name, std::vector<int>& active_joints, int& segment_number); 00177 00178 private: 00179 ros::NodeHandle node_handle_,root_handle_; 00181 KDL::Tree kdl_tree_; 00182 int num_kdl_joints_; 00183 std::map<std::string, std::string> joint_segment_mapping_; 00184 std::map<std::string, std::string> segment_joint_mapping_; 00185 std::vector<std::string> kdl_number_to_urdf_name_; 00186 std::map<std::string, int> urdf_name_to_kdl_number_; 00187 std::map<std::string, ChompPlanningGroup> planning_groups_; 00188 KDL::TreeFkSolverJointPosAxis *fk_solver_; 00189 std::string reference_frame_; 00190 double max_radius_clearance_; 00192 void getLinkInformation(const std::string link_name, std::vector<int>& active_joints, int& segment_number); 00193 00194 00195 // void getActiveJointsSegmentNumberForLink(std::string link_name, 00196 }; 00197 00199 00200 inline const ChompRobotModel::ChompPlanningGroup* ChompRobotModel::getPlanningGroup(const std::string& group_name) const 00201 { 00202 std::map<std::string, ChompRobotModel::ChompPlanningGroup>::const_iterator it = planning_groups_.find(group_name); 00203 if (it == planning_groups_.end()) 00204 return NULL; 00205 else 00206 return &(it->second); 00207 } 00208 00209 inline int ChompRobotModel::getNumKDLJoints() const 00210 { 00211 return num_kdl_joints_; 00212 } 00213 00214 inline const KDL::Tree* ChompRobotModel::getKDLTree() const 00215 { 00216 return &kdl_tree_; 00217 } 00218 00219 inline int ChompRobotModel::urdfNameToKdlNumber(const std::string& urdf_name) const 00220 { 00221 std::map<std::string, int>::const_iterator it = urdf_name_to_kdl_number_.find(urdf_name); 00222 if (it!=urdf_name_to_kdl_number_.end()) 00223 return it->second; 00224 else 00225 return -1; 00226 } 00227 00228 inline const std::string ChompRobotModel::kdlNumberToUrdfName(int kdl_number) const 00229 { 00230 if (kdl_number<0 || kdl_number>=num_kdl_joints_) 00231 return std::string(""); 00232 else 00233 return kdl_number_to_urdf_name_[kdl_number]; 00234 } 00235 00236 inline const KDL::TreeFkSolverJointPosAxis* ChompRobotModel::getForwardKinematicsSolver() const 00237 { 00238 return fk_solver_; 00239 } 00240 00241 inline const std::string& ChompRobotModel::getReferenceFrame() const 00242 { 00243 return reference_frame_; 00244 } 00245 00246 template <typename Derived> 00247 void ChompRobotModel::ChompPlanningGroup::getRandomState(Eigen::MatrixBase<Derived>& state_vec) const 00248 { 00249 for (int i=0; i<num_joints_; i++) 00250 { 00251 double min = chomp_joints_[i].joint_limit_min_; 00252 double max = chomp_joints_[i].joint_limit_max_; 00253 if (!chomp_joints_[i].has_joint_limits_) 00254 { 00255 min = -M_PI/2.0; 00256 max = M_PI/2.0; 00257 } 00258 state_vec(i) = ((((double)rand())/RAND_MAX) * (max-min)) + min; 00259 } 00260 } 00261 00270 template<typename T> 00271 void ChompRobotModel::jointMsgToArray(T& msg_vector, Eigen::MatrixXd::RowXpr joint_array) 00272 { 00273 for (typename T::iterator it=msg_vector.begin(); it!=msg_vector.end(); it++) 00274 { 00275 std::string name = it->joint_name; 00276 int kdl_number = urdfNameToKdlNumber(name); 00277 if (kdl_number>=0) 00278 joint_array(kdl_number) = it->value[0]; //@TODO we assume a single joint value per joint now 00279 } 00280 } 00281 00282 template<typename T> 00283 void ChompRobotModel::jointMsgToArray(T& msg_vector, KDL::JntArray& joint_array) 00284 { 00285 for (typename T::iterator it=msg_vector.begin(); it!=msg_vector.end(); it++) 00286 { 00287 std::string name = it->joint_name; 00288 int kdl_number = urdfNameToKdlNumber(name); 00289 if (kdl_number>=0) 00290 joint_array(kdl_number) = it->value[0]; //@TODO we assume a single joint value per joint now 00291 } 00292 } 00293 00294 inline void ChompRobotModel::jointStateToArray(const sensor_msgs::JointState &joint_state, KDL::JntArray& joint_array) 00295 { 00296 for(unsigned int i=0; i < joint_state.name.size(); i++) 00297 { 00298 std::string name = joint_state.name[i]; 00299 int kdl_number = urdfNameToKdlNumber(name); 00300 if (kdl_number>=0) 00301 joint_array(kdl_number) = joint_state.position[i]; 00302 } 00303 } 00304 00305 inline void ChompRobotModel::jointStateToArray(const sensor_msgs::JointState &joint_state, Eigen::MatrixXd::RowXpr joint_array) 00306 { 00307 for(unsigned int i=0; i < joint_state.name.size(); i++) 00308 { 00309 std::string name = joint_state.name[i]; 00310 int kdl_number = urdfNameToKdlNumber(name); 00311 if (kdl_number>=0) 00312 joint_array(kdl_number) = joint_state.position[i]; 00313 } 00314 } 00315 00316 } // namespace chomp 00317 #endif /* CHOMP_ROBOT_MODEL_H_ */