Implements the kinematics for the Katana6M90T. More...
#include <kinematics6M90T.h>
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) |
Kinematics6M90T () | |
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 stop | |
bool | setLinkLength (const std::vector< double > aLengths) |
set link length | |
~Kinematics6M90T () | |
Destructor. | |
Private Types | |
typedef std::vector< angles_calc > | angles_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 | |
bool | initialize () |
initialization routine | |
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]. | |
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 |
Implements the kinematics for the Katana6M90T.
This class implemets the abstract kinematics interface for the Katana6M90T
Definition at line 30 of file kinematics6M90T.h.
typedef std::vector<angles_calc> AnaGuess::Kinematics6M90T::angles_container [private] |
Definition at line 69 of file kinematics6M90T.h.
Constructor.
Definition at line 11 of file kinematics6M90T.cpp.
Destructor.
Definition at line 15 of file kinematics6M90T.cpp.
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
aPosition | empty vector to store the position |
aAngles | the angle vector |
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
aAngles | empty vector to store the angles |
aEncoders | the encoder vector |
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] |
std::vector< double > AnaGuess::Kinematics6M90T::getAngMin | ( | ) | [virtual] |
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] |
std::vector< double > AnaGuess::Kinematics6M90T::getAngStop | ( | ) | [virtual] |
std::vector< int > AnaGuess::Kinematics6M90T::getDir | ( | ) | [virtual] |
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] |
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 | ( | ) | [private, virtual] |
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
aAngles | empty vector to store the angles |
aPosition | the position vector |
aStartingAngles | starting angle vector to find the best (nearest) solution |
NoSolutionException | if no solutios exists |
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
aEncoders | empty vector to store the encoders |
aAngles | the angle vector |
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] |
bool AnaGuess::Kinematics6M90T::setLinkLength | ( | const std::vector< double > | aLengths | ) | [virtual] |
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.
const int AnaGuess::Kinematics6M90T::cNrOfPossibleSolutions = 8 [static, private] |
Definition at line 70 of file kinematics6M90T.h.
std::vector<double> AnaGuess::Kinematics6M90T::mAngleOffset [private] |
Angle offset vector [rad].
Reimplemented from AnaGuess::Kinematics.
Definition at line 39 of file kinematics6M90T.h.
std::vector<double> AnaGuess::Kinematics6M90T::mAngleStop [private] |
Angle stop vector [rad].
Reimplemented from AnaGuess::Kinematics.
Definition at line 41 of file kinematics6M90T.h.
std::vector<int> AnaGuess::Kinematics6M90T::mEncoderOffset [private] |
Encoder offset vector.
Reimplemented from AnaGuess::Kinematics.
Definition at line 45 of file kinematics6M90T.h.
std::vector<int> AnaGuess::Kinematics6M90T::mEncodersPerCycle [private] |
Encoders per cycle vector.
Reimplemented from AnaGuess::Kinematics.
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.
Reimplemented from AnaGuess::Kinematics.
Definition at line 33 of file kinematics6M90T.h.
int AnaGuess::Kinematics6M90T::mNumberOfSegments [private] |
Number of segments of the robot.
Reimplemented from AnaGuess::Kinematics.
Definition at line 35 of file kinematics6M90T.h.
std::vector<int> AnaGuess::Kinematics6M90T::mRotationDirection [private] |
Rotation direction vector [1|-1].
Reimplemented from AnaGuess::Kinematics.
Definition at line 47 of file kinematics6M90T.h.
std::vector<double> AnaGuess::Kinematics6M90T::mSegmentLength [private] |
Effector segment lengths vector [m].
Reimplemented from AnaGuess::Kinematics.
Definition at line 37 of file kinematics6M90T.h.