Drake
Drake C++ Documentation
PendulumParameters Class Reference

Detailed Description

This class is used to store the numerical parameters defining the model of a simple pendulum with the method MakePendulumPlant().

Refer to this the documentation of this class's constructor for further details on the parameters stored by this class and their default values.

#include <drake/multibody/benchmarks/pendulum/make_pendulum_plant.h>

Public Member Functions

 PendulumParameters (double mass=1.0, double length=0.5, double damping=0.1, double gravity=9.81)
 Constructor used to initialize the physical parameters for a simple pendulum model. More...
 
double m () const
 
double l () const
 
double damping () const
 
double g () const
 
double point_mass_radius () const
 
double massless_rod_radius () const
 
const std::string & body_name () const
 
const std::string & pin_joint_name () const
 
const std::string & actuator_name () const
 
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable
 PendulumParameters (const PendulumParameters &)=default
 
PendulumParametersoperator= (const PendulumParameters &)=default
 
 PendulumParameters (PendulumParameters &&)=default
 
PendulumParametersoperator= (PendulumParameters &&)=default
 

Constructor & Destructor Documentation

◆ PendulumParameters() [1/3]

PendulumParameters ( const PendulumParameters )
default

◆ PendulumParameters() [2/3]

◆ PendulumParameters() [3/3]

PendulumParameters ( double  mass = 1.0,
double  length = 0.5,
double  damping = 0.1,
double  gravity = 9.81 
)

Constructor used to initialize the physical parameters for a simple pendulum model.

Parameters
massValue of the mass of the pendulum's point mass [kg].
lengthLength of the massless rod connecting the point mass to the world [m].
dampingThe joint's damping in N⋅m⋅s.
gravityGravitational constant (m/s²).

Member Function Documentation

◆ actuator_name()

const std::string& actuator_name ( ) const

◆ body_name()

const std::string& body_name ( ) const

◆ damping()

double damping ( ) const

◆ g()

double g ( ) const

◆ l()

double l ( ) const

◆ m()

double m ( ) const

◆ massless_rod_radius()

double massless_rod_radius ( ) const

◆ operator=() [1/2]

PendulumParameters& operator= ( PendulumParameters &&  )
default

◆ operator=() [2/2]

PendulumParameters& operator= ( const PendulumParameters )
default

◆ pin_joint_name()

const std::string& pin_joint_name ( ) const

◆ point_mass_radius()

double point_mass_radius ( ) const

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