|
spatial-dyn
|
#include <rigid_body.h>
Public Member Functions | |
| RigidBody ()=default | |
| RigidBody (const std::string &name) | |
| int | id () const |
| void | set_id (int id) |
| int | id_parent () const |
| void | set_id_parent (int id_parent) |
| const Eigen::Isometry3d & | T_to_parent () const |
| template<typename Derived > | |
| void | set_T_to_parent (const Eigen::RotationBase< Derived, 3 > &ori_in_parent, const Eigen::Vector3d &pos_in_parent) |
| void | set_T_to_parent (const Eigen::Isometry3d &T_to_parent) |
| const SpatialInertiad & | inertia () const |
| void | set_inertia (double mass, const Eigen::Vector3d &com, const Eigen::Vector6d &I_com_flat) |
| void | set_inertia (const SpatialInertiad &inertia) |
| const Joint & | joint () const |
| void | set_joint (const Joint &joint) |
Public Attributes | |
| std::string | name |
| std::vector< Graphics > | graphics |
Rigid body struct for spatial_dyn.
Comprised of an articulated joint and the attached rigid body.
|
default |
Default constructor.
|
inline |
Constructor that sets the name of the rigid body.
| name | Name of the rigid body. |
|
inline |
|
inline |
|
inline |
|
inline |
| void spatial_dyn::RigidBody::set_inertia | ( | const SpatialInertiad & | inertia | ) |
Set the spatial inertia of the rigid body.
| inertia | Spatial inertia of the rigid body. |
| void spatial_dyn::RigidBody::set_inertia | ( | double | mass, |
| const Eigen::Vector3d & | com, | ||
| const Eigen::Vector6d & | I_com_flat | ||
| ) |
Set the spatial inertia of the rigid body.
| mass | Mass of the rigid body. |
| com | Center of mass of the rigid body. |
| I_com_flat | Inertia of the rigid body as a flat vector {I_xx, I_xy, I_xz, I_yy, I_yz, I_zz}`. |
|
inline |
Set the joint attached to the rigid body.
| joint | Joint. |
|
inline |
Set the fixed transform from the rigid body's frame to its parent's frame when the joint position is 0.
| T_to_parent | Transform from the rigid body frame to its parent's frame. |
|
inline |
Set the fixed transform from the rigid body's frame to its parent's frame when the joint position is 0.
| ori_in_parent | Orientation of the rigid body in its parent's frame. |
| pos_in_parent | Position of the rigid body in its parent's frame. |
|
inline |
|
mutable |
Graphics for the rigid body.
|
mutable |
Name of the rigid body for debugging purposes.