Drake
Drake C++ Documentation
AcrobotParameters Class Reference

Detailed Description

This class is used to store the numerical parameters defining the model of an acrobot with the method MakeAcrobotPlant().

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

Note
The default constructor initializes the parameters in accordance to the acrobot.sdf file in this same directory. Therefore this file and acrobot.sdf MUST be kept in sync.

#include <drake/multibody/benchmarks/acrobot/make_acrobot_plant.h>

Public Member Functions

 AcrobotParameters (double m1=1.0, double m2=1.0, double l1=1.0, double l2=2.0, double lc1=0.5, double lc2=1.0, double Ic1=.083, double Ic2=.33, double b1=0.1, double b2=0.1, double g=9.81)
 Constructor used to initialize the physical parameters for an acrobot model. More...
 
double m1 () const
 
double m2 () const
 
double l1 () const
 
double l2 () const
 
double lc1 () const
 
double lc2 () const
 
double Ic1 () const
 
double Ic2 () const
 
double Gc1 () const
 
double Gc2 () const
 
double b1 () const
 
double b2 () const
 
double g () const
 
double r1 () const
 
double r2 () const
 
const std::string & link1_name () const
 
const std::string & link2_name () const
 
const std::string & shoulder_joint_name () const
 
const std::string & elbow_joint_name () const
 
const std::string & actuator_name () const
 
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable
 AcrobotParameters (const AcrobotParameters &)=default
 
AcrobotParametersoperator= (const AcrobotParameters &)=default
 
 AcrobotParameters (AcrobotParameters &&)=default
 
AcrobotParametersoperator= (AcrobotParameters &&)=default
 

Constructor & Destructor Documentation

◆ AcrobotParameters() [1/3]

AcrobotParameters ( const AcrobotParameters )
default

◆ AcrobotParameters() [2/3]

◆ AcrobotParameters() [3/3]

AcrobotParameters ( double  m1 = 1.0,
double  m2 = 1.0,
double  l1 = 1.0,
double  l2 = 2.0,
double  lc1 = 0.5,
double  lc2 = 1.0,
double  Ic1 = .083,
double  Ic2 = .33,
double  b1 = 0.1,
double  b2 = 0.1,
double  g = 9.81 
)

Constructor used to initialize the physical parameters for an acrobot model.

The parameters are defaulted to values in Spong's paper [Spong 1994].

Parameters
m1Mass of link 1 (kg).
m2Mass of link 2 (kg).
l1Length of link 1 (m).
l2Length of link 2 (m).
lc1Vertical distance from shoulder joint to center of mass of link 1 (m).
lc2Vertical distance from elbow joint to center of mass of link 2 (m).
Ic1Inertia of link 1 about the center of mass of link 1 (kg⋅m²).
Ic2Inertia of link 2 about the center of mass of link 2 (kg*m^2).
b1Damping coefficient of the shoulder joint (N⋅m⋅s).
b2Damping coefficient of the elbow joint (N⋅m⋅s).
gGravitational constant (m/s²).
  • [Spong 1994] Spong, M.W., 1994. Swing up control of the acrobot. In Robotics and Automation, 1994. Proceedings., 1994 IEEE International Conference on (pp. 2356-2361). IEEE.

Member Function Documentation

◆ actuator_name()

const std::string& actuator_name ( ) const

◆ b1()

double b1 ( ) const

◆ b2()

double b2 ( ) const

◆ elbow_joint_name()

const std::string& elbow_joint_name ( ) const

◆ g()

double g ( ) const

◆ Gc1()

double Gc1 ( ) const

◆ Gc2()

double Gc2 ( ) const

◆ Ic1()

double Ic1 ( ) const

◆ Ic2()

double Ic2 ( ) const

◆ l1()

double l1 ( ) const

◆ l2()

double l2 ( ) const

◆ lc1()

double lc1 ( ) const

◆ lc2()

double lc2 ( ) const

◆ link1_name()

const std::string& link1_name ( ) const

◆ link2_name()

const std::string& link2_name ( ) const

◆ m1()

double m1 ( ) const

◆ m2()

double m2 ( ) const

◆ operator=() [1/2]

AcrobotParameters& operator= ( AcrobotParameters &&  )
default

◆ operator=() [2/2]

AcrobotParameters& operator= ( const AcrobotParameters )
default

◆ r1()

double r1 ( ) const

◆ r2()

double r2 ( ) const

◆ shoulder_joint_name()

const std::string& shoulder_joint_name ( ) const

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