hrplib/hrpModel/World.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, AIST, the University of Tokyo and General Robotix Inc.
3  * All rights reserved. This program is made available under the terms of the
4  * Eclipse Public License v1.0 which accompanies this distribution, and is
5  * available at http://www.eclipse.org/legal/epl-v10.html
6  * Contributors:
7  * National Institute of Advanced Industrial Science and Technology (AIST)
8  */
13 #ifndef OPENHRP_WORLD_H_INCLUDED
14 #define OPENHRP_WORLD_H_INCLUDED
15 
16 #include <vector>
17 #include <map>
18 #include <boost/shared_ptr.hpp>
19 #include <boost/intrusive_ptr.hpp>
20 #include <hrpUtil/Eigen3d.h>
21 #include "Body.h"
22 #include "ForwardDynamics.h"
23 #include "Config.h"
24 
25 namespace OpenHRP {
26  class CollisionSequence;
27 }
28 
29 namespace hrp {
30 
31  class Link;
32  class RangeSensor;
33 
34  class HRPMODEL_API WorldBase
35  {
36  public:
37  WorldBase();
38  virtual ~WorldBase();
39 
44  unsigned int numBodies() { return bodyInfoArray.size(); }
45 
51  BodyPtr body(int index);
52 
58  BodyPtr body(const std::string& name);
59 
66  return bodyInfoArray[index].forwardDynamics;
67  }
68 
74  int bodyIndex(const std::string& name);
75 
82  int addBody(BodyPtr body);
83 
87  void clearBodies();
88 
92  void clearCollisionPairs();
93 
98  void setTimeStep(double dt);
99 
104  double timeStep(void) const { return timeStep_; }
105 
110  void setCurrentTime(double tm);
111 
116  double currentTime(void) const { return currentTime_; }
117 
122  void setGravityAcceleration(const Vector3& g);
123 
128  const Vector3& getGravityAcceleration() { return g; }
129 
135  void enableSensors(bool on);
136 
140  void setEulerMethod();
141 
145  void setRungeKuttaMethod();
146 
150  virtual void initialize();
151 
155  virtual void calcNextState();
156 
163  std::pair<int,bool> getIndexOfLinkPairs(Link* link1, Link* link2);
164 
165  protected:
166 
167  double currentTime_;
168  double timeStep_;
169 
170  struct BodyInfo {
173  };
174  std::vector<BodyInfo> bodyInfoArray;
175 
177 
178  private:
179  void updateRangeSensors();
180  void updateRangeSensor(RangeSensor *sensor);
181 
182  typedef std::map<std::string, int> NameToIndexMap;
183  NameToIndexMap nameToBodyIndexMap;
184 
185  typedef std::map<BodyPtr, int> BodyToIndexMap;
186  BodyToIndexMap bodyToIndexMap;
187 
188  struct LinkPairKey {
191  bool operator<(const LinkPairKey& pair2) const;
192  };
193  typedef std::map<LinkPairKey, int> LinkPairKeyToIndexMap;
194  LinkPairKeyToIndexMap linkPairKeyToIndexMap;
195 
197 
199 
200  bool isEulerMethod; // Euler or Runge Kutta ?
201 
202  };
203 
204 
205  template <class TConstraintForceSolver> class World : public WorldBase
206  {
207  public:
208  TConstraintForceSolver constraintForceSolver;
209 
210  World() : constraintForceSolver(*this) { }
211 
212  virtual void initialize() {
213  WorldBase::initialize();
214  constraintForceSolver.initialize();
215  }
216 
217  virtual void calcNextState(OpenHRP::CollisionSequence& corbaCollisionSequence) {
218  constraintForceSolver.solve(corbaCollisionSequence);
219  WorldBase::calcNextState();
220  }
221  };
222 
223 };
224 
225 #endif
LinkPairKeyToIndexMap linkPairKeyToIndexMap
boost::shared_ptr< ForwardDynamics > ForwardDynamicsPtr
ForwardDynamicsPtr forwardDynamics
double timeStep(void) const
get time step
virtual void initialize()
initialize this world. This must be called after all bodies are registered.
const Vector3 & getGravityAcceleration()
get gravity acceleration
bool operator<(const EchoSample &, const EchoSample &)
png_infop png_charpp name
Definition: png.h:2382
std::map< LinkPairKey, int > LinkPairKeyToIndexMap
boost::shared_ptr< Body > BodyPtr
Definition: Body.h:315
Eigen::Vector3d Vector3
Definition: EigenTypes.h:11
std::map< BodyPtr, int > BodyToIndexMap
ForwardDynamicsPtr forwardDynamics(int index)
get forward dynamics computation method for body
list index
BodyToIndexMap bodyToIndexMap
NameToIndexMap nameToBodyIndexMap
virtual void calcNextState(OpenHRP::CollisionSequence &corbaCollisionSequence)
TConstraintForceSolver constraintForceSolver
double currentTime(void) const
get current time
std::map< std::string, int > NameToIndexMap
unsigned int numBodies()
get the number of bodies in this world
std::vector< BodyInfo > bodyInfoArray


openhrp3
Author(s): AIST, General Robotix Inc., Nakamura Lab of Dept. of Mechano Informatics at University of Tokyo
autogenerated on Sat May 8 2021 02:42:41