-
Notifications
You must be signed in to change notification settings - Fork 1
Expand file tree
/
Copy pathMotorCtrl.cpp
More file actions
134 lines (108 loc) · 3.09 KB
/
MotorCtrl.cpp
File metadata and controls
134 lines (108 loc) · 3.09 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
/*
MotorCtrl - Clase para control de motor
Created by Rafa Gomez, 2014, 2015
Licensed under GPL v3
*/
#include "MotorCtrl.h"
MotorCtrl::MotorCtrl(int pinPWM, int pinDIRECTION1, int pinDIRECTION2)
{
_pinPWM = pinPWM;
_pinDIRECTION1 = pinDIRECTION1;
_pinDIRECTION2 = pinDIRECTION2;
_maxPWM = 255;
_minPWM = 0;
_startPWM = 1;
_offSetPWM = 0;
_velPWM = 0;
_direction = ND;
}
MotorCtrl::~MotorCtrl()
{
// Nothing to do
}
void MotorCtrl::initMotor() // Inicializa motor
{
pinMode(_pinPWM, OUTPUT);
analogWrite(_pinPWM, 0);
pinMode(_pinDIRECTION1, OUTPUT);
if(_pinDIRECTION2 != -1)
pinMode(_pinDIRECTION2, OUTPUT);
setDirection(AVANZA);
}
void MotorCtrl::setConstants(int max, int min, int start) // Selecciona los valores máximos y mínimos para PWM
{
_maxPWM = max;
_minPWM = min;
_startPWM = start;
}
MotorCtrl::resultados MotorCtrl::setSpeed(int pwm) // Selecciona la velocidad del motor, comprobando que se encuentre dentro de los márgenes adecuados
{
MotorCtrl::resultados resultado = OK;
int min = (_velPWM < _minPWM) ? _startPWM : _minPWM;
if( (pwm - _offSetPWM) < min ) // PWM está por debajo de valor válido
{
resultado = TOOSMALL;
}
else if( (pwm - _offSetPWM) > _maxPWM ) // PWM está por encima de valor válido
{
resultado = TOOBIG;
}
else
{
if ( _velPWM != (pwm - _offSetPWM) ) // escribe sólo si el valor ha cambiado
{
_velPWM = pwm - _offSetPWM;
analogWrite(_pinPWM, _velPWM);
}
}
return resultado;
}
void MotorCtrl::setDirection(MotorCtrl::direccion dir) // Selecciona el sentido de giro del motor
{
if (dir != _direction) // escribe sólo si el valor ha cambiado
{
_direction = dir;
switch(_direction)
{
case AVANZA:
digitalWrite(_pinDIRECTION1, LOW);
if(_pinDIRECTION2 != -1)
digitalWrite(_pinDIRECTION2, HIGH);
break;
case RETROCEDE:
digitalWrite(_pinDIRECTION1, HIGH);
if(_pinDIRECTION2 != -1)
digitalWrite(_pinDIRECTION2, LOW);
break;
default:
// do nothing
break;
}
}
}
MotorCtrl::direccion MotorCtrl::getDirection() // Indica el sentido de giro del motor
{
return _direction;
}
void MotorCtrl::stop() // detiene el motor
{
if ( _velPWM != 0 ) // escribe sólo si el valor ha cambiado
{
if(_pinDIRECTION2 != -1) { // Usa combinaciones de pines de dirección para seleccionar dirección/frenar
digitalWrite(_pinDIRECTION1, LOW);
digitalWrite(_pinDIRECTION2, HIGH);
}
_velPWM = 0;
analogWrite(_pinPWM, _velPWM);
}
}
void MotorCtrl::setOffset(int offset) // selecciona el offset de velocidad del motor
{
int pwm_raw = _velPWM + _offSetPWM;
_offSetPWM = offset;
setSpeed(pwm_raw);
}
int MotorCtrl::getOffset() // devuelve el offset de velocidad del motor
{
return _offSetPWM;
}