Drake
Drake C++ Documentation
BodyShapeDescription Class Referencefinal

Detailed Description

BodyShapeDescription captures all the information necessary to describe a SceneGraph collision shape associated with a MultibodyPlant Body: a shape S, the MultibodyPlant body B (identified by model instance and body names), and the rigid pose of the shape S relative to the body B, X_BS.

Most clients should use the factory method MakeBodyShapeDescription() to construct a valid BodyShapeDescription; it will extract and verify the correct information from a multibody plant and its context.

When moved-from, this object models a "null" description and all of the getter functions will throw.

#include <drake/planning/body_shape_description.h>

Public Member Functions

 BodyShapeDescription (const geometry::Shape &shape, const math::RigidTransformd &X_BS, std::string model_instance_name, std::string body_name)
 Constructs a description with the given attributes. More...
 
const geometry::Shapeshape () const
 
const math::RigidTransformd & pose_in_body () const
 
const std::string & model_instance_name () const
 
const std::string & body_name () const
 
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable
 BodyShapeDescription (const BodyShapeDescription &)=default
 
BodyShapeDescriptionoperator= (const BodyShapeDescription &)=default
 
 BodyShapeDescription (BodyShapeDescription &&)=default
 
BodyShapeDescriptionoperator= (BodyShapeDescription &&)=default
 

Constructor & Destructor Documentation

◆ BodyShapeDescription() [1/3]

◆ BodyShapeDescription() [2/3]

◆ BodyShapeDescription() [3/3]

BodyShapeDescription ( const geometry::Shape shape,
const math::RigidTransformd &  X_BS,
std::string  model_instance_name,
std::string  body_name 
)

Constructs a description with the given attributes.

Does not check or enforce correctness; callers are responsible for providing consistent input.

Member Function Documentation

◆ body_name()

const std::string& body_name ( ) const
Returns
the body name passed at construction.

◆ model_instance_name()

const std::string& model_instance_name ( ) const
Returns
the model instance name passed at construction.

◆ operator=() [1/2]

BodyShapeDescription& operator= ( BodyShapeDescription &&  )
default

◆ operator=() [2/2]

BodyShapeDescription& operator= ( const BodyShapeDescription )
default

◆ pose_in_body()

const math::RigidTransformd& pose_in_body ( ) const
Return values
X_BSThe pose passed at construction.

◆ shape()

const geometry::Shape& shape ( ) const
Returns
the shape passed at construction.

The documentation for this class was generated from the following file: