template<typename T>
class drake::multibody::benchmarks::Acrobot< T >
The Acrobot - a canonical underactuated system as described in Chapter 3 of Underactuated Robotics.
This system essentially is a double pendulum consisting of two links. Link 1 is connected to the world by a "shoulder" revolute joint parameterized by angle theta1 and Link 2 is connected to Link 1 by an "elbow" revolute joint parameterized by angle theta2.
- Template Parameters
-
|
| | Acrobot (const Vector3< T > &normal, const Vector3< T > &up, double m1=1.0, double m2=1.0, double l1=1.0, double l2=1.0, double lc1=0.5, double lc2=0.5, double Ic1=.083, double Ic2=.33, double b1=0.1, double b2=0.1, double g=9.81) |
| | Creates an acrobot model in a plane passing through the world's origin and normal to normal. More...
|
| |
| Matrix2< T > | CalcMassMatrix (const T &theta2) const |
| | Computes the mass matrix H(q) for the double pendulum system. More...
|
| |
| Vector2< T > | CalcCoriolisVector (const T &theta1, const T &theta2, const T &theta1dot, const T &theta2dot) const |
| | Computes the bias term C(q, v) * v containing Coriolis and gyroscopic effects as a function of the state of the pendulum. More...
|
| |
| Vector2< T > | CalcGravityVector (const T &theta1, const T &theta2) const |
| | Computes the effective joint-space torques induced by gravity tau_g(q) containing the effect of gravity as a function of the configuration of the pendulum. More...
|
| |
| math::RigidTransform< T > | CalcLink1PoseInWorldFrame (const T &theta1) const |
| | Computes the pose of the center of mass of link 1 measured and expressed in the world frame. More...
|
| |
| math::RigidTransform< T > | CalcLink2PoseInWorldFrame (const T &theta1, const T &theta2) const |
| | Computes the pose of the center of mass of link 2 measured and expressed in the world frame. More...
|
| |
| math::RigidTransform< T > | CalcElbowOutboardFramePoseInWorldFrame (const T &theta1, const T &theta2) const |
| | Computes the pose of the elbow outboard frame Eo in the world frame W. More...
|
| |
| Vector6< T > | CalcLink1SpatialVelocityInWorldFrame (const T &theta1, const T &theta1dot) const |
| | Computes the spatial velocity of the center of mass of link 1 expressed in the world frame. More...
|
| |
| Vector6< T > | CalcLink2SpatialVelocityInWorldFrame (const T &theta1, const T &theta2, const T &theta1dot, const T &theta2dot) const |
| | Computes the spatial velocity of the center of mass of link 2 expressed in the world frame. More...
|
| |
| Vector6< T > | CalcLink1SpatialAccelerationInWorldFrame (const T &theta1, const T &theta1dot, const T &theta1dotdot) const |
| | Computes the spatial acceleration of the center of mass of link 1 expressed in the world frame. More...
|
| |
| Vector6< T > | CalcLink2SpatialAccelerationInWorldFrame (const T &theta1, const T &theta2, const T &theta1dot, const T &theta2dot, const T &theta1dotdot, const T &theta2dotdot) const |
| | Computes the spatial acceleration of the center of mass of link 2 expressed in the world frame. More...
|
| |
| T | CalcPotentialEnergy (const T &theta1, const T &theta2) const |
| | Computes the total potential energy due to gravity of the acrobot system for the state given by angles theta1 and theta2. More...
|
| |
| Acrobot |
( |
const Vector3< T > & |
normal, |
|
|
const Vector3< T > & |
up, |
|
|
double |
m1 = 1.0, |
|
|
double |
m2 = 1.0, |
|
|
double |
l1 = 1.0, |
|
|
double |
l2 = 1.0, |
|
|
double |
lc1 = 0.5, |
|
|
double |
lc2 = 0.5, |
|
|
double |
Ic1 = .083, |
|
|
double |
Ic2 = .33, |
|
|
double |
b1 = 0.1, |
|
|
double |
b2 = 0.1, |
|
|
double |
g = 9.81 |
|
) |
| |
Creates an acrobot model in a plane passing through the world's origin and normal to normal.
Vector up defines the upwards direction on this plane. Both normal and up are expressed in the world's frame. Essentially the two dimensional equations of the acrobot are described in a model frame D within a x-y plane with y the vertical direction and gravity pointing downwards. Therefore the axes defining the model frame D are:
z_W = normal_W.normalized()
y_W = (up - up.dot(z_W) * z_W).normalized()
x_W = y_W.cross(z_W)
The remaining arguments define the properties of the double pendulum system:
- m1: mass of the first link.
- m2: mass of the second link.
- l1: length of the first link.
- l2: length of the second link.
- lc1: length from the shoulder to the center of mass of the first link.
- lc2: length from the elbow to the center of mass of the second link.
- Ic1: moment of inertia about the center of mass for the first link.
- Ic2: moment of inertia about the center of mass for the second link.
- b1: damping coefficient of the shoulder joint.
- b2: damping coefficient of the elbow joint.
- g: acceleration of gavity.