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

#include <ikBase.h>

Inheritance diagram for CikBase:
Inheritance graph
[legend]

Public Member Functions

 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

void _initKinematics ()
 

Private Attributes

std::unique_ptr< KNI::KatanaKinematics_kinematicsImpl
 
bool _kinematicsIsInitialized
 

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

Definition at line 49 of file ikBase.h.

Constructor & Destructor Documentation

CikBase::CikBase ( )
inline

Definition at line 58 of file ikBase.h.

CikBase::~CikBase ( )

Definition at line 25 of file ikBase.cpp.

Member Function Documentation

void CikBase::_initKinematics ( )
private

Definition at line 35 of file ikBase.cpp.

void CikBase::DKApos ( double *  position)

Returns the current position of the robot in cartesian coordinates.

Note
This method is deprecated, please use getCoordinates(...) instead

Definition at line 196 of file ikBase.cpp.

void CikBase::getCoordinates ( double &  x,
double &  y,
double &  z,
double &  phi,
double &  theta,
double &  psi,
bool  refreshEncoders = true 
)

Returns the current position of the robot in cartesian coordinates.

Parameters
refreshEncodersWith this parameter you can determine if the method reads the actual encoders from the robot or if it will use the cached ones
Note
This function returns a tuple in python

Definition at line 349 of file ikBase.cpp.

void CikBase::getCoordinatesFromEncoders ( std::vector< double > &  pose,
const std::vector< int > &  encs 
)

Returns the position of the robot corresponting to the given encoders in cartesian coordinates.

Definition at line 399 of file ikBase.cpp.

void CikBase::getKinematicsVersion ( std::vector< int > &  version)

Returns the version number of the kinematics used.

Parameters
versionvector to write in version (major, minor, revision)
Note
integrated analytical kinematics returns version 0.1.0
kinematics library returns versions >= 1.0.0

Definition at line 161 of file ikBase.cpp.

void CikBase::IKCalculate ( double  X,
double  Y,
double  Z,
double  Al,
double  Be,
double  Ga,
std::vector< int >::iterator  solution_iter 
)

Calculates a set of encoders for the given coordinates. This method reads the current encoders from the robot and involves therefore also communication to the robot

Definition at line 200 of file ikBase.cpp.

void CikBase::IKCalculate ( double  X,
double  Y,
double  Z,
double  Al,
double  Be,
double  Ga,
std::vector< int >::iterator  solution_iter,
const std::vector< int > &  actualPosition 
)

Calculates a set of encoders for the given coordinates. For this method you have to pass an actualPosition too. No communication with the robot will be done here.

Definition at line 266 of file ikBase.cpp.

void CikBase::IKGoto ( double  X,
double  Y,
double  Z,
double  Al,
double  Be,
double  Ga,
bool  wait = false,
int  tolerance = 100,
long  timeout = TM_ENDLESS 
)

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

Note
This method is deprecated, please use moveRobotTo(...) instead

Definition at line 327 of file ikBase.cpp.

void CikBase::moveRobotTo ( double  x,
double  y,
double  z,
double  phi,
double  theta,
double  psi,
bool  waitUntilReached = false,
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

Definition at line 429 of file ikBase.cpp.

void CikBase::moveRobotTo ( std::vector< double >  coordinates,
bool  waitUntilReached = false,
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

Definition at line 433 of file ikBase.cpp.

void CikBase::setTcpOffset ( double  xoff,
double  yoff,
double  zoff,
double  psioff 
)

Set the offset from the flange to the desired tcp

Parameters
xoffoffset in x direction of flange coordinate system in m
yoffoffset in y direction of flange coordinate system in m
zoffoffset in z direction of flange coordinate system in m
psioffangle offset around x-axis of flange coordinate system in rad

Definition at line 180 of file ikBase.cpp.

Member Data Documentation

std::unique_ptr<KNI::KatanaKinematics> CikBase::_kinematicsImpl
private

Definition at line 52 of file ikBase.h.

bool CikBase::_kinematicsIsInitialized
private

Definition at line 53 of file ikBase.h.


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


kni
Author(s): Martin Günther
autogenerated on Fri Jan 3 2020 04:01:17