configtest.cpp
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 // This file is part of IRI EPOS2 Driver
6 // IRI EPOS2 Driver is free software: you can redistribute it and/or modify
7 // it under the terms of the GNU Lesser General Public License as published by
8 // the Free Software Foundation, either version 3 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 Lesser General Public License for more details.
15 //
16 // You should have received a copy of the GNU Lesser General Public License
17 // along with this program. If not, see <http://www.gnu.org/licenses/>.
18 
35 #include <stdio.h>
36 #include <stdint.h>
37 #include <stdlib.h>
38 
39 #include <cstdio>
40 #include <cstring>
41 #include <ctime>
42 
43 #include <iostream>
44 #include <fstream>
45 #include <vector>
46 
47 #include <time.h>
48 #include <sys/time.h>
49 
50 #include "Epos2.h"
51 
52 
56 bool finish_program=false;
57 bool free_program=true;
59 bool blocking=false,print=false,waiting=true;
60 
61 
62 using namespace std;
63 
64 
72 float mqc2pdg(long int qc)
73 {
74  return((float)qc*3/3700);
75 }
76 
85 long int pdg2mqc(float dg)
86 {
87  return((long int)(dg*3700/3));
88 }
89 
90 
95 void readData(){
96 
97  long int li;
98  int i;
99  li=epos2->readVelocity();
100  cout << " Velocity: " << hex << "0x" << li << " , " << dec << li << endl;
101  li=epos2->readVelocitySensorActual();
102  cout << " Velocity Sensor Actual: " << hex << "0x" << li << " , " << dec << li << endl;
103  li=epos2->readVelocityDemand();
104  cout << " Velocity Demand: " << hex << "0x" << li << " , " << dec << li << endl;
105  li=epos2->readVelocityActual();
106  cout << " Velocity Actual: " << hex << "0x" << li << " , " << dec << li << endl;
107  li=epos2->readPosition();
108  cout << " Position: " << hex << "0x" << li << " , " << dec << li << endl;
109  li=epos2->readEncoderCounter();
110  cout << " Encoder Counter: " << hex << "0x" << li << " , " << dec << li << endl;
111  li=epos2->readEncoderCounterAtIndexPulse();
112  cout << " Encoder Counter @ index pulse: " << hex << "0x" << li << " , " << dec << li << endl;
113  i=epos2->readCurrent();
114  cout << " Current: " << hex << "0x" << i << " , " << dec << i << endl;
115  i=epos2->readCurrentAveraged();
116  cout << " Current Averaged: " << hex << "0x" << i << " , " << dec << i << endl;
117  i=epos2->readCurrentDemanded();
118  cout << " Current Demanded: " << hex << "0x" << i << " , " << dec << i << endl;
119  i=epos2->readStatusWord();
120  cout << " StatusWord: " << hex << "0x" << i << " , " << dec << i << endl;
121  i=epos2->readHallsensorPattern();
122  cout << " Hall Sensor Pattern: " << hex << "0x" << i << " , " << dec << i << endl;
123  i=epos2->readFollowingError();
124  cout << " Following Error: " << hex << "0x" << i << " , " << dec << i << endl;
125  i=epos2->readVersionHardware();
126  cout << " Version Hardware: " << hex << "0x" << i << " , " << dec << i << endl;
127  i=epos2->readVersionSoftware();
128  cout << " Version Software: " << hex << "0x" << i << " , " << dec << i << endl;
129 }
130 
131 
132 
133 
134 
143 void doMovement(char type){
144 
145  long int value;
146  char ui_r;
148  bool opcio_target=true;
149 
150  epos2->enableOperation();
151  switch(type){
152  case 'a':
153  cout << " ConfigTest Absolute Movement\n\n";
154  case 'r':
155  cout << " ConfigTest Relative Movement\n\n";
156  value=epos2->getTargetProfilePosition();
157  break;
158  case 'w':
159  cout << " ConfigTest Profle Velocity\n\n";
160  value=epos2->getTargetProfileVelocity();
161  break;
162  case 'v':
163  cout << " ConfigTest Velocity\n\n";
164  value=epos2->getTargetVelocity();
165  break;
166  case 'k':
167  opcio_target = false;
168  break;
169  }
170  if(opcio_target)
171  {
172  cout << " Is this your desired target? (Y,n) " << value << endl;
173  cin >> ui_r;
174  cout << endl;
175  if(ui_r=='n'){
176  cout << " Type your desired target " << endl;
177  cin >> value;
178  }
179  }
180  switch(type){
181  case 'a':
182  case 'r':
183  epos2->setOperationMode(epos2->PROFILE_POSITION);
184  epos2->setTargetProfilePosition(value);
185  value = epos2->getTargetProfilePosition();
186  cout << " Starting Profile Position to:" << value;
187  if(type == 'a') mode = epos2->ABSOLUTE;
188  if(type == 'r') mode = epos2->RELATIVE;
189  epos2->startProfilePosition(mode,blocking,waiting); // no blocking
190 
191  if(!blocking){
192  while(!epos2->isTargetReached()){
193  epos2->getMovementInfo();
194  }
195  }
196 
197  cout << "\n Profile Position Movement Finished" << endl;
198  break;
199  case 'w':
200  int wcounter;
201  epos2->setOperationMode(epos2->PROFILE_VELOCITY);
202  epos2->setTargetProfileVelocity(value);
203  value=epos2->getTargetProfileVelocity();
204  cout << " Starting Profile Velocity to:" << value;
205  cout << " during 5 seconds" << endl;
206  epos2->startProfileVelocity();
207  wcounter=0;
208  cout << " TARGET VELOCITY REACHED - Press 's' to stop'" << endl;
209  while(wcounter<100){
210  epos2->getMovementInfo();
211  wcounter++;
212  }
213  epos2->stopProfileVelocity();
214  cout << "\n Profile Position Movement Finished" << endl;
215  break;
216  case 'v':
217  char ui_v_stop;
218  epos2->setOperationMode(epos2->VELOCITY);
219  epos2->setTargetVelocity((int)value);
220  epos2->startVelocity();
221  cout << " VELOCITY - Press 's' to stop'" << endl;
222  cin >> ui_v_stop;
223  while(ui_v_stop!='s'){
224  epos2->getMovementInfo();
225  cin >> ui_v_stop;
226  }
227  epos2->stopVelocity();
228  cout << " Velocity Movement Finished" << endl;
229  break;
230  case 'k':
231  /*
232  epos2->setProfileData(200,2000,2000,4000,2000,4500,1);
233  cout << " 1 velocity + profile velocity (400)" << endl;
234  epos2->setOperationMode(epos2->VELOCITY);
235  epos2->setTargetVelocity(400);
236  cout << " velocity" << endl;
237  epos2->startVelocity();
238  sleep(2);
239  epos2->stopVelocity();
240  cout << " stop velocity" << endl;
241  epos2->setOperationMode(epos2->PROFILE_VELOCITY);
242  epos2->setTargetProfileVelocity(1000);
243  cout << " profile velocity" << endl;
244  epos2->startProfileVelocity();
245  sleep(4);
246  epos2->stopProfileVelocity();
247  cout << " stop profile velocity" << endl;
248  sleep(2);
249  cout << " 2 profile velocity with vel change" << endl;
250  epos2->setOperationMode(epos2->PROFILE_VELOCITY);
251  epos2->setTargetProfileVelocity(200);
252  cout << " 1st" << endl;
253  epos2->startProfileVelocity();
254  sleep(4);
255  epos2->stopProfileVelocity();
256  cout << " 2nd" << endl;
257  epos2->stopProfileVelocity();
258  sleep(1);
259  epos2->setTargetProfileVelocity(1800);
260  epos2->startProfileVelocity();
261  sleep(2);
262  epos2->stopProfileVelocity();
263  sleep(2);
264  cout << " 3 velocity with vel change (400 -> 800)" << endl;
265  epos2->setOperationMode(epos2->VELOCITY);
266  cout << " 600" << endl;
267  epos2->setTargetVelocity(600);
268  epos2->startVelocity();
269  sleep(5);
270  cout << " 1000" << endl;
271  epos2->setTargetVelocity(1000);
272  sleep(5);
273  epos2->stopVelocity();
274  */
275  cout << " 4 profile position with change wait without blocking" << endl;
276  epos2->setOperationMode(epos2->PROFILE_POSITION);
277  epos2->setProfileData(500,2000,2000,4000,2000,4500,1);
278  epos2->setTargetProfilePosition(222000);
279  cout << " Start Relative not blocking not waiting" << endl;
280  epos2->startProfilePosition(epos2->RELATIVE, false, false);
281  sleep(2);
282  //cout << " Halt (blocking)" << endl;
283  //epos2->startProfilePosition(epos2->HALT, false, false);
284  epos2->setTargetProfilePosition(50000);
285  epos2->setProfileData(3000,3000,3000,4000,3500,4500,1);
286  cout << " Relative blocking waiting" << endl;
287  epos2->startProfilePosition(epos2->RELATIVE, true, false);
288  epos2->setTargetProfilePosition(-20000);
289  epos2->startProfilePosition(epos2->RELATIVE, true, false);
290  epos2->setTargetProfilePosition(50000);
291  epos2->startProfilePosition(epos2->RELATIVE, true, false);
292  //cout << " 5 profile position with change not waiting" << endl;
293 
294 
295  cout << " End Test" << endl;
296  }
297 }
298 
305 void throwAction(char action)
306 {
307 
308  char cs; // character select
309 
310  switch( action ){
311  case 'a':
312  case 'r':
313  case 'w':
314  case 'v':
315  case 'k':
316  doMovement(action);
317  break;
318  case 'h':
319  cout << " ConfigTest Set Home\n\n";
320  epos2->setHome();
321  break;
322  break;
323  case '1':
324  // Configure
325  cout << " ConfigTest Configure Profile Parameters\n\n";
326  // Profile
327 
328  long prof[7];
329 
330 epos2->getProfileData(prof[0],prof[1],prof[2],prof[3],prof[4],prof[5],prof[6]);
331 
332  cout
333  << " PROFILE DATA" << endl
334  << " "
335  << dec << endl
336  << " Velocity: " << prof[0] << "[rpm]" << endl
337  << " Max Velocity: " << prof[1] << "[rpm]" << endl
338  << " Acceleration: " << prof[2] << "[rpm/s]" << endl
339  << " Deceleration: " << prof[3] << "[rpm/s]" << endl
340  << " QS Decel: " << prof[4] << "[rpm/s]" << endl
341  << " Max Accel: " << prof[5] << "[rpm/s]" << endl
342  << " Type: " << prof[6] << endl<<endl;
343 
344  cout << " Profile: Do you want to configure? (y,n): " ;
345  cin >> cs;
346  while(cs!='y' && cs!='n')
347  {
348  cout << endl << " Input Error. press 'y' or 'n': ";
349  cin >> cs;
350  }
351  cout << endl;
352  if(cs=='y'){
353 
354  cout << " Velocity [rpm] " << endl;
355  cin >> prof[0]; cout << endl;
356  cout << " Max Velocity [rpm] " << endl;
357  cin >> prof[1]; cout << endl;
358  cout << " Acceleration [rpm/s] " << endl;
359  cin >> prof[2]; cout << endl;
360  cout << " Deceleration [rpm/s] " << endl;
361  cin >> prof[3]; cout << endl;
362  cout << " QS Decel [rpm/s] " << endl;
363  cin >> prof[4]; cout << endl;
364  cout << " Max acc [rpm/s] " << endl;
365  cin >> prof[5]; cout << endl;
366  cout << " Type " << endl;
367  cin >> prof[6]; cout << endl;
368 
369 
370 epos2->setProfileData(prof[0],prof[1],prof[2],prof[3],prof[4],prof[5],prof[6]);
371 
372  }
373  break;
374  case '2':
375  cout << " ConfigTest Configure Control Parameters\n\n";
376  // Control
377  long conpar[10];
378 
379 epos2->getControlParameters(conpar[0],conpar[1],conpar[2],conpar[3],conpar[4],
380 conpar[5],conpar[6],conpar[7],conpar[8],conpar[9]);
381 
382  cout
383  << " CONTROL PARAMETERS DATA" << endl
384  << dec << endl
385  << " Current P: " << conpar[0] << endl
386  << " Current I: " << conpar[1] << endl
387  << " Velocity P: " << conpar[2] << endl
388  << " Velocity I: " << conpar[3] << endl
389  << " Velocity SPF: " << conpar[4] << endl
390  << " Position P: " << conpar[5] << endl
391  << " Position I: " << conpar[6] << endl
392  << " Position D: " << conpar[7] << endl
393  << " Position Vff: " << conpar[8] << endl
394  << " Position Aff: " << conpar[9] << endl
395  << endl;
396 
397  cout << " Profile: Do you want to configure? (y,n): " ;
398  cin >> cs;
399  while(cs!='y' && cs!='n')
400  {
401  cout << endl << " Input Error. press 'y' or 'n': ";
402  cin >> cs;
403  }
404  cout << endl;
405  if(cs=='y'){
406 
407  cout << " Current P: " << endl;
408  cin >> conpar[0]; cout << endl;
409  cout << " Current I: " << endl;
410  cin >> conpar[1]; cout << endl;
411  cout << " Velocity P: " << endl;
412  cin >> conpar[2]; cout << endl;
413  cout << " Velocity I: " << endl;
414  cin >> conpar[3]; cout << endl;
415  cout << " Velocity SPF: " << endl;
416  cin >> conpar[4]; cout << endl;
417  cout << " Position P: " << endl;
418  cin >> conpar[5]; cout << endl;
419  cout << " Position I: " << endl;
420  cin >> conpar[6]; cout << endl;
421  cout << " Position D: " << endl;
422  cin >> conpar[7]; cout << endl;
423  cout << " Position Vff: " << endl;
424  cin >> conpar[8]; cout << endl;
425  cout << " Position Aff: " << endl;
426  cin >> conpar[9]; cout << endl;
427 
428 
429 epos2->setControlParameters(conpar[0],conpar[1],conpar[2],conpar[3],conpar[4],
430 conpar[5],conpar[6],conpar[7],conpar[8],conpar[9]);
431 
432  }
433 
434  break;
435  case '3':
436  // Sensor
437  cout << " ConfigTest Configure Sensor Parameters\n\n";
438  break;
439  case '4':
440  // Motor
441  cout << " ConfigTest Configure Motor Parameters\n\n";
442  break;
443  case '5':
444  // Position
445  cout << " ConfigTest Configure Position Parameters\n\n";
446  break;
447  case '6':
448  // Units Dimension
449  cout << " ConfigTest Configure Unit Dimensions\n\n";
450  break;
451  case '7':
452  // Communication
453  cout << " ConfigTest Configure Communication Parameters\n\n";
454  break;
455  case '8':
456  // Save all parameters
457  cout << " ConfigTest Saving Parameters\n\n";
458  cout << " Are you sure you want to save parameters? (Y,n) " << endl;
459  char sure8;
460  cin >> sure8;
461  if(sure8=='Y'){
462  epos2->saveParameters();
463  cout << " Parameters Saved" << endl;
464  }else{
465  cout << " parameters not saved" << endl;
466  }
467  break;
468  case '9':
469  // Restore Default Parameters
470  cout << " ConfigTest Restore Default Parameters\n\n";
471  cout << " Are you sure you want to restore parameters? (Y,n) " <<
472 endl;
473  char sure9;
474  cin >> sure9;
475  if(sure9=='Y'){
476  epos2->restoreDefaultParameters();
477  cout << " Parameters Restored" << endl;
478  }else{
479  cout << " parameters not restored" << endl;
480  }
481  break;
482  case 'E':
483  // Read
484  cout << " ConfigTest Read Errors\n\n";
485  // Error
486  long *errors;
487  epos2->readError();
488  epos2->readErrorHistory(&errors);
489  break;
490  case 'S':
491  // StatusWord
492  cout << " ConfigTest Read Status Word\n\n";
493  cout << " STATUS-WORD: " << hex << epos2->readStatusWord() << endl;
494  break;
495  case 'D':
496  // Data
497  cout << " ConfigTest Read Data\n\n";
498  readData();
499  break;
500  case 'x':
501  case 'X':
502  // Exit
503  finish_program=true;
504  break;
505  default:
506  cout << " Choose another option" << endl << endl;
507  break;
508  }
509 
510 }
511 
512 
513 
520 int main(int argc, char **argv)
521 {
522  // Variable declaration
523  char action;
524  bool verbose = false;
525  int opt;
526 
527  cout << "\n EPOS2 CONFIG&TEST \n\n";
528 
529 
530  // Get some options from the command line
531  while ((opt = getopt(argc, argv, "biphv")) != -1)
532  {
533  switch (opt)
534  {
535  case 'b':
536  // blocking
537  blocking = true;
538  break;
539  case 'i':
540  waiting = false;
541  break;
542  case 'p':
543  // print
544  print = true;
545  break;
546  case 'v':
547  verbose=true;
548  break;
549  case '?':
550  case 'h':
551  default:
552  cout << " USAGE" << endl << "\n"
553  << " " << argv[0] << " [options]" << endl << endl
554  << " OPTIONS" << endl <<
555  "\n"
556  << " -i Interrupt Movements" <<
557  "\tin profile position.\n" << endl
558  << " -v Verbose" <<
559  "\tShows all information\n" << endl << endl;
560  return 1;
561  }
562  }
563  epos2 = new CEpos2();
564 
565  cout << " MENU" << endl <<
566  "\n"
567  << " ▾ Do a movement" << endl
568  << " a" <<
569  "\tProfile Position Absolute\n"
570  << " r" <<
571  "\tProfile Position Relative\n"
572  << " w" <<
573  "\tProfile Velocity\n"
574  << " v" <<
575  "\tVelocity\n"
576  << " k" <<
577  "\tKombo\n"
578  << " h" <<
579  "\tSet Home\n" << endl
580  << " Configure Parameters" << endl
581  << " 1" <<
582  "\tProfile\n"
583  << " 2" <<
584  "\tControl\n"
585  << " 3" <<
586  "\tSensor\n"
587  << " 4" <<
588  "\tMotor (not done)\n"
589  << " 5" <<
590  "\tPosition (not done)\n"
591  << " 6" <<
592  "\tUnits dimension (not done)\n"
593  << " 7" <<
594  "\tCommunication (not done)\n"
595  << " 8" <<
596  "\tSave All Parameters\n"
597  << " 9" <<
598  "\tRestore Default\n" << endl
599  << " Read" << endl
600  << " E" <<
601  "\tError\n"
602  << " S" <<
603  "\tStatusword\n"
604  << " D" <<
605  "\tData\n"
606  << endl
607  << " x" <<
608  "\tExit Program\n"
609  << endl << endl;
610 
611  // Start MOTOR Controller
612  try
613  {
614  cout << " ConfigTest init EPOS2\n\n";
615 
616  epos2->init();
617 
618  epos2->setVerbose(verbose);
619 
620 
621  // Check Error
622  long *errors;
623  epos2->readError();
624  epos2->readErrorHistory(&errors);
625 
626  // enable motor
627  cout << " ConfigTest enable controller\n\n";
628  epos2->enableController();
629 
630  cout << " ConfigTest enable motor\n\n";
631  epos2->enableMotor(epos2->PROFILE_POSITION);
632 
633  cout << " ConfigTest disable operation\n\n";
634  epos2->disableOperation();
635  // Do the program while not finish it
636 
637  while(!finish_program){
638  cout << " ? ";
639  cin >> action;
640  // Wait for action
641  cout << endl;
642  throwAction(action);
643  }
644 
645  // Stop motor controller
646  epos2->close();
647 
648  }catch(std::exception &exc)
649  {
650  cout << "EPOS2 Exception: " << exc.what() << endl;
651  return(-1);
652  }
653  // Program End
654  return(0);
655 }
656 
657 
long readStatusWord()
function to read EPOS2 StatusWord
Definition: Epos2.cpp:1172
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
long readCurrentDemanded()
function to read current demanded
Definition: Epos2.cpp:1162
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
bool blocking
Definition: configtest.cpp:59
void enableMotor(long opmode)
function to facititate transitions from switched on to operation enabled
Definition: Epos2.cpp:696
long readVelocitySensorActual()
function to read velocity sensor actual
Definition: Epos2.cpp:1135
long int pdg2mqc(float dg)
platform [°] to motor [qc] It truncates the value
Definition: configtest.cpp:85
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
long readEncoderCounterAtIndexPulse()
function to read the Encoder Counter at index pulse
Definition: Epos2.cpp:1182
void readErrorHistory(long *error[5])
function to read last 5 errors
Definition: Epos2.cpp:1258
bool free_program
Definition: configtest.cpp:57
float mqc2pdg(long int qc)
motor [qc] to platform [°]
Definition: configtest.cpp:72
long getTargetProfileVelocity()
[OPMODE=profile_velocity] function to get the velocity
Definition: Epos2.cpp:778
void setVerbose(bool verbose)
Definition: Epos2.cpp:90
void setOperationMode(long opmode)
function to set the operation mode
Definition: Epos2.cpp:624
void enableOperation()
function to reach operation_enable state and enables power on motor
Definition: Epos2.cpp:557
epos_posmodes
Definition: Epos2.h:341
bool finish_program
Definition: configtest.cpp:56
long readCurrent()
function to read motor current
Definition: Epos2.cpp:1150
long readVersionSoftware()
function to read the software version
Definition: Epos2.cpp:1303
void readData()
reads all epos2 data
Definition: configtest.cpp:95
long readVelocityDemand()
function to read velocity demand
Definition: Epos2.cpp:1140
void setTargetProfileVelocity(long velocity)
[OPMODE=profile_velocity] function to set the velocity
Definition: Epos2.cpp:787
long readHallsensorPattern()
function to read the Hall Sensor Pattern
Definition: Epos2.cpp:1187
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
void restoreDefaultParameters()
function to restore default parameters of EPOS2.
Definition: Epos2.cpp:1458
bool print
Definition: configtest.cpp:59
void enableController()
function to facititate transitions from the start of the controller to switch it on ...
Definition: Epos2.cpp:632
void saveParameters()
function to save all parameters in EEPROM
Definition: Epos2.cpp:1452
void close()
Disconnects hardware.
Definition: Epos2.cpp:58
Implementation of a driver for EPOS2 Motor Controller.
Definition: Epos2.h:60
void init()
Connects hardware.
Definition: Epos2.cpp:49
void setHome()
function to set a Home position with user interaction
Definition: Epos2.cpp:1636
long getTargetProfilePosition()
function to GET the target position
Definition: Epos2.cpp:817
void throwAction(char action)
throw an action set by user
Definition: configtest.cpp:305
long readVersionHardware()
function to read the hardware version
Definition: Epos2.cpp:1308
long readEncoderCounter()
function to read the Encoder Counter
Definition: Epos2.cpp:1177
CEpos2 * epos2
Definition: configtest.cpp:58
long readFollowingError()
function to read the Following Error
Definition: Epos2.cpp:1192
int32_t readPosition()
function to read motor position
Definition: Epos2.cpp:1167
void doMovement(char type)
Starts a motor movement.
Definition: configtest.cpp:143
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 stopVelocity()
function to stop the motor in velocity mode
Definition: Epos2.cpp:766
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
long getTargetVelocity()
function to GET the target velocity This function gets the target velocity of velocity operation mode...
Definition: Epos2.cpp:742
bool waiting
Definition: configtest.cpp:59
bool isTargetReached()
function to know if the motor has reached the target position or velocity
Definition: Epos2.cpp:720
long readVelocityActual()
function to read velocity sensor actual
Definition: Epos2.cpp:1145
void getMovementInfo()
prints information about movement
Definition: Epos2.cpp:1197
int main(int argc, char **argv)
Programa de prova per a obtenir escaneigs i posicions del motor.
Definition: configtest.cpp:520
void setTargetProfilePosition(long position)
function to SET the target position
Definition: Epos2.cpp:825


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