17#ifndef SDF_COLLISION_HH_
18#define SDF_COLLISION_HH_
23#include <gz/math/Pose3.hh>
24#include <gz/math/Vector3.hh>
25#include <gz/math/Inertial.hh>
26#include <gz/utils/ImplPtr.hh>
30#include "sdf/config.hh"
37 inline namespace SDF_VERSION_NAMESPACE {
43 struct PoseRelativeToGraph;
75 public: std::string
Name()
const;
80 public:
void SetName(
const std::string &_name);
127 public:
const gz::math::Pose3d &
RawPose()
const;
158 gz::math::Inertiald &_inertial,
175 gz::math::Inertiald &_inertial,
177 const std::optional<double> &_density,
205 private:
void SetXmlParentName(
const std::string &_xmlParentName);
211 private:
void SetPoseRelativeToGraph(
220 GZ_UTILS_IMPL_PTR(dataPtr)
A collision element descibes the collision properties associated with a link.
Definition Collision.hh:51
void SetRawPose(const gz::math::Pose3d &_pose)
Set the pose of the collision object.
sdf::ElementPtr AutoInertiaParams() const
Get the ElementPtr to the <auto_inertia_params> element This element can be used as a parent element ...
static double DensityDefault()
Get the default density of a collision if its density is not specified.
void CalculateInertial(sdf::Errors &_errors, gz::math::Inertiald &_inertial, const ParserConfig &_config)
Calculate and return the MassMatrix for the collision.
void SetSurface(const sdf::Surface &_surface)
Set the collision's surface parameters.
const std::string & PoseRelativeTo() const
Get the name of the coordinate frame relative to which this object's pose is expressed.
const gz::math::Pose3d & RawPose() const
Get the pose of the collision object.
const sdf::Surface * Surface() const
Get a pointer to the collisions's surface parameters.
double Density() const
Get the density of the collision.
sdf::ElementPtr Element() const
Get a pointer to the SDF element that was used during load.
void SetAutoInertiaParams(const sdf::ElementPtr _autoInertiaParams)
Function to set the auto inertia params using a sdf ElementPtr object.
Errors Load(sdf::ElementPtr _sdf, const ParserConfig &_config)
Load the collision based on a element pointer.
sdf::ElementPtr ToElement() const
Create and return an SDF element filled with data from this collision.
Errors Load(ElementPtr _sdf)
Load the collision based on a element pointer.
std::string Name() const
Get the name of the collision.
void CalculateInertial(sdf::Errors &_errors, gz::math::Inertiald &_inertial, const ParserConfig &_config, const std::optional< double > &_density, sdf::ElementPtr _autoInertiaParams)
Calculate and return the MassMatrix for the collision.
Collision()
Default constructor.
void SetDensity(double _density)
Set the density of the collision.
void SetGeom(const Geometry &_geom)
Set the collision's geometry.
sdf::ElementPtr ToElement(sdf::Errors &_errors) const
Create and return an SDF element filled with data from this collision.
sdf::SemanticPose SemanticPose() const
Get SemanticPose object of this object to aid in resolving poses.
void SetPoseRelativeTo(const std::string &_frame)
Set the name of the coordinate frame relative to which this object's pose is expressed.
const Geometry * Geom() const
Get a pointer to the collisions's geometry.
void SetName(const std::string &_name)
Set the name of the collision.
Geometry provides access to a shape, such as a Box.
Definition Geometry.hh:93
This class contains configuration options for the libsdformat parser.
Definition ParserConfig.hh:106
Definition Collision.hh:44
SemanticPose is a data structure that can be used by different DOM objects to resolve poses on a Pose...
Definition SemanticPose.hh:55
Surface information for a collision.
Definition Surface.hh:305
std::vector< Error > Errors
A vector of Error.
Definition Types.hh:81
std::shared_ptr< Element > ElementPtr
Definition Element.hh:55
namespace for Simulation Description Format parser
Definition Actor.hh:35
#define SDFORMAT_VISIBLE
Use to represent "symbol visible" if supported.
Definition system_util.hh:25