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

Linear movement Class. More...

#include <lmBase.h>

Inheritance diagram for CLMBase:
Inheritance graph
[legend]

Public Member Functions

 CLMBase ()
 
bool getActivatePositionController ()
 Check if the position controller will be activated after the linear movement. More...
 
double getMaximumLinearVelocity () const
 
void moveRobotLinearTo (double x, double y, double z, double phi, double theta, double psi, bool waitUntilReached=true, int waitTimeout=TM_ENDLESS)
 
void moveRobotLinearTo (std::vector< double > coordinates, bool waitUntilReached=true, int waitTimeout=TM_ENDLESS)
 
void moveRobotTo (double x, double y, double z, double phi, double theta, double psi, bool waitUntilReached=true, int waitTimeout=TM_ENDLESS)
 
void moveRobotTo (std::vector< double > coordinates, bool waitUntilReached=true, int waitTimeout=TM_ENDLESS)
 
void 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 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 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)
 
void setActivatePositionController (bool activate)
 
void setMaximumLinearVelocity (double maximumVelocity)
 
- Public Member Functions inherited from CikBase
 CikBase ()
 
void DKApos (double *position)
 
void getCoordinates (double &x, double &y, double &z, double &phi, double &theta, double &psi, bool refreshEncoders=true)
 
void getCoordinatesFromEncoders (std::vector< double > &pose, const std::vector< int > &encs)
 Returns the position of the robot corresponting to the given encoders in cartesian coordinates. More...
 
void getKinematicsVersion (std::vector< int > &version)
 
void IKCalculate (double X, double Y, double Z, double Al, double Be, double Ga, std::vector< int >::iterator solution_iter)
 
void IKCalculate (double X, double Y, double Z, double Al, double Be, double Ga, std::vector< int >::iterator solution_iter, const std::vector< int > &actualPosition)
 
void IKGoto (double X, double Y, double Z, double Al, double Be, double Ga, bool wait=false, int tolerance=100, long timeout=TM_ENDLESS)
 
void moveRobotTo (double x, double y, double z, double phi, double theta, double psi, bool waitUntilReached=false, int waitTimeout=TM_ENDLESS)
 
void moveRobotTo (std::vector< double > coordinates, bool waitUntilReached=false, int waitTimeout=TM_ENDLESS)
 
void setTcpOffset (double xoff, double yoff, double zoff, double psioff)
 
 ~CikBase ()
 
- Public Member Functions inherited from CKatana
void calibrate ()
 
void calibrate (long idx, TMotCLB clb, TMotSCP scp, TMotDYL dyl)
 
bool checkENLD (long idx, double degrees)
 Check if the absolute position in degrees is out of range. More...
 
 CKatana ()
 Constructor. More...
 
void closeGripper (bool waitUntilReached=false, int waitTimeout=100)
 
void create (const char *configurationFile, CCplBase *protocol)
 Create routine. More...
 
void create (KNI::kmlFactory *infos, CCplBase *protocol)
 
void create (TKatGNL &gnl, TKatMOT &mot, TKatSCT &sct, TKatEFF &eff, CCplBase *protocol)
 Create routine. More...
 
void dec (long idx, int dif, bool wait=false, int tolerance=100, long timeout=TM_ENDLESS)
 Decrements the motor specified by an index postion in encoders. More...
 
void decDegrees (long idx, double dif, bool wait=false, int tolerance=100, long timeout=TM_ENDLESS)
 Decrements the motor specified by an index postion in degree units. More...
 
void disableCrashLimits ()
 crash limits disable More...
 
void enableCrashLimits ()
 crash limits enable More...
 
void flushMoveBuffers ()
 flush move buffers More...
 
void freezeMotor (short number)
 
void freezeRobot ()
 
CKatBaseGetBase ()
 Returns pointer to 'CKatBase*'. More...
 
int getCurrentControllerType (int axis)
 Get the axis controller type. More...
 
short getForce (int axis)
 Get the current force. More...
 
void getGripperParameters (bool &isPresent, int &openEncoders, int &closeEncoders)
 Get the gripper parameters. More...
 
short getMotorAccelerationLimit (short number) const
 
int getMotorEncoders (short number, bool refreshEncoders=true) const
 
short getMotorVelocityLimit (short number) const
 
short getNumberOfMotors () const
 
std::vector< int >::iterator getRobotEncoders (std::vector< int >::iterator start, std::vector< int >::const_iterator end, bool refreshEncoders=true) const
 
std::vector< int > getRobotEncoders (bool refreshEncoders=true) const
 
void inc (long idx, int dif, bool wait=false, int tolerance=100, long timeout=TM_ENDLESS)
 Increments the motor specified by an index postion in encoders. More...
 
void incDegrees (long idx, double dif, bool wait=false, int tolerance=100, long timeout=TM_ENDLESS)
 Increments the motor specified by an index postion in degree units. More...
 
void mov (long idx, int tar, bool wait=false, int tolerance=100, long timeout=TM_ENDLESS)
 Moves the motor specified by an index to a given target position in encoders. More...
 
void movDegrees (long idx, double tar, bool wait=false, int tolerance=100, long timeout=TM_ENDLESS)
 Moves the motor specified by an index to a given target position in degree units. More...
 
void moveMotorBy (short number, double radianAngle, bool waitUntilReached=false, int waitTimeout=0)
 
void moveMotorByEnc (short number, int encoders, bool waitUntilReached=false, int waitTimeout=0)
 
void moveMotorTo (short number, double radianAngle, bool waitUntilReached=false, int waitTimeout=0)
 
void moveMotorToEnc (short number, int encoders, bool waitUntilReached=false, int encTolerance=100, int waitTimeout=0)
 
void moveRobotToEnc (std::vector< int >::const_iterator start, std::vector< int >::const_iterator end, bool waitUntilReached=false, int encTolerance=100, int waitTimeout=0)
 
void moveRobotToEnc (std::vector< int > encoders, bool waitUntilReached=false, int encTolerance=100, int waitTimeout=0)
 
void moveRobotToEnc4D (std::vector< int > target, int velocity=180, int acceleration=1, int encTolerance=100)
 Move to robot to given target in the vector-container with the given velocity, acceleration and tolerance. More...
 
void openGripper (bool waitUntilReached=false, int waitTimeout=100)
 
int readDigitalIO ()
 Read The Digital I/Os. More...
 
void searchMechStop (long idx, TSearchDir dir, TMotSCP scp, TMotDYL dyl)
 
void sendSplineToMotor (short number, short targetPosition, short duration, short p1, short p2, short p3, short p4)
 
void setAndStartPolyMovement (std::vector< short > polynomial, bool exactflag, int moreflag)
 
void setCrashLimit (long idx, int limit)
 unblock robot after a crash More...
 
void setForceLimit (int axis, int limit)
 Set the force limit for the current controller. More...
 
void setGripperParameters (bool isPresent, int openEncoders, int closeEncoders)
 
void setMotorAccelerationLimit (short number, short acceleration)
 
void setMotorVelocityLimit (short number, short velocity)
 
void setPositionCollisionLimit (long idx, int limit)
 set collision position limits More...
 
void setRobotAccelerationLimit (short acceleration)
 
void setRobotVelocityLimit (short velocity)
 
void setSpeedCollisionLimit (long idx, int limit)
 set collision speed limits More...
 
void startSplineMovement (bool exactflag, int moreflag=1)
 
void switchMotorOff (short number)
 
void switchMotorOn (short number)
 
void switchRobotOff ()
 
void switchRobotOn ()
 
void unBlock ()
 unblock robot after a crash More...
 
void waitFor (TMotStsFlg status, int waitTimeout)
 
void waitForMotor (short number, int encoders, int encTolerance=100, short mode=0, int waitTimeout=5000)
 
 ~CKatana ()
 Destructor. More...
 

Private Member Functions

bool checkJointSpeed (std::vector< int > lastsolution, std::vector< int > solution, double time)
 
int getSpeed (int distance, int acceleration, int time)
 
double relPosition (double reltime, double distance, double acc, double dec, double vmax)
 
void splineCoefficients (int steps, double *timearray, double *encoderarray, double *arr_p1, double *arr_p2, double *arr_p3, double *arr_p4)
 
double totalTime (double distance, double acc, double dec, double vmax)
 

Private Attributes

bool _activatePositionController
 
double _maximumVelocity
 

Additional Inherited Members

- Protected Member Functions inherited from CKatana
void setTolerance (long idx, int enc_tolerance)
 Sets the tolerance range in encoder units for the robots movements. More...
 
- Protected Attributes inherited from CKatana
int _gripperCloseEncoders
 
bool _gripperIsPresent
 
int _gripperOpenEncoders
 
CKatBasebase
 base katana More...
 
int mKatanaType
 The type of KatanaXXX (300 or 400) More...
 
int mKinematics
 The kinematics implementation: 0 for Analytical, 1 for RobAnaGuess. More...
 

Detailed Description

Linear movement Class.

This class allows to do linear movements with the Katana robot.

Definition at line 73 of file lmBase.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