test_epos2.cpp
Go to the documentation of this file.
1 /*
2 Copyright (C) 2009-2010 Institut de Robòtica i Informàtica Industrial, CSIC-UPC.
3 Author Martí Morta Garriga (mmorta@iri.upc.edu)
4 All rights reserved.
5 
6 This file is part of IRI EPOS2 Driver
7 IRI EPOS2 Driver is free software: you can redistribute it and/or modify
8 it under the terms of the GNU Lesser General Public License as published by
9 the Free Software Foundation, either version 3 of the License, or
10 at your option) any later version.
11 
12 This program is distributed in the hope that it will be useful,
13 but WITHOUT ANY WARRANTY; without even the implied warranty of
14 MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15 GNU Lesser General Public License for more details.
16 
17 You should have received a copy of the GNU Lesser General Public License
18 along with this program. If not, see <http://www.gnu.org/licenses/>.
19 */
20 
21 #include <stdio.h>
22 #include <unistd.h>
23 
24 #include <iostream>
25 #include "Epos2.h"
26 
27 using namespace std;
28 
72 int main(void){
73 
74  CEpos2 controller;
75 
76  cout << "\n EPOS2 EXAMPLE" << endl;
77 
78 
79  try{
80 
81  // Initiate an EPOS 2 controller
82  controller.setVerbose(true);
83 
84  cout << "\n Example : Init\n" << endl;
85  controller.init();
86 
87  // enable motor in velocity mode
88  cout << "\n Example : Enable Controller\n" << endl;
89  controller.enableController();
90  cout << "\n Example : GREEN LED blinking (controller enabled)\n" << endl;
91  sleep(2);
92 
93  cout << "\n Example : Enable Motor\n" << endl;
94  controller.enableMotor(controller.VELOCITY);
95  cout << "\n Example : GREEN LED on (motor enabled)\n" << endl;
96 
97  controller.setOperationMode(controller.VELOCITY);
98  cout << "\n Example : Current Position = " << controller.readPosition() << " [qc]" << endl;
99 
100  // set motor velocity in RPM
101  cout << "\n Example : Velocity (500 1/min) during 2 seconds\n" << endl;
102  controller.setTargetVelocity(500);
103 
104  // start the movement
105  controller.startVelocity();
106  sleep(2);
107 
108  // stop the movement
109  controller.stopVelocity();
110 
111  cout << "\n Example : Getting profile\n" << endl;
112 
113  long int prof[7];
114  controller.getProfileData(prof[0],prof[1],prof[2],prof[3],prof[4],prof[5],prof[6]);
115 
116  // start profile velocity
117  cout << "\n Example : Profile Velocity (500 1/min) during 2 seconds\n" << endl;
118  controller.setOperationMode(controller.PROFILE_VELOCITY);
119  controller.setTargetProfileVelocity(500);
120  controller.startProfileVelocity();
121  sleep(2);
122  controller.stopProfileVelocity();
123 
124  cout << "\n Example : Profile Position (to 0)\n" << endl;
125  controller.setTargetProfilePosition(0);
126  controller.setOperationMode(controller.PROFILE_POSITION);
127  controller.startProfilePosition(controller.ABSOLUTE,true,true);
128 
129  cout << "\n Example : Closing\n" << endl;
130 
131  controller.close();
132 
133  cout << "\n EPOS2 : GREEN LED blinking\n" << endl;
134 
135  }catch(std::exception &e){
136  cout << e.what() << endl << endl;
137  }
138 
139  return 1;
140 
141 }
142 
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 enableMotor(long opmode)
function to facititate transitions from switched on to operation enabled
Definition: Epos2.cpp:696
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
int main(void)
Definition: test_epos2.cpp:72
void setVerbose(bool verbose)
Definition: Epos2.cpp:90
void setOperationMode(long opmode)
function to set the operation mode
Definition: Epos2.cpp:624
void setTargetProfileVelocity(long velocity)
[OPMODE=profile_velocity] function to set the velocity
Definition: Epos2.cpp:787
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 enableController()
function to facititate transitions from the start of the controller to switch it on ...
Definition: Epos2.cpp:632
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
int32_t readPosition()
function to read motor position
Definition: Epos2.cpp:1167
void stopVelocity()
function to stop the motor in velocity mode
Definition: Epos2.cpp:766
void setTargetVelocity(long velocity)
function to SET the target velocity
Definition: Epos2.cpp:750
void startProfileVelocity()
[OPMODE=profile_velocity] function to move the motor in a velocity
Definition: Epos2.cpp:795
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:01