pydrake.multibody.tree

Bindings for MultibodyTree and related components.

pydrake.multibody.tree.Body

alias of pydrake.multibody.tree.Body_[float]

pydrake.multibody.tree.BodyFrame

alias of pydrake.multibody.tree.BodyFrame_[float]

template pydrake.multibody.tree.BodyFrame_

Instantiations: BodyFrame_[float], BodyFrame_[AutoDiffXd], BodyFrame_[Expression]

class BodyFrame_[float]

Bases: pydrake.multibody.tree.Frame_[float]

A BodyFrame is a material Frame that serves as the unique reference frame for a Body.

Each Body B, regardless of whether it represents a rigid body or a flexible body, has a unique body frame for which we use the same symbol B (with meaning clear from context). The body frame is also referred to as a reference frame in the literature for flexible body mechanics modeling using the Finite Element Method. All properties of a body are defined with respect to its body frame, including its mass properties and attachment locations for joints, constraints, actuators, geometry and so on. Run time motion of the body is defined with respect to the motion of its body frame. We represent a body frame by a BodyFrame object that is created whenever a Body is constructed and is owned by the Body.

Note that the BodyFrame associated with a body does not necessarily need to be located at its center of mass nor does it need to be aligned with the body’s principal axes, although, in practice, it frequently is. For flexible bodies, BodyFrame provides a representation for the body’s reference frame. The flexible degrees of freedom associated with a flexible body describe the body’s deformation in this frame. Therefore, the motion of a flexible body is defined by the motion of its BodyFrame, or reference frame, plus the motion of the material points on the body with respect to its BodyFrame.

A BodyFrame and Body are tightly coupled concepts; neither makes sense without the other. Therefore, a BodyFrame instance is constructed in conjunction with its Body and cannot be constructed anywhere else. However, you can still access the frame associated with a body, see Body::body_frame(). This access is more than a convenience; you can use the BodyFrame to define other frames on the body and to attach other multibody elements to it.

Template parameter T:
The scalar type. Must be a valid Eigen scalar.
class pydrake.multibody.tree.BodyIndex

Type used to identify bodies by index in a multibody tree system.

is_valid(self: pydrake.multibody.tree.BodyIndex) → bool

Reports if the index is valid–the only operation on an invalid index that doesn’t throw an exception in Debug builds.

template pydrake.multibody.tree.Body_

Instantiations: Body_[float], Body_[AutoDiffXd], Body_[Expression]

class Body_[float]

%Body provides the general abstraction of a body with an API that makes no assumption about whether a body is rigid or deformable and neither does it make any assumptions about the underlying physical model or approximation. As an element or component of a MultibodyTree, a body is a MultibodyTreeElement, and therefore it has a unique index of type BodyIndex within the multibody tree it belongs to.

A Body contains a unique BodyFrame; see BodyFrame class documentation for more information.

Template parameter T:
The scalar type. Must be a valid Eigen scalar.
AddInForce(self: pydrake.multibody.tree.Body_[float], context: pydrake.systems.framework.Context_[float], p_BP_E: numpy.ndarray[float64[3, 1]], F_Bp_E: pydrake.multibody.math.SpatialForce_[float], frame_E: pydrake.multibody.tree.Frame_[float], forces: drake::multibody::MultibodyForces<double>) → None

Adds the spatial force on this body B, applied at point P and expressed in a frame E into forces.

Parameter context:
The context containing the current state of the model.
Parameter p_BP_E:
The position of point P in B, expressed in a frame E.
Parameter F_Bp_E:
The spatial force to be applied on body B at point P, expressed in frame E.
Parameter frame_E:
The expressed-in frame E.
Parameter forces:
A multibody forces objects that on output will have F_Bp_E added.
Raises:
  • RuntimeError if forces is nullptr or if it is not consistent
  • with the model to which this body belongs.
AddInForceInWorld(self: pydrake.multibody.tree.Body_[float], context: pydrake.systems.framework.Context_[float], F_Bo_W: pydrake.multibody.math.SpatialForce_[float], forces: drake::multibody::MultibodyForces<double>) → None

Adds the spatial force on this body B, applied at body B’s origin Bo and expressed in the world frame W into forces.

GetForceInWorld(self: pydrake.multibody.tree.Body_[float], context: pydrake.systems.framework.Context_[float], forces: drake::multibody::MultibodyForces<double>) → pydrake.multibody.math.SpatialForce_[float]

Gets the sptatial force on this body B from forces as F_BBo_W: applied at body B’s origin Bo and expressed in world world frame W.

body_frame(self: pydrake.multibody.tree.Body_[float]) → pydrake.multibody.tree.BodyFrame_[float]

Returns a const reference to the associated BodyFrame.

index(self: pydrake.multibody.tree.Body_[float]) → pydrake.multibody.tree.BodyIndex
model_instance(self: pydrake.multibody.tree.Body_[float]) → pydrake.multibody.tree.ModelInstanceIndex
name(self: pydrake.multibody.tree.Body_[float]) → str

Gets the name associated with this body.

pydrake.multibody.tree.FixedOffsetFrame

alias of pydrake.multibody.tree.FixedOffsetFrame_[float]

template pydrake.multibody.tree.FixedOffsetFrame_

Instantiations: FixedOffsetFrame_[float], FixedOffsetFrame_[AutoDiffXd], FixedOffsetFrame_[Expression]

class FixedOffsetFrame_[float]

Bases: pydrake.multibody.tree.Frame_[float]

%FixedOffsetFrame represents a material frame F whose pose is fixed with respect to a parent material frame P. The pose offset is given by a spatial transform X_PF, which is constant after construction. For instance, we could rigidly attach a frame F to move with a rigid body B at a fixed pose X_BF, where B is the BodyFrame associated with body B. Thus, the World frame pose X_WF of a FixedOffsetFrame F depends only on the World frame pose X_WP of its parent P, and the constant pose X_PF, with X_WF=X_WP*X_PF.

For more information about spatial transforms, see multibody_spatial_pose.

Template parameter T:
The scalar type. Must be a valid Eigen scalar.
pydrake.multibody.tree.ForceElement

alias of pydrake.multibody.tree.ForceElement_[float]

class pydrake.multibody.tree.ForceElementIndex

Type used to identify force elements by index within a multibody tree system.

is_valid(self: pydrake.multibody.tree.ForceElementIndex) → bool

Reports if the index is valid–the only operation on an invalid index that doesn’t throw an exception in Debug builds.

template pydrake.multibody.tree.ForceElement_

Instantiations: ForceElement_[float], ForceElement_[AutoDiffXd], ForceElement_[Expression]

class ForceElement_[float]

A ForceElement allows modeling state and time dependent forces in a MultibodyTree model. Examples of such forces are springs, dampers, drag and gravity. Forces that depend on accelerations such as virtual mass cannot be modeled with a ForceElement. This abstract class provides an API that all force elements subclasses must implement in order to be fully defined. These are:

  • CalcAndAddForceContribution(): computes the force contribution of a force element in a MultibodyTree model.
  • CalcPotentialEnergy(): computes a force element potential energy contribution.
  • CalcConservativePower(): computes the power generated by conservative forces.
  • CalcNonConservativePower(): computes the power dissipated by non-conservative forces.
Template parameter T:
The scalar type. Must be a valid Eigen scalar.
index(self: pydrake.multibody.tree.ForceElement_[float]) → pydrake.multibody.tree.ForceElementIndex
model_instance(self: pydrake.multibody.tree.ForceElement_[float]) → pydrake.multibody.tree.ModelInstanceIndex
pydrake.multibody.tree.Frame

alias of pydrake.multibody.tree.Frame_[float]

class pydrake.multibody.tree.FrameIndex

Type used to identify frames by index in a multibody tree system.

is_valid(self: pydrake.multibody.tree.FrameIndex) → bool

Reports if the index is valid–the only operation on an invalid index that doesn’t throw an exception in Debug builds.

template pydrake.multibody.tree.Frame_

Instantiations: Frame_[float], Frame_[AutoDiffXd], Frame_[Expression]

class Frame_[float]

%Frame is an abstract class representing a material frame (also called a physical frame), meaning that it is associated with a material point of a Body. A material frame can be used to apply forces and torques to a multibody system, and can be used as an attachment point for force-producing elements like joints, actuators, and constraints. Despite its name, Frame is not the most general frame representation in Drake; see FrameBase for a more-general discussion.

The pose and motion of a Frame object is always calculated relative to the BodyFrame of the body with which it is associated, and every Frame object can report which Body object that is. Concrete classes derived from Frame differ only in how those kinematic properties are calculated. For soft bodies that calculation may depend on the body’s deformation state variables. A Frame on a rigid body will usually have a fixed offset from its BodyFrame, but that is not required – a frame that moves with respect to its BodyFrame can still be a material frame on that rigid body.

As always in Drake, runtime numerical quantities are stored in a Context. A Frame object does not store runtime values, but provides methods for extracting frame-associated values (such as the Frame object’s kinematics) from a given Context.

Template parameter T:
The scalar type. Must be a valid Eigen scalar.
GetFixedPoseInBodyFrame(self: pydrake.multibody.tree.Frame_[float]) → pydrake.math.RigidTransform_[float]

Variant of CalcPoseInBodyFrame() that returns the fixed pose X_BF of this frame F in the body frame B associated with this frame.

Raises:
  • RuntimeError if called on a Frame that does not have a fixed
  • offset in the body frame.
body(self: pydrake.multibody.tree.Frame_[float]) → drake::multibody::Body<double>

Returns a const reference to the body associated to this Frame.

index(self: pydrake.multibody.tree.Frame_[float]) → pydrake.multibody.tree.FrameIndex
model_instance(self: pydrake.multibody.tree.Frame_[float]) → pydrake.multibody.tree.ModelInstanceIndex
name(self: pydrake.multibody.tree.Frame_[float]) → str

Returns the name of this frame. It may be empty if unnamed.

class pydrake.multibody.tree.JacobianWrtVariable

Enumeration that indicates whether the Jacobian is partial differentiation with respect to q̇ (time-derivatives of generalized positions) or with respect to v (generalized velocities).

Members:

kQDot : < J = ∂V/∂q̇

kV : < J = ∂V/∂v

kQDot = JacobianWrtVariable.kQDot
kV = JacobianWrtVariable.kV
name

(self – handle) -> str

pydrake.multibody.tree.Joint

alias of pydrake.multibody.tree.Joint_[float]

pydrake.multibody.tree.JointActuator

alias of pydrake.multibody.tree.JointActuator_[float]

class pydrake.multibody.tree.JointActuatorIndex

Type used to identify actuators by index within a multibody tree system.

is_valid(self: pydrake.multibody.tree.JointActuatorIndex) → bool

Reports if the index is valid–the only operation on an invalid index that doesn’t throw an exception in Debug builds.

template pydrake.multibody.tree.JointActuator_

Instantiations: JointActuator_[float], JointActuator_[AutoDiffXd], JointActuator_[Expression]

class JointActuator_[float]

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 parameter T:
The scalar type. Must be a valid Eigen scalar.

Instantiated templates for the following kinds of T’s are provided:

  • double
  • AutoDiffXd
  • symbolic::Expression

They are already available to link against in the containing library. No other values for T are currently supported.

index(self: pydrake.multibody.tree.JointActuator_[float]) → pydrake.multibody.tree.JointActuatorIndex
joint(self: pydrake.multibody.tree.JointActuator_[float]) → pydrake.multibody.tree.Joint_[float]

Returns a reference to the joint actuated by this JointActuator.

model_instance(self: pydrake.multibody.tree.JointActuator_[float]) → pydrake.multibody.tree.ModelInstanceIndex
name(self: pydrake.multibody.tree.JointActuator_[float]) → str

Returns the name of the actuator.

class pydrake.multibody.tree.JointIndex

Type used to identify joints by index within a multibody tree system.

is_valid(self: pydrake.multibody.tree.JointIndex) → bool

Reports if the index is valid–the only operation on an invalid index that doesn’t throw an exception in Debug builds.

template pydrake.multibody.tree.Joint_

Instantiations: Joint_[float], Joint_[AutoDiffXd], Joint_[Expression]

class Joint_[float]

A Joint models the kinematical relationship which characterizes the possible relative motion between two bodies. The two bodies connected by a Joint object are referred to as the parent and child bodies. Although the terms parent and child are sometimes used synonymously to describe the relationship between inboard and outboard bodies in multibody models, this usage is wholly unrelated and implies nothing about the inboard-outboard relationship between the bodies. A Joint is a model of a physical kinematic constraint between two bodies, a constraint that in the real physical system does not even allude to the ordering of the bodies.

In Drake we define a frame F rigidly attached to the parent body P with pose X_PF and a frame M rigidly attached to the child body B with pose X_BM. A Joint object specifies a kinematic relation between frames F and M, which in turn imposes a kinematic relation between bodies P and B.

Typical joints include the ball joint, to allow unrestricted rotations about a given point, the revolute joint, that constraints two bodies to rotate about a given common axis, etc.

Consider the following example to build a simple pendulum system:

MultibodyTree<double> model;
// ... Code here to setup quantities below as mass, com, etc. ...
const Body<double>& pendulum =
  model.AddBody<RigidBody>(SpatialInertia<double>(mass, com, unit_inertia));
// We will connect the pendulum body to the world using a RevoluteJoint.
// In this simple case the parent body P is the model's world body and frame
// F IS the world frame.
// Additionally, we need to specify the pose of frame M on the pendulum's
// body frame B.
// Say we declared and initialized X_BM...
const RevoluteJoint<double>& elbow =
  model.AddJoint<RevoluteJoint>(
    "Elbow",                /* joint name
    model.world_body(),     /* parent body
    {},                     /* frame F IS the world frame W
    pendulum,               /* child body, the pendulum
    X_BM,                   /* pose of frame M in the body frame B
    Vector3d::UnitZ());     /* revolute axis in this case

Warning

Do not ever attempt to instantiate and manipulate Joint objects on the stack; it will fail. Add joints to your model using the provided API MultibodyTree::AddJoint() as in the example above.

Template parameter T:
The scalar type. Must be a valid Eigen scalar.
acceleration_lower_limits(self: pydrake.multibody.tree.Joint_[float]) → numpy.ndarray[float64[m, 1]]

Returns the acceleration lower limits.

acceleration_upper_limits(self: pydrake.multibody.tree.Joint_[float]) → numpy.ndarray[float64[m, 1]]

Returns the acceleration upper limits.

child_body(self: pydrake.multibody.tree.Joint_[float]) → pydrake.multibody.tree.Body_[float]

Returns a const reference to the child body B.

frame_on_child(self: pydrake.multibody.tree.Joint_[float]) → pydrake.multibody.tree.Frame_[float]

Returns a const reference to the frame M attached on the child body B.

frame_on_parent(self: pydrake.multibody.tree.Joint_[float]) → pydrake.multibody.tree.Frame_[float]

Returns a const reference to the frame F attached on the parent body P.

index(self: pydrake.multibody.tree.Joint_[float]) → pydrake.multibody.tree.JointIndex
model_instance(self: pydrake.multibody.tree.Joint_[float]) → pydrake.multibody.tree.ModelInstanceIndex
name(self: pydrake.multibody.tree.Joint_[float]) → str

Returns the name of this joint.

num_positions(self: pydrake.multibody.tree.Joint_[float]) → int

Returns the number of generalized positions describing this joint.

num_velocities(self: pydrake.multibody.tree.Joint_[float]) → int

Returns the number of generalized velocities describing this joint.

parent_body(self: pydrake.multibody.tree.Joint_[float]) → pydrake.multibody.tree.Body_[float]

Returns a const reference to the parent body P.

position_lower_limits(self: pydrake.multibody.tree.Joint_[float]) → numpy.ndarray[float64[m, 1]]

@name Methods to get and set the limits of this joint. For position limits, the layout is the same as the generalized position’s. For velocity and acceleration limits, the layout is the same as the generalized velocity’s. A limit with value +/- ∞ implies no upper or lower limit. Returns the position lower limits.

position_start(self: pydrake.multibody.tree.Joint_[float]) → int

Returns the index to the first generalized position for this joint within the vector q of generalized positions for the full multibody system.

position_upper_limits(self: pydrake.multibody.tree.Joint_[float]) → numpy.ndarray[float64[m, 1]]

Returns the position upper limits.

velocity_lower_limits(self: pydrake.multibody.tree.Joint_[float]) → numpy.ndarray[float64[m, 1]]

Returns the velocity lower limits.

velocity_start(self: pydrake.multibody.tree.Joint_[float]) → int

Returns the index to the first generalized velocity for this joint within the vector v of generalized velocities for the full multibody system.

velocity_upper_limits(self: pydrake.multibody.tree.Joint_[float]) → numpy.ndarray[float64[m, 1]]

Returns the velocity upper limits.

class pydrake.multibody.tree.ModelInstanceIndex

Type used to identify model instances by index within a multibody tree system.

is_valid(self: pydrake.multibody.tree.ModelInstanceIndex) → bool

Reports if the index is valid–the only operation on an invalid index that doesn’t throw an exception in Debug builds.

pydrake.multibody.tree.MultibodyForces

alias of pydrake.multibody.tree.MultibodyForces_[float]

template pydrake.multibody.tree.MultibodyForces_

Instantiations: MultibodyForces_[float], MultibodyForces_[AutoDiffXd], MultibodyForces_[Expression]

class MultibodyForces_[float]

A class to hold a set of forces applied to a MultibodyTree system. Forces can include generalized forces as well as body spatial forces.

Template parameter T:
The scalar type. Must be a valid Eigen scalar.

Instantiated templates for the following kinds of T’s are provided:

  • double
  • AutoDiffXd
  • symbolic::Expression

They are already available to link against in the containing library. No other values for T are currently supported.

AddInForces(self: pydrake.multibody.tree.MultibodyForces_[float], addend: pydrake.multibody.tree.MultibodyForces_[float]) → None

Adds into this the force contribution stored in addend.

SetZero(self: pydrake.multibody.tree.MultibodyForces_[float]) → pydrake.multibody.tree.MultibodyForces_[float]

Sets this to store zero forces (no applied forces).

generalized_forces(self: pydrake.multibody.tree.MultibodyForces_[float]) → numpy.ndarray[float64[m, 1]]

(Advanced) Returns a constant reference to the vector of generalized forces stored by this forces object.

mutable_generalized_forces(self: pydrake.multibody.tree.MultibodyForces_[float]) → numpy.ndarray[float64[m, 1]]

(Advanced) Mutable version of generalized_forces().

pydrake.multibody.tree.PrismaticJoint

alias of pydrake.multibody.tree.PrismaticJoint_[float]

template pydrake.multibody.tree.PrismaticJoint_

Instantiations: PrismaticJoint_[float], PrismaticJoint_[AutoDiffXd], PrismaticJoint_[Expression]

class PrismaticJoint_[float]

Bases: pydrake.multibody.tree.Joint_[float]

This Joint allows two bodies to translate relative to one another along a common axis. That is, given a frame F attached to the parent body P and a frame M attached to the child body B (see the Joint class’s documentation), this Joint allows frames F and M to translate with respect to each other along an axis â. The translation distance is defined positive when child body B translates along the direction of â. Axis â is constant and has the same measures in both frames F and M, that is, â_F = â_M.

Template parameter T:
The scalar type. Must be a valid Eigen scalar.

Instantiated templates for the following kinds of T’s are provided:

  • double
  • AutoDiffXd
  • symbolic::Expression

They are already available to link against in the containing library. No other values for T are currently supported.

get_translation(self: pydrake.multibody.tree.PrismaticJoint_[float], context: pydrake.systems.framework.Context_[float]) → float

Gets the translation distance of this mobilizer from context.

Parameter context:
The context of the MultibodyTree this joint belongs to.
Returns:The translation coordinate of this joint read from context.
get_translation_rate(self: pydrake.multibody.tree.PrismaticJoint_[float], context: pydrake.systems.framework.Context_[float]) → float

Gets the rate of change, in meters per second, of this joint’s translation distance (see get_translation()) from context.

Parameter context:
The context of the MultibodyTree this joint belongs to.
Returns:The rate of change of this joint’s translation read from context.
set_random_translation_distribution(self: pydrake.multibody.tree.PrismaticJoint_[float], translation: pydrake.symbolic.Expression) → None
set_translation(self: pydrake.multibody.tree.PrismaticJoint_[float], context: pydrake.systems.framework.Context_[float], translation: float) → pydrake.multibody.tree.PrismaticJoint_[float]

Sets context so that the generalized coordinate corresponding to the translation distance of this joint equals translation.

Parameter context:
The context of the MultibodyTree this joint belongs to.
Parameter translation:
The desired translation in meters to be stored in context.
Returns:a constant reference to this joint.
set_translation_rate(self: pydrake.multibody.tree.PrismaticJoint_[float], context: pydrake.systems.framework.Context_[float], translation_dot: float) → pydrake.multibody.tree.PrismaticJoint_[float]

Sets the rate of change, in meters per second, of this joint’s translation distance to translation_dot. The new rate of change translation_dot gets stored in context.

Parameter context:
The context of the MultibodyTree this joint belongs to.
Parameter translation_dot:
The desired rate of change of this joints’s translation in meters per second.
Returns:a constant reference to this joint.
pydrake.multibody.tree.RevoluteJoint

alias of pydrake.multibody.tree.RevoluteJoint_[float]

template pydrake.multibody.tree.RevoluteJoint_

Instantiations: RevoluteJoint_[float], RevoluteJoint_[AutoDiffXd], RevoluteJoint_[Expression]

class RevoluteJoint_[float]

Bases: pydrake.multibody.tree.Joint_[float]

This Joint allows two bodies to rotate relatively to one another around a common axis. That is, given a frame F attached to the parent body P and a frame M attached to the child body B (see the Joint class’s documentation), this Joint allows frames F and M to rotate with respect to each other about an axis â. The rotation angle’s sign is defined such that child body B rotates about axis â according to the right hand rule, with thumb aligned in the axis direction. Axis â is constant and has the same measures in both frames F and M, that is, â_F = â_M.

Template parameter T:
The scalar type. Must be a valid Eigen scalar.

Instantiated templates for the following kinds of T’s are provided:

  • double
  • AutoDiffXd
  • symbolic::Expression

They are already available to link against in the containing library. No other values for T are currently supported.

get_angle(self: pydrake.multibody.tree.RevoluteJoint_[float], context: pydrake.systems.framework.Context_[float]) → float

Gets the rotation angle of this mobilizer from context.

Parameter context:
The context of the MultibodyTree this joint belongs to.
Returns:The angle coordinate of this joint stored in the context.
set_angle(self: pydrake.multibody.tree.RevoluteJoint_[float], context: pydrake.systems.framework.Context_[float], angle: float) → pydrake.multibody.tree.RevoluteJoint_[float]

Sets the context so that the generalized coordinate corresponding to the rotation angle of this joint equals angle.

Parameter context:
The context of the MultibodyTree this joint belongs to.
Parameter angle:
The desired angle in radians to be stored in context.
Returns:a constant reference to this joint.
set_random_angle_distribution(self: pydrake.multibody.tree.RevoluteJoint_[float], angle: pydrake.symbolic.Expression) → None
pydrake.multibody.tree.RigidBody

alias of pydrake.multibody.tree.RigidBody_[float]

template pydrake.multibody.tree.RigidBody_

Instantiations: RigidBody_[float], RigidBody_[AutoDiffXd], RigidBody_[Expression]

class RigidBody_[float]

Bases: pydrake.multibody.tree.Body_[float]

The term rigid body implies that the deformations of the body under consideration are so small that they have no significant effect on the overall motions of the body and therefore deformations can be neglected. If deformations are neglected, the distance between any two points on the rigid body remains constant at all times. This invariance of the distance between two arbitrary points is often taken as the definition of a rigid body in classical treatments of multibody mechanics [Goldstein 2001]. It can be demonstrated that the unconstrained three-dimensional motions of a rigid body can be described by six coordinates and thus it is often said that a free body in space has six degrees of freedom. These degrees of freedom obey the Newton-Euler equations of motion. However, within a MultibodyTree, a RigidBody is not free in space; instead, it is assigned a limited number of degrees of freedom (0-6) with respect to its parent body in the multibody tree by its Mobilizer (also called a “tree joint” or “inboard joint”). Additional constraints on permissible motion can be added using Constraint objects to remove more degrees of freedom.

  • [Goldstein 2001] H Goldstein, CP Poole, JL Safko, Classical Mechanics
    (3rd Edition), Addison-Wesley, 2001.
Template parameter T:
The scalar type. Must be a valid Eigen scalar.

Instantiated templates for the following kinds of T’s are provided:

  • double
  • AutoDiffXd
  • symbolic::Expression

They are already available to link against in the containing library. No other values for T are currently supported.

pydrake.multibody.tree.SpatialInertia

alias of pydrake.multibody.tree.SpatialInertia_[float]

template pydrake.multibody.tree.SpatialInertia_

Instantiations: SpatialInertia_[float], SpatialInertia_[AutoDiffXd], SpatialInertia_[Expression]

class SpatialInertia_[float]

This class represents the physical concept of a Spatial Inertia. A spatial inertia (or spatial mass matrix) encapsulates the mass, center of mass, and rotational inertia of the mass distribution of a body or composite body S, where with “composite body” we mean a collection of bodies welded together containing at least one body (throughout this documentation “body” is many times used instead of “composite body” but the same concepts apply to a collection of bodies as well.) A spatial inertia is an element of ℝ⁶ˣ⁶ that is symmetric, and positive semi-definite. It logically consists of 3x3 sub-matrices arranged like so, [Jain 2010]:

Spatial mass matrix
          ------------ ------------
       0 |            |            |
       1 |    I_SP    | m p_PScm×  |
       2 |            |            |
          ------------ ------------
       3 |            |            |
       4 | -m p_PScm× |     m Id   |
       5 |            |            |
          ------------ ------------
               Symbol: M

where, with the monogram notation described in multibody_spatial_inertia, I_SP is the rotational inertia of body or composite body S computed about a point P, m is the mass of this composite body, p_PScm is the position vector from point P to the center of mass Scm of the composite body S with p_PScm× denoting its skew-symmetric cross product matrix (defined such that b = a.cross(b)), and Id is the identity matrix in ℝ³ˣ³. See Section 2.1, p. 17 of [Jain 2010]. The logical arrangement as shown above is chosen to be consistent with our logical arrangement for spatial vectors as documented in multibody_spatial_algebra for which the rotational component comes first followed by the translational component.

In typeset material we use the symbol \([M^{S/P}]_E\) to represent the spatial inertia of a body or composite body S about point P, expressed in frame E. For this inertia, the monogram notation reads M_SP_E. If the point P is fixed to a body B, we write that point as \(B_P\) which appears in code and comments as Bp. So if the body or composite body is B and the about point is Bp, the monogram notation reads M_BBp_E, which can be abbreviated to M_Bp_E since the about point Bp also identifies the body. Common cases are that the about point is the origin Bo of the body, or it’s the center of mass Bcm for which the rotational inertia in monogram notation would read as I_Bo_E and I_Bcm_E, respectively. Given M_BP_E (\([M^{B/P}]_E\)), the rotational inertia of this spatial inertia is I_BP_E (\([I^{B/P}]_E\)) and the position vector of the center of mass measured from point P and expressed in E is p_PBcm_E (\([^Pp^{B_{cm}}]_E\)).

Note

This class does not implement any mechanism to track the frame E in which a spatial inertia is expressed or about what point is computed. Methods and operators on this class have no means to determine frame consistency through operations. It is therefore the responsibility of users of this class to keep track of frames in which operations are performed. We suggest doing that using disciplined notation, as described above.

Note

Several methods in this class throw a RuntimeError for invalid rotational inertia operations in debug releases only. This provides speed in a release build while facilitating debugging in debug builds. In addition, these validity tests are only performed for scalar types for which drake::scalar_predicate<T>::is_bool is True. For instance, validity checks are not performed when T is symbolic::Expression.

  • [Jain 2010] Jain, A., 2010. Robot and multibody dynamics: analysis and
    algorithms. Springer Science & Business Media.
Template parameter T:
The underlying scalar type. Must be a valid Eigen scalar.

Instantiated templates for the following kinds of T’s are provided:

  • double
  • AutoDiffXd
  • symbolic::Expression

They are already available to link against in the containing library.

pydrake.multibody.tree.UniformGravityFieldElement

alias of pydrake.multibody.tree.UniformGravityFieldElement_[float]

template pydrake.multibody.tree.UniformGravityFieldElement_

Instantiations: UniformGravityFieldElement_[float], UniformGravityFieldElement_[AutoDiffXd], UniformGravityFieldElement_[Expression]

class UniformGravityFieldElement_[float]

Bases: pydrake.multibody.tree.ForceElement_[float]

This ForceElement allows modeling the effect of a uniform gravity field as felt by bodies on the surface of the Earth. This gravity field acts on all bodies in the MultibodyTree model.

Template parameter T:
The scalar type. Must be a valid Eigen scalar.

Instantiated templates for the following kinds of T’s are provided:

  • double
  • AutoDiffXd
  • symbolic::Expression

They are already available to link against in the containing library. No other values for T are currently supported.

gravity_vector(self: pydrake.multibody.tree.UniformGravityFieldElement_[float]) → numpy.ndarray[float64[3, 1]]

Returns the acceleration of the gravity vector in m/s², expressed in the world frame W.

set_gravity_vector(self: pydrake.multibody.tree.UniformGravityFieldElement_[float], arg0: numpy.ndarray[float64[3, 1]]) → None

Sets the acceleration of gravity vector, expressed in the world frame W in m/s².

pydrake.multibody.tree.UnitInertia

alias of pydrake.multibody.tree.UnitInertia_[float]

template pydrake.multibody.tree.UnitInertia_

Instantiations: UnitInertia_[float], UnitInertia_[AutoDiffXd], UnitInertia_[Expression]

class UnitInertia_[float]

This class is used to represent rotational inertias for unit mass bodies. Therefore, unlike RotationalInertia whose units are kg⋅m², the units of a UnitInertia are those of length squared. A unit inertia is a useful concept to represent the geometric distribution of mass in a body regardless of the actual value of the body mass. The rotational inertia of a body can therefore be obtained by multiplying its unit inertia by its mass. Unit inertia matrices can also be called gyration matrices and therefore we choose to represent them in source code notation with the capital letter G. In contrast, the capital letter I is used to represent non-unit mass rotational inertias. This class restricts the set of allowed operations on a unit inertia to ensure the unit-mass invariant. For instance, multiplication by a scalar can only return a general RotationalInertia but not a UnitInertia.

Note

This class has no means to check at construction from user provided parameters whether it actually represents the unit inertia or gyration matrix of a unit-mass body. However, as previously noted, once a unit inertia is created, a number of operations are disallowed to ensure the unit-mass invariant. Also notice that once a unit inertia is created, it is the unit inertia of some body, perhaps with scaled geometry from the user’s intention.

Template parameter T:
The underlying scalar type. Must be a valid Eigen scalar.

Instantiated templates for the following kinds of T’s are provided:

  • double
  • AutoDiffXd
  • symbolic::Expression

They are already available to link against in the containing library.

pydrake.multibody.tree.WeldJoint

alias of pydrake.multibody.tree.WeldJoint_[float]

template pydrake.multibody.tree.WeldJoint_

Instantiations: WeldJoint_[float], WeldJoint_[AutoDiffXd], WeldJoint_[Expression]

class WeldJoint_[float]

Bases: pydrake.multibody.tree.Joint_[float]

This Joint fixes the relative pose between two frames as if “welding” them together.

Template parameter T:
The scalar type. Must be a valid Eigen scalar.

Instantiated templates for the following kinds of T’s are provided:

  • double
  • AutoDiffXd
  • symbolic::Expression

They are already available to link against in the containing library. No other values for T are currently supported.

pydrake.multibody.tree.world_index() → pydrake.multibody.tree.BodyIndex

For every MultibodyTree the world body always has this unique index and it is always zero.