Drake
Drake C++ Documentation
drake::multibody::benchmarks::pendulum Namespace Reference

Classes

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

Functions

std::unique_ptr< MultibodyPlant< double > > MakePendulumPlant (const PendulumParameters &default_parameters=PendulumParameters(), geometry::SceneGraph< double > *scene_graph=nullptr)
 This method makes a MultibodyPlant model of an idealized pendulum with a point mass at the end of a massless rigid rod. More...
 

Function Documentation

◆ MakePendulumPlant()

std::unique_ptr<MultibodyPlant<double> > drake::multibody::benchmarks::pendulum::MakePendulumPlant ( const PendulumParameters default_parameters = PendulumParameters(),
geometry::SceneGraph< double > *  scene_graph = nullptr 
)

This method makes a MultibodyPlant model of an idealized pendulum with a point mass at the end of a massless rigid rod.

The pendulum oscillates in the x-z plane with its revolute axis coincident with the y-axis. Gravity points downwards in the -z axis direction.

The parameters of the plant are:

  • mass: the mass of the idealized point mass.
  • length: the length of the massless rod on which the mass is suspended.
  • gravity: the acceleration of gravity.

The simple pendulum is a canonical dynamical system as described in Chapter 2 of Underactuated Robotics.

Parameters
[in]default_parametersDefault parameters of the model set at construction. Refer to the documentation of PendulumParameters for further details.
scene_graphIf a SceneGraph is provided with this argument, this factory method will register the new multibody plant to be a source for that geometry system and it will also register geometry for visualization. If this argument is omitted, no geometry will be registered.