Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
CKatana Class Reference

Extended Katana class with additional functions. More...

#include <kmlExt.h>

Inheritance diagram for CKatana:
Inheritance graph
[legend]

Public Member Functions

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...
 

Protected Member Functions

void setTolerance (long idx, int enc_tolerance)
 Sets the tolerance range in encoder units for the robots movements. More...
 

Protected Attributes

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

Extended Katana class with additional functions.

This class uses the 'CKatBase* base' object to refer to a Katana robot.

Definition at line 64 of file kmlExt.h.

Constructor & Destructor Documentation

CKatana::CKatana ( )
inline

Constructor.

Definition at line 88 of file kmlExt.h.

CKatana::~CKatana ( )
inline

Destructor.

Definition at line 91 of file kmlExt.h.

Member Function Documentation

void CKatana::calibrate ( )

Definition at line 115 of file kmlExt.cpp.

void CKatana::calibrate ( long  idx,
TMotCLB  clb,
TMotSCP  scp,
TMotDYL  dyl 
)
Parameters
idxmotor index
clbcalibration struct for one motor
scpstatic controller parameters
dyldynamic controller parameters

Definition at line 181 of file kmlExt.cpp.

bool CKatana::checkENLD ( long  idx,
double  degrees 
)

Check if the absolute position in degrees is out of range.

Definition at line 276 of file kmlExt.cpp.

void CKatana::closeGripper ( bool  waitUntilReached = false,
int  waitTimeout = 100 
)

Definition at line 558 of file kmlExt.cpp.

void CKatana::create ( const char *  configurationFile,
CCplBase protocol 
)

Create routine.

Definition at line 65 of file kmlExt.cpp.

void CKatana::create ( KNI::kmlFactory infos,
CCplBase protocol 
)

Definition at line 73 of file kmlExt.cpp.

void CKatana::create ( TKatGNL gnl,
TKatMOT mot,
TKatSCT sct,
TKatEFF eff,
CCplBase protocol 
)

Create routine.

Parameters
gnlkatana initial attributes
motmotor initial attributes
sctsensor controller initial attributes
effend effector initial attributes
protocolprotocol to be used

Definition at line 110 of file kmlExt.cpp.

void CKatana::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.

Definition at line 42 of file kmlExt.cpp.

void CKatana::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.

Definition at line 56 of file kmlExt.cpp.

void CKatana::disableCrashLimits ( )

crash limits disable

Definition at line 286 of file kmlExt.cpp.

void CKatana::enableCrashLimits ( )

crash limits enable

Definition at line 281 of file kmlExt.cpp.

void CKatana::flushMoveBuffers ( )

flush move buffers

Definition at line 296 of file kmlExt.cpp.

void CKatana::freezeMotor ( short  number)

Definition at line 571 of file kmlExt.cpp.

void CKatana::freezeRobot ( )

Definition at line 566 of file kmlExt.cpp.

CKatBase* CKatana::GetBase ( )
inline

Returns pointer to 'CKatBase*'.

Definition at line 83 of file kmlExt.h.

int CKatana::getCurrentControllerType ( int  axis)

Get the axis controller type.

Returns
0 for position controller, 1 for current controller

Definition at line 351 of file kmlExt.cpp.

short CKatana::getForce ( int  axis)

Get the current force.

Definition at line 344 of file kmlExt.cpp.

void CKatana::getGripperParameters ( bool &  isPresent,
int &  openEncoders,
int &  closeEncoders 
)

Get the gripper parameters.

Definition at line 611 of file kmlExt.cpp.

short CKatana::getMotorAccelerationLimit ( short  number) const

Definition at line 394 of file kmlExt.cpp.

int CKatana::getMotorEncoders ( short  number,
bool  refreshEncoders = true 
) const

Definition at line 362 of file kmlExt.cpp.

short CKatana::getMotorVelocityLimit ( short  number) const

Definition at line 390 of file kmlExt.cpp.

short CKatana::getNumberOfMotors ( ) const

Definition at line 357 of file kmlExt.cpp.

std::vector< int >::iterator CKatana::getRobotEncoders ( std::vector< int >::iterator  start,
std::vector< int >::const_iterator  end,
bool  refreshEncoders = true 
) const

Write the cached encoders into the container. Set refreshEncoders=true if the KNI should fetch them from the robot. If m=distance(start, end) is smaller than the number of motors, only the first m motors will be written to the container, the function will not throw an exception because of this. The return value will point to one element after the last one.

Definition at line 369 of file kmlExt.cpp.

std::vector< int > CKatana::getRobotEncoders ( bool  refreshEncoders = true) const

Get the current robot encoders as a vector-container. This method is mainly provided for convenience. It is easier than the other getRobotEncoders method but probably not so efficient. It is much easier to use via the wrappers.

Definition at line 383 of file kmlExt.cpp.

void CKatana::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.

Definition at line 38 of file kmlExt.cpp.

void CKatana::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.

Definition at line 52 of file kmlExt.cpp.

void CKatana::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.

Definition at line 46 of file kmlExt.cpp.

void CKatana::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.

Definition at line 60 of file kmlExt.cpp.

void CKatana::moveMotorBy ( short  number,
double  radianAngle,
bool  waitUntilReached = false,
int  waitTimeout = 0 
)

Definition at line 432 of file kmlExt.cpp.

void CKatana::moveMotorByEnc ( short  number,
int  encoders,
bool  waitUntilReached = false,
int  waitTimeout = 0 
)

Definition at line 423 of file kmlExt.cpp.

void CKatana::moveMotorTo ( short  number,
double  radianAngle,
bool  waitUntilReached = false,
int  waitTimeout = 0 
)

Definition at line 443 of file kmlExt.cpp.

void CKatana::moveMotorToEnc ( short  number,
int  encoders,
bool  waitUntilReached = false,
int  encTolerance = 100,
int  waitTimeout = 0 
)

Definition at line 438 of file kmlExt.cpp.

void CKatana::moveRobotToEnc ( std::vector< int >::const_iterator  start,
std::vector< int >::const_iterator  end,
bool  waitUntilReached = false,
int  encTolerance = 100,
int  waitTimeout = 0 
)

Move to robot to given encoders. You can provide less values than the number of motors. In that case only the given ones will be moved. This can be usefull in cases where you want to move the robot but you don't want to move the gripper.

Definition at line 463 of file kmlExt.cpp.

void CKatana::moveRobotToEnc ( std::vector< int >  encoders,
bool  waitUntilReached = false,
int  encTolerance = 100,
int  waitTimeout = 0 
)

Move to robot to given encoders in the vector-container. This method is mainly provided for convenience. Catch by value (and not by reference) is intended to avoid nasty wrapping code.

Definition at line 509 of file kmlExt.cpp.

void CKatana::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.

Definition at line 514 of file kmlExt.cpp.

void CKatana::openGripper ( bool  waitUntilReached = false,
int  waitTimeout = 100 
)

Definition at line 551 of file kmlExt.cpp.

int CKatana::readDigitalIO ( )

Read The Digital I/Os.

Definition at line 647 of file kmlExt.cpp.

void CKatana::searchMechStop ( long  idx,
TSearchDir  dir,
TMotSCP  scp,
TMotDYL  dyl 
)
Parameters
idxmotor index
dirsearch direction
scpstatic controller parameters
dyldynamic controller parameters

Definition at line 195 of file kmlExt.cpp.

void CKatana::sendSplineToMotor ( short  number,
short  targetPosition,
short  duration,
short  p1,
short  p2,
short  p3,
short  p4 
)

Send one spline to the motor

Parameters
durationDuration has to be given in 10ms units

Definition at line 631 of file kmlExt.cpp.

void CKatana::setAndStartPolyMovement ( std::vector< short >  polynomial,
bool  exactflag,
int  moreflag 
)

Send polynomials to all motors and start movement

Parameters
polynomialtime, target pos and coefficients of the motor polynomials
exactflagexactflag
moreflag0 = start moving more following, 1 = last or a single polynomial movement, 2 = do not start moving yet more following

Definition at line 636 of file kmlExt.cpp.

void CKatana::setCrashLimit ( long  idx,
int  limit 
)

unblock robot after a crash

Definition at line 301 of file kmlExt.cpp.

void CKatana::setForceLimit ( int  axis,
int  limit 
)

Set the force limit for the current controller.

Parameters
axisaxis number 1-6. If 0, send limit to all axes

Definition at line 314 of file kmlExt.cpp.

void CKatana::setGripperParameters ( bool  isPresent,
int  openEncoders,
int  closeEncoders 
)

Tell the robot about the presence of a gripper.

Parameters
openEncodersWhich encoders should be used as target positions for opening the gripper
closeEncodersDito for closing the gripper

Definition at line 604 of file kmlExt.cpp.

void CKatana::setMotorAccelerationLimit ( short  number,
short  acceleration 
)

Definition at line 411 of file kmlExt.cpp.

void CKatana::setMotorVelocityLimit ( short  number,
short  velocity 
)

Definition at line 399 of file kmlExt.cpp.

void CKatana::setPositionCollisionLimit ( long  idx,
int  limit 
)

set collision position limits

Definition at line 306 of file kmlExt.cpp.

void CKatana::setRobotAccelerationLimit ( short  acceleration)

Set the velocity of all motors together. This does not set the velocity of the TCP.

Definition at line 416 of file kmlExt.cpp.

void CKatana::setRobotVelocityLimit ( short  velocity)

Definition at line 404 of file kmlExt.cpp.

void CKatana::setSpeedCollisionLimit ( long  idx,
int  limit 
)

set collision speed limits

Definition at line 310 of file kmlExt.cpp.

void CKatana::setTolerance ( long  idx,
int  enc_tolerance 
)
protected

Sets the tolerance range in encoder units for the robots movements.

Definition at line 271 of file kmlExt.cpp.

void CKatana::startSplineMovement ( bool  exactflag,
int  moreflag = 1 
)

Start a spline movement

Parameters
exactflagSet it to true if you want the position controller activated after the movement
moreflag0 = start moving more following, 1 = last or a single polynomial movement, 2 = do not start moving yet more following

Definition at line 618 of file kmlExt.cpp.

void CKatana::switchMotorOff ( short  number)

Definition at line 596 of file kmlExt.cpp.

void CKatana::switchMotorOn ( short  number)

Definition at line 589 of file kmlExt.cpp.

void CKatana::switchRobotOff ( )

Definition at line 584 of file kmlExt.cpp.

void CKatana::switchRobotOn ( )

Definition at line 578 of file kmlExt.cpp.

void CKatana::unBlock ( )

unblock robot after a crash

Definition at line 291 of file kmlExt.cpp.

void CKatana::waitFor ( TMotStsFlg  status,
int  waitTimeout 
)

Definition at line 458 of file kmlExt.cpp.

void CKatana::waitForMotor ( short  number,
int  encoders,
int  encTolerance = 100,
short  mode = 0,
int  waitTimeout = 5000 
)

Definition at line 453 of file kmlExt.cpp.

Member Data Documentation

int CKatana::_gripperCloseEncoders
protected

Definition at line 71 of file kmlExt.h.

bool CKatana::_gripperIsPresent
protected

Definition at line 69 of file kmlExt.h.

int CKatana::_gripperOpenEncoders
protected

Definition at line 70 of file kmlExt.h.

CKatBase* CKatana::base
protected

base katana

Definition at line 67 of file kmlExt.h.

int CKatana::mKatanaType
protected

The type of KatanaXXX (300 or 400)

Definition at line 73 of file kmlExt.h.

int CKatana::mKinematics
protected

The kinematics implementation: 0 for Analytical, 1 for RobAnaGuess.

Definition at line 75 of file kmlExt.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