Choreonoid  1.5
Public Types | Public Member Functions | Public Attributes | Friends | List of all members
cnoid::Link Class Reference

#include <Link.h>

Inheritance diagram for cnoid::Link:
cnoid::Referenced cnoid::DyLink

Public Types

enum  JointType {
  REVOLUTE_JOINT = 0, ROTATIONAL_JOINT = REVOLUTE_JOINT, SLIDE_JOINT = 1, FREE_JOINT = 2,
  FIXED_JOINT = 3, PSEUDO_CONTINUOUS_TRACK = 4, CRAWLER_JOINT = 5, AGX_CRAWLER_JOINT = 6
}
 

Public Member Functions

 Link ()
 
 Link (const Link &link)
 
virtual ~Link ()
 
int index () const
 
bool isValid () const
 
Linkparent () const
 
Linksibling () const
 
Linkchild () const
 
bool isRoot () const
 
Bodybody ()
 
const Bodybody () const
 
PositionT ()
 
const PositionT () const
 
Positionposition ()
 
const Positionposition () const
 
template<class Scalar , int Mode, int Options>
void setPosition (const Eigen::Transform< Scalar, 3, Mode, Options > &T)
 
template<typename Derived1 , typename Derived2 >
void setPosition (const Eigen::MatrixBase< Derived1 > &rotation, const Eigen::MatrixBase< Derived2 > &translation)
 
Position::TranslationPart p ()
 
Position::ConstTranslationPart p () const
 
Position::TranslationPart translation ()
 
Position::ConstTranslationPart translation () const
 
template<typename Derived >
void setTranslation (const Eigen::MatrixBase< Derived > &p)
 
Position::LinearPart R ()
 
Position::ConstLinearPart R () const
 
Position::LinearPart rotation ()
 
Position::ConstLinearPart rotation () const
 
template<typename Derived >
void setRotation (const Eigen::MatrixBase< Derived > &R)
 
template<typename T >
void setRotation (const Eigen::AngleAxis< T > &a)
 
PositionTb ()
 
const PositionTb () const
 
Position::ConstTranslationPart b () const
 
Position::ConstTranslationPart offsetTranslation () const
 
Position::ConstLinearPart Rb () const
 
Position::ConstLinearPart offsetRotation () const
 
Matrix3Rs ()
 
const Matrix3Rs () const
 
int jointId () const
 
JointType jointType () const
 
bool isFixedJoint () const
 
bool isFreeJoint () const
 
bool isRotationalJoint () const
 
bool isSlideJoint () const
 
std::string jointTypeString () const
 
const Vector3a () const
 
const Vector3jointAxis () const
 
const Vector3d () const
 
double q () const
 
double & q ()
 
double dq () const
 
double & dq ()
 
double ddq () const
 
double & ddq ()
 
double u () const
 
double & u ()
 
double q_upper () const
 the upper limit of joint values More...
 
double q_lower () const
 the lower limit of joint values More...
 
double dq_upper () const
 the upper limit of joint velocities More...
 
double dq_lower () const
 the upper limit of joint velocities More...
 
const Vector3v () const
 
Vector3v ()
 
const Vector3w () const
 
Vector3w ()
 
const Vector3dv () const
 
Vector3dv ()
 
const Vector3dw () const
 
Vector3dw ()
 
const Vector3c () const
 center of mass (self local) More...
 
const Vector3centerOfMass () const
 
const Vector3wc () const
 center of mass (world coordinate) More...
 
const Vector3centerOfMassGlobal () const
 
Vector3wc ()
 
double m () const
 mass More...
 
double mass () const
 inertia tensor (self local, around c) More...
 
const Matrix3I () const
 
double Jm2 () const
 Equivalent rotor inertia: n^2*Jm [kg.m^2]. More...
 
const Vector6F_ext () const
 
Vector6F_ext ()
 
Vector6::ConstFixedSegmentReturnType< 3 >::Type f_ext () const
 
Vector6::FixedSegmentReturnType< 3 >::Type f_ext ()
 
Vector6::ConstFixedSegmentReturnType< 3 >::Type tau_ext () const
 
Vector6::FixedSegmentReturnType< 3 >::Type tau_ext ()
 
const std::string & name () const
 
SgNodeshape () const
 
SgNodevisualShape () const
 
SgNodecollisionShape () const
 
void setIndex (int index)
 
virtual void prependChild (Link *link)
 
virtual void appendChild (Link *link)
 
bool removeChild (Link *link)
 
void setOffsetPosition (const Position &T)
 
template<typename Derived >
void setOffsetTranslation (const Eigen::MatrixBase< Derived > &offset)
 
template<typename Derived >
void setOffsetRotation (const Eigen::MatrixBase< Derived > &offset)
 
template<typename T >
void setOffsetRotation (const Eigen::AngleAxis< T > &a)
 
template<typename Derived >
void setAccumulatedSegmentRotation (const Eigen::MatrixBase< Derived > &Rs)
 
void setJointType (JointType type)
 
void setJointId (int id)
 
void setJointAxis (const Vector3 &axis)
 
void setJointRange (double lower, double upper)
 
void setJointVelocityRange (double lower, double upper)
 
void setCenterOfMass (const Vector3 &c)
 
void setMass (double m)
 
void setInertia (const Matrix3 &I)
 
void setEquivalentRotorInertia (double Jm2)
 
void setName (const std::string &name)
 
void setShape (SgNode *shape)
 
void setVisualShape (SgNode *shape)
 
void setCollisionShape (SgNode *shape)
 
Matrix3 attitude () const
 
void setAttitude (const Matrix3 &Ra)
 
Matrix3 calcRfromAttitude (const Matrix3 &Ra)
 
const Mappinginfo () const
 
Mappinginfo ()
 
template<typename T >
T info (const std::string &key) const
 
template<typename T >
T info (const std::string &key, const T &defaultValue) const
 
template<typename T >
void setInfo (const std::string &key, const T &value)
 
void resetInfo (Mapping *info)
 
double initialJointDisplacement () const
 
double & initialJointDisplacement ()
 
template<>
double info (const std::string &key) const
 
template<>
double info (const std::string &key, const double &defaultValue) const
 
template<>
void setInfo (const std::string &key, const double &value)
 
template<>
CNOID_EXPORT double info (const std::string &key) const
 
template<>
CNOID_EXPORT double info (const std::string &key, const double &defaultValue) const
 
template<>
CNOID_EXPORT void setInfo (const std::string &key, const double &value)
 
- Public Member Functions inherited from cnoid::Referenced
virtual ~Referenced ()
 
void addRef ()
 
void releaseRef ()
 

Public Attributes

 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 

Friends

class Body
 

Additional Inherited Members

- Protected Member Functions inherited from cnoid::Referenced
 Referenced ()
 
 Referenced (const Referenced &org)
 
int refCount () const
 

Member Enumeration Documentation

◆ JointType

Enumerator
REVOLUTE_JOINT 

rotational joint (1 dof)

ROTATIONAL_JOINT 
SLIDE_JOINT 

translational joint (1 dof)

FREE_JOINT 

6-DOF root link

FIXED_JOINT 

fixed joint(0 dof)

PSEUDO_CONTINUOUS_TRACK 

special joint for simplified simulation of a continuous track

CRAWLER_JOINT 
AGX_CRAWLER_JOINT 

Constructor & Destructor Documentation

◆ Link() [1/2]

Link::Link ( )

◆ Link() [2/2]

Link::Link ( const Link link)

This does shallow copy. You have to use the copy constructor of the Body class to copy the link tree

Todo:
add the mode for doing deep copy of the following objects

◆ ~Link()

Link::~Link ( )
virtual

Member Function Documentation

◆ a()

const Vector3& cnoid::Link::a ( ) const
inline

◆ appendChild()

void Link::appendChild ( Link link)
virtual

Reimplemented in cnoid::DyLink.

◆ attitude()

Matrix3 cnoid::Link::attitude ( ) const
inline

◆ b()

Position::ConstTranslationPart cnoid::Link::b ( ) const
inline

◆ body() [1/2]

Body* cnoid::Link::body ( )
inline

◆ body() [2/2]

const Body* cnoid::Link::body ( ) const
inline

◆ c()

const Vector3& cnoid::Link::c ( ) const
inline

center of mass (self local)

◆ calcRfromAttitude()

Matrix3 cnoid::Link::calcRfromAttitude ( const Matrix3 Ra)
inline

◆ centerOfMass()

const Vector3& cnoid::Link::centerOfMass ( ) const
inline

◆ centerOfMassGlobal()

const Vector3& cnoid::Link::centerOfMassGlobal ( ) const
inline

◆ child()

Link* cnoid::Link::child ( ) const
inline

◆ collisionShape()

SgNode* cnoid::Link::collisionShape ( ) const
inline

◆ d()

const Vector3& cnoid::Link::d ( ) const
inline

◆ ddq() [1/2]

double cnoid::Link::ddq ( ) const
inline

◆ ddq() [2/2]

double& cnoid::Link::ddq ( )
inline

◆ dq() [1/2]

double cnoid::Link::dq ( ) const
inline

◆ dq() [2/2]

double& cnoid::Link::dq ( )
inline

◆ dq_lower()

double cnoid::Link::dq_lower ( ) const
inline

the upper limit of joint velocities

◆ dq_upper()

double cnoid::Link::dq_upper ( ) const
inline

the upper limit of joint velocities

◆ dv() [1/2]

const Vector3& cnoid::Link::dv ( ) const
inline

◆ dv() [2/2]

Vector3& cnoid::Link::dv ( )
inline

◆ dw() [1/2]

const Vector3& cnoid::Link::dw ( ) const
inline

◆ dw() [2/2]

Vector3& cnoid::Link::dw ( )
inline

◆ F_ext() [1/2]

const Vector6& cnoid::Link::F_ext ( ) const
inline

◆ F_ext() [2/2]

Vector6& cnoid::Link::F_ext ( )
inline

◆ f_ext() [1/2]

Vector6::ConstFixedSegmentReturnType<3>::Type cnoid::Link::f_ext ( ) const
inline

◆ f_ext() [2/2]

Vector6::FixedSegmentReturnType<3>::Type cnoid::Link::f_ext ( )
inline

◆ I()

const Matrix3& cnoid::Link::I ( ) const
inline

◆ index()

int cnoid::Link::index ( ) const
inline

◆ info() [1/8]

template<>
double cnoid::Link::info ( const std::string &  key) const

◆ info() [2/8]

template<>
double cnoid::Link::info ( const std::string &  key,
const double &  defaultValue 
) const

◆ info() [3/8]

const Mapping* cnoid::Link::info ( ) const
inline

◆ info() [4/8]

Mapping* cnoid::Link::info ( )
inline

◆ info() [5/8]

template<typename T >
T cnoid::Link::info ( const std::string &  key) const

◆ info() [6/8]

template<typename T >
T cnoid::Link::info ( const std::string &  key,
const T defaultValue 
) const

◆ info() [7/8]

template<>
CNOID_EXPORT double cnoid::Link::info ( const std::string &  key) const

◆ info() [8/8]

template<>
CNOID_EXPORT double cnoid::Link::info ( const std::string &  key,
const double &  defaultValue 
) const

◆ initialJointDisplacement() [1/2]

double cnoid::Link::initialJointDisplacement ( ) const
inline

◆ initialJointDisplacement() [2/2]

double& cnoid::Link::initialJointDisplacement ( )
inline

◆ isFixedJoint()

bool cnoid::Link::isFixedJoint ( ) const
inline

◆ isFreeJoint()

bool cnoid::Link::isFreeJoint ( ) const
inline

◆ isRoot()

bool cnoid::Link::isRoot ( ) const
inline

◆ isRotationalJoint()

bool cnoid::Link::isRotationalJoint ( ) const
inline

◆ isSlideJoint()

bool cnoid::Link::isSlideJoint ( ) const
inline

◆ isValid()

bool cnoid::Link::isValid ( ) const
inline

◆ Jm2()

double cnoid::Link::Jm2 ( ) const
inline

Equivalent rotor inertia: n^2*Jm [kg.m^2].

◆ jointAxis()

const Vector3& cnoid::Link::jointAxis ( ) const
inline

◆ jointId()

int cnoid::Link::jointId ( ) const
inline

◆ jointType()

JointType cnoid::Link::jointType ( ) const
inline

◆ jointTypeString()

std::string Link::jointTypeString ( ) const

◆ m()

double cnoid::Link::m ( ) const
inline

mass

◆ mass()

double cnoid::Link::mass ( ) const
inline

inertia tensor (self local, around c)

◆ name()

const std::string& cnoid::Link::name ( ) const
inline

◆ offsetRotation()

Position::ConstLinearPart cnoid::Link::offsetRotation ( ) const
inline

◆ offsetTranslation()

Position::ConstTranslationPart cnoid::Link::offsetTranslation ( ) const
inline

◆ p() [1/2]

Position::TranslationPart cnoid::Link::p ( )
inline

◆ p() [2/2]

Position::ConstTranslationPart cnoid::Link::p ( ) const
inline

◆ parent()

Link* cnoid::Link::parent ( ) const
inline

◆ position() [1/2]

Position& cnoid::Link::position ( )
inline

◆ position() [2/2]

const Position& cnoid::Link::position ( ) const
inline

◆ prependChild()

void Link::prependChild ( Link link)
virtual

Reimplemented in cnoid::DyLink.

◆ q() [1/2]

double cnoid::Link::q ( ) const
inline

◆ q() [2/2]

double& cnoid::Link::q ( )
inline

◆ q_lower()

double cnoid::Link::q_lower ( ) const
inline

the lower limit of joint values

◆ q_upper()

double cnoid::Link::q_upper ( ) const
inline

the upper limit of joint values

◆ R() [1/2]

Position::LinearPart cnoid::Link::R ( )
inline

◆ R() [2/2]

Position::ConstLinearPart cnoid::Link::R ( ) const
inline

◆ Rb()

Position::ConstLinearPart cnoid::Link::Rb ( ) const
inline

◆ removeChild()

bool Link::removeChild ( Link childToRemove)

A child link is removed from the link. If a link given by the parameter is not a child of the link, false is returned.

◆ resetInfo()

void Link::resetInfo ( Mapping info)

◆ rotation() [1/2]

Position::LinearPart cnoid::Link::rotation ( )
inline

◆ rotation() [2/2]

Position::ConstLinearPart cnoid::Link::rotation ( ) const
inline

◆ Rs() [1/2]

Matrix3& cnoid::Link::Rs ( )
inline

◆ Rs() [2/2]

const Matrix3& cnoid::Link::Rs ( ) const
inline

◆ setAccumulatedSegmentRotation()

template<typename Derived >
void cnoid::Link::setAccumulatedSegmentRotation ( const Eigen::MatrixBase< Derived > &  Rs)
inline

◆ setAttitude()

void cnoid::Link::setAttitude ( const Matrix3 Ra)
inline

◆ setCenterOfMass()

void cnoid::Link::setCenterOfMass ( const Vector3 c)
inline

◆ setCollisionShape()

void Link::setCollisionShape ( SgNode shape)

◆ setEquivalentRotorInertia()

void cnoid::Link::setEquivalentRotorInertia ( double  Jm2)
inline

◆ setIndex()

void cnoid::Link::setIndex ( int  index)
inline

◆ setInertia()

void cnoid::Link::setInertia ( const Matrix3 I)
inline

◆ setInfo() [1/3]

template<>
void cnoid::Link::setInfo ( const std::string &  key,
const double &  value 
)

◆ setInfo() [2/3]

template<typename T >
void cnoid::Link::setInfo ( const std::string &  key,
const T value 
)

◆ setInfo() [3/3]

template<>
CNOID_EXPORT void cnoid::Link::setInfo ( const std::string &  key,
const double &  value 
)

◆ setJointAxis()

void cnoid::Link::setJointAxis ( const Vector3 axis)
inline

◆ setJointId()

void cnoid::Link::setJointId ( int  id)
inline

◆ setJointRange()

void cnoid::Link::setJointRange ( double  lower,
double  upper 
)
inline

◆ setJointType()

void cnoid::Link::setJointType ( JointType  type)
inline

◆ setJointVelocityRange()

void cnoid::Link::setJointVelocityRange ( double  lower,
double  upper 
)
inline

◆ setMass()

void cnoid::Link::setMass ( double  m)
inline

◆ setName()

void Link::setName ( const std::string &  name)

◆ setOffsetPosition()

void cnoid::Link::setOffsetPosition ( const Position T)
inline

◆ setOffsetRotation() [1/2]

template<typename Derived >
void cnoid::Link::setOffsetRotation ( const Eigen::MatrixBase< Derived > &  offset)
inline

◆ setOffsetRotation() [2/2]

template<typename T >
void cnoid::Link::setOffsetRotation ( const Eigen::AngleAxis< T > &  a)
inline

◆ setOffsetTranslation()

template<typename Derived >
void cnoid::Link::setOffsetTranslation ( const Eigen::MatrixBase< Derived > &  offset)
inline

◆ setPosition() [1/2]

template<class Scalar , int Mode, int Options>
void cnoid::Link::setPosition ( const Eigen::Transform< Scalar, 3, Mode, Options > &  T)
inline

◆ setPosition() [2/2]

template<typename Derived1 , typename Derived2 >
void cnoid::Link::setPosition ( const Eigen::MatrixBase< Derived1 > &  rotation,
const Eigen::MatrixBase< Derived2 > &  translation 
)
inline

◆ setRotation() [1/2]

template<typename Derived >
void cnoid::Link::setRotation ( const Eigen::MatrixBase< Derived > &  R)
inline

◆ setRotation() [2/2]

template<typename T >
void cnoid::Link::setRotation ( const Eigen::AngleAxis< T > &  a)
inline

◆ setShape()

void Link::setShape ( SgNode shape)

◆ setTranslation()

template<typename Derived >
void cnoid::Link::setTranslation ( const Eigen::MatrixBase< Derived > &  p)
inline

◆ setVisualShape()

void Link::setVisualShape ( SgNode shape)

◆ shape()

SgNode* cnoid::Link::shape ( ) const
inline

◆ sibling()

Link* cnoid::Link::sibling ( ) const
inline

◆ T() [1/2]

Position& cnoid::Link::T ( )
inline

◆ T() [2/2]

const Position& cnoid::Link::T ( ) const
inline

◆ tau_ext() [1/2]

Vector6::ConstFixedSegmentReturnType<3>::Type cnoid::Link::tau_ext ( ) const
inline

◆ tau_ext() [2/2]

Vector6::FixedSegmentReturnType<3>::Type cnoid::Link::tau_ext ( )
inline

◆ Tb() [1/2]

Position& cnoid::Link::Tb ( )
inline

◆ Tb() [2/2]

const Position& cnoid::Link::Tb ( ) const
inline

◆ translation() [1/2]

Position::TranslationPart cnoid::Link::translation ( )
inline

◆ translation() [2/2]

Position::ConstTranslationPart cnoid::Link::translation ( ) const
inline

◆ u() [1/2]

double cnoid::Link::u ( ) const
inline

◆ u() [2/2]

double& cnoid::Link::u ( )
inline

◆ v() [1/2]

const Vector3& cnoid::Link::v ( ) const
inline

◆ v() [2/2]

Vector3& cnoid::Link::v ( )
inline

◆ visualShape()

SgNode* cnoid::Link::visualShape ( ) const
inline

◆ w() [1/2]

const Vector3& cnoid::Link::w ( ) const
inline

◆ w() [2/2]

Vector3& cnoid::Link::w ( )
inline

◆ wc() [1/2]

const Vector3& cnoid::Link::wc ( ) const
inline

center of mass (world coordinate)

◆ wc() [2/2]

Vector3& cnoid::Link::wc ( )
inline

Friends And Related Function Documentation

◆ Body

friend class Body
friend

Member Data Documentation

◆ EIGEN_MAKE_ALIGNED_OPERATOR_NEW

cnoid::Link::EIGEN_MAKE_ALIGNED_OPERATOR_NEW

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