DART 6.10.1
Loading...
Searching...
No Matches
Geom.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_GEOM_HPP_
34#define DART_UTILS_MJCF_DETAIL_GEOM_HPP_
35
36#include <tinyxml2.h>
37
43
44namespace dart {
45namespace utils {
46namespace MjcfParser {
47namespace detail {
48
49class Body;
50
51class Geom final
52{
53public:
55 Geom() = default;
56
58
59 const std::string& getName() const;
60 GeomType getType() const;
61 int getConType() const;
62 int getConAffinity() const;
63 int getConDim() const;
64 int getGroup() const;
65 int getPriority() const;
66
67 const Eigen::Vector3d& getSize() const;
68
69 Eigen::Vector2d getPlaneHalfSize() const;
70
71 double getSphereRadius() const;
72
73 double getCapsuleRadius() const;
74 double getCapsuleHalfLength() const;
75 double getCapsuleLength() const;
76
77 const Eigen::Vector3d& getEllipsoidRadii() const;
78 Eigen::Vector3d getEllipsoidDiameters() const;
79
80 double getCylinderRadius() const;
81 double getCylinderHalfLength() const;
82 double getCylinderLength() const;
83
84 const Eigen::Vector3d& getBoxHalfSize() const;
85 Eigen::Vector3d getBoxSize() const;
86
87 const Eigen::Vector4d& getRGBA() const;
88 const Eigen::Vector3d& getFriction() const;
89
90 double getMass() const;
91 double getDensity() const;
92 double getVolume() const;
93 const Eigen::Matrix3d& getInertia() const;
94
95 double getSolMix() const;
96 double getMargine() const;
97 double getGap() const;
98
99 void setRelativeTransform(const Eigen::Isometry3d& tf);
100 const Eigen::Isometry3d& getRelativeTransform() const;
101
102 void setWorldTransform(const Eigen::Isometry3d& tf);
103 const Eigen::Isometry3d& getWorldTransform() const;
104
105 const std::string& getHField() const;
106 const std::string& getMesh() const;
107
109
110private:
111 // Private members used by Body and WorldBody class
112 friend class Body;
113 friend class Worldbody;
114 Errors read(
115 tinyxml2::XMLElement* element,
116 const Defaults& defaults,
117 const GeomAttributes& defaultAttributes);
118
120 Errors preprocess(const Compiler& compiler);
121
124 Errors compile(const Compiler& compiler);
125
127 Errors postprocess(const Body* body, const Compiler& compiler);
128
129private:
130 double computeVolume() const;
131 Eigen::Matrix3d computeInertia() const;
132
134
136 std::string mName{""};
137
140
141 int mConType{1};
142
144
145 int mConDim{3};
146
147 int mGroup{0};
148
149 int mPriority{0};
150
152 Eigen::Vector3d mSize{Eigen::Vector3d::Zero()};
153
154 Eigen::Vector4d mRGBA{Eigen::Vector4d(0.5, 0.5, 0.5, 1)};
155
156 Eigen::Vector3d mFriction{Eigen::Vector3d(1, 0.005, 0.0001)};
157
158 double mMass;
159
161 double mDensity{1000};
162
163 double mVolume{0};
164
165 Eigen::Matrix3d mInertia{Eigen::Matrix3d::Identity()};
166
169 double mSolMix{1};
170
173 double mMargin{0};
174
178 double mGap{0};
179
180 Eigen::Isometry3d mRelativeTransform{Eigen::Isometry3d::Identity()};
181
182 Eigen::Isometry3d mWorldTransform{Eigen::Isometry3d::Identity()};
183
184 std::string mHField;
185 std::string mMesh;
186
187 double mFitScale{1};
188};
189
190} // namespace detail
191} // namespace MjcfParser
192} // namespace utils
193} // namespace dart
194
195#endif // #ifndef DART_UTILS_MJCF_DETAIL_GEOM_HPP_
int getConDim() const
Definition Geom.cpp:372
double mGap
This attribute is used to enable the generation of inactive contacts, i.e.
Definition Geom.hpp:178
double getCapsuleLength() const
Definition Geom.cpp:420
Eigen::Vector3d getEllipsoidDiameters() const
Definition Geom.cpp:432
const Eigen::Isometry3d & getWorldTransform() const
Definition Geom.cpp:552
void setRelativeTransform(const Eigen::Isometry3d &tf)
Definition Geom.cpp:534
double getGap() const
Definition Geom.cpp:516
Eigen::Vector3d getBoxSize() const
Definition Geom.cpp:462
Eigen::Isometry3d mRelativeTransform
Definition Geom.hpp:180
Eigen::Vector4d mRGBA
Definition Geom.hpp:154
const Eigen::Isometry3d & getRelativeTransform() const
Definition Geom.cpp:540
Errors postprocess(const Body *body, const Compiler &compiler)
Updates attributes and elements that require the compiled parent element.
Definition Geom.cpp:316
double getMargine() const
Definition Geom.cpp:510
double mVolume
Definition Geom.hpp:163
double getCylinderRadius() const
Definition Geom.cpp:438
Errors read(tinyxml2::XMLElement *element, const Defaults &defaults, const GeomAttributes &defaultAttributes)
Definition Geom.cpp:50
Eigen::Vector3d mFriction
Definition Geom.hpp:156
const std::string & getHField() const
Definition Geom.cpp:522
GeomType getType() const
Definition Geom.cpp:354
const std::string & getName() const
Definition Geom.cpp:348
int mPriority
Definition Geom.hpp:149
double getCapsuleRadius() const
Definition Geom.cpp:408
GeomType mType
Type of geometric shape.
Definition Geom.hpp:139
double mFitScale
Definition Geom.hpp:187
const Eigen::Vector3d & getBoxHalfSize() const
Definition Geom.cpp:456
Eigen::Isometry3d mWorldTransform
Definition Geom.hpp:182
const Eigen::Vector4d & getRGBA() const
Definition Geom.cpp:468
double mMass
Definition Geom.hpp:158
const Eigen::Vector3d & getFriction() const
Definition Geom.cpp:474
const Eigen::Vector3d & getSize() const
Definition Geom.cpp:390
double getSolMix() const
Definition Geom.cpp:504
int getPriority() const
Definition Geom.cpp:384
const std::string & getMesh() const
Definition Geom.cpp:528
int mGroup
Definition Geom.hpp:147
double getVolume() const
Definition Geom.cpp:492
int mConDim
Definition Geom.hpp:145
std::string mMesh
Definition Geom.hpp:185
int getConType() const
Definition Geom.cpp:360
double getMass() const
Definition Geom.cpp:480
Errors preprocess(const Compiler &compiler)
Updates attributes and elements that doesn't require any other elements.
Definition Geom.cpp:113
const Eigen::Vector3d & getEllipsoidRadii() const
Definition Geom.cpp:426
Errors compile(const Compiler &compiler)
Updates attributes and elements that require the preprocessed child elements of this <geom>.
Definition Geom.cpp:309
int getConAffinity() const
Definition Geom.cpp:366
double getCapsuleHalfLength() const
Definition Geom.cpp:414
double getCylinderHalfLength() const
Definition Geom.cpp:444
double mMargin
Distance threshold below which contacts are detected and included in the global array mjData....
Definition Geom.hpp:173
Eigen::Matrix3d mInertia
Definition Geom.hpp:165
double mSolMix
Weight used for averaging of contact parameters, and interacts with the priority attribute.
Definition Geom.hpp:169
double getSphereRadius() const
Definition Geom.cpp:402
int getGroup() const
Definition Geom.cpp:378
Eigen::Vector3d mSize
Geom size parameters.
Definition Geom.hpp:152
double getDensity() const
Definition Geom.cpp:486
int mConAffinity
Definition Geom.hpp:143
GeomAttributes mAttributes
Definition Geom.hpp:133
void setWorldTransform(const Eigen::Isometry3d &tf)
Definition Geom.cpp:546
std::string mHField
Definition Geom.hpp:184
double mDensity
Material density used to compute the geom mass and inertia.
Definition Geom.hpp:161
std::string mName
Name of the geom.
Definition Geom.hpp:136
Eigen::Matrix3d computeInertia() const
Definition Geom.cpp:583
const Eigen::Matrix3d & getInertia() const
Definition Geom.cpp:498
Eigen::Vector2d getPlaneHalfSize() const
Definition Geom.cpp:396
double computeVolume() const
Definition Geom.cpp:558
double getCylinderLength() const
Definition Geom.cpp:450
int mConType
Definition Geom.hpp:141
Geom()=default
Default constructor.
GeomType
Definition Types.hpp:119
std::vector< Error > Errors
Definition Error.hpp:85
Definition BulletCollisionDetector.cpp:65
Intermediate raw data read from the XML file.
Definition GeomAttributes.hpp:53