#include <RigidBody.h>
Inheritance diagram for Physsim::RigidBody:

Public Member Functions | |
| RigidBody () | |
| Default constructor. | |
| virtual void | load_state (BaseConstPtr clone, bimap< BasePtr, BasePtr > *correspondence=NULL) |
| Loads the state of this body from another RigidBody object. | |
| virtual bool | is_struct_identical (BaseConstPtr object) const |
| Verifies that two object structures are identical. | |
| virtual void | save_state (BasePtr object, bimap< BasePtr, BasePtr > *correspondence=NULL) const |
| Saves the state of this body to another RigidBody object with the same structure. | |
| virtual void | clone (BasePtr &cloned, bimap< BasePtr, BasePtr > *obj_map=NULL) const |
| Clones this body. | |
| void | set_avel (const Vector3 &avel, bool update_angular_momentum=false) |
| Sets the angular velocity, optionally updating the angular momentum. | |
| void | set_qvel (const Quat &qd, bool update_angular_momentum=false) |
| Sets the differential quaternion of this body. | |
| void | set_lvel (const Vector3 &lvel, bool update_linear_momentum=false) |
| Sets the linear velocity of this body. | |
| virtual VectorN | get_state_deriv () |
| Gets the derivative of the state. | |
| virtual void | set_state (const VectorN &state) |
| Sets the current state. | |
| virtual VectorN | get_state () |
| Gets the current state. | |
| void | add_force (const Vector3 &force) |
| Adds a force to the center-of-mass of this link. | |
| void | add_torque (const Vector3 &torque) |
| Adds a torque to the center-of-mass of this body. | |
| void | set_transform (const Matrix4 &transform) |
| Sets the current 4x4 homogeneous transformation for this rigid body. | |
| void | set_transform (const Quat &q, const Vector3 &x) |
| Sets the current 4x4 homogeneous transformation for this body using quaternion and vector position. | |
| void | set_inertia (const Matrix3 &m) |
| Sets the inertia tensor for this body. | |
| void | set_enabled (bool flag) |
| Sets the body to enabled / disabled. | |
| void | set_orientation (const Quat &q) |
| Sets the orientation for this rigid body. | |
| void | set_position (const Vector3 &pos) |
| Sets the position for this rigid body. | |
| void | remove_collision_geometry (CollisionGeometryPtr g) |
| Removes the specified geometry from the rigid body. | |
| void | add_force (const Vector3 &f, const Vector3 &p) |
| Adds a force at a particular point on the body. | |
| void | apply_impulse (const Vector3 &j, const Vector3 &p) |
| Applies a linear impulse to this link at the specified point. | |
| void | apply_impulse (const Vector3 &j, const Vector3 &k, const Vector3 &p) |
| Applies linear and angular impulses to this link at the specified point. | |
| void | set_mass (Real mass) |
| Sets the mass of this body. | |
| Matrix3 | det_collision_matrix (const Matrix3 &contact_frame_transpose, const Vector3 &contact_point) |
| Computes the collision matrix K (as described in [Mirtich, 1996], p. 61, for this body only. | |
| virtual void | transform (const Matrix4 &transform) |
| Transforms the dynamic body by the given transform. | |
| virtual void | calc_fwd_dyn () |
| Computes the forward dynamics for this body. | |
| std::list< CollisionGeometryPtr > | get_all_collision_geometries () const |
| Gets all collision geometries of this rigid body (including all descendants of collision geometries). | |
| void | set_linear_momentum (const Vector3 &P, bool update_velocity=false) |
| Sets the linear momentum, optionally updating the linear velocity. | |
| void | set_angular_momentum (const Vector3 &L, bool update_velocity=false) |
| Sets the angular momentum, optionally updating the angular velocity. | |
| virtual void | set_visualization_data (SoNode *vdata) |
| Sets the visualization data from a node. | |
| virtual void | load_from_xml (XMLTreeConstPtr node, std::map< std::string, BasePtr > &id_map) |
| Implements Base::load_from_xml(). | |
| virtual void | save_to_xml (XMLTreePtr node, std::list< BaseConstPtr > &shared_objects) const |
| Implements Base::save_to_xml(). | |
| Real | calc_point_accel (const Vector3 &point, const Vector3 &dir) |
| Calculates the acceleration at a point (typically somewhere on this body) along the desired direction. | |
| Real | calc_point_vel (const Vector3 &point, const Vector3 &dir) const |
| Calculates the velocity of a point on this rigid body in a given direction. | |
| virtual void | output_object_state (std::ostream &out) const |
| Outputs the object state to the specified stream. | |
| bool | remove_child_link (RigidBodyConstPtr link) |
| Removes the specified child link from this link. | |
| Vector3 | get_inner_joint_to_com_vector_global () const |
| Gets the vector that points from the inboard joint on this link to the center of mass on the link. | |
| void | set_inner_joint_to_com_vector_link (const Vector3 &v) |
| Sets the vector that points from the inboard joint on this link to the center of mass on the link. | |
| void | set_inner_joint_to_com_vector_global (const Vector3 &v) |
| Sets the vector that points from the inboard joint on this link to the center of mass on the link. | |
| const Vector3 & | get_com_to_outer_joint_vector_link (RigidBodyConstPtr child) const |
| Gets the vector that points from the center of mass of this link to the inboard joint of the specified child link. | |
| Vector3 | get_com_to_outer_joint_vector_global (RigidBodyConstPtr child) const |
| Gets the vector that points from the center of mass of this link to the inboard joint of the i'th child link. | |
| void | add_child_link_global (RigidBodyPtr child, const Vector3 &v) |
| Adds a child link to the list of children of this link. | |
| bool | is_child_link (RigidBodyConstPtr query) const |
| Determines whether the given link is a child link of this. | |
| void | reset_spatial_transforms () |
| Resets all spatial computations. | |
| const SMatrix6 & | get_spatial_transform_forward () |
| Returns the spatial transform from this link's parent to this link. | |
| const SMatrix6 & | get_spatial_transform_backward () |
| Returns the spatial transform from this link to this link's parent. | |
| const SMatrix6 & | get_spatial_transform_link_to_global () |
| Returns the spatial transform from this link to the global coordinate system. | |
| const SMatrix6 & | get_spatial_transform_global_to_link () |
| Returns the spatial transform from the global coordinates system to this link. | |
| SVector6 | get_spatial_accel (ReferenceFrameType rftype) |
| Gets the spatial acceleration for this link. | |
| void | set_spatial_accel (const SVector6 &a, ReferenceFrameType rftype) |
| Sets the spatial acceleration. | |
| SVector6 | get_spatial_velocity (ReferenceFrameType rftype) |
| Gets the spatial velocity for this link. | |
| void | set_spatial_velocity (const SVector6 &v, ReferenceFrameType rftype) |
| Sets the spatial velocity. | |
| std::list< RigidBodyPtr > | get_child_links () const |
| Gets a list of child links. | |
| void | add_child_link_link (RigidBodyPtr l, const Vector3 &com_to_child_inner_joint_vec_link) |
| Adds a child link to the list of children of this link. | |
| void | set_inner_joint (JointPtr j) |
| Sets the inner joint for this link. | |
| void | set_parent_link (RigidBodyPtr l) |
| Sets the parent of this link; set to NULL to indicate no parent. | |
| RigidBodyPtr | get_this () |
| Gets the shared pointer for this. | |
| RigidBodyConstPtr | get_this () const |
| Gets the shared const pointer for this. | |
| const Matrix4 & | get_transform () const |
| Gets the current transform of this body. | |
| Real | get_mass () const |
| Gets the mass of this body. | |
| Real | get_mass_inv () const |
| Gets the inverse mass of this body. | |
| const Matrix3 & | get_inertia () const |
| Gets the 3x3 inertia tensor of this body. | |
| const Matrix3 & | get_inertia_inv () const |
| Gets the inverse of the 3x3 inertia tensor of this body. | |
| const Vector3 & | get_position () const |
| Gets the position of this body. | |
| const Quat & | get_orientation () const |
| Gets the quaternion orientation of this body. | |
| const Vector3 & | get_lvel () const |
| Gets the linear velocity of this body. | |
| const Vector3 & | get_avel () const |
| Gets the angular velocity of this body. | |
| const Quat & | get_qvel () const |
| Gets the differential quaternion of this body. | |
| const Vector3 & | get_laccel () |
| Gets the linear acceleration of this body. | |
| const Vector3 & | get_aaccel () |
| Gets the angular acceleration of this body. | |
| void | set_aaccel (const Vector3 &a) |
| Sets the angular acceleration of this link. | |
| void | set_laccel (const Vector3 &a) |
| Sets the angular acceleration of this link. | |
| const SMatrix6 & | get_spatial_iso_inertia_link () |
| Gets the spatial isolated inertia of this link, in link coordinates. | |
| void | reset_accumulators () |
| Resets the force and torque accumulators of this body. | |
| const Vector3 & | sum_forces () const |
| Gets the sum of forces on this body. | |
| const Vector3 & | sum_torques () const |
| Gets the sum of torques on this body. | |
| bool | is_enabled () const |
| Gets whether this body is enabled. | |
| unsigned | num_collision_geometries () const |
| Gets the number of collision geometries for this body. | |
| void | add_collision_geometry (CollisionGeometryPtr g) |
| Adds a collision geometry for this body. | |
| void | remove_collision_geometry (unsigned i) |
| Removes a collision geometry of this body. | |
| void | clear_collision_geometries () |
| Clears the set of collision geometries. | |
| CollisionGeometryPtr | get_collision_geometry (unsigned i) |
| Gets the specified collision geometry of this body. | |
| const std::vector< CollisionGeometryPtr > & | get_collision_geometries () const |
| Gets all collision geometries of this body. | |
| const Vector3 & | get_linear_momentum () const |
| Gets the linear momentum of this body. | |
| void | update_linear_momentum () |
| Updates the linear momentum of this body using the linear velocity. | |
| const Vector3 & | get_angular_momentum () const |
| Gets the angular momentum of this body. | |
| void | update_angular_momentum () |
| Updates the angular momentum of this body using the angular velocity. | |
| boost::weak_ptr< ArticulatedBody > | get_articulated_body () const |
| Gets the articulated body corresponding to this body. | |
| void | set_articulated_body (boost::weak_ptr< ArticulatedBody > body) |
| Sets the articulated body corresponding to this body. | |
|
const std::map< RigidBodyPtr, Vector3 > & | get_child_link_map () const |
| Returns the map of child links to their corresponding vector from this link's com to the child link's com, in this link's frame. | |
| bool | is_base () const |
| Determines whether this link is the base (faster than get_parent_link() == NULL). | |
| const Vector3 & | get_inner_joint_to_com_vector_link () const |
| Gets the vector that points from the inboard joint on this link to the center of mass on the link. | |
| boost::weak_ptr< Joint > | get_inner_joint () const |
| Gets the inner joint for this link. | |
| boost::weak_ptr< RigidBody > | get_parent_link () const |
| Gets the parent link of this link; returns NULL if there is no parent. | |
| unsigned | num_child_links () const |
| Gets the number of child links of this link. | |
| bool | is_end_effector () const |
| Gets whether this body is an end-effector (i.e., the number of child links is zero) in an articulated body. | |
| void | set_child_link_link (RigidBodyPtr child, const Vector3 &com_to_inner_joint_vec_link) |
| Adds a child link to the list of children of this link. | |
| void | set_child_link_global (RigidBodyPtr child, const Vector3 &com_to_inner_joint_vec_global) |
| Sets a child link to the list of children of this link. | |
| void | clear_child_links () |
| Removes all child links from this link. | |
| unsigned | get_index () |
| Gets the link index (returns std::numeric_limits<unsigned>::max() if not set). | |
| void | set_index (unsigned index) |
| Sets the link index. | |
Static Public Member Functions | |
| static Real | calc_sep_accel (RigidBody &rb1, RigidBody &rb2, const Vector3 &point, const Vector3 &dir, const Vector3 &dir_dot) |
| Calculates the separation acceleration of a common point on two bodies along the desired direction. | |
Contains information needed to represent a rigid body, including position and velocity (both linear and angular), mass, center of mass, inertia matrix, collision data, and visualization data. This class is used for both non-articulated and articulated rigid bodies, though not all member data may be used in the latter.
| RigidBody::RigidBody | ( | ) |
Default constructor.
Constructs a rigid body with zero mass, zero inertia tensor, and center of mass at [0,0,0] with position at [0,0,0], identity orientation, and zero linear and angular velocity. Body is enabled by default.
| void RigidBody::load_state | ( | BaseConstPtr | object, | |
| bimap< BasePtr, BasePtr > * | correspondence = NULL | |||
| ) | [virtual] |
Loads the state of this body from another RigidBody object.
The structure of the two rigid bodies must be identical -- specifically, both must have the same number of collision geometries (each of which has identical structure as well) and both must have one/no pointer to an articulated body.
Reimplemented from Physsim::Visualizable.
| void RigidBody::save_state | ( | BasePtr | object, | |
| bimap< BasePtr, BasePtr > * | correspondence = NULL | |||
| ) | const [virtual] |
Saves the state of this body to another RigidBody object with the same structure.
The structure of the two rigid bodies must be identical -- specifically, both must have the same number of collision geometries (each of which has identical structure as well) and both must have one/no pointer to an articulated body.
Reimplemented from Physsim::Visualizable.
| void RigidBody::clone | ( | BasePtr & | cloned, | |
| bimap< BasePtr, BasePtr > * | object_map = NULL | |||
| ) | const [virtual] |
Clones this body.
Performs a shallow copy of the underlying collision geometry and visualization data.
Reimplemented from Physsim::Visualizable.
| void RigidBody::set_qvel | ( | const Quat & | qd, | |
| bool | update_ang_momentum = false | |||
| ) |
Sets the differential quaternion of this body.
| VectorN RigidBody::get_state_deriv | ( | ) | [virtual] |
Gets the derivative of the state.
If the body is disabled, the derivative is a zero vector.
| return | a 13-dimensional vector partitioned as follows: 0-2 linear velocity 3-6 angular velocity (quaternion form) 7-9 cumulative force vector <br / 10-12 cumulative torque vector |
Implements Physsim::DynamicBody.
| void RigidBody::set_state | ( | const VectorN & | state | ) | [virtual] |
Sets the current state.
| state | a 13-dimensional vector, partitioned as follows: 0-2 position of center of mass 3-6 quaternion orientation of body 7-9 linear momentum of body 10-12 angular momentum of body |
Implements Physsim::DynamicBody.
| VectorN RigidBody::get_state | ( | ) | [virtual] |
Gets the current state.
Implements Physsim::DynamicBody.
| void RigidBody::add_force | ( | const Vector3 & | force | ) |
Adds a force to the center-of-mass of this link.
The frame of the applied force is centered at the center-of-mass of the body and is aligned with the global frame.
| void RigidBody::add_torque | ( | const Vector3 & | torque | ) |
Adds a torque to the center-of-mass of this body.
The frame of the applied torque is centered at the center-of-mass of the body and is aligned with the global frame.
| void RigidBody::set_transform | ( | const Matrix4 & | T | ) |
Sets the current 4x4 homogeneous transformation for this rigid body.
Also updates the transforms for associated visualization and collision data.
| void RigidBody::set_enabled | ( | bool | flag | ) |
Sets the body to enabled / disabled.
If the body is disabled, the linear and angular velocity are set to zero, and the body will not be updated if it is attempted to integrate its equations of motion.
| void RigidBody::set_orientation | ( | const Quat & | q | ) |
Sets the orientation for this rigid body.
Also updates the transforms for associated visualization and collision data.
| void RigidBody::set_position | ( | const Vector3 & | v | ) |
Sets the position for this rigid body.
Also updates the transforms for associated visualization and collision data.
Adds a force at a particular point on the body.
The frame of the applied force is centered at p and is aligned with the global frame.
| f | the force | |
| p | the position on the body in world coordinates (i.e., not relative to the center-of-mass) |
Applies a linear impulse to this link at the specified point.
| j | the linear component of the impulse | |
| k | the angular component of the impulse | |
| p | the point (global frame) at which the impulse is to be applied |
Applies linear and angular impulses to this link at the specified point.
| j | the linear component of the impulse | |
| k | the angular component of the impulse | |
| p | the point (global frame) at which the impulse is to be applied |
| Matrix3 RigidBody::det_collision_matrix | ( | const Matrix3 & | contact_frame_transpose, | |
| const Vector3 & | contact_point | |||
| ) |
Computes the collision matrix K (as described in [Mirtich, 1996], p. 61, for this body only.
| contact_frame_transpose | the transpose of the contact frame | |
| contact_point | the point of contact |
Calculates the acceleration at a point (typically somewhere on this body) along the desired direction.
| point | the point in the global frame | |
| dir | the direction in which acceleration is to be computed | |
| dir_dot | the derivative of the direction in which acceleration is to be computed |
| void RigidBody::output_object_state | ( | std::ostream & | out | ) | const [virtual] |
Outputs the object state to the specified stream.
This method outputs all of the low-level details to the stream; if serialization is desired, use save_to_xml() instead.
Reimplemented from Physsim::Base.
| bool RigidBody::remove_child_link | ( | RigidBodyConstPtr | child | ) |
Removes the specified child link from this link.
Also removes the associated _com_ to outboard vector. Returns true if the link was found.
| Vector3 RigidBody::get_inner_joint_to_com_vector_global | ( | ) | const |
Gets the vector that points from the inboard joint on this link to the center of mass on the link.
Gets the vector from the inboard joint to the center-of-mass in world coordinates (i.e., varies with link transform).
| void RigidBody::set_inner_joint_to_com_vector_link | ( | const Vector3 & | v | ) |
Sets the vector that points from the inboard joint on this link to the center of mass on the link.
Sets the vector from the inboard joint to the center-of-mass in link coordinates of the link (i.e., invariant to link orientation).
| void RigidBody::set_inner_joint_to_com_vector_global | ( | const Vector3 & | v | ) |
Sets the vector that points from the inboard joint on this link to the center of mass on the link.
Sets the vector from the inboard joint to the center-of-mass in world coordinates (i.e., varies with link transform).
| v | the global position of the inboard joint |
| const Vector3 & RigidBody::get_com_to_outer_joint_vector_link | ( | RigidBodyConstPtr | child | ) | const |
Gets the vector that points from the center of mass of this link to the inboard joint of the specified child link.
Gets the vector from the center-of-mass of the link to the inboard joint of the specified child link in link coordinates (i.e., invariant to link orientation).
| Vector3 RigidBody::get_com_to_outer_joint_vector_global | ( | RigidBodyConstPtr | link | ) | const |
Gets the vector that points from the center of mass of this link to the inboard joint of the i'th child link.
Gets the vector from the center-of-mass of the link to the inboard joint of the i'th child link in global coordinates (i.e., varies with link orientation).
| void RigidBody::add_child_link_global | ( | RigidBodyPtr | child, | |
| const Vector3 & | com_to_inner_joint_vec_global | |||
| ) |
Adds a child link to the list of children of this link.
| child | the child link; if child is already a child link of this link the new com_to_inner_joint_vec_global will be used | |
| com_to_inner_joint_vec_global | a vector from the center-of-mass of this link to the inner joint of the child link (i.e., the outer joint of this link) in the global frame |
this method is synonymous with set_child_link_global()
| void RigidBody::reset_spatial_transforms | ( | ) |
Resets all spatial computations.
"Forward", "backward", link-to-global and global-to-link transforms are all reset.
| const SMatrix6 & RigidBody::get_spatial_transform_forward | ( | ) |
Returns the spatial transform from this link's parent to this link.
| const SMatrix6 & RigidBody::get_spatial_transform_backward | ( | ) |
Returns the spatial transform from this link to this link's parent.
| const SMatrix6 & RigidBody::get_spatial_transform_link_to_global | ( | ) |
Returns the spatial transform from this link to the global coordinate system.
| const SMatrix6 & RigidBody::get_spatial_transform_global_to_link | ( | ) |
Returns the spatial transform from the global coordinates system to this link.
| void RigidBody::add_child_link_link | ( | RigidBodyPtr | child, | |
| const Vector3 & | com_to_child_inner_joint_vec_link | |||
| ) |
Adds a child link to the list of children of this link.
| child | the child link; if child is already a child link of this link the new com_to_inner_joint_vec_link will be used | |
| com_to_inner_joint_vec_link | a vector from the center-of-mass of this link to the inner joint of the child link (i.e., the outer joint of this link) in this link's frame |
this method is synonymous with set_child_link_link()
| void RigidBody::set_inner_joint | ( | JointPtr | j | ) |
Sets the inner joint for this link.
Also attempts to update articulated body pointers as well as parent IDs, if possible...
| void RigidBody::set_parent_link | ( | RigidBodyPtr | l | ) |
Sets the parent of this link; set to NULL to indicate no parent.
Also attempts to update articulated body pointers as well as parent IDs, if possible...
| const Vector3& Physsim::RigidBody::get_laccel | ( | ) | [inline] |
Gets the linear acceleration of this body.
| const Vector3& Physsim::RigidBody::get_aaccel | ( | ) | [inline] |
Gets the angular acceleration of this body.
| const Vector3& Physsim::RigidBody::sum_forces | ( | ) | const [inline] |
Gets the sum of forces on this body.
The frame of the sum of forces is centered at the center-of-mass of the body and is aligned with the global frame.
| const Vector3& Physsim::RigidBody::sum_torques | ( | ) | const [inline] |
Gets the sum of torques on this body.
The frame of the sum of torques is centered at the center-of-mass of the body and is aligned with the global frame.
| boost::weak_ptr<ArticulatedBody> Physsim::RigidBody::get_articulated_body | ( | ) | const [inline] |
Gets the articulated body corresponding to this body.
| void Physsim::RigidBody::set_articulated_body | ( | boost::weak_ptr< ArticulatedBody > | body | ) | [inline] |
Sets the articulated body corresponding to this body.
| body | a pointer to the articulated body or NULL if this body is not a link in an articulated body |
| const Vector3& Physsim::RigidBody::get_inner_joint_to_com_vector_link | ( | ) | const [inline] |
Gets the vector that points from the inboard joint on this link to the center of mass on the link.
Gets the vector from the inboard joint to the center-of-mass in the link frame.
| void Physsim::RigidBody::set_child_link_link | ( | RigidBodyPtr | child, | |
| const Vector3 & | com_to_inner_joint_vec_link | |||
| ) | [inline] |
Adds a child link to the list of children of this link.
| child | the child link; if child is already a child link of this * link the new com_to_inner_joint_vec_link will be used | |
| com_to_inner_joint_vec_link | a vector from the center-of-mass of this link to the inner joint of the child link (i.e., the outer joint of this link) in this link's frame |
automatically makes child point to this as its parent
| void Physsim::RigidBody::set_child_link_global | ( | RigidBodyPtr | child, | |
| const Vector3 & | com_to_inner_joint_vec_global | |||
| ) | [inline] |
Sets a child link to the list of children of this link.
| child | the child link; if child is already a child link of this link the new com_to_inner_joint_vec_global will be used | |
| com_to_inner_joint_vec_global | a vector from the center-of-mass of this link to the inner joint of the child link (i.e., the outer joint of this link) in the global frame |
automatically makes child point to this as its parent
| void Physsim::RigidBody::set_index | ( | unsigned | index | ) | [inline] |
Sets the link index.
This is set automatically by RCArticulatedBody. Users should not change this index or unknown behavior will result.
1.5.1