Drake
Drake C++ Documentation
JointActuator< T > Class Template Referencefinal

Detailed Description

template<typename T>
class drake::multibody::JointActuator< T >

The JointActuator class is mostly a simple bookkeeping structure to represent an actuator acting on a given Joint.

It helps to flag whether a given Joint is actuated or not so that MultibodyTree clients can apply forces on actuated joints through their actuators, see AddInOneForce().

Template Parameters
TThe scalar type, which must be one of the default scalars.

#include <drake/multibody/tree/multibody_tree.h>

Public Member Functions

 JointActuator (const std::string &name, const Joint< T > &joint, double effort_limit=std::numeric_limits< double >::infinity())
 Creates an actuator for joint with the given name. More...
 
JointActuatorIndex index () const
 Returns this element's unique index. More...
 
const std::string & name () const
 Returns the name of the actuator. More...
 
const Joint< T > & joint () const
 Returns a reference to the joint actuated by this JointActuator. More...
 
void AddInOneForce (const systems::Context< T > &context, int joint_dof, const T &tau, MultibodyForces< T > *forces) const
 Adds into forces a force along one of the degrees of freedom of the Joint actuated by this actuator. More...
 
const Eigen::Ref< const VectorX< T > > get_actuation_vector (const VectorX< T > &u) const
 Gets the actuation values for this actuator from the actuation vector u for the entire plant model. More...
 
void set_actuation_vector (const Eigen::Ref< const VectorX< T >> &u_actuator, EigenPtr< VectorX< T >> u) const
 Given the actuation values u_actuator for this actuator, updates the actuation vector u for the entire multibody model to which this actuator belongs to. More...
 
int input_start () const
 Returns the index to the first element for this joint actuator / within the vector of actuation inputs for the full multibody / system. More...
 
int num_inputs () const
 Returns the number of inputs associated with this actuator. More...
 
double effort_limit () const
 Returns the actuator effort limit. More...
 
Does not allow copy, move, or assignment
 JointActuator (const JointActuator &)=delete
 
JointActuatoroperator= (const JointActuator &)=delete
 
 JointActuator (JointActuator &&)=delete
 
JointActuatoroperator= (JointActuator &&)=delete
 
Reflected Inertia

The JointActuator class offers the ability to model the effects of reflected inertia for revolute and prismatic joints via an approximation commonly used in robotics (see [Featherstone, 2008]). Reflected inertia is an approximate method for accounting for the mass/inertia contributions to kinetic energy and equations of motion for effects of a spinning motor's rotor (and any additional shafts/gears) inside a gearmotor. This "quick and dirty" approximation does not depend on the internals of the gearbox (e.g., whether there is a single stage or multistage gear, whether there are additional shafts/gears, or the relative position or orientation of the outboard shaft with respect to the motor rotor's shaft. Note: Reflected inertia does not account for mass/inertia of the body attached to the gearmotor's output shaft (labeled S in the figure below). The value of reflected inertia is a function of the gear ratio and the rotor inertia of the modeled motor. JointActuator exposes these two values as parameters (see SetRotorInertia() and SetGearRatio()). Reflected inertia has units of kg for prismatic joints and units of kg⋅m² for revolute joints. A zero value indicates reflected inertia is not modeled. This value is used as part of an approximation of a rotor's inertial effects in a geared motor. It should be noted that the approximation is reasonable for high gear ratios but less so for small gear ratios (see [Featherstone, 2008], Chapter 9.6 on gears).

GearBoxSchematic.png
GearedMotorAPiqselsComCC0.jpg

Actuated revolute joints

For an actuator driving a revolute joint, the reflected inertia can be estimated from the rotational inertia Iᵣ of the actuator's rotor about its axis of rotation and from the dimensionless gear ratio ρ. To define gear ratio ρ, consider a gear-motor combination that has a stator/rigid case A, motor rotor R, and output shaft B. Rotor R spins relative to stator A with angular speed wR and shaft B spins relative to stator A with angular speed wB. The gear ratio is defined ρ ≝ wR / wB. Typically, ρ >> 1. For this gear-motor, reflected inertia Iᵣᵢ = ρ² ⋅ Iᵣ.

Actuated prismatic joints

To define the gear ratio ρ for prismatic joints, consider a gear-motor combination that has a stator/rigid case A, motor rotor R, and translating output shaft B. Rotor R spins relative to stator A with angular speed wR and shaft B translates relative to stator A with translational speed vB. The gear ratio is defined ρ ≝ wR / vB (units of 1/m). Typically, ρ >> 1. For the gear-motor here, reflected inertia Iᵣᵢ = ρ² ⋅ Iᵣ (units of kg).

double default_rotor_inertia () const
 Gets the default value for this actuator's rotor inertia. More...
 
double default_gear_ratio () const
 Gets the default value for this actuator's gear ratio. More...
 
void set_default_rotor_inertia (double rotor_inertia)
 Sets the default value for this actuator's rotor inertia. More...
 
void set_default_gear_ratio (double gear_ratio)
 Sets the default value for this actuator's gear ratio. More...
 
double default_reflected_inertia () const
 Returns the default value for this actuator's reflected inertia. More...
 
const T & rotor_inertia (const systems::Context< T > &context) const
 Returns the associated rotor inertia value for this actuator, stored in context. More...
 
const T & gear_ratio (const systems::Context< T > &context) const
 Returns the associated gear ratio value for this actuator, stored in context. More...
 
void SetRotorInertia (systems::Context< T > *context, const T &rotor_inertia) const
 Sets the associated rotor inertia value for this actuator in context. More...
 
void SetGearRatio (systems::Context< T > *context, const T &gear_ratio) const
 Sets the associated gear ratio value for this actuator in context. More...
 
calc_reflected_inertia (const systems::Context< T > &context) const
 Calculates the reflected inertia value for this actuator in context. More...
 
PD Controlled Actuators

Refer to Actuation for further details on the modeling of PD controlled actuators.

void set_controller_gains (PdControllerGains gains)
 Set controller gains for this joint actuator. More...
 
bool has_controller () const
 Returns true if controller gains have been specified with a call to set_controller_gains(). More...
 
const PdControllerGainsget_controller_gains () const
 Returns a reference to the controller gains for this actuator. More...
 
- Public Member Functions inherited from MultibodyElement< T >
virtual ~MultibodyElement ()
 
ModelInstanceIndex model_instance () const
 Returns the ModelInstanceIndex of the model instance to which this element belongs. More...
 
template<typename MultibodyPlantDeferred = MultibodyPlant<T>>
const MultibodyPlantDeferred & GetParentPlant () const
 Returns the MultibodyPlant that owns this MultibodyElement. More...
 
void DeclareParameters (internal::MultibodyTreeSystem< T > *tree_system)
 Declares MultibodyTreeSystem Parameters at MultibodyTreeSystem::Finalize() time. More...
 
void SetDefaultParameters (systems::Parameters< T > *parameters) const
 Sets default values of parameters belonging to each MultibodyElement in parameters at a call to MultibodyTreeSystem::SetDefaultParameters(). More...
 
 MultibodyElement (const MultibodyElement &)=delete
 
MultibodyElementoperator= (const MultibodyElement &)=delete
 
 MultibodyElement (MultibodyElement &&)=delete
 
MultibodyElementoperator= (MultibodyElement &&)=delete
 

Friends

template<typename U >
class JointActuator
 

Additional Inherited Members

- Protected Member Functions inherited from MultibodyElement< T >
 MultibodyElement ()
 Default constructor made protected so that sub-classes can still declare their default constructors if they need to. More...
 
 MultibodyElement (ModelInstanceIndex model_instance)
 Constructor which allows specifying a model instance. More...
 
 MultibodyElement (ModelInstanceIndex model_instance, int64_t index)
 Both the model instance and element index are specified. More...
 
template<typename ElementIndexType >
ElementIndexType index_impl () const
 Returns this element's unique index. More...
 
const internal::MultibodyTree< T > & get_parent_tree () const
 Returns a constant reference to the parent MultibodyTree that owns this element. More...
 
const internal::MultibodyTreeSystem< T > & GetParentTreeSystem () const
 Returns a constant reference to the parent MultibodyTreeSystem that owns the parent MultibodyTree that owns this element. More...
 
void SetTopology (const internal::MultibodyTreeTopology &tree)
 Gives MultibodyElement-derived objects the opportunity to retrieve their topology after MultibodyTree::Finalize() is invoked. More...
 
systems::NumericParameterIndex DeclareNumericParameter (internal::MultibodyTreeSystem< T > *tree_system, const systems::BasicVector< T > &model_vector)
 To be used by MultibodyElement-derived objects when declaring parameters in their implementation of DoDeclareParameters(). More...
 
systems::AbstractParameterIndex DeclareAbstractParameter (internal::MultibodyTreeSystem< T > *tree_system, const AbstractValue &model_value)
 To be used by MultibodyElement-derived objects when declaring parameters in their implementation of DoDeclareParameters(). More...
 

Constructor & Destructor Documentation

◆ JointActuator() [1/3]

JointActuator ( const JointActuator< T > &  )
delete

◆ JointActuator() [2/3]

JointActuator ( JointActuator< T > &&  )
delete

◆ JointActuator() [3/3]

JointActuator ( const std::string &  name,
const Joint< T > &  joint,
double  effort_limit = std::numeric_limits< double >::infinity() 
)

Creates an actuator for joint with the given name.

The name must be unique within the given multibody model. This is enforced by MultibodyPlant::AddJointActuator().

Parameters
[in]nameA string with a name identifying this actuator.
[in]jointThe joint that the created actuator will act on.
[in]effort_limitThe maximum effort for the actuator. It must be strictly positive, otherwise an std::exception is thrown. If +∞, the actuator has no limit, which is the default. The effort limit has physical units in accordance to the joint type it actuates. For instance, it will have units of N⋅m (torque) for revolute joints while it will have units of N (force) for prismatic joints.

Member Function Documentation

◆ AddInOneForce()

void AddInOneForce ( const systems::Context< T > &  context,
int  joint_dof,
const T &  tau,
MultibodyForces< T > *  forces 
) const

Adds into forces a force along one of the degrees of freedom of the Joint actuated by this actuator.

The meaning for this degree of freedom, sign conventions and even its dimensional units depend on the specific joint sub-class being actuated. For a RevoluteJoint for instance, joint_dof can only be 0 since revolute joints's motion subspace only has one degree of freedom, while the units of tau are those of torque (N⋅m in the MKS system of units). For multi-dof joints please refer to the documentation provided by specific joint sub-classes regarding the meaning of joint_dof.

Parameters
[in]contextThe context storing the state and parameters for the model to which this joint belongs.
[in]joint_dofIndex specifying one of the degrees of freedom for this joint. The index must be in the range 0 <= joint_dof < num_inputs() or otherwise this method will throw an exception.
[in]joint_tauGeneralized force corresponding to the degree of freedom indicated by joint_dof to be added into forces. Refer to the specific Joint sub-class documentation for details on the meaning and units for this degree of freedom.
[out]forcesOn return, this method will add force tau for the degree of freedom joint_dof into the output forces. This method aborts if forces is nullptr or if forces doest not have the right sizes to accommodate a set of forces for the model to which this actuator belongs.

◆ calc_reflected_inertia()

T calc_reflected_inertia ( const systems::Context< T > &  context) const

Calculates the reflected inertia value for this actuator in context.

See reflected_inertia.

◆ default_gear_ratio()

double default_gear_ratio ( ) const

Gets the default value for this actuator's gear ratio.

See reflected_inertia.

◆ default_reflected_inertia()

double default_reflected_inertia ( ) const

Returns the default value for this actuator's reflected inertia.

It is calculated as ρ²⋅Iᵣ, where ρ is the default gear ratio and Iᵣ is the default rotor inertia for this actuator. See reflected_inertia.

◆ default_rotor_inertia()

double default_rotor_inertia ( ) const

Gets the default value for this actuator's rotor inertia.

See reflected_inertia.

◆ effort_limit()

double effort_limit ( ) const

Returns the actuator effort limit.

◆ gear_ratio()

const T& gear_ratio ( const systems::Context< T > &  context) const

Returns the associated gear ratio value for this actuator, stored in context.

See reflected_inertia.

◆ get_actuation_vector()

const Eigen::Ref<const VectorX<T> > get_actuation_vector ( const VectorX< T > &  u) const

Gets the actuation values for this actuator from the actuation vector u for the entire plant model.

Returns
a reference to a nv-dimensional vector, where nv is the number of velocity variables of joint().

◆ get_controller_gains()

const PdControllerGains& get_controller_gains ( ) const

Returns a reference to the controller gains for this actuator.

Precondition
has_controller() is true.

◆ has_controller()

bool has_controller ( ) const

Returns true if controller gains have been specified with a call to set_controller_gains().

◆ index()

JointActuatorIndex index ( ) const

Returns this element's unique index.

◆ input_start()

int input_start ( ) const

Returns the index to the first element for this joint actuator / within the vector of actuation inputs for the full multibody / system.

Exceptions
std::exceptionif the MultibodyTree model is not finalized.

◆ joint()

const Joint<T>& joint ( ) const

Returns a reference to the joint actuated by this JointActuator.

◆ name()

const std::string& name ( ) const

Returns the name of the actuator.

◆ num_inputs()

int num_inputs ( ) const

Returns the number of inputs associated with this actuator.

Exceptions
std::exceptionif the MultibodyTree model is not finalized.

◆ operator=() [1/2]

JointActuator& operator= ( JointActuator< T > &&  )
delete

◆ operator=() [2/2]

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

◆ rotor_inertia()

const T& rotor_inertia ( const systems::Context< T > &  context) const

Returns the associated rotor inertia value for this actuator, stored in context.

See reflected_inertia.

◆ set_actuation_vector()

void set_actuation_vector ( const Eigen::Ref< const VectorX< T >> &  u_actuator,
EigenPtr< VectorX< T >>  u 
) const

Given the actuation values u_actuator for this actuator, updates the actuation vector u for the entire multibody model to which this actuator belongs to.

Parameters
[in]u_actuatorActuation values for this actuator. It must be of size equal to num_inputs(). For units and sign conventions refer to the specific Joint sub-class documentation.
[in,out]uActuation values for the entire plant model to which this actuator belongs to, indexed by JointActuatorIndex. Only values corresponding to this actuator are changed.
Exceptions
std::exceptionif u_actuator.size() != this->num_inputs().
std::exceptionif u is nullptr.
std::exceptionif u.size() != this->GetParentPlant().num_actuated_dofs().

◆ set_controller_gains()

void set_controller_gains ( PdControllerGains  gains)

Set controller gains for this joint actuator.

This enables the modeling of a simple PD controller of the form: ũ = -Kp⋅(q − qd) - Kd⋅(v − vd) + u_ff u = max(−e, min(e, ũ)) where qd and vd are the desired configuration and velocity for joint(), Kp and Kd are the proportional and derivative gains specified in gains, u_ff is the feedforward actuation and e corresponds to effort_limit().

For simulation, feedforward actuation can be provided through MultibodyPlant::get_actuation_input_port(). Desired configuration and velocity are specified through MultibodyPlant::get_desired_state_input_port().

Exceptions
iffthe proportional gain is not strictly positive or if the derivative gain is negative.
iffthe owning MultibodyPlant is finalized. See MultibodyPlant::Finalize().

◆ set_default_gear_ratio()

void set_default_gear_ratio ( double  gear_ratio)

Sets the default value for this actuator's gear ratio.

See reflected_inertia.

◆ set_default_rotor_inertia()

void set_default_rotor_inertia ( double  rotor_inertia)

Sets the default value for this actuator's rotor inertia.

See reflected_inertia.

◆ SetGearRatio()

void SetGearRatio ( systems::Context< T > *  context,
const T &  gear_ratio 
) const

Sets the associated gear ratio value for this actuator in context.

See reflected_inertia.

◆ SetRotorInertia()

void SetRotorInertia ( systems::Context< T > *  context,
const T &  rotor_inertia 
) const

Sets the associated rotor inertia value for this actuator in context.

See reflected_inertia.

Friends And Related Function Documentation

◆ JointActuator

friend class JointActuator
friend

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