Formula Student Electronics & Software
The code for the embedded software
Loading...
Searching...
No Matches
main.cpp
Go to the documentation of this file.
1#include <Arduino.h>
2#include <Bounce2.h>
3#include <FlexCAN_T4.h>
4
5#include "apps.h"
6#include "can.h"
7#include "debug.h"
8#include "display.h"
9#include "statemachine.hpp"
10
11
13extern elapsedMillis ASEmergencyTimer;
14
15volatile bool disabled = false;
16volatile bool BTBReady = false;
17volatile bool transmissionEnabled = false;
18
19volatile bool TSOn = false;
20volatile bool R2DOverride = false;
21
22volatile bool ASReady = false; // true if ASState = ASReady
23
24extern FlexCAN_T4<CAN1, RX_SIZE_256, TX_SIZE_16> can1;
25
26extern CAN_message_t statusRequest;
27
28extern CAN_message_t disable;
29
30extern CAN_message_t DCVoltageRequest;
31extern CAN_message_t actualSpeedRequest;
32
33extern int speed;
34
35extern status R2DStatus;
36
37uint8_t current_byte1; // MSB
38uint8_t current_byte2; // LSB
39CAN_message_t current_msg;
40
42Bounce r2dButton = Bounce();
43
44elapsedMillis R2DTimer;
45extern elapsedMillis APPSTimer;
46elapsedMillis CURRENTtimer;
47elapsedMicros mainLoopPeriod;
48
49void sendMout(int value)
50{
51 uint8_t byte1 = (value >> 8) & 0xFF;
52 uint8_t byte2 = value & 0xFF;
53
54 CAN_message_t msg;
56 msg.len = 3;
57 msg.buf[0] = 0xA0;
58 msg.buf[1] = byte2;
59 msg.buf[2] = byte1;
60 can1.write(msg);
61}
62
64{
66 digitalWrite(buzzerPin, HIGH);
67 else
68 digitalWrite(buzzerPin, LOW);
69}
70
71void setup()
72{
73 Serial.begin(9600);
74 pinMode(APPS_1_PIN, INPUT);
75 pinMode(APPS_2_PIN, INPUT);
76
77 pinMode(buzzerPin, OUTPUT);
78 canSetup();
79
80 r2dButton.attach(R2D_PIN, INPUT);
81 r2dButton.interval(0.1);
82
84 R2DTimer = 0;
85
86 // Init the timer higher than the timeout (ASBuzzer)
87 ASEmergencyTimer = 100000;
88
89 delay(STARTUP_DELAY_MS);
90
91 can1.write(disable);
92 can1.write(statusRequest);
94
95#if DATA_DISPLAY > 0
96 // can1.write(actualSpeedRequest);
98#endif
99#ifdef MAIN_DEBUG
100 LOG("Setup complete, Waiting for R2D\n");
101#endif
102
103 //Uncomment this to run the integration test on the Testing Board
104 //testing_setup();
105}
106
107void loop()
108{
109 if (mainLoopPeriod < 10)
110 return;
111 statemachine();
113 //Uncomment this to run the integration test on the Testing Board
114 //integrationtest(R2DStatus);
115}
void setup()
Definition main.cpp:10
void loop()
AMI main loop: Button gets picked and lights up the corresponding LED LAST BUTTON CHECKED WINS.
Definition main.cpp:23
#define APPS_1_PIN
Definition apps.h:4
#define APPS_2_PIN
Definition apps.h:5
int speed
Definition main.cpp:68
int8_t current_byte2
Definition main.cpp:95
int8_t current_byte1
Definition main.cpp:94
elapsedMillis CURRENTtimer
Definition main.cpp:54
FlexCAN_T4< CAN1, RX_SIZE_256, TX_SIZE_16 > can1
Definition main.cpp:87
#define BAMO_COMMAND_ID
Definition can.h:12
void canSetup()
Definition can.cpp:333
status R2DStatus
Definition main.cpp:41
CAN_message_t current_msg
Definition main.cpp:39
volatile bool ASReady
Definition main.cpp:22
volatile bool disabled
Definition main.cpp:15
elapsedMillis ASEmergencyTimer
Definition can.cpp:76
CAN_message_t DCVoltageRequest
Definition can.cpp:15
volatile bool transmissionEnabled
Definition main.cpp:17
volatile bool TSOn
Definition main.cpp:19
CAN_message_t disable
Definition can.cpp:6
int current_BMS
Definition main.cpp:12
elapsedMillis APPSTimer
CAN_message_t actualSpeedRequest
Definition can.cpp:16
void sendMout(int value)
Definition main.cpp:49
void checkASEmergencySound()
Definition main.cpp:63
elapsedMicros mainLoopPeriod
Definition main.cpp:47
CAN_message_t statusRequest
Definition can.cpp:12
Bounce r2dButton
Definition main.cpp:42
elapsedMillis R2DTimer
Definition main.cpp:44
volatile bool R2DOverride
Definition main.cpp:20
volatile bool BTBReady
Definition main.cpp:16
#define LOG(...)
Definition debug.h:25
void displaySetup()
Definition display.cpp:36
#define R2D_PIN
status
@ IDLE
void statemachine()
#define buzzerPin
#define ASBuzzer
#define STARTUP_DELAY_MS
CAN_message_t msg