DART  6.10.1
GeomAttributes.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_GEOMATTRIBUTES_HPP_
34 #define DART_UTILS_MJCF_DETAIL_GEOMATTRIBUTES_HPP_
35 
36 #include <Eigen/Core>
37 
38 #include <tinyxml2.h>
39 
40 #include "dart/common/Optional.hpp"
41 #include "dart/math/MathTypes.hpp"
44 
45 namespace dart {
46 namespace utils {
47 namespace MjcfParser {
48 namespace detail {
49 
52 struct GeomAttributes final
53 {
56 
59 
60  int mConType{1};
61 
62  int mConAffinity{1};
63 
64  int mConDim{3};
65 
66  int mGroup{0};
67 
68  int mPriority{0};
69 
71  Eigen::Vector3d mSize{Eigen::Vector3d::Zero()};
72 
73  Eigen::Vector4d mRGBA{Eigen::Vector4d(0.5, 0.5, 0.5, 1)};
74 
75  Eigen::Vector3d mFriction{Eigen::Vector3d(1, 0.005, 0.0001)};
76 
79 
81  double mDensity{1000};
82 
85  double mSolMix{1};
86 
89  double mMargin{0};
90 
94  double mGap{0};
95 
100 
103  Eigen::Vector3d mPos{Eigen::Vector3d::Zero()};
104 
106  Eigen::Quaterniond mQuat{Eigen::Quaterniond::Identity()};
107 
112 
115 
121 
124 
126 
128 
129  double mFitScale{1};
130 };
131 
133  GeomAttributes& attributes, tinyxml2::XMLElement* element);
134 
135 } // namespace detail
136 } // namespace MjcfParser
137 } // namespace utils
138 } // namespace dart
139 
140 #endif // #ifndef DART_UTILS_MJCF_DETAIL_GEOMATTRIBUTES_HPP_
boost::optional< T > optional
Definition: Optional.hpp:50
GeomType
Definition: Types.hpp:119
Errors appendGeomAttributes(GeomAttributes &attributes, tinyxml2::XMLElement *element)
Definition: GeomAttributes.cpp:44
std::vector< Error > Errors
Definition: Error.hpp:85
Definition: BulletCollisionDetector.cpp:65
Intermediate raw data read from the XML file.
Definition: GeomAttributes.hpp:53
common::optional< Eigen::Vector4d > mAxisAngle
These are the quantities (x, y, z, a) mentioned above.
Definition: GeomAttributes.hpp:111
double mSolMix
Weight used for averaging of contact parameters, and interacts with the priority attribute.
Definition: GeomAttributes.hpp:85
double mDensity
Material density used to compute the geom mass and inertia.
Definition: GeomAttributes.hpp:81
int mConType
Definition: GeomAttributes.hpp:60
double mGap
This attribute is used to enable the generation of inactive contacts, i.e.
Definition: GeomAttributes.hpp:94
common::optional< Eigen::Vector6d > mXYAxes
The first 3 numbers are the X axis of the frame.
Definition: GeomAttributes.hpp:120
int mConDim
Definition: GeomAttributes.hpp:64
common::optional< Eigen::Vector3d > mEuler
Rotation angles around three coordinate axes.
Definition: GeomAttributes.hpp:114
common::optional< std::string > mHField
Definition: GeomAttributes.hpp:125
common::optional< std::string > mName
Name of the geom.
Definition: GeomAttributes.hpp:55
Eigen::Vector3d mPos
Position of the geom frame, in local or global coordinates as determined by the coordinate attribute ...
Definition: GeomAttributes.hpp:103
common::optional< double > mMass
Mass.
Definition: GeomAttributes.hpp:78
int mConAffinity
Definition: GeomAttributes.hpp:62
Eigen::Vector4d mRGBA
Definition: GeomAttributes.hpp:73
GeomType mType
Type of geometric shape.
Definition: GeomAttributes.hpp:58
Eigen::Vector3d mSize
Geom size parameters.
Definition: GeomAttributes.hpp:71
double mMargin
Distance threshold below which contacts are detected and included in the global array mjData....
Definition: GeomAttributes.hpp:89
Eigen::Quaterniond mQuat
Quaternion.
Definition: GeomAttributes.hpp:106
int mPriority
Definition: GeomAttributes.hpp:68
int mGroup
Definition: GeomAttributes.hpp:66
common::optional< std::string > mMesh
Definition: GeomAttributes.hpp:127
Eigen::Vector3d mFriction
Definition: GeomAttributes.hpp:75
double mFitScale
Definition: GeomAttributes.hpp:129
common::optional< Eigen::Vector6d > mFromTo
This attribute can only be used with capsule, cylinder, ellipsoid and box geoms.
Definition: GeomAttributes.hpp:99
common::optional< Eigen::Vector3d > mZAxis
The Z axis of the frame.
Definition: GeomAttributes.hpp:123