Classes | Functions | Variables
Exceptions

Classes

class  CannotGetSetPortAttributesException
class  CannotOpenPortException
class  CLMBase
 Linear movement Class. More...
class  ConfigFileEntryNotFoundException
class  ConfigFileOpenException
class  ConfigFileSectionNotFoundException
class  ConfigFileStateException
class  ConfigFileSubsectionNotFoundException
class  ConfigFileSyntaxErrorException
struct  Context
class  DeviceReadException
class  DeviceWriteException
class  ErrorException
class  Exception
class  FirmwareException
class  JointSpeedException
class  MotorCrashException
class  MotorOutOfRangeException
class  MotorTimeoutException
class  KNI::NoSolutionException
class  ParameterReadingException
class  ParameterWritingException
class  PortNotOpenException
class  ReadNotCompleteException
class  ReadWriteNotCompleteException
class  SlaveErrorException
class  WaitParameterException
class  WriteNotCompleteException
class  WrongCRCException
class  WrongParameterException

Functions

bool CLMBase::checkJointSpeed (std::vector< int > lastsolution, std::vector< int > solution, double time)
 CLMBase::CLMBase ()
bool CLMBase::getActivatePositionController ()
double CLMBase::getMaximumLinearVelocity () const
int CLMBase::getSpeed (int distance, int acceleration, int time)
 JointSpeedException::JointSpeedException () throw ()
void CLMBase::moveRobotLinearTo (double x, double y, double z, double phi, double theta, double psi, bool waitUntilReached=true, int waitTimeout=TM_ENDLESS)
void CLMBase::moveRobotLinearTo (std::vector< double > coordinates, bool waitUntilReached=true, int waitTimeout=TM_ENDLESS)
void CLMBase::moveRobotTo (double x, double y, double z, double phi, double theta, double psi, bool waitUntilReached=true, int waitTimeout=TM_ENDLESS)
void CLMBase::moveRobotTo (std::vector< double > coordinates, bool waitUntilReached=true, int waitTimeout=TM_ENDLESS)
void CLMBase::movLM (double X, double Y, double Z, double Al, double Be, double Ga, bool exactflag, double vmax, bool wait=true, int tolerance=100, long timeout=TM_ENDLESS)
void CLMBase::movLM2P (double X1, double Y1, double Z1, double Al1, double Be1, double Ga1, double X2, double Y2, double Z2, double Al2, double Be2, double Ga2, bool exactflag, double vmax, bool wait=true, int tolerance=100, long timeout=TM_ENDLESS)
void CLMBase::movP2P (double X1, double Y1, double Z1, double Ph1, double Th1, double Ps1, double X2, double Y2, double Z2, double Ph2, double Th2, double Ps2, bool exactflag, double vmax, bool wait=true, long timeout=TM_ENDLESS)
double CLMBase::relPosition (double reltime, double distance, double acc, double dec, double vmax)
void CLMBase::setActivatePositionController (bool activate)
void CLMBase::setMaximumLinearVelocity (double maximumVelocity)
void CLMBase::splineCoefficients (int steps, double *timearray, double *encoderarray, double *arr_p1, double *arr_p2, double *arr_p3, double *arr_p4)
double CLMBase::totalTime (double distance, double acc, double dec, double vmax)
 WaitParameterException::WaitParameterException () throw ()

Variables

bool CLMBase::_activatePositionController
double CLMBase::_maximumVelocity

Function Documentation

bool CLMBase::checkJointSpeed ( std::vector< int >  lastsolution,
std::vector< int >  solution,
double  time 
) [private]

Checks if the joint speeds are below speed limit.

Maximum joint speed is 180enc / 10ms.

Author:
Jonas Haller
Parameters:
lastsolutionencoder values of last point
solutionencoder values of current point
timetime difference between the points in s
Returns:
true if joint speeds ok, false if joint speed too high

Definition at line 407 of file lmBase.cpp.

CLMBase::CLMBase ( ) [inline]

Definition at line 153 of file lmBase.h.

Check if the position controller will be activated after the linear movement

Definition at line 914 of file lmBase.cpp.

Definition at line 907 of file lmBase.cpp.

int CLMBase::getSpeed ( int  distance,
int  acceleration,
int  time 
) [private]

Calculates speed from distance, acceleration and time for the movement.

Author:
Jonas Haller
Parameters:
distanceabsolute (positive) distance of the movement in encoder
accelerationacceleration and deceleration in enc / s^2
timetime that can be used for the movement in s
Returns:
speed in enc / s to finish the movement on time

Definition at line 423 of file lmBase.cpp.

Definition at line 54 of file lmBase.h.

void CLMBase::moveRobotLinearTo ( double  x,
double  y,
double  z,
double  phi,
double  theta,
double  psi,
bool  waitUntilReached = true,
int  waitTimeout = TM_ENDLESS 
)
Parameters:
waitUntilReachedhas to be true with new implementation of movLM2P

Definition at line 869 of file lmBase.cpp.

void CLMBase::moveRobotLinearTo ( std::vector< double >  coordinates,
bool  waitUntilReached = true,
int  waitTimeout = TM_ENDLESS 
)

This method does the same as the one above and is mainly provided for convenience

Note:
You can call this function in python using tuples: Example: katana.moveRobotLinearTo( (x,y,z,phi,theta,psi) )
If the size of the container is smaller than 6, it will throw an exception!

Definition at line 876 of file lmBase.cpp.

void CLMBase::moveRobotTo ( double  x,
double  y,
double  z,
double  phi,
double  theta,
double  psi,
bool  waitUntilReached = true,
int  waitTimeout = TM_ENDLESS 
)

Moves to robot to given cartesian coordinates and euler-angles.

Note:
Instead of a given tolerance, a default tolerance is being used

Reimplemented from CikBase.

Definition at line 880 of file lmBase.cpp.

void CLMBase::moveRobotTo ( std::vector< double >  coordinates,
bool  waitUntilReached = true,
int  waitTimeout = TM_ENDLESS 
)

This method does the same as the one above and is mainly provided for convenience

Note:
You can call this function in python using tuples: Example: katana.moveRobotTo( (x,y,z,phi,theta,psi) )
If the size of the container is smaller than 6, it will throw an exception

Reimplemented from CikBase.

Definition at line 895 of file lmBase.cpp.

void CLMBase::movLM ( double  X,
double  Y,
double  Z,
double  Al,
double  Be,
double  Ga,
bool  exactflag,
double  vmax,
bool  wait = true,
int  tolerance = 100,
long  timeout = TM_ENDLESS 
)
Parameters:
waithas to be true with new implementation of movLM2P

Definition at line 853 of file lmBase.cpp.

void CLMBase::movLM2P ( double  X1,
double  Y1,
double  Z1,
double  Al1,
double  Be1,
double  Ga1,
double  X2,
double  Y2,
double  Z2,
double  Al2,
double  Be2,
double  Ga2,
bool  exactflag,
double  vmax,
bool  wait = true,
int  tolerance = 100,
long  timeout = TM_ENDLESS 
)

Move linear from point to point using multiple splines.

Author:
Jonas Haller
Parameters:
X1,Y1,Z1,Ph1,Th1,Ps1X, Y, Z, Phi, Theta, Psi of actual position
X2,Y2,Z2,Ph2,Th2,Ps2X, Y, Z, Phi, Theta, Psi of target position
exactflagactivate the position controller after the movement
vmaxmaximum velocity of the movement in mm/s
waitwait for end of movement
tolerancetolerance for all motor encoders
timeouttimeout for linear movement in ms
Exceptions:
NoSolutionExceptionif no solution found for IK
JointSpeedExceptionif joint speed too high
WaitParameterExceptionif wait set to false
Returns:
void

Definition at line 32 of file lmBase.cpp.

void CLMBase::movP2P ( double  X1,
double  Y1,
double  Z1,
double  Ph1,
double  Th1,
double  Ps1,
double  X2,
double  Y2,
double  Z2,
double  Ph2,
double  Th2,
double  Ps2,
bool  exactflag,
double  vmax,
bool  wait = true,
long  timeout = TM_ENDLESS 
)

Move point to point using splines.

Author:
Jonas Haller
Parameters:
X1,Y1,Z1,Ph1,Th1,Ps1X, Y, Z, Phi, Theta, Psi of actual position
X2,Y2,Z2,Ph2,Th2,Ps2X, Y, Z, Phi, Theta, Psi of target position
exactflagactivate the position controller after the movement
vmaxmaximum velocity for motors
waitwait for end of movement
tolerancetolerance for all motor encoders
timeouttimeout for movement in ms
Exceptions:
NoSolutionExceptionif no solution found for IK
JointSpeedExceptionif joint speed too high
WaitParameterExceptionif wait set to false
Returns:
void

Definition at line 457 of file lmBase.cpp.

double CLMBase::relPosition ( double  reltime,
double  distance,
double  acc,
double  dec,
double  vmax 
) [private]

Calculates the relative position reached after the relative time given.

Author:
Jonas Haller
Parameters:
reltimerelative time (fraction of totaltime)
distancedistance of the movement in mm
accacceleration at the beginning in mm/s^2
decdeceleration at the end in mm/s^2
vmaxmaximum velocity of the movement in mm/s
Returns:
relative distance (fraction of distance)

Definition at line 284 of file lmBase.cpp.

void CLMBase::setActivatePositionController ( bool  activate)

Re-Activate the position controller after the linear movement.

Note:
This can result in a small movement after the movement

Definition at line 911 of file lmBase.cpp.

void CLMBase::setMaximumLinearVelocity ( double  maximumVelocity)

Definition at line 900 of file lmBase.cpp.

void CLMBase::splineCoefficients ( int  steps,
double *  timearray,
double *  encoderarray,
double *  arr_p1,
double *  arr_p2,
double *  arr_p3,
double *  arr_p4 
) [private]

Calculates the spline coefficient and stores them in arr_p1 - arr_p4.

Boundary conditions are that f_1'=0 and f_n'=0 (zero velocity at beginning and end of the movement) and f_i''=P_(i+1)''.

Author:
Jonas Haller
Parameters:
stepsnumber of splines to calculate
timearraytimes of the points (length = steps + 1)
encoderarrayencoder values of the points (length = steps + 1)
arr_p1to return parameters 1 (length = steps)
arr_p2to return parameters 2 (length = steps)
arr_p3to return parameters 3 (length = steps)
arr_p4to return parameters 4 (length = steps)
Returns:
void

Definition at line 316 of file lmBase.cpp.

double CLMBase::totalTime ( double  distance,
double  acc,
double  dec,
double  vmax 
) [private]

Calculates time needed for movement over a distance.

Author:
Jonas Haller
Parameters:
distancedistance of the movement in mm
accacceleration at the beginning in mm/s^2
decdeceleration at the end in mm/s^2
vmaxmaximum velocity of the movement in mm/s
Returns:
time needed for the movement in s

Definition at line 267 of file lmBase.cpp.

Definition at line 62 of file lmBase.h.


Variable Documentation

Definition at line 77 of file lmBase.h.

double CLMBase::_maximumVelocity [private]

Definition at line 76 of file lmBase.h.



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