Ravelin
Public Member Functions | Static Public Member Functions | Public Attributes | List of all members
Ravelin::SPATIAL_AB_INERTIA Class Reference

A 6x6 spatial algebra matrix typically used for dynamics calculations. More...

#include <SpatialABInertiad.h>

Public Member Functions

 SPATIAL_AB_INERTIA (boost::shared_ptr< const POSE3 > pose=boost::shared_ptr< const POSE3 >())
 
 SPATIAL_AB_INERTIA (boost::shared_ptr< POSE3 > pose)
 
 SPATIAL_AB_INERTIA (const MATRIX3 &M, const MATRIX3 &H, const MATRIX3 &J, boost::shared_ptr< const POSE3 > pose=boost::shared_ptr< const POSE3 >())
 
 SPATIAL_AB_INERTIA (const MATRIX3 &M, const MATRIX3 &H, const MATRIX3 &J, boost::shared_ptr< POSE3 > pose=boost::shared_ptr< POSE3 >())
 
 SPATIAL_AB_INERTIA (const SPATIAL_AB_INERTIA &source)
 
 SPATIAL_AB_INERTIA (const SPATIAL_RB_INERTIA &source)
 
void set_zero ()
 
SACCEL inverse_mult (const SFORCE &f) const
 
SVELOCITY inverse_mult (const SMOMENTUM &m) const
 
std::vector< SACCEL > & inverse_mult (const std::vector< SFORCE > &w, std::vector< SACCEL > &result) const
 
SPATIAL_AB_INERTIAoperator= (const SPATIAL_RB_INERTIA &source)
 
SPATIAL_AB_INERTIAoperator= (const SPATIAL_AB_INERTIA &source)
 
SPATIAL_AB_INERTIAoperator+= (const SPATIAL_AB_INERTIA &m)
 
SPATIAL_AB_INERTIAoperator-= (const SPATIAL_AB_INERTIA &m)
 
SPATIAL_AB_INERTIAoperator*= (const SPATIAL_AB_INERTIA &m)
 
SPATIAL_AB_INERTIAoperator*= (REAL scalar)
 
SPATIAL_AB_INERTIAoperator/= (REAL scalar)
 
SPATIAL_RB_INERTIA to_rb_inertia () const
 
SPATIAL_AB_INERTIA operator+ (const SPATIAL_RB_INERTIA &m) const
 
SPATIAL_AB_INERTIAoperator+= (const SPATIAL_RB_INERTIA &m)
 
SPATIAL_AB_INERTIA operator+ (const SPATIAL_AB_INERTIA &m) const
 
SPATIAL_AB_INERTIA operator- (const SPATIAL_AB_INERTIA &m) const
 
SPATIAL_AB_INERTIA operator* (const SPATIAL_AB_INERTIA &m) const
 
SPATIAL_AB_INERTIA operator* (REAL scalar) const
 
SPATIAL_AB_INERTIA operator/ (REAL scalar) const
 
SFORCE operator* (const SACCEL &s) const
 
SFORCE mult (const SACCEL &s) const
 
std::vector< SFORCE > & mult (const std::vector< SACCEL > &s, std::vector< SFORCE > &result) const
 
SMOMENTUM operator* (const SVELOCITY &s) const
 
SMOMENTUM mult (const SVELOCITY &s) const
 
std::vector< SMOMENTUM > & mult (const std::vector< SVELOCITY > &s, std::vector< SMOMENTUM > &result) const
 
SPATIAL_AB_INERTIA operator- () const
 
template<class Mat >
Mat & to_matrix (Mat &m) const
 
 SPATIAL_AB_INERTIA (boost::shared_ptr< const POSE3 > pose=boost::shared_ptr< const POSE3 >())
 
 SPATIAL_AB_INERTIA (boost::shared_ptr< POSE3 > pose)
 
 SPATIAL_AB_INERTIA (const MATRIX3 &M, const MATRIX3 &H, const MATRIX3 &J, boost::shared_ptr< const POSE3 > pose=boost::shared_ptr< const POSE3 >())
 
 SPATIAL_AB_INERTIA (const MATRIX3 &M, const MATRIX3 &H, const MATRIX3 &J, boost::shared_ptr< POSE3 > pose=boost::shared_ptr< POSE3 >())
 
 SPATIAL_AB_INERTIA (const SPATIAL_AB_INERTIA &source)
 
 SPATIAL_AB_INERTIA (const SPATIAL_RB_INERTIA &source)
 
void set_zero ()
 
SACCEL inverse_mult (const SFORCE &f) const
 
SVELOCITY inverse_mult (const SMOMENTUM &m) const
 
std::vector< SACCEL > & inverse_mult (const std::vector< SFORCE > &w, std::vector< SACCEL > &result) const
 
SPATIAL_AB_INERTIAoperator= (const SPATIAL_RB_INERTIA &source)
 
SPATIAL_AB_INERTIAoperator= (const SPATIAL_AB_INERTIA &source)
 
SPATIAL_AB_INERTIAoperator+= (const SPATIAL_AB_INERTIA &m)
 
SPATIAL_AB_INERTIAoperator-= (const SPATIAL_AB_INERTIA &m)
 
SPATIAL_AB_INERTIAoperator*= (const SPATIAL_AB_INERTIA &m)
 
SPATIAL_AB_INERTIAoperator*= (REAL scalar)
 
SPATIAL_AB_INERTIAoperator/= (REAL scalar)
 
SPATIAL_RB_INERTIA to_rb_inertia () const
 
SPATIAL_AB_INERTIA operator+ (const SPATIAL_RB_INERTIA &m) const
 
SPATIAL_AB_INERTIAoperator+= (const SPATIAL_RB_INERTIA &m)
 
SPATIAL_AB_INERTIA operator+ (const SPATIAL_AB_INERTIA &m) const
 
SPATIAL_AB_INERTIA operator- (const SPATIAL_AB_INERTIA &m) const
 
SPATIAL_AB_INERTIA operator* (const SPATIAL_AB_INERTIA &m) const
 
SPATIAL_AB_INERTIA operator* (REAL scalar) const
 
SPATIAL_AB_INERTIA operator/ (REAL scalar) const
 
SFORCE operator* (const SACCEL &s) const
 
SFORCE mult (const SACCEL &s) const
 
std::vector< SFORCE > & mult (const std::vector< SACCEL > &s, std::vector< SFORCE > &result) const
 
SMOMENTUM operator* (const SVELOCITY &s) const
 
SMOMENTUM mult (const SVELOCITY &s) const
 
std::vector< SMOMENTUM > & mult (const std::vector< SVELOCITY > &s, std::vector< SMOMENTUM > &result) const
 
SPATIAL_AB_INERTIA operator- () const
 
template<class Mat >
Mat & to_matrix (Mat &m) const
 

Static Public Member Functions

static SPATIAL_AB_INERTIA zero ()
 
static SPATIAL_AB_INERTIA inverse_inertia (const SPATIAL_AB_INERTIA &I)
 
template<class Mat >
static SPATIAL_AB_INERTIA from_matrix (const Mat &m, boost::shared_ptr< const POSE3 > pose=boost::shared_ptr< const POSE3 >())
 
template<class Mat >
static SPATIAL_AB_INERTIA from_matrix (const Mat &m, boost::shared_ptr< POSE3 > pose=boost::shared_ptr< POSE3 >())
 
static SPATIAL_AB_INERTIA zero ()
 
static SPATIAL_AB_INERTIA inverse_inertia (const SPATIAL_AB_INERTIA &I)
 
template<class Mat >
static SPATIAL_AB_INERTIA from_matrix (const Mat &m, boost::shared_ptr< const POSE3 > pose=boost::shared_ptr< const POSE3 >())
 
template<class Mat >
static SPATIAL_AB_INERTIA from_matrix (const Mat &m, boost::shared_ptr< POSE3 > pose=boost::shared_ptr< POSE3 >())
 

Public Attributes

MATRIX3 H
 The lower right hand matrix 'H' (and transpose of upper left matrix)
 
MATRIX3 J
 The lower left matrix.
 
MATRIX3 M
 The upper right matrix.
 
boost::shared_ptr< const POSE3pose
 The pose that this inertia is defined in.
 

Detailed Description

A 6x6 spatial algebra matrix typically used for dynamics calculations.

Note: this representation differs from Featherstone's new spatial AB inertia representation: | H' M | | J H |


The documentation for this class was generated from the following files: