$search
00001 /* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2008, 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 Willow Garage, Inc. 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 COLLISION_SPACE_CCD_ENVIRONMENT_MODEL_H 00038 #define COLLISION_SPACE_CCD_ENVIRONMENT_MODEL_H 00039 00040 #include "collision_space_ccd/environment_objects.h" 00041 #include <planning_models/kinematic_model.h> 00042 #include <planning_models/kinematic_state.h> 00043 #include <geometric_shapes/bodies.h> 00044 #include <LinearMath/btVector3.h> 00045 #include <boost/thread/recursive_mutex.hpp> 00046 #include <boost/shared_ptr.hpp> 00047 #include <vector> 00048 #include <string> 00049 00050 00052 namespace collision_space_ccd 00053 { 00054 00061 class EnvironmentModel 00062 { 00063 public: 00064 00065 enum BodyType { 00066 LINK, 00067 ATTACHED, 00068 OBJECT 00069 }; 00070 00072 struct Contact 00073 { 00075 btVector3 pos; 00077 btVector3 normal; 00079 double depth; 00080 00082 std::string body_name_1; 00083 BodyType body_type_1; 00084 00086 std::string body_name_2; 00087 BodyType body_type_2; 00088 }; 00089 00091 struct AllowedContact 00092 { 00094 boost::shared_ptr<bodies::Body> bound; 00095 00097 std::vector<std::string> links; 00098 00100 double depth; 00101 }; 00102 00104 /* False means that no collisions are allowed, true means ok */ 00105 class AllowedCollisionMatrix 00106 { 00107 public: 00108 00109 AllowedCollisionMatrix(){ 00110 valid_ = true; 00111 } 00112 00113 AllowedCollisionMatrix(const std::vector<std::string>& names, 00114 bool allowed = false); 00115 00116 AllowedCollisionMatrix(const std::vector<std::vector<bool> >& all_coll_vectors, 00117 const std::map<std::string, unsigned int>& all_coll_indices); 00118 00119 AllowedCollisionMatrix(const AllowedCollisionMatrix& acm); 00120 00121 bool getAllowedCollision(const std::string& name1, const std::string& name2, 00122 bool& allowed_collision) const; 00123 00124 bool getAllowedCollision(unsigned int i, unsigned int j, 00125 bool& allowed_collision) const; 00126 00127 bool hasEntry(const std::string& name) const; 00128 00129 bool getEntryIndex(const std::string& name, 00130 unsigned int& index) const; 00131 00132 bool getEntryName(const unsigned int ind, 00133 std::string& name) const; 00134 00135 bool removeEntry(const std::string& name); 00136 00137 bool addEntry(const std::string& name, bool allowed); 00138 00139 bool changeEntry(bool allowed); 00140 00141 bool changeEntry(const std::string& name, bool allowed); 00142 00143 bool changeEntry(const std::string& name1, 00144 const std::string& name2, 00145 bool allowed); 00146 00147 bool changeEntry(const unsigned int ind_1, 00148 const unsigned int ind_2, 00149 bool allowed); 00150 00151 bool changeEntry(const std::string& name, 00152 const std::vector<std::string>& change_names, 00153 bool allowed); 00154 00155 bool changeEntry(const std::vector<std::string>& change_names_1, 00156 const std::vector<std::string>& change_names_2, 00157 bool allowed); 00158 00159 bool getValid() const { 00160 return valid_; 00161 }; 00162 00163 unsigned int getSize() const { 00164 return allowed_entries_.size(); 00165 } 00166 00167 typedef boost::bimap<std::string, unsigned int> entry_type; 00168 00169 const entry_type& getEntriesBimap() const { 00170 return allowed_entries_bimap_; 00171 } 00172 00173 private: 00174 00175 bool valid_; 00176 std::vector<std::vector<bool> > allowed_entries_; 00177 00178 entry_type allowed_entries_bimap_; 00179 }; 00180 00181 EnvironmentModel(void) 00182 { 00183 verbose_ = false; 00184 objects_ = new EnvironmentObjects(); 00185 use_altered_collision_matrix_ = false; 00186 } 00187 00188 virtual ~EnvironmentModel(void) 00189 { 00190 if (objects_) 00191 delete objects_; 00192 } 00193 00194 /**********************************************************************/ 00195 /* Collision Environment Configuration */ 00196 /**********************************************************************/ 00197 00204 virtual void setRobotModel(const planning_models::KinematicModel* model, 00205 const AllowedCollisionMatrix& acm, 00206 const std::map<std::string, double>& link_padding_map, 00207 double default_padding = 0.0, 00208 double scale = 1.0); 00209 00211 double getRobotScale(void) const; 00212 00214 double getRobotPadding(void) const; 00215 00217 virtual void updateRobotModel(const planning_models::KinematicState* state) = 0; 00218 00220 virtual void updateAttachedBodies() = 0; 00221 00223 const planning_models::KinematicModel* getRobotModel(void) const; 00224 00225 /**********************************************************************/ 00226 /* Collision Checking Routines */ 00227 /**********************************************************************/ 00228 00229 00231 virtual bool isCollision(void) const = 0; 00232 00234 virtual bool isSelfCollision(void) const = 0; 00235 00237 virtual bool isEnvironmentCollision(void) const = 0; 00238 00240 virtual bool getCollisionContacts(const std::vector<AllowedContact> &allowedContacts, std::vector<Contact> &contacts, unsigned int max_count = 1) const = 0; 00241 00243 virtual bool getAllCollisionContacts(const std::vector<AllowedContact> &allowedContacts, std::vector<Contact> &contacts, unsigned int num_per_contact = 1) const = 0; 00244 00245 bool getCollisionContacts(std::vector<Contact> &contacts, unsigned int max_count = 1) const; 00246 00247 /**********************************************************************/ 00248 /* Collision Bodies */ 00249 /**********************************************************************/ 00250 00252 virtual void clearObjects(void) = 0; 00253 00255 virtual void clearObjects(const std::string &ns) = 0; 00256 00258 virtual bool hasObject(const std::string& ns) const = 0; 00259 00261 virtual void addObject(const std::string &ns, shapes::StaticShape *shape) = 0; 00262 00264 virtual void addObject(const std::string &ns, shapes::Shape* shape, const btTransform &pose) = 0; 00265 00267 virtual void addObjects(const std::string &ns, const std::vector<shapes::Shape*> &shapes, const std::vector<btTransform> &poses) = 0; 00268 00269 virtual void getAttachedBodyPoses(std::map<std::string, std::vector<btTransform> >& pose_map) const = 0; 00270 00272 virtual void setAlteredLinkPadding(const std::map<std::string, double>& link_padding_map); 00273 00275 virtual void revertAlteredLinkPadding(); 00276 00277 const std::map<std::string,double>& getDefaultLinkPaddingMap() const; 00278 00279 std::map<std::string,double> getCurrentLinkPaddingMap() const; 00280 00281 double getCurrentLinkPadding(std::string name) const; 00282 00284 const EnvironmentObjects* getObjects(void) const; 00285 00286 const AllowedCollisionMatrix& getDefaultAllowedCollisionMatrix() const; 00287 00288 const AllowedCollisionMatrix& getCurrentAllowedCollisionMatrix() const; 00289 00291 virtual void setAlteredCollisionMatrix(const AllowedCollisionMatrix& acm); 00292 00294 virtual void revertAlteredCollisionMatrix(); 00295 00296 /**********************************************************************/ 00297 /* Miscellaneous Routines */ 00298 /**********************************************************************/ 00299 00301 void lock(void) const; 00302 00304 void unlock(void) const; 00305 00307 void setVerbose(bool verbose); 00308 00310 bool getVerbose(void) const; 00311 00313 virtual EnvironmentModel* clone(void) const = 0; 00314 00315 protected: 00316 00318 mutable boost::recursive_mutex lock_; 00319 00321 bool verbose_; 00322 00324 const planning_models::KinematicModel* robot_model_; 00325 00327 EnvironmentObjects *objects_; 00328 00330 double robot_scale_; 00331 00333 double default_robot_padding_; 00334 00335 AllowedCollisionMatrix default_collision_matrix_; 00336 AllowedCollisionMatrix altered_collision_matrix_; 00337 00338 bool use_altered_collision_matrix_; 00339 00340 std::map<std::string, double> default_link_padding_map_; 00341 std::map<std::string, double> altered_link_padding_map_; 00342 00343 bool use_altered_link_padding_map_; 00344 00345 }; 00346 } 00347 00348 #endif 00349