DART  6.10.1
Body.hpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2011-2021, The DART development contributors
3  * All rights reserved.
4  *
5  * The list of contributors can be found at:
6  * https://github.com/dartsim/dart/blob/master/LICENSE
7  *
8  * This file is provided under the following "BSD-style" License:
9  * Redistribution and use in source and binary forms, with or
10  * without modification, are permitted provided that the following
11  * conditions are met:
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
19  * CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
20  * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
21  * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
22  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
23  * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
24  * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
25  * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF
26  * USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  */
32 
33 #ifndef DART_UTILS_MJCF_DETAIL_BODY_HPP_
34 #define DART_UTILS_MJCF_DETAIL_BODY_HPP_
35 
36 #include <tinyxml2.h>
37 
45 
46 namespace dart {
47 namespace utils {
48 namespace MjcfParser {
49 namespace detail {
50 
51 class Size;
52 
53 class Body final
54 {
55 public:
57  Body() = default;
58 
60 
62  const std::string& getName() const;
63 
65  bool getMocap() const;
66 
68  void setRelativeTransform(const Eigen::Isometry3d& tf);
69 
71  const Eigen::Isometry3d& getRelativeTransform() const;
72 
74  void setWorldTransform(const Eigen::Isometry3d& tf);
75 
77  const Eigen::Isometry3d& getWorldTransform() const;
78 
80 
82 
88  const Inertial& getInertial() const;
89 
91  std::size_t getNumJoints() const;
92 
94  const Joint& getJoint(std::size_t index) const;
95 
97  std::size_t getNumChildBodies() const;
98 
100  const Body& getChildBody(std::size_t index) const;
101 
103  std::size_t getNumGeoms() const;
104 
106  const Geom& getGeom(std::size_t index) const;
107 
109  std::size_t getNumSites() const;
110 
112  const Site& getSite(std::size_t index) const;
113 
115 
116 private:
117  // Private members used by Worldbody class
118  friend class Worldbody;
119  Errors read(
120  tinyxml2::XMLElement* element,
121  const common::optional<Size>& size,
122  const Defaults& defaults,
123  const Default* currentDefault);
124 
126  Errors preprocess(const Compiler& compiler);
127 
130  Errors compile(const Compiler& compiler);
131 
133  Errors postprocess(const Body* body, const Compiler& compiler);
134 
135 private:
137  const std::vector<Geom>& geoms, const Compiler& compiler);
138 
140 
142  std::string mName{""};
143 
145  bool mMocap{false};
146 
147  Eigen::Isometry3d mRelativeTransform{Eigen::Isometry3d::Identity()};
148 
149  Eigen::Isometry3d mWorldTransform{Eigen::Isometry3d::Identity()};
150 
151  Eigen::VectorXd mUser;
152 
154 
155  std::vector<Joint> mJoints;
156  std::vector<Body> mChildBodies;
157  std::vector<Geom> mGeoms;
158  std::vector<Site> mSites;
159 };
160 
161 } // namespace detail
162 } // namespace MjcfParser
163 } // namespace utils
164 } // namespace dart
165 
166 #endif // #ifndef DART_UTILS_MJCF_DETAIL_BODY_HPP_
std::size_t index
Definition: SkelParser.cpp:1672
std::size_t getNumJoints() const
Returns the number of <joint> elements.
Definition: Body.cpp:352
Eigen::Isometry3d mWorldTransform
Definition: Body.hpp:149
const Eigen::Isometry3d & getWorldTransform() const
Returns the world transform of this <body>.
Definition: Body.cpp:420
bool mMocap
If this attribute is "true", the body is labeled as a mocap body.
Definition: Body.hpp:145
std::size_t getNumSites() const
Returns the number of <site> elements.
Definition: Body.cpp:388
Errors compile(const Compiler &compiler)
Updates attributes and elements that require the preprocessed child elements of this <body>.
Definition: Body.cpp:186
std::size_t getNumChildBodies() const
Returns the number of child <body> elements.
Definition: Body.cpp:364
std::vector< Body > mChildBodies
Definition: Body.hpp:156
const Body & getChildBody(std::size_t index) const
Returns a child <body> element at index.
Definition: Body.cpp:370
const Geom & getGeom(std::size_t index) const
Returns a <geom> element at index.
Definition: Body.cpp:382
const Site & getSite(std::size_t index) const
Returns a <site> element at index.
Definition: Body.cpp:394
const Joint & getJoint(std::size_t index) const
Returns a <joint> element at index.
Definition: Body.cpp:358
Eigen::Isometry3d mRelativeTransform
Definition: Body.hpp:147
std::string mName
Name of the body.
Definition: Body.hpp:142
std::vector< Joint > mJoints
Definition: Body.hpp:155
BodyAttributes mAttributes
Definition: Body.hpp:139
Eigen::VectorXd mUser
Definition: Body.hpp:151
Inertial mInertial
Definition: Body.hpp:153
const std::string & getName() const
Returns 'name' attribute.
Definition: Body.cpp:334
const Eigen::Isometry3d & getRelativeTransform() const
Returns the transform relative to the parent <body> or <worldbody>.
Definition: Body.cpp:407
std::vector< Site > mSites
Definition: Body.hpp:158
bool getMocap() const
Returns 'mocap' attribute.
Definition: Body.cpp:340
void setWorldTransform(const Eigen::Isometry3d &tf)
Sets the world transform of this <body>.
Definition: Body.cpp:413
Body()=default
Default constructor.
std::size_t getNumGeoms() const
Returns the number of <geom> elements.
Definition: Body.cpp:376
Errors read(tinyxml2::XMLElement *element, const common::optional< Size > &size, const Defaults &defaults, const Default *currentDefault)
Definition: Body.cpp:47
Errors postprocess(const Body *body, const Compiler &compiler)
Updates attributes and elements that require the compiled parent element.
Definition: Body.cpp:245
Errors preprocess(const Compiler &compiler)
Updates attributes and elements that doesn't require any other elements.
Definition: Body.cpp:141
std::vector< Geom > mGeoms
Definition: Body.hpp:157
void setRelativeTransform(const Eigen::Isometry3d &tf)
Sets the transform relative to the parent <body> or <worldbody>.
Definition: Body.cpp:400
const Inertial & getInertial() const
Returns <inertial> element.
Definition: Body.cpp:346
Inertial computeInertialFromGeoms(const std::vector< Geom > &geoms, const Compiler &compiler)
Definition: Body.cpp:426
Definition: Worldbody.hpp:54
boost::optional< T > optional
Definition: Optional.hpp:50
std::vector< Error > Errors
Definition: Error.hpp:85
Definition: BulletCollisionDetector.cpp:65
Intermediate raw data read from the XML file.
Definition: BodyAttributes.hpp:56