DART 6.12.2
Loading...
Searching...
No Matches
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#include <tinyxml2.h>
38
43
44namespace dart {
45namespace utils {
46namespace MjcfParser {
47namespace detail {
48
51struct GeomAttributes final
52{
55
58
59 int mConType{1};
60
62
63 int mConDim{3};
64
65 int mGroup{0};
66
67 int mPriority{0};
68
70 Eigen::Vector3d mSize{Eigen::Vector3d::Zero()};
71
72 Eigen::Vector4d mRGBA{Eigen::Vector4d(0.5, 0.5, 0.5, 1)};
73
74 Eigen::Vector3d mFriction{Eigen::Vector3d(1, 0.005, 0.0001)};
75
78
80 double mDensity{1000};
81
84 double mSolMix{1};
85
88 double mMargin{0};
89
93 double mGap{0};
94
99
102 Eigen::Vector3d mPos{Eigen::Vector3d::Zero()};
103
105 Eigen::Quaterniond mQuat{Eigen::Quaterniond::Identity()};
106
111
114
120
123
125
127
128 double mFitScale{1};
129};
130
132 GeomAttributes& attributes, tinyxml2::XMLElement* element);
133
134} // namespace detail
135} // namespace MjcfParser
136} // namespace utils
137} // namespace dart
138
139#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:60
Intermediate raw data read from the XML file.
Definition GeomAttributes.hpp:52
common::optional< Eigen::Vector4d > mAxisAngle
These are the quantities (x, y, z, a) mentioned above.
Definition GeomAttributes.hpp:110
double mSolMix
Weight used for averaging of contact parameters, and interacts with the priority attribute.
Definition GeomAttributes.hpp:84
double mDensity
Material density used to compute the geom mass and inertia.
Definition GeomAttributes.hpp:80
int mConType
Definition GeomAttributes.hpp:59
double mGap
This attribute is used to enable the generation of inactive contacts, i.e.
Definition GeomAttributes.hpp:93
common::optional< Eigen::Vector6d > mXYAxes
The first 3 numbers are the X axis of the frame.
Definition GeomAttributes.hpp:119
int mConDim
Definition GeomAttributes.hpp:63
common::optional< Eigen::Vector3d > mEuler
Rotation angles around three coordinate axes.
Definition GeomAttributes.hpp:113
common::optional< std::string > mHField
Definition GeomAttributes.hpp:124
common::optional< std::string > mName
Name of the geom.
Definition GeomAttributes.hpp:54
Eigen::Vector3d mPos
Position of the geom frame, in local or global coordinates as determined by the coordinate attribute ...
Definition GeomAttributes.hpp:102
common::optional< double > mMass
Mass.
Definition GeomAttributes.hpp:77
int mConAffinity
Definition GeomAttributes.hpp:61
Eigen::Vector4d mRGBA
Definition GeomAttributes.hpp:72
GeomType mType
Type of geometric shape.
Definition GeomAttributes.hpp:57
Eigen::Vector3d mSize
Geom size parameters.
Definition GeomAttributes.hpp:70
double mMargin
Distance threshold below which contacts are detected and included in the global array mjData....
Definition GeomAttributes.hpp:88
Eigen::Quaterniond mQuat
Quaternion.
Definition GeomAttributes.hpp:105
int mPriority
Definition GeomAttributes.hpp:67
int mGroup
Definition GeomAttributes.hpp:65
common::optional< std::string > mMesh
Definition GeomAttributes.hpp:126
Eigen::Vector3d mFriction
Definition GeomAttributes.hpp:74
double mFitScale
Definition GeomAttributes.hpp:128
common::optional< Eigen::Vector6d > mFromTo
This attribute can only be used with capsule, cylinder, ellipsoid and box geoms.
Definition GeomAttributes.hpp:98
common::optional< Eigen::Vector3d > mZAxis
The Z axis of the frame.
Definition GeomAttributes.hpp:122