Choreonoid  1.8
Classes | Public Types | Public Member Functions | Static Public Member Functions | Static Public Attributes | Protected Member Functions | List of all members
cnoid::Link Class Reference

#include <Link.h>

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

Classes

class  ContactPoint
 All the members are described in the global coordinate system. More...
 

Public Types

enum  JointType {
  RevoluteJoint = 0, PrismaticJoint = 1, FreeJoint = 2, FixedJoint = 3,
  PseudoContinuousTrackJoint = 4, REVOLUTE_JOINT = RevoluteJoint, ROTATIONAL_JOINT = RevoluteJoint, PRISMATIC_JOINT = PrismaticJoint,
  SLIDE_JOINT = PrismaticJoint, FREE_JOINT = FreeJoint, FIXED_JOINT = FixedJoint, PSEUDO_CONTINUOUS_TRACK = PseudoContinuousTrackJoint
}
 
enum  StateFlag {
  StateNone = 0, JointDisplacement = 1 << 0, JointAngle = JointDisplacement, JointVelocity = 1 << 1,
  JointAcceleration = 1 << 2, JointEffort = 1 << 3, JointForce = JointEffort, JointTorque = JointEffort,
  LinkPosition = 1 << 4, LinkTwist = 1 << 5, LinkExtWrench = 1 << 6, LinkContactState = 1 << 7,
  HighGainActuation = 1 << 8, DeprecatedJointSurfaceVelocity = 1 << 9, MaxStateTypeBit = 9, NumStateTypes = 10,
  NO_ACTUATION = StateNone, JOINT_TORQUE = JointTorque, JOINT_FORCE = JointForce, JOINT_EFFORT = JointEffort,
  JOINT_ANGLE = JointAngle, JOINT_DISPLACEMENT = JointDisplacement, JOINT_VELOCITY = JointVelocity, LINK_POSITION = LinkPosition
}
 
typedef StateFlag ActuationMode
 

Public Member Functions

EIGEN_MAKE_ALIGNED_OPERATOR_NEW Link ()
 
 Link (const Link &link)
 
Linkclone () const
 
virtual ~Link ()
 
virtual void initializeState ()
 
const std::string & name () const
 
int index () const
 
bool isValid () const
 
bool isRoot () const
 
bool isStatic () const
 
bool isFixedToRoot () const
 
bool isOwnerOf (const Link *link) const
 
bool isEndLink () const
 
Bodybody ()
 
const Bodybody () const
 
Linkparent () const
 
Linksibling () const
 
Linkchild () const
 
Isometry3T ()
 
const Isometry3T () const
 
Isometry3position ()
 
const Isometry3position () const
 
template<class Scalar , int Mode, int Options>
void setPosition (const Eigen::Transform< Scalar, 3, Mode, Options > &T)
 
template<class Derived >
void setPosition (const Eigen::MatrixBase< Derived > &T)
 
template<typename Derived1 , typename Derived2 >
void setPosition (const Eigen::MatrixBase< Derived1 > &rotation, const Eigen::MatrixBase< Derived2 > &translation)
 
Isometry3::TranslationPart p ()
 
Isometry3::ConstTranslationPart p () const
 
Isometry3::TranslationPart translation ()
 
Isometry3::ConstTranslationPart translation () const
 
template<typename Derived >
void setTranslation (const Eigen::MatrixBase< Derived > &p)
 
Isometry3::LinearPart R ()
 
Isometry3::ConstLinearPart R () const
 
Isometry3::LinearPart rotation ()
 
Isometry3::ConstLinearPart rotation () const
 
template<typename Derived >
void setRotation (const Eigen::MatrixBase< Derived > &R)
 
template<typename T >
void setRotation (const Eigen::AngleAxis< T > &a)
 
template<typename Derived >
void setRotation (const Eigen::QuaternionBase< Derived > &q)
 
const Isometry3Tb () const
 
const Isometry3offsetPosition () const
 
Isometry3::ConstTranslationPart b () const
 
Isometry3::ConstTranslationPart offsetTranslation () const
 
Isometry3::ConstLinearPart Rb () const
 
Isometry3::ConstLinearPart offsetRotation () const
 
Matrix3 Rs () const
 
int jointId () const
 
const std::string & jointName () const
 
const std::string & jointSpecificName () const
 
JointType jointType () const
 
const char * jointTypeLabel () const
 
const char * jointTypeSymbol () const
 
const char * jointTypeString (bool useUnderscore=false) const
 
bool isFixedJoint () const
 
bool isFreeJoint () const
 
bool isRevoluteJoint () const
 
bool isPrismaticJoint () const
 
bool hasJoint () const
 
bool isRotationalJoint () const
 deprecated More...
 
bool isSlideJoint () const
 deprecated More...
 
const Vector3a () const
 
const Vector3jointAxis () const
 
const Vector3d () const
 
double Jm2 () const
 Equivalent rotor inertia: n^2*Jm [kg.m^2]. More...
 
short actuationMode () const
 
void setActuationMode (short mode)
 
short sensingMode () const
 
void setSensingMode (short mode)
 
void mergeSensingMode (short mode)
 
double q () const
 
double & q ()
 
double dq () const
 
double & dq ()
 
double ddq () const
 
double & ddq ()
 
double u () const
 
double & u ()
 
double q_initial () const
 
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...
 
const Matrix3I () const
 
const Vector6externalWrench () const
 
Vector6externalWrench ()
 
Vector6::ConstFixedSegmentReturnType< 3 >::Type externalForce () const
 
Vector6::FixedSegmentReturnType< 3 >::Type externalForce ()
 
Vector6::ConstFixedSegmentReturnType< 3 >::Type externalTorque () const
 
Vector6::FixedSegmentReturnType< 3 >::Type externalTorque ()
 
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 ()
 
void addExternalForceAtLocalPosition (const Vector3 &f_global, const Vector3 &p_local)
 
void addExternalForceAtGlobalPosition (const Vector3 &f_global, const Vector3 &p_global)
 
void addExternalForce (const Vector3 &f_global, const Vector3 &p_local)
 
int materialId () const
 
std::string materialName () const
 
std::vector< ContactPoint > & contactPoints ()
 
const std::vector< ContactPoint > & contactPoints () const
 
SgGroupshape () const
 
SgGroupvisualShape () const
 
SgGroupcollisionShape () const
 
bool hasDedicatedCollisionShape () const
 
void setBodyToSubTree (Body *newBody)
 
void setParent (Link *parent)
 
void setIndex (int index)
 
void setName (const std::string &name)
 
virtual void prependChild (Link *link)
 
virtual void appendChild (Link *link)
 
bool removeChild (Link *link)
 
void setOffsetPosition (const Isometry3 &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 > &)
 
void setJointType (JointType type)
 
void setJointId (int id)
 
void setJointName (const std::string &name)
 
void resetJointSpecificName ()
 
void setJointAxis (const Vector3 &axis)
 
void setInitialJointDisplacement (double q)
 
void setInitialJointAngle (double q)
 
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 setMaterial (int id)
 
void setMaterial (const std::string &name)
 
void addShapeNode (SgNode *shape, SgUpdateRef update=nullptr)
 
void addVisualShapeNode (SgNode *shape, SgUpdateRef update=nullptr)
 
void addCollisionShapeNode (SgNode *shape, SgUpdateRef update=nullptr)
 
void removeShapeNode (SgNode *shape, SgUpdateRef update=nullptr)
 
void clearShapeNodes (SgUpdateRef update=nullptr)
 
void updateShapeRs ()
 
Isometry3 Ta () const
 
Matrix3 attitude () const
 
void setAttitude (const Matrix3 &Ra)
 
Matrix3 calcRfromAttitude (const Matrix3 &Ra)
 
void getAttitudeAndTranslation (Isometry3 &out_T)
 
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)
 
std::string info (const std::string &key, const char *defaultValue) const
 
void resetInfo (Mapping *info)
 
template<>
double info (const std::string &key) const
 
template<>
double info (const std::string &key, const double &defaultValue) const
 
template<>
bool info (const std::string &key, const bool &defaultValue) const
 
template<>
void setInfo (const std::string &key, const double &value)
 
template<>
void setInfo (const std::string &key, const bool &value)
 
- Public Member Functions inherited from cnoid::Referenced
virtual ~Referenced ()
 

Static Public Member Functions

static std::string getStateModeString (short mode)
 

Static Public Attributes

static constexpr int PseudoContinousTrack = PseudoContinuousTrackJoint
 
static constexpr int JOINT_SURFACE_VELOCITY = DeprecatedJointSurfaceVelocity
 
static constexpr short AllStateHighGainActuationMode
 

Protected Member Functions

ReferenceddoClone (CloneMap *cloneMap) const override
 
- Protected Member Functions inherited from cnoid::Referenced
 Referenced ()
 
 Referenced (const Referenced &)
 
int refCount () const
 

Member Typedef Documentation

◆ ActuationMode

Member Enumeration Documentation

◆ JointType

Enumerator
RevoluteJoint 
PrismaticJoint 
FreeJoint 

6-DOF root link

FixedJoint 
PseudoContinuousTrackJoint 

Special joint for simplified simulation of a continuous track

REVOLUTE_JOINT 
ROTATIONAL_JOINT 
PRISMATIC_JOINT 
SLIDE_JOINT 
FREE_JOINT 
FIXED_JOINT 
PSEUDO_CONTINUOUS_TRACK 

◆ StateFlag

Enumerator
StateNone 
JointDisplacement 
JointAngle 
JointVelocity 
JointAcceleration 
JointEffort 
JointForce 
JointTorque 
LinkPosition 
LinkTwist 
LinkExtWrench 
LinkContactState 
HighGainActuation 
DeprecatedJointSurfaceVelocity 
MaxStateTypeBit 
NumStateTypes 
NO_ACTUATION 
JOINT_TORQUE 
JOINT_FORCE 
JOINT_EFFORT 
JOINT_ANGLE 
JOINT_DISPLACEMENT 
JOINT_VELOCITY 
LINK_POSITION 

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

◆ ~Link()

Link::~Link ( )
virtual

Member Function Documentation

◆ a()

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

◆ actuationMode()

short cnoid::Link::actuationMode ( ) const
inline

◆ addCollisionShapeNode()

void Link::addCollisionShapeNode ( SgNode shape,
SgUpdateRef  update = nullptr 
)

◆ addExternalForce()

void cnoid::Link::addExternalForce ( const Vector3 f_global,
const Vector3 p_local 
)
inline

◆ addExternalForceAtGlobalPosition()

void cnoid::Link::addExternalForceAtGlobalPosition ( const Vector3 f_global,
const Vector3 p_global 
)
inline

◆ addExternalForceAtLocalPosition()

void cnoid::Link::addExternalForceAtLocalPosition ( const Vector3 f_global,
const Vector3 p_local 
)
inline

◆ addShapeNode()

void Link::addShapeNode ( SgNode shape,
SgUpdateRef  update = nullptr 
)

◆ addVisualShapeNode()

void Link::addVisualShapeNode ( SgNode shape,
SgUpdateRef  update = nullptr 
)

◆ appendChild()

void Link::appendChild ( Link link)
virtual

Reimplemented in cnoid::DyLink.

◆ attitude()

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

◆ b()

Isometry3::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

◆ clearShapeNodes()

void Link::clearShapeNodes ( SgUpdateRef  update = nullptr)

◆ clone()

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

◆ collisionShape()

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

◆ contactPoints() [1/2]

std::vector<ContactPoint>& cnoid::Link::contactPoints ( )
inline

The following contact date is avaiable if LinkContactState is included in the sensingMode.

Note
A dynamics engine should update the data when the above flag is specified in the sensingMode.

◆ contactPoints() [2/2]

const std::vector<ContactPoint>& cnoid::Link::contactPoints ( ) const
inline

◆ d()

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

◆ ddq() [1/2]

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

◆ ddq() [2/2]

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

◆ doClone()

Referenced * Link::doClone ( CloneMap cloneMap) const
overrideprotectedvirtual

◆ dq() [1/2]

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

◆ dq() [2/2]

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

◆ dv() [1/2]

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

◆ dv() [2/2]

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

◆ dw() [1/2]

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

◆ dw() [2/2]

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

◆ externalForce() [1/2]

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

◆ externalForce() [2/2]

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

◆ externalTorque() [1/2]

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

◆ externalTorque() [2/2]

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

◆ externalWrench() [1/2]

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

◆ externalWrench() [2/2]

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

◆ F_ext() [1/2]

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

◆ f_ext() [1/2]

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

◆ F_ext() [2/2]

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

◆ f_ext() [2/2]

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

◆ getAttitudeAndTranslation()

void cnoid::Link::getAttitudeAndTranslation ( Isometry3 out_T)
inline

◆ getStateModeString()

std::string Link::getStateModeString ( short  mode)
static

◆ hasDedicatedCollisionShape()

bool Link::hasDedicatedCollisionShape ( ) const

◆ hasJoint()

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

◆ I()

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

◆ index()

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

◆ info() [1/8]

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

◆ info() [2/8]

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

◆ info() [3/8]

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

◆ info() [4/8]

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

◆ info() [5/8]

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

◆ info() [6/8]

std::string Link::info ( const std::string &  key,
const char *  defaultValue 
) const

◆ info() [7/8]

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

◆ info() [8/8]

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

◆ initializeState()

void Link::initializeState ( )
virtual

Reimplemented in cnoid::DyLink.

◆ isEndLink()

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

◆ isFixedJoint()

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

◆ isFixedToRoot()

bool Link::isFixedToRoot ( ) const

◆ isFreeJoint()

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

◆ isOwnerOf()

bool Link::isOwnerOf ( const Link link) const

◆ isPrismaticJoint()

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

◆ isRevoluteJoint()

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

◆ isRoot()

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

◆ isRotationalJoint()

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

deprecated

◆ isSlideJoint()

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

deprecated

◆ isStatic()

bool Link::isStatic ( ) const

◆ 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

◆ jointName()

const std::string & Link::jointName ( ) const

◆ jointSpecificName()

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

◆ jointType()

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

◆ jointTypeLabel()

const char * Link::jointTypeLabel ( ) const

◆ jointTypeString()

const char * Link::jointTypeString ( bool  useUnderscore = false) const

◆ jointTypeSymbol()

const char * Link::jointTypeSymbol ( ) const

◆ m()

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

mass

◆ materialId()

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

◆ materialName()

std::string Link::materialName ( ) const

◆ mergeSensingMode()

void cnoid::Link::mergeSensingMode ( short  mode)
inline

◆ name()

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

◆ offsetPosition()

const Isometry3& cnoid::Link::offsetPosition ( ) const
inline

◆ offsetRotation()

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

◆ offsetTranslation()

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

◆ p() [1/2]

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

◆ p() [2/2]

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

◆ parent()

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

◆ position() [1/2]

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

◆ position() [2/2]

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

◆ prependChild()

void Link::prependChild ( Link link)
virtual

Reimplemented in cnoid::DyLink.

◆ q() [1/2]

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

◆ q() [2/2]

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

◆ q_initial()

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

◆ R() [1/2]

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

◆ R() [2/2]

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

◆ Rb()

Isometry3::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.

◆ removeShapeNode()

void Link::removeShapeNode ( SgNode shape,
SgUpdateRef  update = nullptr 
)

◆ resetInfo()

void Link::resetInfo ( Mapping info)

◆ resetJointSpecificName()

void Link::resetJointSpecificName ( )

◆ rotation() [1/2]

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

◆ rotation() [2/2]

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

◆ Rs()

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

◆ sensingMode()

short cnoid::Link::sensingMode ( ) const
inline

◆ setAccumulatedSegmentRotation()

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

◆ setActuationMode()

void cnoid::Link::setActuationMode ( short  mode)
inline

◆ setAttitude()

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

◆ setBodyToSubTree()

void Link::setBodyToSubTree ( Body newBody)

◆ setCenterOfMass()

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

◆ 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<>
CNOID_EXPORT void cnoid::Link::setInfo ( const std::string &  key,
const bool &  value 
)

◆ setInfo() [2/3]

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

◆ setInfo() [3/3]

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

◆ setInitialJointAngle()

void cnoid::Link::setInitialJointAngle ( double  q)
inline

◆ setInitialJointDisplacement()

void cnoid::Link::setInitialJointDisplacement ( double  q)
inline

◆ setJointAxis()

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

◆ setJointId()

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

◆ setJointName()

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

◆ 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

◆ setMaterial() [1/2]

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

◆ setMaterial() [2/2]

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

◆ setName()

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

◆ setOffsetPosition()

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

◆ setOffsetRotation() [1/2]

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

◆ setOffsetRotation() [2/2]

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

◆ setOffsetTranslation()

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

◆ setParent()

void cnoid::Link::setParent ( Link parent)
inline

◆ setPosition() [1/3]

template<class Derived >
void cnoid::Link::setPosition ( const Eigen::MatrixBase< Derived > &  T)
inline

◆ setPosition() [2/3]

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

◆ setPosition() [3/3]

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

◆ setRotation() [1/3]

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

◆ setRotation() [2/3]

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

◆ setRotation() [3/3]

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

◆ setSensingMode()

void cnoid::Link::setSensingMode ( short  mode)
inline

◆ setTranslation()

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

◆ shape()

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

◆ sibling()

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

◆ T() [1/2]

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

◆ T() [2/2]

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

◆ Ta()

Isometry3 cnoid::Link::Ta ( ) const
inline

◆ tau_ext() [1/2]

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

◆ tau_ext() [2/2]

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

◆ Tb()

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

◆ translation() [1/2]

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

◆ translation() [2/2]

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

◆ u() [1/2]

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

◆ u() [2/2]

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

◆ updateShapeRs()

void cnoid::Link::updateShapeRs ( )
inline

◆ v() [1/2]

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

◆ v() [2/2]

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

◆ visualShape()

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

◆ w() [1/2]

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

◆ w() [2/2]

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

◆ wc() [1/2]

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

◆ wc() [2/2]

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

center of mass (world coordinate)

Member Data Documentation

◆ AllStateHighGainActuationMode

constexpr short cnoid::Link::AllStateHighGainActuationMode
staticconstexpr
Initial value:

The special mode which can be used to calculate contact forces only. In order for this mode to work correctly, the mode should be specified for all the movable links. The mode is currently supported by AISTSimulator.

◆ JOINT_SURFACE_VELOCITY

constexpr int cnoid::Link::JOINT_SURFACE_VELOCITY = DeprecatedJointSurfaceVelocity
staticconstexpr

◆ PseudoContinousTrack

constexpr int cnoid::Link::PseudoContinousTrack = PseudoContinuousTrackJoint
staticconstexpr

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