Drake
Drake C++ Documentation
AxiallySymmetricFreeBodyPlant< T > Class Template Reference

Detailed Description

template<typename T>
class drake::multibody::test::AxiallySymmetricFreeBodyPlant< T >

This plant models the free motion of a torque free body in space.

This body is axially symmetric with rotational inertia about its axis of revolution J and with a rotational inertia I about any axis perpendicular to its axis of revolution. This particular case has a nice closed form analytical solution which we have implemented in drake::multibody::benchmarks::free_body::FreeBody.

Template Parameters
TThe scalar type, which must be double.

#include <drake/multibody/test_utilities/floating_body_plant.h>

Public Member Functions

 AxiallySymmetricFreeBodyPlant (double mass, double I, double J, double g, double time_step=0.0)
 Constructor from known rotational inertia values. More...
 
 ~AxiallySymmetricFreeBodyPlant ()
 
const MultibodyPlant< T > & plant () const
 Returns the underlying MbP model. More...
 
std::unique_ptr< systems::Context< T > > CreatePlantContext () const
 Returns a MbP context in which the free body frame B is coincident with the world frame W and the angular and translational velocities have a value as returned by get_default_initial_angular_velocity() and get_default_initial_translational_velocity(), respectively. More...
 
Vector3< T > get_angular_velocity (const systems::Context< T > &context) const
 Returns the angular velocity w_WB stored in context of the free body B in the world frame W. More...
 
Vector3< T > get_translational_velocity (const systems::Context< T > &context) const
 Returns the translational velocity v_WB stored in context of the free body B in the world frame W. More...
 
math::RigidTransform< T > CalcPoseInWorldFrame (const systems::Context< T > &context) const
 Computes the pose X_WB of the body in the world frame. More...
 
SpatialVelocity< T > CalcSpatialVelocityInWorldFrame (const systems::Context< T > &context) const
 Calculates V_WB, this body B's spatial velocity in the world frame W. More...
 
const RigidBody< T > & body () const
 Returns a constant reference to the free body model of this plant. More...
 
Does not allow copy, move, or assignment
 AxiallySymmetricFreeBodyPlant (const AxiallySymmetricFreeBodyPlant &)=delete
 
AxiallySymmetricFreeBodyPlantoperator= (const AxiallySymmetricFreeBodyPlant &)=delete
 
 AxiallySymmetricFreeBodyPlant (AxiallySymmetricFreeBodyPlant &&)=delete
 
AxiallySymmetricFreeBodyPlantoperator= (AxiallySymmetricFreeBodyPlant &&)=delete
 

Static Public Member Functions

static Vector3< doubleget_default_initial_angular_velocity ()
 Returns the default value of the angular velocity set by default by SetDefaultState(). More...
 
static Vector3< doubleget_default_initial_translational_velocity ()
 Returns the default value of the translational velocity set by default by SetDefaultState(). More...
 

Constructor & Destructor Documentation

◆ AxiallySymmetricFreeBodyPlant() [1/3]

◆ AxiallySymmetricFreeBodyPlant() [2/3]

◆ AxiallySymmetricFreeBodyPlant() [3/3]

AxiallySymmetricFreeBodyPlant ( double  mass,
double  I,
double  J,
double  g,
double  time_step = 0.0 
)

Constructor from known rotational inertia values.

Rotational inertia values have units of kg⋅m².

Parameters
massThe mass of the body.
Irotational inertia about any axis perpendicular to the axis of revolution of the body.
Jrotational inertia about the axis of revolution of the body.
gAcceleration of gravity. In this model if g > 0 the gravity vector points downward in the z-axis direction.
time_step[optional] See MultibodyPlant::MultibodyPlant.

◆ ~AxiallySymmetricFreeBodyPlant()

Member Function Documentation

◆ body()

const RigidBody<T>& body ( ) const

Returns a constant reference to the free body model of this plant.

◆ CalcPoseInWorldFrame()

math::RigidTransform<T> CalcPoseInWorldFrame ( const systems::Context< T > &  context) const

Computes the pose X_WB of the body in the world frame.

◆ CalcSpatialVelocityInWorldFrame()

SpatialVelocity<T> CalcSpatialVelocityInWorldFrame ( const systems::Context< T > &  context) const

Calculates V_WB, this body B's spatial velocity in the world frame W.

Parameters
[in]contextContains the state of the model.
Return values
V_WB_Wthis free-body B's spatial velocity in the world frame W, expressed in W (for point Bo, the body frame's origin).

◆ CreatePlantContext()

std::unique_ptr<systems::Context<T> > CreatePlantContext ( ) const

Returns a MbP context in which the free body frame B is coincident with the world frame W and the angular and translational velocities have a value as returned by get_default_initial_angular_velocity() and get_default_initial_translational_velocity(), respectively.

◆ get_angular_velocity()

Vector3<T> get_angular_velocity ( const systems::Context< T > &  context) const

Returns the angular velocity w_WB stored in context of the free body B in the world frame W.

◆ get_default_initial_angular_velocity()

static Vector3<double> get_default_initial_angular_velocity ( )
static

Returns the default value of the angular velocity set by default by SetDefaultState().

Currently a non-zero value.

◆ get_default_initial_translational_velocity()

static Vector3<double> get_default_initial_translational_velocity ( )
static

Returns the default value of the translational velocity set by default by SetDefaultState().

Currently a non-zero value.

◆ get_translational_velocity()

Vector3<T> get_translational_velocity ( const systems::Context< T > &  context) const

Returns the translational velocity v_WB stored in context of the free body B in the world frame W.

◆ operator=() [1/2]

◆ operator=() [2/2]

AxiallySymmetricFreeBodyPlant& operator= ( const AxiallySymmetricFreeBodyPlant< T > &  )
delete

◆ plant()

const MultibodyPlant<T>& plant ( ) const

Returns the underlying MbP model.


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