Classes | Public Types | Public Member Functions | Public Attributes | Private Member Functions | Friends
hrp::Link Class Reference

#include <Link.h>

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

List of all members.

Classes

struct  ConstraintForce

Public Types

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

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

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.

Definition at line 54 of file Link.h.

Definition at line 55 of file Link.h.

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.

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.

Deprecated:
use attitude().

Definition at line 77 of file Link.h.

Definition at line 53 of file Link.h.

void Link::setBodyIter ( Body body) [private]

Definition at line 196 of file Link.cpp.

Deprecated:
use setAttitude().

Definition at line 72 of file Link.h.

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

rotational joint axis (self local)

Definition at line 125 of file Link.h.

relative position (parent local)

Definition at line 127 of file Link.h.

Definition at line 83 of file Link.h.

center of mass (self local)

Definition at line 133 of file Link.h.

Definition at line 101 of file Link.h.

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

Definition at line 173 of file Link.h.

Definition at line 186 of file Link.h.

Definition at line 194 of file Link.h.

dsv * dq (cross velocity term)

Definition at line 147 of file Link.h.

dsw * dq (cross velocity term)

Definition at line 148 of file Link.h.

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.

joint acceleration

Definition at line 122 of file Link.h.

Definition at line 175 of file Link.h.

double hrp::Link::dq

joint velocity

Definition at line 121 of file Link.h.

linear acceleration

Definition at line 117 of file Link.h.

derivative of vo

Definition at line 137 of file Link.h.

derivative of omega

Definition at line 118 of file Link.h.

Definition at line 177 of file Link.h.

external force

Definition at line 150 of file Link.h.

Definition at line 180 of file Link.h.

Definition at line 179 of file Link.h.

top block of Ia*s

Definition at line 162 of file Link.h.

bottom bock of Ia*s

Definition at line 163 of file Link.h.

inertia tensor (self local, around c)

Definition at line 132 of file Link.h.

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.

Definition at line 184 of file Link.h.

Definition at line 183 of file Link.h.

top left block of the articulated inertia

Definition at line 159 of file Link.h.

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

Definition at line 158 of file Link.h.

bottm right block of the articulated inertia

Definition at line 157 of file Link.h.

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

Definition at line 167 of file Link.h.

jointId value written in a model file

Definition at line 86 of file Link.h.

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.

the lower limit of joint values

Definition at line 170 of file Link.h.

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.

position

Definition at line 103 of file Link.h.

Definition at line 99 of file Link.h.

bias force (linear element)

Definition at line 160 of file Link.h.

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.

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.

Definition at line 181 of file Link.h.

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.

Definition at line 100 of file Link.h.

mass of subtree

Definition at line 196 of file Link.h.

sum of m x wc of subtree

Definition at line 197 of file Link.h.

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.

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.

external torque (around the world origin)

Definition at line 151 of file Link.h.

Definition at line 176 of file Link.h.

double hrp::Link::u

joint torque

Definition at line 123 of file Link.h.

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.

the upper limit of joint velocities

Definition at line 171 of file Link.h.

linear velocity

Definition at line 115 of file Link.h.

translation elements of spacial velocity

Definition at line 136 of file Link.h.

angular velocity, omega

Definition at line 116 of file Link.h.

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 Thu Apr 11 2019 03:30:22