Classes | Public Member Functions | Private Types | Private Member Functions | Private Attributes | Static Private Attributes
AnaGuess::Kinematics6M90G Class Reference

Implements the kinematics for the Katana6M90G. More...

#include <kinematics6M90G.h>

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

List of all members.

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
std::vector< double > getAngMin ()
 get angle min
std::vector< double > getAngOff ()
 get angle offset
std::vector< double > getAngRange ()
 get angle range
std::vector< double > getAngStop ()
 get angle stop
std::vector< int > getDir ()
 get direction
std::vector< int > getEncOff ()
 get encoder offset
std::vector< int > getEpc ()
 get encoders per cycle
std::vector< double > getLinkLength ()
 get link length
bool inverseKinematics (std::vector< double > &aAngles, const std::vector< double > aPosition, const std::vector< double > aStartingAngles)
 Kinematics6M90G ()
 Constructor.
bool rad2enc (std::vector< int > &aEncoders, const std::vector< double > aAngles)
bool setAngOff (const std::vector< double > aAngOff)
 set angle offset
bool setAngStop (const std::vector< double > aAngStop)
 set angle offset
bool setLinkLength (const std::vector< double > aLengths)
 set link length
 ~Kinematics6M90G ()
 Destructor.

Private Types

typedef std::vector< angles_calcangles_container

Private Member Functions

bool angledef (angles_calc &a) const
bool AnglePositionTest (const angles_calc &a) 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
bool initialize ()
 initialization routine
bool PositionTest6MS (const angles_calc &a, const position &p) const
void thetacomp (angles_calc &angle, const position &p_m) const

Private Attributes

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

Static Private Attributes

static const int cNrOfPossibleSolutions = 8

Detailed Description

Implements the kinematics for the Katana6M90G.

This class implemets the abstract kinematics interface for the Katana6M90G

Definition at line 30 of file kinematics6M90G.h.


Member Typedef Documentation

Definition at line 68 of file kinematics6M90G.h.


Constructor & Destructor Documentation

Constructor.

Definition at line 11 of file kinematics6M90G.cpp.

Destructor.

Definition at line 15 of file kinematics6M90G.cpp.


Member Function Documentation

bool AnaGuess::Kinematics6M90G::angledef ( angles_calc a) const [private]

Definition at line 512 of file kinematics6M90G.cpp.

bool AnaGuess::Kinematics6M90G::AnglePositionTest ( const angles_calc a) const [private]

Definition at line 533 of file kinematics6M90G.cpp.

bool AnaGuess::Kinematics6M90G::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 141 of file kinematics6M90G.cpp.

bool AnaGuess::Kinematics6M90G::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 126 of file kinematics6M90G.cpp.

std::vector< double > AnaGuess::Kinematics6M90G::getAngMax ( ) [virtual]

get angle max

Implements AnaGuess::Kinematics.

Definition at line 76 of file kinematics6M90G.cpp.

std::vector< double > AnaGuess::Kinematics6M90G::getAngMin ( ) [virtual]

get angle min

Implements AnaGuess::Kinematics.

Definition at line 64 of file kinematics6M90G.cpp.

std::vector< double > AnaGuess::Kinematics6M90G::getAngOff ( ) [virtual]

get angle offset

Implements AnaGuess::Kinematics.

Definition at line 40 of file kinematics6M90G.cpp.

std::vector< double > AnaGuess::Kinematics6M90G::getAngRange ( ) [virtual]

get angle range

Implements AnaGuess::Kinematics.

Definition at line 50 of file kinematics6M90G.cpp.

std::vector< double > AnaGuess::Kinematics6M90G::getAngStop ( ) [virtual]

get angle stop

Implements AnaGuess::Kinematics.

Definition at line 45 of file kinematics6M90G.cpp.

std::vector< int > AnaGuess::Kinematics6M90G::getDir ( ) [virtual]

get direction

Implements AnaGuess::Kinematics.

Definition at line 35 of file kinematics6M90G.cpp.

std::vector< int > AnaGuess::Kinematics6M90G::getEncOff ( ) [virtual]

get encoder offset

Implements AnaGuess::Kinematics.

Definition at line 30 of file kinematics6M90G.cpp.

std::vector< int > AnaGuess::Kinematics6M90G::getEpc ( ) [virtual]

get encoders per cycle

Implements AnaGuess::Kinematics.

Definition at line 25 of file kinematics6M90G.cpp.

std::vector< double > AnaGuess::Kinematics6M90G::getLinkLength ( ) [virtual]

get link length

Implements AnaGuess::Kinematics.

Definition at line 20 of file kinematics6M90G.cpp.

bool AnaGuess::Kinematics6M90G::GripperTest ( const position p_gr,
const angles_calc angle 
) const [private]

Definition at line 460 of file kinematics6M90G.cpp.

void AnaGuess::Kinematics6M90G::IK_b1b2costh3_6MS ( angles_calc angle,
const position p 
) const [private]

Definition at line 473 of file kinematics6M90G.cpp.

void AnaGuess::Kinematics6M90G::IK_theta234theta5 ( angles_calc angle,
const position p_gr 
) const [private]

helper functions

Definition at line 418 of file kinematics6M90G.cpp.

bool AnaGuess::Kinematics6M90G::initialize ( ) [private, virtual]

initialization routine

Implements AnaGuess::Kinematics.

Definition at line 361 of file kinematics6M90G.cpp.

bool AnaGuess::Kinematics6M90G::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 223 of file kinematics6M90G.cpp.

bool AnaGuess::Kinematics6M90G::PositionTest6MS ( const angles_calc a,
const position p 
) const [private]

Definition at line 498 of file kinematics6M90G.cpp.

bool AnaGuess::Kinematics6M90G::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 133 of file kinematics6M90G.cpp.

bool AnaGuess::Kinematics6M90G::setAngOff ( const std::vector< double >  aAngOff) [virtual]

set angle offset

Implements AnaGuess::Kinematics.

Definition at line 101 of file kinematics6M90G.cpp.

bool AnaGuess::Kinematics6M90G::setAngStop ( const std::vector< double >  aAngStop) [virtual]

set angle offset

set angle stop

Implements AnaGuess::Kinematics.

Definition at line 113 of file kinematics6M90G.cpp.

bool AnaGuess::Kinematics6M90G::setLinkLength ( const std::vector< double >  aLengths) [virtual]

set link length

Implements AnaGuess::Kinematics.

Definition at line 89 of file kinematics6M90G.cpp.

void AnaGuess::Kinematics6M90G::thetacomp ( angles_calc angle,
const position p_m 
) const [private]

Definition at line 487 of file kinematics6M90G.cpp.


Member Data Documentation

const int AnaGuess::Kinematics6M90G::cNrOfPossibleSolutions = 8 [static, private]

Definition at line 69 of file kinematics6M90G.h.

std::vector<double> AnaGuess::Kinematics6M90G::mAngleOffset [private]

Angle offset vector [rad].

Reimplemented from AnaGuess::Kinematics.

Definition at line 39 of file kinematics6M90G.h.

std::vector<double> AnaGuess::Kinematics6M90G::mAngleStop [private]

Angle stop vector [rad].

Reimplemented from AnaGuess::Kinematics.

Definition at line 41 of file kinematics6M90G.h.

std::vector<int> AnaGuess::Kinematics6M90G::mEncoderOffset [private]

Encoder offset vector.

Reimplemented from AnaGuess::Kinematics.

Definition at line 45 of file kinematics6M90G.h.

Encoders per cycle vector.

Reimplemented from AnaGuess::Kinematics.

Definition at line 43 of file kinematics6M90G.h.

Initialized flag.

Definition at line 49 of file kinematics6M90G.h.

Number of motors of the robot.

Reimplemented from AnaGuess::Kinematics.

Definition at line 33 of file kinematics6M90G.h.

Number of segments of the robot.

Reimplemented from AnaGuess::Kinematics.

Definition at line 35 of file kinematics6M90G.h.

Rotation direction vector [1|-1].

Reimplemented from AnaGuess::Kinematics.

Definition at line 47 of file kinematics6M90G.h.

std::vector<double> AnaGuess::Kinematics6M90G::mSegmentLength [private]

Effector segment lengths vector [m].

Reimplemented from AnaGuess::Kinematics.

Definition at line 37 of file kinematics6M90G.h.


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


kni
Author(s): Martin Günther
autogenerated on Thu Aug 27 2015 13:40:08