kmlExt.h
Go to the documentation of this file.
1 /*
2  * Katana Native Interface - A C++ interface to the robot arm Katana.
3  * Copyright (C) 2005 Neuronics AG
4  * Check out the AUTHORS file for detailed contact information.
5  *
6  * This program is free software; you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License as published by
8  * the Free Software Foundation; either version 2 of the License, or
9  * (at your option) any later version.
10  *
11  * This program is distributed in the hope that it will be useful,
12  * but WITHOUT ANY WARRANTY; without even the implied warranty of
13  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14  * GNU General Public License for more details.
15  *
16  * You should have received a copy of the GNU General Public License
17  * along with this program; if not, write to the Free Software
18  * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
19  */
20 
21 
22 /******************************************************************************************************************/
23 #ifndef _KMLEXT_H_
24 #define _KMLEXT_H_
25 /******************************************************************************************************************/
26 #include "common/dllexport.h"
27 #include "common/exception.h"
28 
29 #include "KNI/kmlBase.h"
30 #include "KNI/kmlMotBase.h"
31 
32 #include <vector>
33 
34 
35 /******************************************************************************************************************/
36 
41 
46 public:
47  ConfigFileOpenException(const std::string & port) throw ():
48  Exception("Cannot open configuration file '" + port + "'", -40) {}
49 };
50 
54 
55 namespace KNI {
56  class kmlFactory;
57 }
58 
64 class DLLDIR CKatana {
65 protected:
66  //-------------------------------------//
68 
76 
79  void setTolerance(long idx, int enc_tolerance);
80 
81 public:
82  //-------------------------------------//
83  CKatBase* GetBase() { return base; }
84 
88  CKatana() { base = new CKatBase; }
91  ~CKatana() { delete base; }
92  //------------------------------------------------------------------------------//
95  void create(const char* configurationFile, CCplBase* protocol);
96  void create(KNI::kmlFactory* infos, CCplBase* protocol);
97 
100  void create(TKatGNL& gnl,
101  TKatMOT& mot,
102  TKatSCT& sct,
103  TKatEFF& eff,
104  CCplBase* protocol
105  );
106  //------------------------------------------------------------------------------//
107 
108 
109  /* \brief calibrates the robot
110  */
111  void calibrate();
112 
113  void calibrate( long idx,
114  TMotCLB clb,
115  TMotSCP scp,
116  TMotDYL dyl
117  );
118 
119  //------------------------------------------------------------------------------//
120 
121  void searchMechStop(long idx,
122  TSearchDir dir,
123  TMotSCP scp,
124  TMotDYL dyl
125  );
126 
127 
128  //------------------------------------------------------------------------------//
131  void inc(long idx, int dif, bool wait = false, int tolerance = 100, long timeout = TM_ENDLESS);
134  void dec(long idx, int dif, bool wait = false, int tolerance = 100, long timeout = TM_ENDLESS);
138  void mov(long idx, int tar, bool wait = false, int tolerance = 100, long timeout = TM_ENDLESS);
139 
140  //------------------------------------------------------------------------------//
143  void incDegrees(long idx, double dif, bool wait = false, int tolerance = 100, long timeout = TM_ENDLESS);
146  void decDegrees(long idx, double dif, bool wait = false, int tolerance = 100, long timeout = TM_ENDLESS);
150  void movDegrees(long idx, double tar, bool wait = false, int tolerance = 100, long timeout = TM_ENDLESS);
151 
152  //------------------------------------------------------------------------------//
153  // public just for dubbuging purposes
157  bool checkENLD(long idx, double degrees);
158 
159  //------------------------------------------------------------------------------//
160 
164  void setGripperParameters(bool isPresent, int openEncoders, int closeEncoders);
166  void getGripperParameters(bool &isPresent, int &openEncoders, int &closeEncoders);
167  //------------------------------------------------------------------------------//
168 
171  void enableCrashLimits();
174  void disableCrashLimits();
177  void unBlock();
180  void flushMoveBuffers();
183  void setCrashLimit(long idx, int limit);
186  void setPositionCollisionLimit(long idx, int limit);
189  void setSpeedCollisionLimit(long idx, int limit);
193  void setForceLimit(int axis, int limit);
194 
195  //------------------------------------------------------------------------------//
196 
197  short getNumberOfMotors() const;
198  int getMotorEncoders(short number, bool refreshEncoders = true) const;
199 
203  std::vector<int>::iterator getRobotEncoders(std::vector<int>::iterator start, std::vector<int>::const_iterator end, bool refreshEncoders = true) const;
204 
208  std::vector<int> getRobotEncoders(bool refreshEncoders = true) const;
209 
210  short getMotorVelocityLimit( short number ) const;
211  short getMotorAccelerationLimit( short number ) const;
212 
213  void setMotorVelocityLimit( short number, short velocity );
214  void setMotorAccelerationLimit( short number, short acceleration );
217  short getForce(int axis);
221  int getCurrentControllerType(int axis);
222 
223  void setRobotVelocityLimit( short velocity );
226  void setRobotAccelerationLimit( short acceleration );
227 
228  void moveMotorByEnc( short number, int encoders, bool waitUntilReached = false, int waitTimeout = 0);
229  void moveMotorBy ( short number, double radianAngle, bool waitUntilReached = false, int waitTimeout = 0);
230 
231  void moveMotorToEnc( short number, int encoders, bool waitUntilReached = false, int encTolerance = 100, int waitTimeout = 0);
232  void moveMotorTo ( short number, double radianAngle, bool waitUntilReached = false, int waitTimeout = 0);
233 
234  void waitForMotor( short number, int encoders, int encTolerance = 100, short mode = 0, int waitTimeout = 5000);
235  void waitFor(TMotStsFlg status, int waitTimeout);
236 
240  void moveRobotToEnc(std::vector<int>::const_iterator start, std::vector<int>::const_iterator end, bool waitUntilReached = false, int encTolerance = 100, int waitTimeout = 0);
244  void moveRobotToEnc(std::vector<int> encoders, bool waitUntilReached = false, int encTolerance = 100, int waitTimeout = 0);
246  void moveRobotToEnc4D(std::vector<int> target, int velocity=180, int acceleration = 1, int encTolerance = 100);
247 
248  void openGripper (bool waitUntilReached = false, int waitTimeout = 100);
249  void closeGripper(bool waitUntilReached = false, int waitTimeout = 100);
250 
251  void freezeRobot();
252  void freezeMotor(short number);
253  void switchRobotOn();
254  void switchRobotOff();
255  void switchMotorOn(short number);
256  void switchMotorOff(short number);
257 
261  void startSplineMovement(bool exactflag, int moreflag = 1);
262 
266  void sendSplineToMotor(short number, short targetPosition, short duration, short p1, short p2, short p3, short p4);
267 
272  void setAndStartPolyMovement(std::vector<short> polynomial, bool exactflag, int moreflag);
273 
275  int readDigitalIO();
276 };
277 
278 /******************************************************************************************************************/
279 #endif //_KMLEXT_H_
280 /******************************************************************************************************************/
int mKatanaType
The type of KatanaXXX (300 or 400)
Definition: kmlExt.h:73
int acceleration
CKatBase * base
base katana
Definition: kmlExt.h:67
static std::unique_ptr< CCplSerialCRC > protocol
Definition: kni_wrapper.cpp:24
Abstract base class for protocol definiton.
Definition: cplBase.h:47
[SCT] every sens ctrl&#39;s attributes
Definition: kmlSctBase.h:41
#define DLLDIR
Definition: dllexport.h:30
~CKatana()
Destructor.
Definition: kmlExt.h:91
ConfigFileOpenException(const std::string &port)
Definition: kmlExt.h:47
#define TM_ENDLESS
timeout symbol for &#39;endless&#39; waiting
Definition: kmlBase.h:51
Base Katana class.
Definition: kmlBase.h:132
DLLEXPORT int getForce(int axis)
set the current force
DLLEXPORT int getCurrentControllerType(int axis)
Exception(const std::string &message, const int error_number)
TSearchDir
Definition: kmlMotBase.h:69
TMotStsFlg
status flags
Definition: kmlMotBase.h:58
calibrate
Definition: KNI.py:143
bool _gripperIsPresent
Definition: kmlExt.h:69
[DYL] dynamic limits
Definition: kmlMotBase.h:138
DLLEXPORT int setForceLimit(int axis, int limit)
closeGripper
Definition: KNI.py:145
getNumberOfMotors
Definition: KNI.py:151
Calibration structure for single motors.
Definition: kmlMotBase.h:182
sendSplineToMotor
Definition: KNI.py:168
Inverse Kinematics structure of the endeffektor.
Definition: kmlBase.h:113
[MOT] every motor&#39;s attributes
Definition: kmlMotBase.h:40
CKatBase * GetBase()
Returns pointer to &#39;CKatBase*&#39;.
Definition: kmlExt.h:83
setPositionCollisionLimit
Definition: KNI.py:175
int mKinematics
The kinematics implementation: 0 for Analytical, 1 for RobAnaGuess.
Definition: kmlExt.h:75
Extended Katana class with additional functions.
Definition: kmlExt.h:64
[SCP] static controller parameters
Definition: kmlMotBase.h:110
[GNL] general robot attributes
Definition: kmlBase.h:67
int velocity
CKatana()
Constructor.
Definition: kmlExt.h:88
DLLEXPORT int flushMoveBuffers()
flush all the movebuffers
openGripper
Definition: KNI.py:164
startSplineMovement
Definition: KNI.py:177
int _gripperCloseEncoders
Definition: kmlExt.h:71
int _gripperOpenEncoders
Definition: kmlExt.h:70
std::vector< int > encoders
Definition: kni_wrapper.cpp:29
Definition: Timer.h:30


kni
Author(s): Martin Günther
autogenerated on Fri Jun 7 2019 22:06:44