Epos2.h
Go to the documentation of this file.
1 // Copyright (C) 2009-2010 Institut de Robòtica i Informàtica Industrial, CSIC-UPC.
2 // Author Martí Morta Garriga (mmorta@iri.upc.edu)
3 // All rights reserved.
4 //
5 // Copyright (C) 2013 Jochen Sprickerhof <jochen@sprickerhof.de>
6 //
7 // This file is part of IRI EPOS2 Driver
8 // IRI EPOS2 Driver is free software: you can redistribute it and/or modify
9 // it under the terms of the GNU Lesser General Public License as published by
10 // the Free Software Foundation, either version 3 of the License, or
11 // at your option) any later version.
12 //
13 // This program is distributed in the hope that it will be useful,
14 // but WITHOUT ANY WARRANTY; without even the implied warranty of
15 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
16 // GNU Lesser General Public License for more details.
17 //
18 // You should have received a copy of the GNU Lesser General Public License
19 // along with this program. If not, see <http://www.gnu.org/licenses/>.
20 
21 #ifndef Epos2_H
22 #define Epos2_H
23 
24 #include <string>
25 #include <stdexcept>
26 #include <ftdi.hpp>
27 
60 class CEpos2 {
61 
62 
63  private:
64 
65  int8_t node_id;
66 
80  static Ftdi::Context ftdi;
81  static bool ftdi_initialized;
82 
83 
86 
87 
93  void openDevice();
94 
104  int32_t readObject(int16_t index, int8_t subindex);
105 
116  int writeObject(int16_t index, int8_t subindex, int32_t data);
117 
126  void sendFrame(int16_t *frame);
127 
139  void receiveFrame(uint16_t* ans_frame);
140 
150  int16_t computeChecksum(int16_t *pDataArray, int16_t numberOfWords);
151 
152 
154 
163  long getNegativeLong (long number);
164 
165  bool verbose;
166 
175  void p(const char *text);
176 
177 
178  void p(const std::stringstream& text);
179 
180 
181  public:
182 
185  CEpos2(int8_t nodeId = 0x00);
186 
189  ~CEpos2();
190 
193  void init();
194 
197  void close();
198 
201 
208  long getState ();
209 
215  void shutdown ();
216 
222  void switchOn ();
223 
229  void quickStop ();
230 
236  void enableOperation ();
237 
243  void disableOperation ();
244 
250  void disableVoltage ();
251 
261  void faultReset ();
262 
265 
273  long getOperationMode ();
274 
280  std::string getOpModeDescription (long opmode);
281 
287  void setOperationMode (long opmode);
288 
295  void enableController ();
296 
306  void enableMotor (long opmode);
307 
314  bool isTargetReached ();
315 
317 
318 
322 
329 
337 
343 
345 
348 
353  long getTargetVelocity ();
354 
362  void setTargetVelocity (long velocity);
363 
371  void startVelocity ();
372 
380  void stopVelocity ();
381 
383 
386 
393  long getTargetProfilePosition ();
394 
402  void setTargetProfilePosition (long position);
403 
416  void startProfilePosition (epos_posmodes mode, bool blocking=true, bool wait=true, bool new_point=true);
417 
419 
422 
429  long getTargetProfileVelocity ();
430 
437  void setTargetProfileVelocity (long velocity);
438 
444  void startProfileVelocity ();
445 
451  void stopProfileVelocity ();
452 
454 
457 
465  long getTargetCurrent ();
466 
474  void setTargetCurrent (long current);
475 
483  void startCurrent ();
484 
492  void stopCurrent ();
494 
497 
508  void setHome ();
509 
517  void setHomePosition (long home_position_qc);
518 
526  long getHomePosition ();
528 
529 
533 
542  long getCurrentPGain ();
543 
551  void setCurrentPGain (long gain);
552 
560  long getCurrentIGain ();
561 
569  void setCurrentIGain (long gain);
570 
571  // Velocity
572 
580  long getVelocityPGain ();
581 
589  void setVelocityPGain (long gain);
590 
598  long getVelocityIGain ();
599 
607  void setVelocityIGain (long gain);
608 
617 
627  void setVelocitySetPointFactorPGain (long gain);
628 
629  // Position
630 
638  long getPositionPGain ();
639 
647  void setPositionPGain (long gain);
648 
656  long getPositionIGain ();
657 
665  void setPositionIGain (long gain);
666 
674  long getPositionDGain ();
675 
683  void setPositionDGain (long gain);
684 
692  long getPositionVFFGain ();
693 
701  void setPositionVFFGain (long gain);
702 
710  long getPositionAFFGain ();
711 
719  void setPositionAFFGain (long gain);
720 
721  // General
722 
739  void getControlParameters(long &cp,long &ci,long &vp,long &vi,long &vspf, long &pp,long &pi,long &pd,long &pv,long &pa);
740 
757  void setControlParameters(long cp,long ci,long vp,long vi,long vspf,long pp,long pi,long pd,long pv,long pa);
758 
775  void printControlParameters(long cp,long ci,long vp,long vi,long vspf,long pp,long pi,long pd,long pv,long pa);
776 
778 
779 
784 
795  long getProfileVelocity (void);
796 
797 
807  void setProfileVelocity (long velocity);
808 
817  long getProfileMaxVelocity (void);
818 
827  void setProfileMaxVelocity (long velocity);
828 
837  long getProfileAcceleration (void);
838 
847  void setProfileAcceleration (long acceleration);
848 
857  long getProfileDeceleration (void);
858 
867  void setProfileDeceleration (long deceleration);
868 
877  long getProfileQuickStopDecel(void);
878 
887  void setProfileQuickStopDecel (long deceleration);
888 
897  long getProfileType (void);
898 
906  void setProfileType (long type);
907 
916  long getMaxAcceleration (void);
917 
926  void setMaxAcceleration (long max_acceleration);
927 
928  // General
929 
944  void getProfileData (long &vel,long &maxvel,long &acc,long &dec,long &qsdec, long &maxacc, long &type);
945 
960  void setProfileData (long vel,long maxvel,long acc,long dec,long qsdec,long maxacc,long type);
961 
963 
964 
967 
975  long readVelocity ();
976 
990  long readVelocitySensorActual ();
991 
999  long readVelocityDemand ();
1000 
1011  long readVelocityActual ();
1012 
1021  long readCurrent ();
1022 
1032  long readCurrentAveraged ();
1033 
1043  long readCurrentDemanded ();
1044 
1055  int32_t readPosition ();
1056 
1065  long readStatusWord ();
1066 
1076  long readEncoderCounter ();
1077 
1088 
1099  long readHallsensorPattern ();
1100 
1109  long readFollowingError ();
1110 
1118  void getMovementInfo ();
1119 
1120  // Errors
1121 
1129  char readError ();
1130 
1138  void readErrorHistory (long *error[5]);
1139 
1145  std::string searchErrorDescription (long error_code);
1146 
1148  static const std::string error_names[];
1149 
1151  static const int error_codes[];
1152 
1154  static const std::string error_descriptions[];
1155 
1156  // Versions
1157 
1166  long readVersionSoftware ();
1167 
1175  long readVersionHardware ();
1176 
1177 
1178 
1180 
1181 
1184 
1191  long getEncoderPulseNumber ();
1192 
1202  void setEncoderPulseNumber (long pulses);
1203 
1211  long getEncoderType ();
1212 
1222  void setEncoderType (long type);
1223 
1231  long getEncoderPolarity ();
1232 
1245  void setEncoderPolarity (long polarity);
1246 
1247  // General
1248 
1256  void getEncoderParameters(long &pulses, long &type, long &polarity);
1257 
1265  void setEncoderParameters(long pulses, long type, long polarity);
1266 
1267 
1269 
1270 
1273 
1280  long getMotorType ();
1281 
1294  void setMotorType (long type);
1295 
1304 
1313  void setMotorContinuousCurrentLimit (long current_mA);
1314 
1323 
1332  void setMotorOutputCurrentLimit (long current_mA);
1333 
1341  long getMotorPolePairNumber ();
1342 
1353  void setMotorPolePairNumber (char pole_pairs);
1354 
1362  long getThermalTimeCtWinding ();
1363 
1372  void setThermalTimeCtWinding (long time_ds);
1373 
1374  // General
1375 
1385  void getMotorParameters(long &type, long &current_c_mA, long &current_out_mA, char &pole_pairs, long &time_ds);
1386 
1395  void setMotorParameters(long type, long current_c_mA, long current_out_mA, char pole_pairs, long time_ds);
1396 
1398 
1399  // CONFIGURATION
1400 
1401 
1404 
1411  long getRS232Baudrate ();
1412 
1428  void setRS232Baudrate (long baudrate);
1429 
1437  long getRS232FrameTimeout ();
1438 
1447  void setRS232FrameTimeout (long timeout);
1448 
1456  long getUSBFrameTimeout ();
1457 
1466  void setUSBFrameTimeout (long timeout);
1468 
1471 
1479  long getMaxFollowingError ();
1480 
1481 
1490  void setMaxFollowingError (long follerror);
1491 
1500  long getMinPositionLimit ();
1501 
1510  void setMinPositionLimit (long limit);
1511 
1520  long getMaxPositionLimit ();
1521 
1530  void setMaxPositionLimit (long limit);
1531 
1540  void disablePositionLimits (void);
1541 
1549  long getPositionWindow ();
1550 
1560  void setPositionWindow (long window_qc);
1561 
1569  long getPositionWindowTime ();
1570 
1579  void setPositionWindowTime (long time_ms);
1580 
1588  long getVelocityWindow ();
1589 
1598  void setVelocityWindow (long window_rm);
1599 
1607  long getVelocityWindowTime ();
1608 
1617  void setVelocityWindowTime (long time_ms);
1618 
1620 
1623 
1630  long getPositionNotationIndex ();
1631 
1639  void setPositionNotationIndex (long notation);
1640 
1648  long getVelocityNotationIndex ();
1649 
1657  void setVelocityNotationIndex (long notation);
1658 
1667 
1675  void setAccelerationNotationIndex (long notation);
1676 
1677 
1685  long getPositionDimensionIndex ();
1686 
1694  void setPositionDimensionIndex (long Dimension);
1695 
1703  long getVelocityDimensionIndex ();
1704 
1713  void setVelocityDimensionIndex (long Dimension);
1714 
1723 
1732  void setAccelerationDimensionIndex (long Dimension);
1734 
1735 
1738 
1748  long getAnalogOutput1 ();
1749 
1762  void setAnalogOutput1 (long voltage_mV);
1763 
1770  void saveParameters ();
1771 
1778  void restoreDefaultParameters ();
1779 
1780  bool getVerbose();
1781 
1782  void setVerbose(bool verbose);
1783 
1789  long getPositionMarker(int buffer = 0);
1790 
1800  void setPositionMarker(char polarity = 0, char edge_type = 0,
1801  char mode = 0, char digitalIN = 2);
1802 
1807  void waitPositionMarker();
1808 
1843  void setHoming(int home_method = 11, int speed_pos = 100,
1844  int speed_zero = 100, int acc = 1000, int digitalIN = 2);
1845 
1851  void doHoming(bool blocking=false);
1852 
1857  static void *threadTargetReached(void *param);
1858 
1863  void stopHoming();
1864 
1870  int getDigInState(int digitalIN = 2);
1871 
1877  int getDigInStateMask();
1878 
1884  int getDigInFuncMask();
1885 
1892  int getDigInPolarity();
1893 
1899  int getDigInExecutionMask();
1900 
1902 };
1903 
1904 class EPOS2OpenException : public std::runtime_error
1905 {
1906  public:
1907  EPOS2OpenException(const std::string& error_description)
1908  : std::runtime_error (error_description) {}
1909 };
1910 
1911 class EPOS2IOException : public std::runtime_error
1912 {
1913  public:
1914  EPOS2IOException(const std::string& error_description)
1915  : std::runtime_error (error_description) {}
1916 };
1917 
1918 class EPOS2UnknownStateException : public std::runtime_error
1919 {
1920  public:
1921  EPOS2UnknownStateException(const std::string& error_description)
1922  : std::runtime_error (error_description) {}
1923 };
1924 
1925 #endif
long getState()
function to get current controller&#39;s state
Definition: Epos2.cpp:397
void setCurrentPGain(long gain)
function to set P Current Gain
Definition: Epos2.cpp:877
void setVelocityIGain(long gain)
function to set I Velocity Gain
Definition: Epos2.cpp:909
long getPositionAFFGain()
function to get Acceleration Feed Forward Position Gain
Definition: Epos2.cpp:967
long readStatusWord()
function to read EPOS2 StatusWord
Definition: Epos2.cpp:1172
long getPositionWindowTime()
function to get Position Window Time
Definition: Epos2.cpp:1415
long getThermalTimeCtWinding()
function to GET Motor Thermal Time Constant Winding
Definition: Epos2.cpp:1363
char readError()
function to read an Error information
Definition: Epos2.cpp:1226
void disableOperation()
function to reach switch_on and disables power on motor
Definition: Epos2.cpp:549
void startProfilePosition(epos_posmodes mode, bool blocking=true, bool wait=true, bool new_point=true)
function to move the motor to a position in profile position mode
Definition: Epos2.cpp:831
void setHomePosition(long home_position_qc)
function to set a Home position
Definition: Epos2.cpp:1627
long readCurrentDemanded()
function to read current demanded
Definition: Epos2.cpp:1162
long getMaxAcceleration(void)
function to GET Max Acceleration
Definition: Epos2.cpp:1089
void getControlParameters(long &cp, long &ci, long &vp, long &vi, long &vspf, long &pp, long &pi, long &pd, long &pv, long &pa)
function to get all control parameters
Definition: Epos2.cpp:977
void waitPositionMarker()
wait for marker position reached
Definition: Epos2.cpp:1546
bool blocking
Definition: configtest.cpp:59
void enableMotor(long opmode)
function to facititate transitions from switched on to operation enabled
Definition: Epos2.cpp:696
void setPositionMarker(char polarity=0, char edge_type=0, char mode=0, char digitalIN=2)
Sets the configuration of a marker position.
Definition: Epos2.cpp:1530
void setMinPositionLimit(long limit)
function to SET the Min Position Limit
Definition: Epos2.cpp:1386
long readVelocitySensorActual()
function to read velocity sensor actual
Definition: Epos2.cpp:1135
void setPositionWindow(long window_qc)
function to set Position Window
Definition: Epos2.cpp:1413
void setPositionWindowTime(long time_ms)
function to set Position Window Time
Definition: Epos2.cpp:1417
int getDigInExecutionMask()
Gives Digital Inputs Execution Mask.
Definition: Epos2.cpp:1618
long getMaxFollowingError()
function to GET the Max Following Error
Definition: Epos2.cpp:1371
void setVelocitySetPointFactorPGain(long gain)
function to SET Speed Regulator Set Point Factor P Velocity Gain
Definition: Epos2.cpp:919
void setRS232Baudrate(long baudrate)
function to SET the RS232 Baudrate
Definition: Epos2.cpp:1469
void getEncoderParameters(long &pulses, long &type, long &polarity)
function to GET encoder parameters
Definition: Epos2.cpp:1339
long getUSBFrameTimeout()
function to GET the USB Frame Timeout
Definition: Epos2.cpp:1484
long getPositionDimensionIndex()
function to get Position Dimension Index
Definition: Epos2.cpp:1439
void setMotorParameters(long type, long current_c_mA, long current_out_mA, char pole_pairs, long time_ds)
function to SET motor parameters
long getPositionNotationIndex()
function to get Position Notation Index
Definition: Epos2.cpp:1427
void shutdown()
function to reach ready_to_switch_on state
Definition: Epos2.cpp:517
void getProfileData(long &vel, long &maxvel, long &acc, long &dec, long &qsdec, long &maxacc, long &type)
function to GET all data of the velocity profile
Definition: Epos2.cpp:1099
int16_t computeChecksum(int16_t *pDataArray, int16_t numberOfWords)
function to compute EPOS2 checksum
Definition: Epos2.cpp:366
static Ftdi::Context ftdi
a reference to the FTDI USB device
Definition: Epos2.h:80
int32_t readObject(int16_t index, int8_t subindex)
function to read an object from the EPOS2
Definition: Epos2.cpp:123
long getMinPositionLimit()
function to GET the Min Position Limit
Definition: Epos2.cpp:1381
long readEncoderCounterAtIndexPulse()
function to read the Encoder Counter at index pulse
Definition: Epos2.cpp:1182
long getEncoderPulseNumber()
function to GET the Encoder Pulses
Definition: Epos2.cpp:1317
int getDigInPolarity()
Gives Digital Inputs Polarity Mask.
Definition: Epos2.cpp:1613
long getVelocityPGain()
function to get P Velocity Gain
Definition: Epos2.cpp:894
void setPositionNotationIndex(long notation)
function to set Position Notation Index
Definition: Epos2.cpp:1429
void readErrorHistory(long *error[5])
function to read last 5 errors
Definition: Epos2.cpp:1258
void setAnalogOutput1(long voltage_mV)
function to set analog output 1
Definition: Epos2.cpp:1508
void setMotorType(long type)
function to SET Motor type
Definition: Epos2.cpp:1349
~CEpos2()
Destructor.
Definition: Epos2.cpp:39
void setMaxPositionLimit(long limit)
function to SET the Max Position Limit
Definition: Epos2.cpp:1397
long getMotorType()
function to GET Motor type
Definition: Epos2.cpp:1347
void startCurrent()
[OPMODE=current] function to move the motor in current mode
Definition: Epos2.cpp:862
long getPositionIGain()
function to get I Position Gain
Definition: Epos2.cpp:936
void setPositionDGain(long gain)
function to set D Position Gain
Definition: Epos2.cpp:952
long getTargetProfileVelocity()
[OPMODE=profile_velocity] function to get the velocity
Definition: Epos2.cpp:778
EPOS2IOException(const std::string &error_description)
Definition: Epos2.h:1914
void switchOn()
function to reach switch_on state
Definition: Epos2.cpp:525
bool getVerbose()
Definition: Epos2.cpp:82
void setAccelerationDimensionIndex(long Dimension)
function to set Acceleration Dimension Index
Definition: Epos2.cpp:1449
long getProfileQuickStopDecel(void)
function to GET the Quick Stop Deceleration in profile
Definition: Epos2.cpp:1069
epos_opmodes
Definition: Epos2.h:334
static const std::string error_names[]
Strings of generic error descriptions.
Definition: Epos2.h:1148
void setVerbose(bool verbose)
Definition: Epos2.cpp:90
void setOperationMode(long opmode)
function to set the operation mode
Definition: Epos2.cpp:624
void setVelocityNotationIndex(long notation)
function to set Velocity Notation Index
Definition: Epos2.cpp:1433
void enableOperation()
function to reach operation_enable state and enables power on motor
Definition: Epos2.cpp:557
epos_posmodes
Definition: Epos2.h:341
long getProfileMaxVelocity(void)
function to GET the Max Velocity allowed in Profile
Definition: Epos2.cpp:1039
void setMaxAcceleration(long max_acceleration)
function to SET Max Acceleration
Definition: Epos2.cpp:1094
int8_t node_id
Definition: Epos2.h:65
long readCurrent()
function to read motor current
Definition: Epos2.cpp:1150
long getNegativeLong(long number)
function to make a unsigned long signed
Definition: Epos2.cpp:1494
void setProfileType(long type)
function to SET the type in profile
Definition: Epos2.cpp:1084
void setVelocityWindow(long window_rm)
function to set Velocity Window
Definition: Epos2.cpp:1421
long readVersionSoftware()
function to read the software version
Definition: Epos2.cpp:1303
int getDigInStateMask()
Gives Digital Inputs State Mask.
Definition: Epos2.cpp:1603
void setThermalTimeCtWinding(long time_ds)
function to SET Motor Thermal Time Constant Winding
Definition: Epos2.cpp:1365
long getAccelerationDimensionIndex()
function to get Acceleration Dimension Index
Definition: Epos2.cpp:1447
void setPositionAFFGain(long gain)
function to set Acceleration Feed Forward Position Gain
Definition: Epos2.cpp:972
void setVelocityWindowTime(long time_ms)
function to set Velocity Window Time
Definition: Epos2.cpp:1425
long getAnalogOutput1()
function to get the value in the Analog Output1
Definition: Epos2.cpp:1506
long readVelocityDemand()
function to read velocity demand
Definition: Epos2.cpp:1140
long getProfileAcceleration(void)
function to GET the Acceleration in profile
Definition: Epos2.cpp:1049
void setRS232FrameTimeout(long timeout)
function to SET the RS232 Frame Timeout
Definition: Epos2.cpp:1479
int writeObject(int16_t index, int8_t subindex, int32_t data)
function to write an object to the EPOS2
Definition: Epos2.cpp:158
static void * threadTargetReached(void *param)
Thread listens to target reached.
long getRS232Baudrate()
function to GET the RS232 Baudrate
Definition: Epos2.cpp:1464
void faultReset()
function to reach switch_on_disabled state after a FAULT
Definition: Epos2.cpp:565
void setTargetProfileVelocity(long velocity)
[OPMODE=profile_velocity] function to set the velocity
Definition: Epos2.cpp:787
void disablePositionLimits(void)
function to DISABLE Position Limits
Definition: Epos2.cpp:1402
void setAccelerationNotationIndex(long notation)
function to set Acceleration Notation Index
Definition: Epos2.cpp:1437
long readHallsensorPattern()
function to read the Hall Sensor Pattern
Definition: Epos2.cpp:1187
long getPositionPGain()
function to get P Position Gain
Definition: Epos2.cpp:926
void setPositionPGain(long gain)
function to set P Position Gain
Definition: Epos2.cpp:931
void setCurrentIGain(long gain)
function to set I Current Gain
Definition: Epos2.cpp:887
void setProfileDeceleration(long deceleration)
function to SET the Deceleration in profile
Definition: Epos2.cpp:1064
long getProfileType(void)
function to GET the type in profile
Definition: Epos2.cpp:1079
std::string getOpModeDescription(long opmode)
function to show the name of the operation mode
Definition: Epos2.cpp:590
void printControlParameters(long cp, long ci, long vp, long vi, long vspf, long pp, long pi, long pd, long pv, long pa)
function to show all control parameters
Definition: Epos2.cpp:1015
long getVelocitySetPointFactorPGain()
function to GET Speed Regulator Set Point Factor P Velocity Gain
Definition: Epos2.cpp:914
static const std::string error_descriptions[]
error descriptions
Definition: Epos2.h:1154
void setMotorContinuousCurrentLimit(long current_mA)
function to SET Motor Continous Current Limit
Definition: Epos2.cpp:1353
long getOperationMode()
function to know which operation mode is set
Definition: Epos2.cpp:576
void setUSBFrameTimeout(long timeout)
function to SET the USB Frame Timeout
Definition: Epos2.cpp:1489
long readCurrentAveraged()
function to read motor averaged current
Definition: Epos2.cpp:1156
void startVelocity()
function to move the motor in Velocity mode
Definition: Epos2.cpp:758
void stopProfileVelocity()
[OPMODE=profile_velocity] function to stop the motor
Definition: Epos2.cpp:805
static bool ftdi_initialized
Definition: Epos2.h:81
long getVelocityWindowTime()
function to get Velocity Window Time
Definition: Epos2.cpp:1423
void restoreDefaultParameters()
function to restore default parameters of EPOS2.
Definition: Epos2.cpp:1458
long getCurrentPGain()
function to get P Current Gain
Definition: Epos2.cpp:872
std::string searchErrorDescription(long error_code)
given an error code it returns its description
Definition: Epos2.cpp:1275
void setProfileMaxVelocity(long velocity)
function to SET the Max Velocity allowed in Profile
Definition: Epos2.cpp:1044
void enableController()
function to facititate transitions from the start of the controller to switch it on ...
Definition: Epos2.cpp:632
long getVelocityNotationIndex()
function to get Velocity Notation Index
Definition: Epos2.cpp:1431
void saveParameters()
function to save all parameters in EEPROM
Definition: Epos2.cpp:1452
void stopCurrent()
[OPMODE=current] function to stop the motor in current mode
Definition: Epos2.cpp:864
EPOS2UnknownStateException(const std::string &error_description)
Definition: Epos2.h:1921
long getHomePosition()
function to get the Home position
Definition: Epos2.cpp:1631
void close()
Disconnects hardware.
Definition: Epos2.cpp:58
void quickStop()
function to reach switch_on state
Definition: Epos2.cpp:541
void disableVoltage()
function to reach switch_on_disabled state
Definition: Epos2.cpp:533
void sendFrame(int16_t *frame)
function send a frame to EPOS2
Definition: Epos2.cpp:186
void setTargetCurrent(long current)
[OPMODE=current] function to SET the target current
Definition: Epos2.cpp:860
void setPositionVFFGain(long gain)
function to set Velocity Feed Forward Position Gain
Definition: Epos2.cpp:962
Implementation of a driver for EPOS2 Motor Controller.
Definition: Epos2.h:60
void init()
Connects hardware.
Definition: Epos2.cpp:49
void p(const char *text)
function to make a unsigned long signed
Definition: Epos2.cpp:74
long getProfileDeceleration(void)
function to GET the Deceleration in profile
Definition: Epos2.cpp:1059
void setHome()
function to set a Home position with user interaction
Definition: Epos2.cpp:1636
long getProfileVelocity(void)
function to GET the velocity of the Velocity Profile
Definition: Epos2.cpp:1029
void setProfileVelocity(long velocity)
function to SET the velocity of the Velocity Profile
Definition: Epos2.cpp:1034
bool verbose
Definition: Epos2.h:165
long getTargetProfilePosition()
function to GET the target position
Definition: Epos2.cpp:817
long readVersionHardware()
function to read the hardware version
Definition: Epos2.cpp:1308
long readEncoderCounter()
function to read the Encoder Counter
Definition: Epos2.cpp:1177
void receiveFrame(uint16_t *ans_frame)
function receive a frame from EPOS2
Definition: Epos2.cpp:229
long getVelocityDimensionIndex()
function to get Velocity Dimension Index
Definition: Epos2.cpp:1443
long getMotorContinuousCurrentLimit()
function to GET Motor Continous Current Limit
Definition: Epos2.cpp:1351
long readFollowingError()
function to read the Following Error
Definition: Epos2.cpp:1192
long getAccelerationNotationIndex()
function to get Acceleration Notation Index
Definition: Epos2.cpp:1435
void setVelocityPGain(long gain)
function to set P Velocity Gain
Definition: Epos2.cpp:899
long getMaxPositionLimit()
function to GET the Max Position Limit
Definition: Epos2.cpp:1392
CEpos2(int8_t nodeId=0x00)
Constructor.
Definition: Epos2.cpp:33
void setMotorOutputCurrentLimit(long current_mA)
function to SET Motor Output Current Limit
Definition: Epos2.cpp:1357
long getCurrentIGain()
function to get I Current Gain
Definition: Epos2.cpp:882
int32_t readPosition()
function to read motor position
Definition: Epos2.cpp:1167
void setProfileAcceleration(long acceleration)
function to SET the Acceleration in profile
Definition: Epos2.cpp:1054
void setPositionIGain(long gain)
function to set I Position Gain
Definition: Epos2.cpp:941
long getPositionDGain()
function to get D Position Gain
Definition: Epos2.cpp:946
void setProfileQuickStopDecel(long deceleration)
function to SET the Quick Stop Deceleration in profile
Definition: Epos2.cpp:1074
EPOS2OpenException(const std::string &error_description)
Definition: Epos2.h:1907
long getPositionVFFGain()
function to get Velocity Feed Forward Position Gain
Definition: Epos2.cpp:957
void setEncoderPulseNumber(long pulses)
function to SET the Encoder Pulses
Definition: Epos2.cpp:1322
void setProfileData(long vel, long maxvel, long acc, long dec, long qsdec, long maxacc, long type)
function to SET all data of the velocity profile
Definition: Epos2.cpp:1111
void setHoming(int home_method=11, int speed_pos=100, int speed_zero=100, int acc=1000, int digitalIN=2)
Sets the configuration of a homing operation.
Definition: Epos2.cpp:1562
long getMotorPolePairNumber()
function to GET Motor Pole Pair Number
Definition: Epos2.cpp:1359
void setPositionDimensionIndex(long Dimension)
function to set Position Dimension Index
Definition: Epos2.cpp:1441
void stopVelocity()
function to stop the motor in velocity mode
Definition: Epos2.cpp:766
void stopHoming()
stops a homing operation
Definition: Epos2.cpp:1587
void setControlParameters(long cp, long ci, long vp, long vi, long vspf, long pp, long pi, long pd, long pv, long pa)
function to set all control parameters
Definition: Epos2.cpp:996
void setTargetVelocity(long velocity)
function to SET the target velocity
Definition: Epos2.cpp:750
long readVelocity()
function to read motor average velocity
Definition: Epos2.cpp:1130
void startProfileVelocity()
[OPMODE=profile_velocity] function to move the motor in a velocity
Definition: Epos2.cpp:795
void openDevice()
open EPOS2 device using CFTDI
Definition: Epos2.cpp:105
void setMotorPolePairNumber(char pole_pairs)
function to SET Motor Pole Pair Number
Definition: Epos2.cpp:1361
long getTargetVelocity()
function to GET the target velocity This function gets the target velocity of velocity operation mode...
Definition: Epos2.cpp:742
void setEncoderType(long type)
function to SET the Encoder type
Definition: Epos2.cpp:1330
void setEncoderPolarity(long polarity)
function to SET the Encoder polarity
Definition: Epos2.cpp:1336
void setMaxFollowingError(long follerror)
function to SET the Max Following Error
Definition: Epos2.cpp:1376
void doHoming(bool blocking=false)
starts a homing operation
Definition: Epos2.cpp:1577
int getDigInFuncMask()
Gives Digital Inputs Functionalities Mask.
Definition: Epos2.cpp:1608
void getMotorParameters(long &type, long &current_c_mA, long &current_out_mA, char &pole_pairs, long &time_ds)
function to GET encoder parameters
bool isTargetReached()
function to know if the motor has reached the target position or velocity
Definition: Epos2.cpp:720
void setVelocityDimensionIndex(long Dimension)
function to set Velocity Dimension Index
Definition: Epos2.cpp:1445
void setEncoderParameters(long pulses, long type, long polarity)
function to SET encoder parameters
Definition: Epos2.cpp:1342
long getPositionWindow()
function to get Position Window
Definition: Epos2.cpp:1411
long readVelocityActual()
function to read velocity sensor actual
Definition: Epos2.cpp:1145
epos_states
Definition: Epos2.h:325
long getTargetCurrent()
[OPMODE=current] function to GET the target current
Definition: Epos2.cpp:858
long getMotorOutputCurrentLimit()
function to GET Motor Output Current Limit
Definition: Epos2.cpp:1355
long getVelocityWindow()
function to get Velocity Window
Definition: Epos2.cpp:1419
long getEncoderPolarity()
function to GET the Encoder Pulses
Definition: Epos2.cpp:1333
void getMovementInfo()
prints information about movement
Definition: Epos2.cpp:1197
int getDigInState(int digitalIN=2)
Gives the state of a certain digital Input.
Definition: Epos2.cpp:1598
long getVelocityIGain()
function to get I Velocity Gain
Definition: Epos2.cpp:904
long getEncoderType()
function to GET the Encoder Pulses
Definition: Epos2.cpp:1327
void setTargetProfilePosition(long position)
function to SET the target position
Definition: Epos2.cpp:825
long getRS232FrameTimeout()
function to GET the RS232 Frame Timeout
Definition: Epos2.cpp:1474
long getPositionMarker(int buffer=0)
gets the position marked by the sensor
Definition: Epos2.cpp:1512
static const int error_codes[]
error integer codes
Definition: Epos2.h:1151


epos2_motor_controller
Author(s): Martí Morta Garriga , Jochen Sprickerhof
autogenerated on Mon Jul 22 2019 03:19:01