-
Notifications
You must be signed in to change notification settings - Fork 8
/
Copy pathBRAKE.ino
184 lines (161 loc) · 4.92 KB
/
BRAKE.ino
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
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
/* BRAKE
* DONT USE ON PUBLIC ROADS!
*/
//________________import can libary https://github.com/sandeepmistry/arduino-CAN
#include <CAN.h>
//________________this values needs to be define for each car
int PERM_ERROR = 2; // will allow a diffrence between targetPressure and currentPressure
int maxPressure = 190; // the max pressure your actuator is able to aply
int minPressure = 100; //the pressure in stand still
float maxACC_CMD = 500; //the max Value which comes from OP
float minACC_CMD = 0; //the min Value which comes from OP
int brake_pressed_threshold = 5; // threshold when user input is detected
int brake_light_threshold = 5; // threshold when brakelights schould turn on
//________________define_pins
int pressurePin = A2;
int brakelightPin = A5;
int M_DIR = 8;
int M_PWM = 9;
int S_DIR = 7;
int S_PWM = 6;
//________________values
float targetPressure;
float currentPressure;
float ACC_CMD_PERCENT;
float ACC_CMD;
float ACC_CMD1;
boolean BRAKE_PRESSED = true;
boolean releasing_by_OP = false;
boolean open_solenoid = true;
long previousMillis;
void setup() {
//________________begin Monitor - only use for debugging
// Serial.begin(115200);
//________________begin CAN
CAN.begin(500E3);
CAN.filter(0x343);
//________________set up pin modes
pinMode(pressurePin, INPUT);
pinMode(M_DIR, OUTPUT); // LOW is Left / HIGH is Right
pinMode(M_PWM, OUTPUT); // 255 is run / LOW is stop
pinMode(S_DIR, OUTPUT); // LOW is Left / HIGH is Right
pinMode(S_PWM, OUTPUT); // 255 is run / LOW is stop
digitalWrite(S_DIR, HIGH); // the direction for the solenoid does not matter
pinMode(brakelightPin, OUTPUT);
}
void loop() {
//________________read pressure sensor
currentPressure = (analogRead(pressurePin));
//________________read ACC_CMD from CANbus
CAN.parsePacket();
if (CAN.packetId() == 0x343)
{
uint8_t dat[8];
for (int ii = 0; ii <= 7; ii++) {
dat[ii] = (char) CAN.read();
}
ACC_CMD = ((dat[0] << 8 | dat[1] << 0) * -1);
}
//________________calculating ACC_CMD into ACC_CMD_PERCENT
if (ACC_CMD >= minACC_CMD) {
ACC_CMD1 = ACC_CMD;
}
else {
ACC_CMD1 = minACC_CMD;
}
ACC_CMD_PERCENT = ((100/(maxACC_CMD - minACC_CMD)) * (ACC_CMD1 - minACC_CMD));
//________________calculating targetPressure
targetPressure = (((ACC_CMD_PERCENT / 100) * (maxPressure - minPressure)) + minPressure); // conversion from ACC_CMD_PERCENT % into targetpressure
//________________press or release the pedal to match targetPressure
if (abs(currentPressure - targetPressure) >= PERM_ERROR)
{
open_solenoid = false;
if ((currentPressure < targetPressure) && (ACC_CMD_PERCENT > 0))
{
analogWrite(M_PWM, 255); //run Motor
digitalWrite(M_DIR, HIGH); //motor driection left | press the pedal
releasing_by_OP = false;
}
else if (currentPressure > targetPressure)
{
analogWrite(M_PWM, 255); //run Motor
digitalWrite(M_DIR, LOW); //motor driection right | release the pedal
releasing_by_OP = true;
}
else if (ACC_CMD_PERCENT == 0)
{
analogWrite(M_PWM, 255); //run Motor
digitalWrite(M_DIR, LOW); //motor driection right | release the pedal
releasing_by_OP = false;
}
}
else
{
open_solenoid = false;
analogWrite(M_PWM, 0); //if we match target position, just stay here
releasing_by_OP = false;
}
//________________logic to read if brake is pressed by driver
if ((currentPressure >= (targetPressure + brake_pressed_threshold)) && !releasing_by_OP)
{
BRAKE_PRESSED = true;
open_solenoid = true;
}
else {
BRAKE_PRESSED = false;
}
//________________operate solenoid
if (open_solenoid)
{
analogWrite(S_PWM, 0);
}
else
{
analogWrite(S_PWM, 255);
}
//________________light up brakelights when brake is pressed
long currentMillis = millis();
if (currentMillis - previousMillis >= 200)
{
if (currentPressure >= (minPressure + brake_light_threshold))
{
analogWrite(brakelightPin, 255);
}
else
{
analogWrite(brakelightPin, 0);
}
previousMillis = currentMillis;
}
//________________send CAN BUS messages
//0x3b7 msg ESP_CONTROL
uint8_t dat_3b7[8];
dat_3b7[0] = (BRAKE_PRESSED << 5) & 0x20;
dat_3b7[1] = 0x0;
dat_3b7[2] = 0x0;
dat_3b7[3] = 0x0;
dat_3b7[4] = 0x0;
dat_3b7[5] = 0x0;
dat_3b7[6] = 0x0;
dat_3b7[7] = 0x08;
CAN.beginPacket(0x3b7);
for (int ii = 0; ii < 8; ii++) {
CAN.write(dat_3b7[ii]);
}
CAN.endPacket();
//________________print stuff if you want to DEBUG
/*
Serial.print("ACC_CMD_");
Serial.print(ACC_CMD);
Serial.print("_____");
Serial.print(ACC_CMD_PERCENT);
Serial.print("_%");
Serial.print("_____");
Serial.print("target_");
Serial.print(targetPressure);
Serial.print("_____");
Serial.print("Pressure");
Serial.println(currentPressure);
Serial.println("");
*/
}