satnogs-rotator-firmware
Loading...
Searching...
No Matches
motor.h
Go to the documentation of this file.
1
11#ifndef MOTOR_H_
12#define MOTOR_H_
13
14#include <Arduino.h>
15
16/**************************************************************************/
36/**************************************************************************/
37class motor {
38
39public:
40 motor(uint8_t pwm_pin1, uint8_t pwm_pin2, uint8_t fb_pin, uint8_t en_pin,
41 uint8_t sf_pin, uint16_t maxSpeed, uint16_t minSpeed) {
42 _pwm_pin1 = pwm_pin1;
43 _pwm_pin2 = pwm_pin2;
44 _maxSpeed = maxSpeed;
45 _minSpeed = minSpeed;
46 _fb_pin = fb_pin;
47 _en_pin = en_pin;
48 _sf_pin = sf_pin;
49 stop();
50 }
51
52 /**************************************************************************/
56 /**************************************************************************/
57 void init_pin() {
58 pinMode(_pwm_pin1, OUTPUT);
59 pinMode(_pwm_pin2, OUTPUT);
60 /* Feedback and sense */
61 pinMode(_fb_pin, INPUT);
62 pinMode(_sf_pin,INPUT);
63 /* Enable Motors */
64 pinMode(_en_pin, OUTPUT);
65 }
66
67 /**************************************************************************/
96 /**************************************************************************/
97 void init_timer(uint8_t timer, uint16_t divisor) {
98 if (timer == 0) {
99 if (divisor == 1) {
100 TCCR0B = (TCCR0B & B11111000) | B00000001;
101 } else if (divisor == 8) {
102 TCCR0B = (TCCR0B & B11111000) | B00000010;
103 } else if (divisor == 64) {
104 TCCR0B = (TCCR0B & B11111000) | B00000011;
105 } else if (divisor == 256) {
106 TCCR0B = (TCCR0B & B11111000) | B00000100;
107 } else if (divisor == 1024) {
108 TCCR0B = (TCCR0B & B11111000) | B00000101;
109 }
110 }
111 if (timer == 1) {
112 if (divisor == 1) {
113 TCCR1B = (TCCR1B & B11111000) | B00000001;
114 } else if (divisor == 8) {
115 TCCR1B = (TCCR1B & B11111000) | B00000010;
116 } else if (divisor == 64) {
117 TCCR1B = (TCCR1B & B11111000) | B00000011;
118 } else if (divisor == 256) {
119 TCCR1B = (TCCR1B & B11111000) | B00000100;
120 } else if (divisor == 1024) {
121 TCCR1B = (TCCR1B & B11111000) | B00000101;
122 }
123 }
124 if (timer == 2) {
125 if (divisor == 1) {
126 TCCR2B = (TCCR2B & B11111000) | B00000001;
127 } else if (divisor == 8) {
128 TCCR2B = (TCCR2B & B11111000) | B00000010;
129 } else if (divisor == 32){
130 TCCR2B = (TCCR2B & B11111000) | B00000011;
131 } else if (divisor == 64) {
132 TCCR2B = (TCCR2B & B11111000) | B00000100;
133 } else if (divisor == 128) {
134 TCCR2B = (TCCR2B & B11111000) | B00000101;
135 } else if (divisor == 256) {
136 TCCR2B = (TCCR2B & B11111000) | B00000110;
137 } else if (divisor == 1024) {
138 TCCR2B = (TCCR2B & B11111000) | B00000111;
139 }
140 }
141 }
142
143 /**************************************************************************/
147 /**************************************************************************/
148 void enable() {
149 digitalWrite(_en_pin, HIGH);
150 }
151
152 /**************************************************************************/
156 /**************************************************************************/
157 void disenable() {
158 digitalWrite(_en_pin, LOW);
159 }
160
161 /**************************************************************************/
166 /**************************************************************************/
167 uint16_t get_load() {
168 return analogRead(_fb_pin);
169 }
170
171 /**************************************************************************/
177 /**************************************************************************/
178 uint8_t get_fault()
179 {
180 return digitalRead(_sf_pin);
181 }
182
183 /**************************************************************************/
189 /**************************************************************************/
190 void move(int16_t speed) {
191 if (speed == 0) {
192 stop();
193 return;
194 }
195 if (speed >= 0) {
197 if (speed > _maxSpeed)
199 analogWrite(_pwm_pin1, 0);
200 analogWrite(_pwm_pin2, speed);
201 } else {
202 speed = -speed;
204 if (speed > _maxSpeed)
206 analogWrite(_pwm_pin1, speed);
207 analogWrite(_pwm_pin2, 0);
208 }
209 }
210
211 /**************************************************************************/
215 /**************************************************************************/
216 void stop() {
217 analogWrite(_pwm_pin1, 0);
218 analogWrite(_pwm_pin2, 0);
219 }
220
221 /**************************************************************************/
227 /**************************************************************************/
228 void set_min(uint16_t min) {
229 _minSpeed = min;
230 }
231
232 /**************************************************************************/
238 /**************************************************************************/
239 void set_max(uint16_t max) {
240 _maxSpeed = max;
241 }
242
243private:
246};
247
248#endif /* MOTOR_H_ */
Class that functions for interacting with a Motor Driver Carrier.
Definition motor.h:37
void move(int16_t speed)
Move the DC motor with constant voltage (~speed)
Definition motor.h:190
uint8_t _fb_pin
Definition motor.h:244
int16_t _minSpeed
Definition motor.h:245
void init_timer(uint8_t timer, uint16_t divisor)
Set timer frequency, for timers 0, 1, 2.
Definition motor.h:97
motor(uint8_t pwm_pin1, uint8_t pwm_pin2, uint8_t fb_pin, uint8_t en_pin, uint8_t sf_pin, uint16_t maxSpeed, uint16_t minSpeed)
Definition motor.h:40
uint8_t get_fault()
Get the status flag of motor driver.
Definition motor.h:178
int16_t _maxSpeed
Definition motor.h:245
void init_pin()
Initialize pins of DC motor driver.
Definition motor.h:57
void stop()
Stop moving the DC motor.
Definition motor.h:216
void set_max(uint16_t max)
Update the maximum speed of DC motor.
Definition motor.h:239
uint8_t _en_pin
Definition motor.h:244
uint8_t _pwm_pin1
Definition motor.h:244
void enable()
Enable motor driver.
Definition motor.h:148
uint8_t _pwm_pin2
Definition motor.h:244
uint8_t _sf_pin
Definition motor.h:244
uint16_t get_load()
Calculate the load of DC motor.
Definition motor.h:167
void disenable()
Disable motor driver.
Definition motor.h:157
void set_min(uint16_t min)
Update the minimum speed of DC motor.
Definition motor.h:228
@ speed
Definition globals.h:26