Drake
Drake C++ Documentation
Loading...
Searching...
No Matches
PropellerInfo Struct Reference

Detailed Description

Parameters that describe the kinematic frame and force-production properties of a single propeller.

#include <drake/multibody/plant/propeller.h>

Public Member Functions

 PropellerInfo (const BodyIndex &body_index_, const math::RigidTransform< double > &X_BP_=math::RigidTransform< double >::Identity(), double thrust_ratio_=1.0, double moment_ratio_=0.0)
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable
 PropellerInfo (const PropellerInfo &)=default
PropellerInfooperator= (const PropellerInfo &)=default
 PropellerInfo (PropellerInfo &&)=default
PropellerInfooperator= (PropellerInfo &&)=default

Public Attributes

BodyIndex body_index
 The BodyIndex of a RigidBody in the MultibodyPlant to which the propeller is attached.
math::RigidTransform< doubleX_BP {}
 Pose of the propeller frame P measured in the body frame B.
double thrust_ratio {1.0}
 The z component (in frame P) of the spatial force will have magnitude thrust_ratio*command in Newtons.
double moment_ratio {0.0}
 The moment about the z axis (in frame P) of the spatial force will have magnitude moment_ratio*command in Newton-meters.

Constructor & Destructor Documentation

◆ PropellerInfo() [1/3]

PropellerInfo ( const PropellerInfo & )
default

◆ PropellerInfo() [2/3]

PropellerInfo ( PropellerInfo && )
default

◆ PropellerInfo() [3/3]

PropellerInfo ( const BodyIndex & body_index_,
const math::RigidTransform< double > & X_BP_ = math::RigidTransform<double>::Identity(),
double thrust_ratio_ = 1.0,
double moment_ratio_ = 0.0 )
explicit

Member Function Documentation

◆ operator=() [1/2]

PropellerInfo & operator= ( const PropellerInfo & )
default

◆ operator=() [2/2]

PropellerInfo & operator= ( PropellerInfo && )
default

Member Data Documentation

◆ body_index

BodyIndex body_index

The BodyIndex of a RigidBody in the MultibodyPlant to which the propeller is attached.

The spatial forces will be applied to this body.

◆ moment_ratio

double moment_ratio {0.0}

The moment about the z axis (in frame P) of the spatial force will have magnitude moment_ratio*command in Newton-meters.

The default is 0, which makes the propeller a simple Cartesian force generator.

◆ thrust_ratio

double thrust_ratio {1.0}

The z component (in frame P) of the spatial force will have magnitude thrust_ratio*command in Newtons.

The default is 1 (command in Newtons), but this can also be used to scale an actuator command to the resulting force.

◆ X_BP

Pose of the propeller frame P measured in the body frame B.


Default: is the identity matrix.


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