Classes | Public Types | Public Member Functions | Public Attributes | Private Member Functions | Friends | List of all members
hrp::Link Class Reference

#include <Link.h>

Inheritance diagram for hrp::Link:
Inheritance graph
[legend]

Classes

struct  ConstraintForce
 

Public Types

typedef std::vector< ConstraintForceConstraintForceArray
 
enum  JointType { FIXED_JOINT, FREE_JOINT, ROTATIONAL_JOINT, SLIDE_JOINT }
 

Public Member Functions

void addChild (Link *link)
 
Matrix33 attitude ()
 
Matrix33 calcRfromAttitude (const Matrix33 &R)
 
void calcSubMassCM ()
 compute sum of m x wc of subtree More...
 
void calcSubMassInertia (Matrix33 &subIw)
 compute sum of I of subtree More...
 
bool detachChild (Link *link)
 
bool isRoot ()
 
bool isValid ()
 
 Link ()
 
 Link (const Link &link)
 
Matrix33 segmentAttitude ()
 
void setAttitude (const Matrix33 &R)
 
void setSegmentAttitude (const Matrix33 &R)
 
void updateColdetModelPosition ()
 
virtual ~Link ()
 

Public Attributes

Vector3 a
 rotational joint axis (self local) More...
 
Vector3 b
 relative position (parent local) More...
 
Bodybody
 
Vector3 c
 center of mass (self local) More...
 
Linkchild
 
double climit
 the upper limit of joint current (tlimit = climit x grarRatio x torqueConst) More...
 
ColdetModelPtr coldetModel
 
ConstraintForceArray constraintForces
 
Vector3 cv
 dsv * dq (cross velocity term) More...
 
Vector3 cw
 dsw * dq (cross velocity term) More...
 
Vector3 d
 translation joint axis (self local) More...
 
double dd
 Ia*s*s^T. More...
 
double ddq
 joint acceleration More...
 
double defaultJointValue
 
double dq
 joint velocity More...
 
Vector3 dv
 linear acceleration More...
 
Vector3 dvo
 derivative of vo More...
 
Vector3 dw
 derivative of omega More...
 
double encoderPulse
 
Vector3 fext
 external force More...
 
double gearEfficiency
 
double gearRatio
 
Vector3 hhv
 top block of Ia*s More...
 
Vector3 hhw
 bottom bock of Ia*s More...
 
Matrix33 I
 inertia tensor (self local, around c) More...
 
int index
 
double Ir
 rotor inertia [kg.m^2] More...
 
bool isCrawler
 
bool isHighGainMode
 
Matrix33 Ivv
 top left block of the articulated inertia More...
 
Matrix33 Iwv
 bottom left block (transpose of top right block) of the articulated inertia More...
 
Matrix33 Iww
 bottm right block of the articulated inertia More...
 
double Jm2
 Equivalent rotor inertia: n^2*Jm [kg.m^2]. More...
 
int jointId
 jointId value written in a model file More...
 
JointType jointType
 
std::vector< Light * > lights
 lights attached to this link More...
 
double llimit
 the lower limit of joint values More...
 
double lvlimit
 the lower limit of joint velocities More...
 
double m
 mass More...
 
std::string name
 
Vector3 p
 position More...
 
Linkparent
 
Vector3 pf
 bias force (linear element) More...
 
Vector3 ptau
 bias force (torque element) More...
 
double q
 joint value More...
 
Matrix33 R
 
double rotorResistor
 
Matrix33 Rs
 relative attitude of the link segment (self local) More...
 
std::vector< Sensor * > sensors
 sensors attached to this link More...
 
Linksibling
 
double subm
 mass of subtree More...
 
Vector3 submwc
 sum of m x wc of subtree More...
 
Vector3 sv
 
Vector3 sw
 
Vector3 tauext
 external torque (around the world origin) More...
 
double torqueConst
 
double u
 joint torque More...
 
double ulimit
 the upper limit of joint values More...
 
double uu
 
double uvlimit
 the upper limit of joint velocities More...
 
Vector3 v
 linear velocity More...
 
Vector3 vo
 translation elements of spacial velocity More...
 
Vector3 w
 angular velocity, omega More...
 
Vector3 wc
 R * c + p. More...
 

Private Member Functions

Linkoperator= (const Link &link)
 
void putInformation (std::ostream &out)
 
void setBodyIter (Body *body)
 

Friends

std::ostream & operator<< (std::ostream &out, hrp::Link &link)
 

Detailed Description

Definition at line 40 of file Link.h.

Member Typedef Documentation

Definition at line 193 of file Link.h.

Member Enumeration Documentation

Enumerator
FIXED_JOINT 

fixed joint(0 dof)

FREE_JOINT 
ROTATIONAL_JOINT 

6-DOF root link

rotational joint (1 dof)

SLIDE_JOINT 

translational joint (1 dof)

Definition at line 90 of file Link.h.

Constructor & Destructor Documentation

Link::Link ( )

Definition at line 50 of file Link.cpp.

Link::Link ( const Link link)

Definition at line 67 of file Link.cpp.

Link::~Link ( )
virtual

Definition at line 136 of file Link.cpp.

Member Function Documentation

void Link::addChild ( Link link)

Definition at line 147 of file Link.cpp.

Matrix33 hrp::Link::attitude ( )
inline

Definition at line 54 of file Link.h.

Matrix33 hrp::Link::calcRfromAttitude ( const Matrix33 R)
inline

Definition at line 55 of file Link.h.

void Link::calcSubMassCM ( )

compute sum of m x wc of subtree

Note
assuming wc is already computed by Body::calcCM()

Definition at line 291 of file Link.cpp.

void Link::calcSubMassInertia ( Matrix33 subIw)

compute sum of I of subtree

Note
assuming wc,submw,submwc is already computed by Body::calcCM(),Link::calcSubMassCM()

Definition at line 313 of file Link.cpp.

bool Link::detachChild ( Link childToRemove)

A child link is detached from the link. The detached child link is not deleted by this function. If a link given by the parameter is not a child of the link, false is returned.

Definition at line 166 of file Link.cpp.

bool hrp::Link::isRoot ( )
inline

Definition at line 51 of file Link.h.

bool hrp::Link::isValid ( )
inline

Definition at line 48 of file Link.h.

Link& hrp::Link::operator= ( const Link link)
private
void Link::putInformation ( std::ostream &  out)
private

Definition at line 211 of file Link.cpp.

Matrix33 hrp::Link::segmentAttitude ( )
inline
Deprecated:
use attitude().

Definition at line 77 of file Link.h.

void hrp::Link::setAttitude ( const Matrix33 R)
inline

Definition at line 53 of file Link.h.

void Link::setBodyIter ( Body body)
private

Definition at line 196 of file Link.cpp.

void hrp::Link::setSegmentAttitude ( const Matrix33 R)
inline
Deprecated:
use setAttitude().

Definition at line 72 of file Link.h.

void hrp::Link::updateColdetModelPosition ( )
inline

Definition at line 79 of file Link.h.

Friends And Related Function Documentation

std::ostream& operator<< ( std::ostream &  out,
hrp::Link link 
)
friend

Definition at line 205 of file Link.cpp.

Member Data Documentation

Vector3 hrp::Link::a

rotational joint axis (self local)

Definition at line 125 of file Link.h.

Vector3 hrp::Link::b

relative position (parent local)

Definition at line 127 of file Link.h.

Body* hrp::Link::body

Definition at line 83 of file Link.h.

Vector3 hrp::Link::c

center of mass (self local)

Definition at line 133 of file Link.h.

Link* hrp::Link::child

Definition at line 101 of file Link.h.

double hrp::Link::climit

the upper limit of joint current (tlimit = climit x grarRatio x torqueConst)

Definition at line 173 of file Link.h.

ColdetModelPtr hrp::Link::coldetModel

Definition at line 186 of file Link.h.

ConstraintForceArray hrp::Link::constraintForces

Definition at line 194 of file Link.h.

Vector3 hrp::Link::cv

dsv * dq (cross velocity term)

Definition at line 147 of file Link.h.

Vector3 hrp::Link::cw

dsw * dq (cross velocity term)

Definition at line 148 of file Link.h.

Vector3 hrp::Link::d

translation joint axis (self local)

Definition at line 126 of file Link.h.

double hrp::Link::dd

Ia*s*s^T.

Definition at line 165 of file Link.h.

double hrp::Link::ddq

joint acceleration

Definition at line 122 of file Link.h.

double hrp::Link::defaultJointValue

Definition at line 175 of file Link.h.

double hrp::Link::dq

joint velocity

Definition at line 121 of file Link.h.

Vector3 hrp::Link::dv

linear acceleration

Definition at line 117 of file Link.h.

Vector3 hrp::Link::dvo

derivative of vo

Definition at line 137 of file Link.h.

Vector3 hrp::Link::dw

derivative of omega

Definition at line 118 of file Link.h.

double hrp::Link::encoderPulse

Definition at line 177 of file Link.h.

Vector3 hrp::Link::fext

external force

Definition at line 150 of file Link.h.

double hrp::Link::gearEfficiency

Definition at line 180 of file Link.h.

double hrp::Link::gearRatio

Definition at line 179 of file Link.h.

Vector3 hrp::Link::hhv

top block of Ia*s

Definition at line 162 of file Link.h.

Vector3 hrp::Link::hhw

bottom bock of Ia*s

Definition at line 163 of file Link.h.

Matrix33 hrp::Link::I

inertia tensor (self local, around c)

Definition at line 132 of file Link.h.

int Link::index

Index among all the links in the body.

Definition at line 85 of file Link.h.

double hrp::Link::Ir

rotor inertia [kg.m^2]

Definition at line 178 of file Link.h.

bool hrp::Link::isCrawler

Definition at line 184 of file Link.h.

bool hrp::Link::isHighGainMode

Definition at line 183 of file Link.h.

Matrix33 hrp::Link::Ivv

top left block of the articulated inertia

Definition at line 159 of file Link.h.

Matrix33 hrp::Link::Iwv

bottom left block (transpose of top right block) of the articulated inertia

Definition at line 158 of file Link.h.

Matrix33 hrp::Link::Iww

bottm right block of the articulated inertia

Definition at line 157 of file Link.h.

double hrp::Link::Jm2

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

Definition at line 167 of file Link.h.

int hrp::Link::jointId

jointId value written in a model file

Definition at line 86 of file Link.h.

JointType hrp::Link::jointType

Definition at line 97 of file Link.h.

std::vector<Light *> hrp::Link::lights

lights attached to this link

Definition at line 199 of file Link.h.

double hrp::Link::llimit

the lower limit of joint values

Definition at line 170 of file Link.h.

double hrp::Link::lvlimit

the lower limit of joint velocities

Definition at line 172 of file Link.h.

double hrp::Link::m

mass

Definition at line 131 of file Link.h.

std::string hrp::Link::name

Definition at line 88 of file Link.h.

Vector3 hrp::Link::p

position

Definition at line 103 of file Link.h.

Link* hrp::Link::parent

Definition at line 99 of file Link.h.

Vector3 hrp::Link::pf

bias force (linear element)

Definition at line 160 of file Link.h.

Vector3 hrp::Link::ptau

bias force (torque element)

Definition at line 161 of file Link.h.

double hrp::Link::q

joint value

Definition at line 120 of file Link.h.

Matrix33 hrp::Link::R

Internal world attitude. In the model computation, it corresponds to the identity matrix when all the joint angles of a robot are zero so that multiplication of local attitdue matrices can be omitted to simplify the computation. If you want to use the original coordinate in the model file, use setAttitude() and attitude() to access.

Definition at line 113 of file Link.h.

double hrp::Link::rotorResistor

Definition at line 181 of file Link.h.

Matrix33 hrp::Link::Rs

relative attitude of the link segment (self local)

Definition at line 129 of file Link.h.

std::vector<Sensor *> hrp::Link::sensors

sensors attached to this link

Definition at line 198 of file Link.h.

Link* hrp::Link::sibling

Definition at line 100 of file Link.h.

double hrp::Link::subm

mass of subtree

Definition at line 196 of file Link.h.

Vector3 hrp::Link::submwc

sum of m x wc of subtree

Definition at line 197 of file Link.h.

Vector3 hrp::Link::sv

A unit vector of spatial velocity (the world coordinate) generated by the joint. The value is parent->R * d when the joint is the translation type.

Definition at line 145 of file Link.h.

Vector3 hrp::Link::sw

A unit vector of angular velocity (the world coordinate) generated by the joint The value is parent->R * a when the joint is the rotational type.

Definition at line 141 of file Link.h.

Vector3 hrp::Link::tauext

external torque (around the world origin)

Definition at line 151 of file Link.h.

double hrp::Link::torqueConst

Definition at line 176 of file Link.h.

double hrp::Link::u

joint torque

Definition at line 123 of file Link.h.

double hrp::Link::ulimit

the upper limit of joint values

Definition at line 169 of file Link.h.

double hrp::Link::uu

Definition at line 164 of file Link.h.

double hrp::Link::uvlimit

the upper limit of joint velocities

Definition at line 171 of file Link.h.

Vector3 hrp::Link::v

linear velocity

Definition at line 115 of file Link.h.

Vector3 hrp::Link::vo

translation elements of spacial velocity

Definition at line 136 of file Link.h.

Vector3 hrp::Link::w

angular velocity, omega

Definition at line 116 of file Link.h.

Vector3 hrp::Link::wc

R * c + p.

Definition at line 134 of file Link.h.


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


openhrp3
Author(s): AIST, General Robotix Inc., Nakamura Lab of Dept. of Mechano Informatics at University of Tokyo
autogenerated on Sat May 8 2021 02:42:45