Classes | Public Member Functions | Private Types | Private Member Functions | Private Attributes | Static Private Attributes | List of all members
AnaGuess::Kinematics6M90T Class Reference

Implements the kinematics for the Katana6M90T. More...

#include <kinematics6M90T.h>

Inheritance diagram for AnaGuess::Kinematics6M90T:
Inheritance graph
[legend]

Classes

struct  angles_calc
 
struct  position
 structs, type and constants used in inverse kinematics calculation More...
 

Public Member Functions

bool directKinematics (std::vector< double > &aPosition, const std::vector< double > aAngles)
 
bool enc2rad (std::vector< double > &aAngles, const std::vector< int > aEncoders)
 
std::vector< double > getAngMax ()
 get angle max More...
 
std::vector< double > getAngMin ()
 get angle min More...
 
std::vector< double > getAngOff ()
 get angle offset More...
 
std::vector< double > getAngRange ()
 get angle range More...
 
std::vector< double > getAngStop ()
 get angle stop More...
 
std::vector< int > getDir ()
 get direction More...
 
std::vector< int > getEncOff ()
 get encoder offset More...
 
std::vector< int > getEpc ()
 get encoders per cycle More...
 
std::vector< double > getLinkLength ()
 get link length More...
 
bool inverseKinematics (std::vector< double > &aAngles, const std::vector< double > aPosition, const std::vector< double > aStartingAngles)
 
 Kinematics6M90T ()
 Constructor. More...
 
bool rad2enc (std::vector< int > &aEncoders, const std::vector< double > aAngles)
 
bool setAngOff (const std::vector< double > aAngOff)
 set angle offset More...
 
bool setAngStop (const std::vector< double > aAngStop)
 set angle stop More...
 
bool setLinkLength (const std::vector< double > aLengths)
 set link length More...
 
 ~Kinematics6M90T ()
 Destructor. More...
 
- Public Member Functions inherited from AnaGuess::Kinematics
virtual ~Kinematics ()
 Virtual destructor. More...
 

Private Types

typedef std::vector< angles_calcangles_container
 

Private Member Functions

bool angledef (angles_calc &a) const
 
bool AnglePositionTest (const angles_calc &a) const
 
double findFirstEqualAngle (const std::vector< double > &v1, const std::vector< double > &v2) const
 
bool GripperTest (const position &p_gr, const angles_calc &angle) const
 
void IK_b1b2costh3_6MS (angles_calc &angle, const position &p) const
 
void IK_theta234theta5 (angles_calc &angle, const position &p_gr) const
 helper functions More...
 
bool initialize ()
 initialization routine More...
 
bool PositionTest6MS (const double &theta1, const double &theta2, const double &theta3, const double &theta234, const position &p) const
 
void thetacomp (angles_calc &angle, const position &p_m, const std::vector< double > &pose) const
 

Private Attributes

std::vector< double > mAngleOffset
 Angle offset vector [rad]. More...
 
std::vector< double > mAngleStop
 Angle stop vector [rad]. More...
 
std::vector< int > mEncoderOffset
 Encoder offset vector. More...
 
std::vector< int > mEncodersPerCycle
 Encoders per cycle vector. More...
 
bool mIsInitialized
 Initialized flag. More...
 
int mNumberOfMotors
 Number of motors of the robot. More...
 
int mNumberOfSegments
 Number of segments of the robot. More...
 
std::vector< int > mRotationDirection
 Rotation direction vector [1|-1]. More...
 
std::vector< double > mSegmentLength
 Effector segment lengths vector [m]. More...
 

Static Private Attributes

static const int cNrOfPossibleSolutions = 8
 

Detailed Description

Implements the kinematics for the Katana6M90T.

This class implemets the abstract kinematics interface for the Katana6M90T

Definition at line 30 of file kinematics6M90T.h.

Member Typedef Documentation

Definition at line 69 of file kinematics6M90T.h.

Constructor & Destructor Documentation

AnaGuess::Kinematics6M90T::Kinematics6M90T ( )

Constructor.

Definition at line 11 of file kinematics6M90T.cpp.

AnaGuess::Kinematics6M90T::~Kinematics6M90T ( )

Destructor.

Definition at line 15 of file kinematics6M90T.cpp.

Member Function Documentation

bool AnaGuess::Kinematics6M90T::angledef ( angles_calc a) const
private

Definition at line 626 of file kinematics6M90T.cpp.

bool AnaGuess::Kinematics6M90T::AnglePositionTest ( const angles_calc a) const
private

Definition at line 653 of file kinematics6M90T.cpp.

bool AnaGuess::Kinematics6M90T::directKinematics ( std::vector< double > &  aPosition,
const std::vector< double >  aAngles 
)
virtual

calculates the direct kinematics

Parameters
aPositionempty vector to store the position
aAnglesthe angle vector
Returns
true if no error occurred, false on error

Implements AnaGuess::Kinematics.

Definition at line 140 of file kinematics6M90T.cpp.

bool AnaGuess::Kinematics6M90T::enc2rad ( std::vector< double > &  aAngles,
const std::vector< int >  aEncoders 
)
virtual

calculates the angles corresponding to the given encoders

Parameters
aAnglesempty vector to store the angles
aEncodersthe encoder vector
Returns
true if no error occurred, false on error

Implements AnaGuess::Kinematics.

Definition at line 125 of file kinematics6M90T.cpp.

double AnaGuess::Kinematics6M90T::findFirstEqualAngle ( const std::vector< double > &  v1,
const std::vector< double > &  v2 
) const
private

Definition at line 505 of file kinematics6M90T.cpp.

std::vector< double > AnaGuess::Kinematics6M90T::getAngMax ( )
virtual

get angle max

Implements AnaGuess::Kinematics.

Definition at line 75 of file kinematics6M90T.cpp.

std::vector< double > AnaGuess::Kinematics6M90T::getAngMin ( )
virtual

get angle min

Implements AnaGuess::Kinematics.

Definition at line 63 of file kinematics6M90T.cpp.

std::vector< double > AnaGuess::Kinematics6M90T::getAngOff ( )
virtual

get angle offset

Implements AnaGuess::Kinematics.

Definition at line 39 of file kinematics6M90T.cpp.

std::vector< double > AnaGuess::Kinematics6M90T::getAngRange ( )
virtual

get angle range

Implements AnaGuess::Kinematics.

Definition at line 49 of file kinematics6M90T.cpp.

std::vector< double > AnaGuess::Kinematics6M90T::getAngStop ( )
virtual

get angle stop

Implements AnaGuess::Kinematics.

Definition at line 44 of file kinematics6M90T.cpp.

std::vector< int > AnaGuess::Kinematics6M90T::getDir ( )
virtual

get direction

Implements AnaGuess::Kinematics.

Definition at line 34 of file kinematics6M90T.cpp.

std::vector< int > AnaGuess::Kinematics6M90T::getEncOff ( )
virtual

get encoder offset

Implements AnaGuess::Kinematics.

Definition at line 29 of file kinematics6M90T.cpp.

std::vector< int > AnaGuess::Kinematics6M90T::getEpc ( )
virtual

get encoders per cycle

Implements AnaGuess::Kinematics.

Definition at line 24 of file kinematics6M90T.cpp.

std::vector< double > AnaGuess::Kinematics6M90T::getLinkLength ( )
virtual

get link length

Implements AnaGuess::Kinematics.

Definition at line 19 of file kinematics6M90T.cpp.

bool AnaGuess::Kinematics6M90T::GripperTest ( const position p_gr,
const angles_calc angle 
) const
private

Definition at line 478 of file kinematics6M90T.cpp.

void AnaGuess::Kinematics6M90T::IK_b1b2costh3_6MS ( angles_calc angle,
const position p 
) const
private

Definition at line 491 of file kinematics6M90T.cpp.

void AnaGuess::Kinematics6M90T::IK_theta234theta5 ( angles_calc angle,
const position p_gr 
) const
private

helper functions

Definition at line 437 of file kinematics6M90T.cpp.

bool AnaGuess::Kinematics6M90T::initialize ( )
privatevirtual

initialization routine

Implements AnaGuess::Kinematics.

Definition at line 380 of file kinematics6M90T.cpp.

bool AnaGuess::Kinematics6M90T::inverseKinematics ( std::vector< double > &  aAngles,
const std::vector< double >  aPosition,
const std::vector< double >  aStartingAngles 
)
virtual

caltulates the inverse kinematics

Parameters
aAnglesempty vector to store the angles
aPositionthe position vector
aStartingAnglesstarting angle vector to find the best (nearest) solution
Exceptions
NoSolutionExceptionif no solutios exists
Returns
true if no error occurred, false on error

Implements AnaGuess::Kinematics.

Definition at line 243 of file kinematics6M90T.cpp.

bool AnaGuess::Kinematics6M90T::PositionTest6MS ( const double &  theta1,
const double &  theta2,
const double &  theta3,
const double &  theta234,
const position p 
) const
private

Definition at line 612 of file kinematics6M90T.cpp.

bool AnaGuess::Kinematics6M90T::rad2enc ( std::vector< int > &  aEncoders,
const std::vector< double >  aAngles 
)
virtual

calculates the encoders corresponding to the given angles

Parameters
aEncodersempty vector to store the encoders
aAnglesthe angle vector
Returns
true if no error occurred, false on error

Implements AnaGuess::Kinematics.

Definition at line 132 of file kinematics6M90T.cpp.

bool AnaGuess::Kinematics6M90T::setAngOff ( const std::vector< double >  aAngOff)
virtual

set angle offset

Implements AnaGuess::Kinematics.

Definition at line 100 of file kinematics6M90T.cpp.

bool AnaGuess::Kinematics6M90T::setAngStop ( const std::vector< double >  aAngStop)
virtual

set angle stop

Implements AnaGuess::Kinematics.

Definition at line 112 of file kinematics6M90T.cpp.

bool AnaGuess::Kinematics6M90T::setLinkLength ( const std::vector< double >  aLengths)
virtual

set link length

Implements AnaGuess::Kinematics.

Definition at line 88 of file kinematics6M90T.cpp.

void AnaGuess::Kinematics6M90T::thetacomp ( angles_calc angle,
const position p_m,
const std::vector< double > &  pose 
) const
private

Definition at line 517 of file kinematics6M90T.cpp.

Member Data Documentation

const int AnaGuess::Kinematics6M90T::cNrOfPossibleSolutions = 8
staticprivate

Definition at line 70 of file kinematics6M90T.h.

std::vector<double> AnaGuess::Kinematics6M90T::mAngleOffset
private

Angle offset vector [rad].

Definition at line 39 of file kinematics6M90T.h.

std::vector<double> AnaGuess::Kinematics6M90T::mAngleStop
private

Angle stop vector [rad].

Definition at line 41 of file kinematics6M90T.h.

std::vector<int> AnaGuess::Kinematics6M90T::mEncoderOffset
private

Encoder offset vector.

Definition at line 45 of file kinematics6M90T.h.

std::vector<int> AnaGuess::Kinematics6M90T::mEncodersPerCycle
private

Encoders per cycle vector.

Definition at line 43 of file kinematics6M90T.h.

bool AnaGuess::Kinematics6M90T::mIsInitialized
private

Initialized flag.

Definition at line 49 of file kinematics6M90T.h.

int AnaGuess::Kinematics6M90T::mNumberOfMotors
private

Number of motors of the robot.

Definition at line 33 of file kinematics6M90T.h.

int AnaGuess::Kinematics6M90T::mNumberOfSegments
private

Number of segments of the robot.

Definition at line 35 of file kinematics6M90T.h.

std::vector<int> AnaGuess::Kinematics6M90T::mRotationDirection
private

Rotation direction vector [1|-1].

Definition at line 47 of file kinematics6M90T.h.

std::vector<double> AnaGuess::Kinematics6M90T::mSegmentLength
private

Effector segment lengths vector [m].

Definition at line 37 of file kinematics6M90T.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