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
00037 #ifndef CHOMP_ROBOT_MODEL_H_
00038 #define CHOMP_ROBOT_MODEL_H_
00039
00040
00041 #include <chomp_motion_planner/treefksolverjointposaxis.hpp>
00042 #include <chomp_motion_planner/treefksolverjointposaxis_partial.hpp>
00043 #include <chomp_motion_planner/chomp_collision_point.h>
00044 #include <ros/ros.h>
00045 #include <planning_environment/monitors/collision_space_monitor.h>
00046 #include <kdl/tree.hpp>
00047 #include <kdl/chain.hpp>
00048 #include <boost/shared_ptr.hpp>
00049 #include <mapping_msgs/AttachedCollisionObject.h>
00050 #include <motion_planning_msgs/RobotState.h>
00051
00052 #include <sensor_msgs/JointState.h>
00053
00054 #include <map>
00055 #include <vector>
00056 #include <string>
00057 #include <Eigen/Core>
00058 #include <cstdlib>
00059
00060 namespace chomp
00061 {
00062
00070 class ChompRobotModel
00071 {
00072 public:
00073
00077 struct ChompJoint
00078 {
00079 const KDL::Joint* kdl_joint_;
00080 int kdl_joint_index_;
00081 int chomp_joint_index_;
00082 std::string joint_name_;
00083 std::string link_name_;
00084 bool wrap_around_;
00085 bool has_joint_limits_;
00086 double joint_limit_min_;
00087 double joint_limit_max_;
00088 double joint_update_limit_;
00089 };
00090
00094 struct ChompPlanningGroup
00095 {
00096 std::string name_;
00097 int num_joints_;
00098 std::vector<ChompJoint> chomp_joints_;
00099 std::vector<std::string> link_names_;
00100 std::vector<std::string> collision_link_names_;
00101 std::vector<ChompCollisionPoint> collision_points_;
00102 boost::shared_ptr<KDL::TreeFkSolverJointPosAxisPartial> fk_solver_;
00107 template <typename Derived>
00108 void getRandomState(Eigen::MatrixBase<Derived>& state_vec) const;
00109
00115 bool addCollisionPoint(ChompCollisionPoint& collision_point, ChompRobotModel& robot_model);
00116 };
00117
00118 ChompRobotModel();
00119 virtual ~ChompRobotModel();
00120
00126 bool init(planning_environment::CollisionSpaceMonitor* monitor_, std::string& reference_frame);
00127
00131 const ChompPlanningGroup* getPlanningGroup(const std::string& group_name) const;
00132
00136 const planning_environment::RobotModels* getRobotModels() const;
00137
00141 int getNumKDLJoints() const;
00142
00146 const KDL::Tree* getKDLTree() const;
00147
00153 int urdfNameToKdlNumber(const std::string& urdf_name) const;
00154
00160 const std::string kdlNumberToUrdfName(int kdl_number) const;
00161
00162 const KDL::TreeFkSolverJointPosAxis* getForwardKinematicsSolver() const;
00163
00164 const std::string& getReferenceFrame() const;
00165
00174 template<typename T>
00175 void jointMsgToArray(T& msg_vector, Eigen::MatrixXd::RowXpr joint_array);
00176
00185 template<typename T>
00186 void jointMsgToArray(T& msg_vector, KDL::JntArray& joint_array);
00187
00188 void jointStateToArray(const sensor_msgs::JointState &joint_state, KDL::JntArray& joint_array);
00189
00190 void jointStateToArray(const sensor_msgs::JointState &joint_state, Eigen::MatrixXd::RowXpr joint_array);
00191
00192 void getLinkCollisionPoints(std::string link_name, std::vector<ChompCollisionPoint>& points);
00193
00197 double getMaxRadiusClearance() const;
00198
00202 void attachedObjectCallback(const mapping_msgs::AttachedCollisionObjectConstPtr& attached_object);
00203
00204 void generateAttachedObjectCollisionPoints(const motion_planning_msgs::RobotState* robot_state);
00205 void generateLinkCollisionPoints();
00206 void populatePlanningGroupCollisionPoints();
00207
00208 void publishCollisionPoints(ros::Publisher& vis_marker);
00209
00210 private:
00211 ros::NodeHandle node_handle_,root_handle_;
00212 planning_environment::CollisionSpaceMonitor* monitor_;
00213 ros::Subscriber attached_object_subscriber_;
00215 KDL::Tree kdl_tree_;
00216 int num_kdl_joints_;
00217 std::map<std::string, std::string> joint_segment_mapping_;
00218 std::map<std::string, std::string> segment_joint_mapping_;
00219 std::vector<std::string> kdl_number_to_urdf_name_;
00220 std::map<std::string, int> urdf_name_to_kdl_number_;
00221 std::map<std::string, ChompPlanningGroup> planning_groups_;
00222 KDL::TreeFkSolverJointPosAxis *fk_solver_;
00223 double collision_clearance_default_;
00224 std::string reference_frame_;
00225 std::map<std::string, std::vector<ChompCollisionPoint> > link_collision_points_;
00226 std::map<std::string, std::vector<ChompCollisionPoint> > link_attached_object_collision_points_;
00227 double max_radius_clearance_;
00228 std::map<std::string, mapping_msgs::AttachedCollisionObject> attached_objects_;
00230 void addCollisionPointsFromLink(const planning_models::KinematicState& state, std::string link_name, double clearance);
00231
00232 void getLinkInformation(const std::string link_name, std::vector<int>& active_joints, int& segment_number);
00233
00234
00235 };
00236
00238
00239 inline const ChompRobotModel::ChompPlanningGroup* ChompRobotModel::getPlanningGroup(const std::string& group_name) const
00240 {
00241 std::map<std::string, ChompRobotModel::ChompPlanningGroup>::const_iterator it = planning_groups_.find(group_name);
00242 if (it == planning_groups_.end())
00243 return NULL;
00244 else
00245 return &(it->second);
00246 }
00247
00248 inline const planning_environment::RobotModels* ChompRobotModel::getRobotModels() const
00249 {
00250 return monitor_->getCollisionModels();
00251 }
00252
00253 inline int ChompRobotModel::getNumKDLJoints() const
00254 {
00255 return num_kdl_joints_;
00256 }
00257
00258 inline const KDL::Tree* ChompRobotModel::getKDLTree() const
00259 {
00260 return &kdl_tree_;
00261 }
00262
00263 inline int ChompRobotModel::urdfNameToKdlNumber(const std::string& urdf_name) const
00264 {
00265 std::map<std::string, int>::const_iterator it = urdf_name_to_kdl_number_.find(urdf_name);
00266 if (it!=urdf_name_to_kdl_number_.end())
00267 return it->second;
00268 else
00269 return -1;
00270 }
00271
00272 inline const std::string ChompRobotModel::kdlNumberToUrdfName(int kdl_number) const
00273 {
00274 if (kdl_number<0 || kdl_number>=num_kdl_joints_)
00275 return std::string("");
00276 else
00277 return kdl_number_to_urdf_name_[kdl_number];
00278 }
00279
00280 inline const KDL::TreeFkSolverJointPosAxis* ChompRobotModel::getForwardKinematicsSolver() const
00281 {
00282 return fk_solver_;
00283 }
00284
00285 inline const std::string& ChompRobotModel::getReferenceFrame() const
00286 {
00287 return reference_frame_;
00288 }
00289
00290 template <typename Derived>
00291 void ChompRobotModel::ChompPlanningGroup::getRandomState(Eigen::MatrixBase<Derived>& state_vec) const
00292 {
00293 for (int i=0; i<num_joints_; i++)
00294 {
00295 double min = chomp_joints_[i].joint_limit_min_;
00296 double max = chomp_joints_[i].joint_limit_max_;
00297 if (!chomp_joints_[i].has_joint_limits_)
00298 {
00299 min = -M_PI/2.0;
00300 max = M_PI/2.0;
00301 }
00302 state_vec(i) = ((((double)rand())/RAND_MAX) * (max-min)) + min;
00303 }
00304 }
00305
00314 template<typename T>
00315 void ChompRobotModel::jointMsgToArray(T& msg_vector, Eigen::MatrixXd::RowXpr joint_array)
00316 {
00317 for (typename T::iterator it=msg_vector.begin(); it!=msg_vector.end(); it++)
00318 {
00319 std::string name = it->joint_name;
00320 int kdl_number = urdfNameToKdlNumber(name);
00321 if (kdl_number>=0)
00322 joint_array(kdl_number) = it->value[0];
00323 }
00324 }
00325
00326 template<typename T>
00327 void ChompRobotModel::jointMsgToArray(T& msg_vector, KDL::JntArray& joint_array)
00328 {
00329 for (typename T::iterator it=msg_vector.begin(); it!=msg_vector.end(); it++)
00330 {
00331 std::string name = it->joint_name;
00332 int kdl_number = urdfNameToKdlNumber(name);
00333 if (kdl_number>=0)
00334 joint_array(kdl_number) = it->value[0];
00335 }
00336 }
00337
00338 inline void ChompRobotModel::jointStateToArray(const sensor_msgs::JointState &joint_state, KDL::JntArray& joint_array)
00339 {
00340 for(unsigned int i=0; i < joint_state.name.size(); i++)
00341 {
00342 std::string name = joint_state.name[i];
00343 int kdl_number = urdfNameToKdlNumber(name);
00344 if (kdl_number>=0)
00345 joint_array(kdl_number) = joint_state.position[i];
00346 }
00347 }
00348
00349 inline void ChompRobotModel::jointStateToArray(const sensor_msgs::JointState &joint_state, Eigen::MatrixXd::RowXpr joint_array)
00350 {
00351 for(unsigned int i=0; i < joint_state.name.size(); i++)
00352 {
00353 std::string name = joint_state.name[i];
00354 int kdl_number = urdfNameToKdlNumber(name);
00355 if (kdl_number>=0)
00356 joint_array(kdl_number) = joint_state.position[i];
00357 }
00358 }
00359
00360
00361 inline double ChompRobotModel::getMaxRadiusClearance() const
00362 {
00363 return max_radius_clearance_;
00364 }
00365
00366
00367 }
00368 #endif