Public Member Functions | Public Attributes | Private Attributes | Friends | List of all members
Link Class Reference

Link definitions. More...

#include <robot.h>

Public Member Functions

Real get_a (void) const
 Return a. More...
 
Real get_alpha (void) const
 Return alpha. More...
 
Real get_B (void) const
 Return B. More...
 
Real get_Cf (void) const
 Return Cf. More...
 
Real get_d (void) const
 Return d. More...
 
bool get_DH (void) const
 Return DH value. More...
 
Real get_Gr (void) const
 Return Gr. More...
 
ReturnMatrix get_I (void) const
 Return I. More...
 
Real get_Im (void) const
 Return Im. More...
 
bool get_immobile (void) const
 Return immobile. More...
 
Real get_joint_offset (void) const
 Return joint_offset. More...
 
int get_joint_type (void) const
 Return the joint type. More...
 
Real get_m (void) const
 Return m. More...
 
ReturnMatrix get_mc (void)
 Return mc. More...
 
ReturnMatrix get_p (void) const
 Return p. More...
 
Real get_q (void) const
 Return joint position (theta if joint type is rotoide, d otherwise). More...
 
ReturnMatrix get_r (void)
 Return r. More...
 
Real get_theta (void) const
 Return theta. More...
 
Real get_theta_max (void) const
 Return theta_max. More...
 
Real get_theta_min (void) const
 Return theta_min. More...
 
 Link (const int jt=0, const Real it=0.0, const Real id=0.0, const Real ia=0.0, const Real ial=0.0, const Real theta_min=-M_PI/2, const Real theta_max=M_PI/2, const Real it_off=0.0, const Real mass=1.0, const Real cmx=0.0, const Real cmy=0.0, const Real cmz=0.0, const Real ixx=0.0, const Real ixy=0.0, const Real ixz=0.0, const Real iyy=0.0, const Real iyz=0.0, const Real izz=0.0, const Real iIm=0.0, const Real iGr=0.0, const Real iB=0.0, const Real iCf=0.0, const bool dh=true, const bool min_inertial_para=false, const bool immobile=false)
 Constructor. More...
 
void set_B (const Real B_)
 Set B. More...
 
void set_Cf (const Real Cf_)
 Set Cf. More...
 
void set_I (const Matrix &I)
 Set I. More...
 
void set_Im (const Real Im_)
 Set Im. More...
 
void set_immobile (bool im)
 Set immobile. More...
 
void set_m (const Real m_)
 Set m. More...
 
void set_mc (const ColumnVector &mc_)
 Set mc. More...
 
void set_r (const ColumnVector &r_)
 Set r. More...
 
void transform (const Real q)
 Set the rotation matrix R and the vector p. More...
 
 ~Link ()
 Destructor. More...
 

Public Attributes

Real qp
 Joint velocity. More...
 
Real qpp
 Joint acceleration. More...
 
Matrix R
 Orientation matrix of actual link w.r.t to previous link. More...
 

Private Attributes

Real a
 a DH parameter. More...
 
Real alpha
 alpha DH parameter. More...
 
Real B
 Viscous coefficient. More...
 
Real Cf
 Coulomb fiction coefficient. More...
 
Real d
 d DH parameter. More...
 
bool DH
 DH notation(true) or DH modified notation. More...
 
Real Gr
 Gear Ratio. More...
 
Matrix I
 Inertia matrix w.r.t. center of mass and link coordinate system orientation. More...
 
Real Im
 Motor Inertia. More...
 
bool immobile
 true if the joint is to be considered locked - ignored for inverse kinematics, but can still be reassigned through transform More...
 
Real joint_offset
 Offset in joint angle (rotoide and prismatic). More...
 
int joint_type
 Joint type. More...
 
Real m
 Mass of the link. More...
 
ColumnVector mc
 Mass $\times$ center of gravity (used if min_para = true). More...
 
bool min_para
 Minimum inertial parameter. More...
 
ColumnVector p
 Position vector of actual link w.r.t to previous link. More...
 
ColumnVector r
 Position of center of mass w.r.t. link coordinate system (min_para=F). More...
 
Real theta
 theta DH parameter. More...
 
Real theta_max
 Max joint angle. More...
 
Real theta_min
 Min joint angle. More...
 

Friends

class mRobot
 
class mRobot_min_para
 
class Robot
 
class Robot_basic
 

Detailed Description

Link definitions.

A n degree of freedom (dof) serial manipulator is composed of n links. This class describe the property of a link. A n dof robot has n instance of the class Link.

Definition at line 137 of file robot.h.

Constructor & Destructor Documentation

Link::Link ( const int  jt = 0,
const Real  it = 0.0,
const Real  id = 0.0,
const Real  ia = 0.0,
const Real  ial = 0.0,
const Real  theta_min = -M_PI/2,
const Real  theta_max = M_PI/2,
const Real  it_off = 0.0,
const Real  mass = 1.0,
const Real  cmx = 0.0,
const Real  cmy = 0.0,
const Real  cmz = 0.0,
const Real  ixx = 0.0,
const Real  ixy = 0.0,
const Real  ixz = 0.0,
const Real  iyy = 0.0,
const Real  iyz = 0.0,
const Real  izz = 0.0,
const Real  iIm = 0.0,
const Real  iGr = 0.0,
const Real  iB = 0.0,
const Real  iCf = 0.0,
const bool  dh = true,
const bool  min_inertial_para = false,
const bool  immobile = false 
)

Constructor.

Definition at line 150 of file robot.cpp.

Link::~Link ( )
inline

Destructor.

Definition at line 154 of file robot.h.

Member Function Documentation

Real Link::get_a ( void  ) const
inline

Return a.

Definition at line 160 of file robot.h.

Real Link::get_alpha ( void  ) const
inline

Return alpha.

Definition at line 161 of file robot.h.

Real Link::get_B ( void  ) const
inline

Return B.

Definition at line 172 of file robot.h.

Real Link::get_Cf ( void  ) const
inline

Return Cf.

Definition at line 173 of file robot.h.

Real Link::get_d ( void  ) const
inline

Return d.

Definition at line 159 of file robot.h.

bool Link::get_DH ( void  ) const
inline

Return DH value.

Definition at line 156 of file robot.h.

Real Link::get_Gr ( void  ) const
inline

Return Gr.

Definition at line 171 of file robot.h.

ReturnMatrix Link::get_I ( void  ) const
inline

Return I.

Definition at line 174 of file robot.h.

Real Link::get_Im ( void  ) const
inline

Return Im.

Definition at line 170 of file robot.h.

bool Link::get_immobile ( void  ) const
inline

Return immobile.

Definition at line 175 of file robot.h.

Real Link::get_joint_offset ( void  ) const
inline

Return joint_offset.

Definition at line 165 of file robot.h.

int Link::get_joint_type ( void  ) const
inline

Return the joint type.

Definition at line 157 of file robot.h.

Real Link::get_m ( void  ) const
inline

Return m.

Definition at line 169 of file robot.h.

ReturnMatrix Link::get_mc ( void  )
inline

Return mc.

Definition at line 166 of file robot.h.

ReturnMatrix Link::get_p ( void  ) const
inline

Return p.

Definition at line 168 of file robot.h.

Real Link::get_q ( void  ) const

Return joint position (theta if joint type is rotoide, d otherwise).

The joint offset is removed from the value.

Definition at line 299 of file robot.cpp.

ReturnMatrix Link::get_r ( void  )
inline

Return r.

Definition at line 167 of file robot.h.

Real Link::get_theta ( void  ) const
inline

Return theta.

Definition at line 158 of file robot.h.

Real Link::get_theta_max ( void  ) const
inline

Return theta_max.

Definition at line 164 of file robot.h.

Real Link::get_theta_min ( void  ) const
inline

Return theta_min.

Definition at line 163 of file robot.h.

void Link::set_B ( const Real  B_)
inline

Set B.

Definition at line 180 of file robot.h.

void Link::set_Cf ( const Real  Cf_)
inline

Set Cf.

Definition at line 181 of file robot.h.

void Link::set_I ( const Matrix I)

Set I.

Set the inertia matrix.

Definition at line 335 of file robot.cpp.

void Link::set_Im ( const Real  Im_)
inline

Set Im.

Definition at line 179 of file robot.h.

void Link::set_immobile ( bool  im)
inline

Set immobile.

Definition at line 183 of file robot.h.

void Link::set_m ( const Real  m_)
inline

Set m.

Definition at line 176 of file robot.h.

void Link::set_mc ( const ColumnVector mc_)

Set mc.

Set the mass $\times$ center of gravity position.

Definition at line 322 of file robot.cpp.

void Link::set_r ( const ColumnVector r_)

Set r.

Set the center of gravity position.

Definition at line 313 of file robot.cpp.

void Link::transform ( const Real  q)

Set the rotation matrix R and the vector p.

Definition at line 244 of file robot.cpp.

Friends And Related Function Documentation

friend class mRobot
friend

Definition at line 141 of file robot.h.

friend class mRobot_min_para
friend

Definition at line 142 of file robot.h.

friend class Robot
friend

Definition at line 140 of file robot.h.

friend class Robot_basic
friend

Definition at line 139 of file robot.h.

Member Data Documentation

Real Link::a
private

a DH parameter.

Definition at line 191 of file robot.h.

Real Link::alpha
private

alpha DH parameter.

Definition at line 191 of file robot.h.

Real Link::B
private

Viscous coefficient.

Definition at line 202 of file robot.h.

Real Link::Cf
private

Coulomb fiction coefficient.

Definition at line 202 of file robot.h.

Real Link::d
private

d DH parameter.

Definition at line 191 of file robot.h.

bool Link::DH
private

DH notation(true) or DH modified notation.

Definition at line 198 of file robot.h.

Real Link::Gr
private

Gear Ratio.

Definition at line 202 of file robot.h.

Matrix Link::I
private

Inertia matrix w.r.t. center of mass and link coordinate system orientation.

Definition at line 208 of file robot.h.

Real Link::Im
private

Motor Inertia.

Definition at line 202 of file robot.h.

bool Link::immobile
private

true if the joint is to be considered locked - ignored for inverse kinematics, but can still be reassigned through transform

Definition at line 209 of file robot.h.

Real Link::joint_offset
private

Offset in joint angle (rotoide and prismatic).

Definition at line 191 of file robot.h.

int Link::joint_type
private

Joint type.

Definition at line 190 of file robot.h.

Real Link::m
private

Mass of the link.

Definition at line 202 of file robot.h.

ColumnVector Link::mc
private

Mass $\times$ center of gravity (used if min_para = true).

Definition at line 207 of file robot.h.

bool Link::min_para
private

Minimum inertial parameter.

Definition at line 198 of file robot.h.

ColumnVector Link::p
private

Position vector of actual link w.r.t to previous link.

Definition at line 200 of file robot.h.

Real Link::qp

Joint velocity.

Definition at line 186 of file robot.h.

Real Link::qpp

Joint acceleration.

Definition at line 186 of file robot.h.

Matrix Link::R

Orientation matrix of actual link w.r.t to previous link.

Definition at line 185 of file robot.h.

ColumnVector Link::r
private

Position of center of mass w.r.t. link coordinate system (min_para=F).

Definition at line 200 of file robot.h.

Real Link::theta
private

theta DH parameter.

Definition at line 191 of file robot.h.

Real Link::theta_max
private

Max joint angle.

Definition at line 191 of file robot.h.

Real Link::theta_min
private

Min joint angle.

Definition at line 191 of file robot.h.


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


kni
Author(s): Martin Günther
autogenerated on Fri Jun 7 2019 22:06:46