RigidBodyGeometry.h
1 /*********************************************************************
2 * Rice University Software Distribution License
3 *
4 * Copyright (c) 2010, Rice University
5 * All Rights Reserved.
6 *
7 * For a full description see the file named LICENSE.
8 *
9 *********************************************************************/
10 
11 /* Author: Ioan Sucan */
12 
13 #ifndef OMPLAPP_GEOMETRY_RIGID_BODY_GEOMETRY_
14 #define OMPLAPP_GEOMETRY_RIGID_BODY_GEOMETRY_
15 
16 #include "omplapp/config.h"
17 #include "omplapp/geometry/GeometrySpecification.h"
18 #include <ompl/base/SpaceInformation.h>
19 #include <ompl/base/spaces/RealVectorBounds.h>
20 #include <memory>
21 #include <assimp/scene.h>
22 #include <assimp/Importer.hpp>
23 #include <boost/filesystem.hpp>
24 #include <string>
25 #include <vector>
26 
27 namespace ompl
28 {
29 
31  namespace app
32  {
34  enum CollisionChecker
35  { PQP, FCL };
36 
37  class RigidBodyGeometry
38  {
39  public:
40 
42  explicit
45  RigidBodyGeometry(MotionModel mtype, CollisionChecker ctype) : mtype_(mtype), factor_(1.0), add_(0.0), ctype_(ctype)
46  {
47  }
48 
52  explicit
53  RigidBodyGeometry(MotionModel mtype) : mtype_(mtype), factor_(1.0), add_(0.0), ctype_(FCL)
54  {
55  }
56 
57  virtual ~RigidBodyGeometry() = default;
58 
59  MotionModel getMotionModel() const
60  {
61  return mtype_;
62  }
63 
64  CollisionChecker getCollisionCheckerType() const
65  {
66  return ctype_;
67  }
68 
69  bool hasEnvironment() const
70  {
71  return !importerEnv_.empty();
72  }
73 
74  bool hasRobot() const
75  {
76  return !importerRobot_.empty();
77  }
78 
79  unsigned int getLoadedRobotCount() const
80  {
81  return importerRobot_.size();
82  }
83 
85  aiVector3D getRobotCenter(unsigned int robotIndex) const;
86 
90  virtual bool setEnvironmentMesh(const std::string &env);
91 
95  virtual bool addEnvironmentMesh(const std::string &env);
96 
99  virtual bool setRobotMesh(const std::string &robot);
100 
103  virtual bool addRobotMesh(const std::string &robot);
104 
106  virtual void setStateValidityCheckerType (CollisionChecker ctype);
107 
109  const base::StateValidityCheckerPtr& allocStateValidityChecker(const base::SpaceInformationPtr &si, const GeometricStateExtractor &se, bool selfCollision);
110 
111  const GeometrySpecification& getGeometrySpecification() const;
112 
117  void setBoundsFactor(double factor)
118  {
119  factor_ = factor;
120  }
121 
123  double getBoundsFactor() const
124  {
125  return factor_;
126  }
127 
132  void setBoundsAddition(double add)
133  {
134  add_ = add;
135  }
136 
138  double getBoundsAddition() const
139  {
140  return add_;
141  }
142 
148 
150  void setMeshPath(const std::vector<boost::filesystem::path>& path)
151  {
152  for (const auto &p : path)
153  if (!boost::filesystem::is_directory(p))
154  OMPL_WARN("Mesh path '%s' is not an existing directory", p.c_str());
155  meshPath_ = path;
156  }
157 
158  protected:
160  boost::filesystem::path findMeshFile(const std::string& fname);
161 
162  void computeGeometrySpecification();
163 
164  MotionModel mtype_;
165 
167  double factor_;
168 
170  double add_;
171 
173  std::vector< std::shared_ptr<Assimp::Importer> > importerEnv_;
174 
176  std::vector< std::shared_ptr<Assimp::Importer> > importerRobot_;
177 
180 
182  base::StateValidityCheckerPtr validitySvc_;
183 
186 
189  std::vector<boost::filesystem::path> meshPath_{OMPLAPP_RESOURCE_DIR};
190 
191  };
192 
193  }
194 }
195 
196 #endif
void setBoundsAddition(double add)
The bounds of the environment are inferred based on the axis-aligned bounding box for the objects in ...
RigidBodyGeometry(MotionModel mtype, CollisionChecker ctype)
Constructor expects a state space that can represent a rigid body.
virtual void setStateValidityCheckerType(CollisionChecker ctype)
Change the type of collision checking for the rigid body.
MotionModel
Specify whether bodies are moving in 2D or bodies moving in 3D.
virtual bool setRobotMesh(const std::string &robot)
This function specifies the name of the CAD file representing the robot (robot). Returns 1 on success...
virtual bool setEnvironmentMesh(const std::string &env)
This function specifies the name of the CAD file representing the environment (env)....
std::vector< std::shared_ptr< Assimp::Importer > > importerEnv_
Instance of assimp importer used to load environment.
void setBoundsFactor(double factor)
The bounds of the environment are inferred based on the axis-aligned bounding box for the objects in ...
virtual bool addRobotMesh(const std::string &robot)
This function specifies the name of the CAD file representing a part of the robot (robot)....
CollisionChecker
Enumeration of the possible collision checker types.
std::vector< boost::filesystem::path > meshPath_
Paths to search for mesh files if mesh file names do not correspond to absolute paths.
aiVector3D getRobotCenter(unsigned int robotIndex) const
Get the robot's center (average of all the vertices of all its parts)
std::vector< std::shared_ptr< Assimp::Importer > > importerRobot_
Instance of assimp importer used to load robot.
virtual bool addEnvironmentMesh(const std::string &env)
This function specifies the name of the CAD file representing a part of the environment (env)....
double getBoundsAddition() const
Get the data set by setBoundsAddition()
double getBoundsFactor() const
Get the data set by setBoundsFactor()
#define OMPL_WARN(fmt,...)
Log a formatted warning string.
Definition: Console.h:66
void setMeshPath(const std::vector< boost::filesystem::path > &path)
set path to search for mesh files
base::StateValidityCheckerPtr validitySvc_
Instance of the state validity checker for collision checking.
GeometrySpecification geom_
Object containing mesh data for robot and environment.
const base::StateValidityCheckerPtr & allocStateValidityChecker(const base::SpaceInformationPtr &si, const GeometricStateExtractor &se, bool selfCollision)
Allocate default state validity checker using FCL.
boost::filesystem::path findMeshFile(const std::string &fname)
return absolute path to mesh file if it exists and an empty path otherwise
base::RealVectorBounds inferEnvironmentBounds() const
Given the representation of an environment, infer its bounds. The bounds will be 2-dimensional when p...
CollisionChecker ctype_
Value containing the type of collision checking to use.
double factor_
The factor to multiply inferred environment bounds by (default 1)
double add_
The value to add to inferred environment bounds (default 0)
Main namespace. Contains everything in this library.
Definition: AppBase.h:21
The lower and upper bounds for an Rn space.