-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathRoverFunctions.cpp
More file actions
151 lines (131 loc) · 4.05 KB
/
RoverFunctions.cpp
File metadata and controls
151 lines (131 loc) · 4.05 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
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
#include "RoverFunctions.hpp"
#define MOTOR1B_PWM_PIN 11
#define MOTOR1B_PHASE_PIN 8
#define MOTOR1A_PWM_PIN 10
#define MOTOR1A_PHASE_PIN 7
#define MOTOR1_MODE_PIN 5
#define MOTOR2B_PWM_PIN 9
#define MOTOR2B_PHASE_PIN 4
#define MOTOR2A_PWM_PIN 6
#define MOTOR2A_PHASE_PIN 3
#define MOTOR2_MODE_PIN 2
#define DEFAULT_SPEED 220
#define DEFAULT_SPEED_SLOW 210
int motor1BSpeed = 0;
int motor1ASpeed = 0;
int motor2BSpeed = 0;
int motor2ASpeed = 0;
static inline bool ReachTarget(int* current, int target){
bool ret = false;
if(*current < target){
(*current)++;
ret = true;
}
else if (*current > target){
(*current)--;
ret = true;
}
return ret;
}
void DelaySeconds(float time){
if(time < 0) time = -1*time;
if(time>MAX_DELAY) time = MAX_DELAY;
delay(time*1000);
}
bool ButtonPressed(void){
if(digitalRead(BUTTON)){
return false;
} else {
return true;
}
}
static void SetSpeeds(int M1BTarget,int M1ATarget,int M2BTarget,int M2ATarget){
int expirationCnt = 0;
bool refresh = true;
while(refresh && (expirationCnt<255)){
refresh = false;
if(ReachTarget(&motor1BSpeed,M1BTarget)){
analogWrite(MOTOR1B_PWM_PIN, motor1BSpeed);
refresh = true;
}
if(ReachTarget(&motor1ASpeed,M1ATarget)){
analogWrite(MOTOR1A_PWM_PIN, motor1ASpeed);
refresh = true;
}
if(ReachTarget(&motor2BSpeed,M2BTarget)){
analogWrite(MOTOR2B_PWM_PIN, motor2BSpeed);
refresh = true;
}
if(ReachTarget(&motor2ASpeed,M2ATarget)){
analogWrite(MOTOR2A_PWM_PIN, motor2ASpeed);
refresh = true;
}
delay(2);
expirationCnt++;
}
}
void Stop(void){
SetSpeeds(0,0,0,0);
/*analogWrite(MOTOR1B_PWM_PIN, 0);
analogWrite(MOTOR1A_PWM_PIN, 0);
analogWrite(MOTOR2B_PWM_PIN, 0);
analogWrite(MOTOR2A_PWM_PIN, 0);*/
}
void Forward(float time){
digitalWrite(MOTOR1B_PHASE_PIN, FORWARD);
digitalWrite(MOTOR1A_PHASE_PIN, FORWARD);
digitalWrite(MOTOR2B_PHASE_PIN, FORWARD);
digitalWrite(MOTOR2A_PHASE_PIN, FORWARD);
SetSpeeds(DEFAULT_SPEED,DEFAULT_SPEED,DEFAULT_SPEED,DEFAULT_SPEED);
/*analogWrite(MOTOR1B_PWM_PIN, DEFAULT_SPEED);
analogWrite(MOTOR1A_PWM_PIN, DEFAULT_SPEED);
analogWrite(MOTOR2B_PWM_PIN, DEFAULT_SPEED);
analogWrite(MOTOR2A_PWM_PIN, DEFAULT_SPEED);*/
DelaySeconds(time);
Stop();
}
void Backward(float time){
digitalWrite(MOTOR1B_PHASE_PIN, BACKWARD);
digitalWrite(MOTOR1A_PHASE_PIN, BACKWARD);
digitalWrite(MOTOR2B_PHASE_PIN, BACKWARD);
digitalWrite(MOTOR2A_PHASE_PIN, BACKWARD);
SetSpeeds(DEFAULT_SPEED,DEFAULT_SPEED,DEFAULT_SPEED,DEFAULT_SPEED);
/*analogWrite(MOTOR1B_PWM_PIN, DEFAULT_SPEED);
analogWrite(MOTOR1A_PWM_PIN, DEFAULT_SPEED);
analogWrite(MOTOR2B_PWM_PIN, DEFAULT_SPEED);
analogWrite(MOTOR2A_PWM_PIN, DEFAULT_SPEED);*/
DelaySeconds(time);
Stop();
}
void Spin(bool dir, float time){
digitalWrite(MOTOR1B_PHASE_PIN, dir);
digitalWrite(MOTOR1A_PHASE_PIN, !dir);
digitalWrite(MOTOR2B_PHASE_PIN, dir);
digitalWrite(MOTOR2A_PHASE_PIN, !dir);
SetSpeeds(DEFAULT_SPEED,DEFAULT_SPEED,DEFAULT_SPEED,DEFAULT_SPEED);
/*analogWrite(MOTOR1B_PWM_PIN, DEFAULT_SPEED);
analogWrite(MOTOR1A_PWM_PIN, DEFAULT_SPEED);
analogWrite(MOTOR2B_PWM_PIN, DEFAULT_SPEED);
analogWrite(MOTOR2A_PWM_PIN, DEFAULT_SPEED);*/
DelaySeconds(time);
Stop();
}
void InitializeRover(void){
pinMode(MOTOR1B_PWM_PIN, OUTPUT);
pinMode(MOTOR1B_PHASE_PIN, OUTPUT);
pinMode(MOTOR1A_PWM_PIN, OUTPUT);
pinMode(MOTOR1A_PHASE_PIN, OUTPUT);
pinMode(MOTOR1_MODE_PIN, OUTPUT);
pinMode(MOTOR2B_PWM_PIN, OUTPUT);
pinMode(MOTOR2B_PHASE_PIN, OUTPUT);
pinMode(MOTOR2A_PWM_PIN, OUTPUT);
pinMode(MOTOR2A_PHASE_PIN, OUTPUT);
pinMode(MOTOR2_MODE_PIN, OUTPUT);
pinMode(BUTTON, INPUT_PULLUP);
digitalWrite(MOTOR1_MODE_PIN, HIGH);
digitalWrite(MOTOR1B_PHASE_PIN, HIGH);
digitalWrite(MOTOR1A_PHASE_PIN, HIGH);
digitalWrite(MOTOR2_MODE_PIN, HIGH);
digitalWrite(MOTOR2B_PHASE_PIN, HIGH);
digitalWrite(MOTOR2A_PHASE_PIN, HIGH);
}