forked from Lukilink/ECU
-
Notifications
You must be signed in to change notification settings - Fork 1
/
GAS.ino
155 lines (130 loc) · 4.32 KB
/
GAS.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
// GAS - DONT USE ON PUBLIC ROAD
//________________import can libary https://github.com/sandeepmistry/arduino-CAN
#include <CAN.h>
//________________this values needs to be define for each car
int PERM_ERROR = 8; //will allow a diffrence between targetPressure and currentPressure
int minPot = 86; //measured at actuators lowest position
int maxPot = 920; //measured at actuators highest position
float maxACC_CMD = 1500; //the max Value which comes from OP on CAN ID 0x200
float minACC_CMD = 475; //the min Value which comes from OP on CAN ID 0x200
int user_input_threshold = 150; // threshold to trigger user gas_press (potiPossition >= tagetposition + user_input_threshold)
//________________define_pins
int cancel_pin = 3; //pulled to GND when pedal pressed
int potPin = A3; // connect the potentiometer of your cars throllte
int M_DIR = 8; // LOW is Left / HIGH is Right
int M_PWM = 9; // 255 is run / LOW is stopp
int S_DIR = 7; // LOW is Left / HIGH is Right
int S_PWM = 6; // 255 is run / LOW is stopp
//________________values
int targetPosition = 0;
int potiPosition = 0;
float ACC_CMD_PERCENT = 0;
float ACC_CMD = 0;
float ACC_CMD1 = 0;
boolean cancel = false;
boolean GAS_RELEASED = false;
void setup() {
//________________begin Monitor - only use it for debugging
//Serial.begin(115200);
//________________begin CAN
CAN.begin(500E3);
CAN.filter(0x200);
//________________set up pin modes
pinMode(cancel_pin, INPUT_PULLUP);
pinMode(potPin, INPUT);
pinMode(M_DIR, OUTPUT);
pinMode(M_PWM, OUTPUT);
pinMode(S_DIR, OUTPUT);
pinMode(S_PWM, OUTPUT);
digitalWrite(S_DIR, LOW);
}
void loop() {
//________________read cancel pin
cancel = (digitalRead(cancel_pin));
//________________read poti Position
int potiPosition = (analogRead(potPin));
//________________read ACC_CMD from CANbus
CAN.parsePacket();
if (CAN.packetId() == 0x200)
{
uint8_t dat[8];
for (int ii = 0; ii <= 7; ii++) {
dat[ii] = (char) CAN.read();
}
ACC_CMD = (dat[0] << 8 | dat[1] << 0);
}
//________________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 ACC_CMD_PERCENT into targetPosition
float targetPosition = (((ACC_CMD_PERCENT / 100) * (maxPot - minPot)) + minPot);
//________________do nothing if cancel = flase or if ACC_CMD is 0
if (!cancel || ACC_CMD_PERCENT == 0) {
analogWrite(S_PWM, 0); //open solenoid
analogWrite(M_PWM, 0); //stop Motor
}
//________________press or release the pedal to match targetPosition
else {
analogWrite(S_PWM, 255);
if (abs(potiPosition - targetPosition) >= PERM_ERROR)
{
if ((potiPosition < targetPosition) && (potiPosition < maxPot)) //if we are lower than target and not at endpoint
{
analogWrite(M_PWM, 255); //run Motor
digitalWrite(M_DIR, LOW); //motor driection left
}
else if ((potiPosition > targetPosition) && (potiPosition >= minPot)) //if we are higher than target and not at endpoint
{
analogWrite(M_PWM, 255); //run Motor
digitalWrite(M_DIR, HIGH); //motor driection right
}
}
else {
analogWrite(M_PWM, 0); // if we match target position, just stay here
}
}
//________________logic if gas is pressed by user
if (potiPosition >= (targetPosition + user_input_threshold))
{
GAS_RELEASED = false;
}
else {
GAS_RELEASED = true;
}
//______________SENDING_CAN_MESSAGES
// 0x2c1 msg GAS_PEDAL
uint8_t dat_2c1[8];
dat_2c1[0] = (GAS_RELEASED << 3) & 0x08;
dat_2c1[1] = 0x0;
dat_2c1[2] = 0x0;
dat_2c1[3] = 0x0;
dat_2c1[4] = 0x0;
dat_2c1[5] = 0x0;
dat_2c1[6] = 0x0;
dat_2c1[7] = 0x0;
CAN.beginPacket(0x2c1);
for (int ii = 0; ii < 8; ii++) {
CAN.write(dat_2c1[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(targetPosition);
Serial.print("_____");
Serial.print("Position_");
Serial.print(potiPosition);
Serial.println("");
*/
}