Formula Student Electronics & Software
The code for the embedded software
Loading...
Searching...
No Matches
digitalReceiver.hpp
Go to the documentation of this file.
1// ReSharper disable CppMemberFunctionMayBeConst
2#pragma once
3
4#include <Bounce2.h>
6#include <model/structure.hpp>
7
8#include "digitalSettings.hpp"
9#include "debugUtils.hpp"
10
16public:
17 static double _current_left_wheel_rpm; // Class variable to store the left wheel RPM (non-static)
18 static unsigned long last_wheel_pulse_ts; // Timestamp of the last pulse for RPM calculation
19
23 void digitalReads();
24
28 static void updateLeftWheelRpm();
29
33 DigitalReceiver(DigitalData *digitalData, Mission *mission)
34 : digitalData(digitalData), mission(mission) {
35 pinMode(SDC_STATE_PIN, INPUT);
36 pinMode(SDC_LOGIC_WATCHDOG_IN_PIN, INPUT);
37 pinMode(SDC_LOGIC_WATCHDOG_OUT_PIN, OUTPUT);
38 pinMode(MISSION_ACCELERATION_PIN, INPUT);
39 pinMode(MISSION_AUTOCROSS_PIN, INPUT);
40 pinMode(MISSION_EBSTEST_PIN, INPUT);
41 pinMode(MISSION_INSPECTION_PIN, INPUT);
42 pinMode(MISSION_MANUAL_PIN, INPUT);
43 pinMode(MISSION_SKIDPAD_PIN, INPUT);
44 pinMode(MISSION_TRACKDRIVE_PIN, INPUT);
45 pinMode(ASMS_IN_PIN, INPUT);
46 pinMode(SENSOR_PRESSURE_1_PIN, INPUT);
47 pinMode(SENSOR_PRESSURE_2_PIN, INPUT);
48
49 // attachInterrupt(digitalPinToInterrupt(LWSS_PIN), DigitalReceiver::updateLeftWheelRpm, RISING);
50 }
51
52private:
53 DigitalData *digitalData;
54 Mission *mission;
55
56 unsigned int asms_change_counter = 0;
57 unsigned int aats_change_counter = 0;
58 unsigned int pneumatic_change_counter = 0;
59 unsigned int mission_change_counter = 0;
60 Mission last_tried_mission_ = MANUAL;
61
66 void readPneumaticLine();
67
72 void readMission();
73
78 void readAsmsSwitch();
79
84 void readAatsState();
85
90 void readWatchdog();
91
92};
93
94// double DigitalReceiver::_current_left_wheel_rpm = 0.0;
95// unsigned long DigitalReceiver::last_wheel_pulse_ts = millis();
96
97// inline void DigitalReceiver::updateLeftWheelRpm() {
98// // rpm = 1 / ([dT seconds] * No. Pulses in Rotation) * [60 seconds]
99// unsigned long now = micros();
100// unsigned long time_interval_s = (now - last_wheel_pulse_ts);
101// _current_left_wheel_rpm = 1 / (time_interval_s * 1e-6 * PULSES_PER_ROTATION) * 60;
102// last_wheel_pulse_ts = now; // refresh timestamp
103// // DEBUG_PRINT_VAR(_current_left_wheel_rpm);
104// }
105
107 readPneumaticLine();
108 readMission();
109 readAsmsSwitch();
110 readAatsState();
111 readWatchdog();
112 // digitalData->_left_wheel_rpm = _current_left_wheel_rpm;
113}
114
115inline void DigitalReceiver::readPneumaticLine() {
116 bool pneumatic1 = digitalRead(SENSOR_PRESSURE_1_PIN);
117 bool pneumatic2 = digitalRead(SENSOR_PRESSURE_2_PIN);
118 if (pneumatic1 == 0) {
119 // DEBUG_PRINT_VAR(digitalRead(SENSOR_PRESSURE_1_PIN));
120 }
121 if (pneumatic2 == 0) {
122 // DEBUG_PRINT_VAR(digitalRead(SENSOR_PRESSURE_2_PIN));
123 }
124 bool temp_res = pneumatic1 && pneumatic2;
125
126 // Only change the value if it has been different 5 times in a row
127 pneumatic_change_counter = temp_res == digitalData->pneumatic_line_pressure ? 0 : pneumatic_change_counter + 1;
128 if (pneumatic_change_counter >= DIGITAL_INPUT_COUNTER_LIMIT) {
129 digitalData->pneumatic_line_pressure = temp_res; // both need to be True
130 pneumatic_change_counter = 0;
131 }
132 // DEBUG_PRINT_VAR(digitalData->pneumatic_line_pressure);
133
134}
135
136inline void DigitalReceiver::readMission() {
137
138 Mission temp_res = static_cast<Mission>(
139 digitalRead(MISSION_MANUAL_PIN) * MANUAL |
141 digitalRead(MISSION_SKIDPAD_PIN) * SKIDPAD |
142 digitalRead(MISSION_AUTOCROSS_PIN) * AUTOCROSS |
143 digitalRead(MISSION_TRACKDRIVE_PIN) * TRACKDRIVE |
144 digitalRead(MISSION_EBSTEST_PIN) * EBS_TEST |
145 digitalRead(MISSION_INSPECTION_PIN) * INSPECTION);
146
147 mission_change_counter = (temp_res == *mission) &&
148 (temp_res == last_tried_mission_) ?
149 0 : mission_change_counter + 1;
150 this->last_tried_mission_ = temp_res;
151 if (mission_change_counter >= DIGITAL_INPUT_COUNTER_LIMIT) {
152 *mission = temp_res;
153 mission_change_counter = 0;
154 }
155 // DEBUG_PRINT_VAR(*mission);
156}
157
158inline void DigitalReceiver::readAsmsSwitch() {
159 bool temp_res = digitalRead(ASMS_IN_PIN);
160
161 // Only change the value if it has been different 5 times in a row
162 asms_change_counter = temp_res == digitalData->asms_on ? 0 : asms_change_counter + 1;
163 if (asms_change_counter >= DIGITAL_INPUT_COUNTER_LIMIT) {
164 digitalData->asms_on = temp_res;
165 asms_change_counter = 0;
166 }
167}
168
169inline void DigitalReceiver::readAatsState() {
170 // AATS is on if SDC is closed (SDC STATE PIN AS HIGH)
171 bool temp_res = !digitalRead(SDC_STATE_PIN);
172 // Only change the value if it has been different 5 times in a row
173 aats_change_counter = temp_res == digitalData->sdcState_OPEN ? 0 : aats_change_counter + 1;
174 if (aats_change_counter >= DIGITAL_INPUT_COUNTER_LIMIT) {
175 digitalData->sdcState_OPEN = temp_res; // both need to be True
176 aats_change_counter = 0;
177 }
178 // DEBUG_PRINT_VAR(digitalData->sdcState_OPEN);
179}
180
181inline void DigitalReceiver::readWatchdog() {
182 digitalData->watchdog_state = digitalRead(SDC_LOGIC_WATCHDOG_IN_PIN);
183 if (digitalData->watchdog_state) {
184 digitalData->watchdogTimestamp.reset();
185 }
186 // DEBUG_PRINT_VAR(digitalData->watchdog_state);
187}
Class responsible for the reading of the digital inputs into the Master teensy.
static void updateLeftWheelRpm()
callback to update rl wheel rpm
static double _current_left_wheel_rpm
DigitalReceiver(DigitalData *digitalData, Mission *mission)
Constructor for the class, sets pintmodes and buttons.
void digitalReads()
read all digital inputs
static unsigned long last_wheel_pulse_ts
void reset()
Resets the timer to the current time.
Definition metro.h:125
#define ASMS_IN_PIN
#define MISSION_EBSTEST_PIN
#define SENSOR_PRESSURE_2_PIN
#define MISSION_ACCELERATION_PIN
#define DIGITAL_INPUT_COUNTER_LIMIT
#define SDC_LOGIC_WATCHDOG_OUT_PIN
#define MISSION_MANUAL_PIN
#define MISSION_SKIDPAD_PIN
#define MISSION_AUTOCROSS_PIN
#define SENSOR_PRESSURE_1_PIN
#define MISSION_TRACKDRIVE_PIN
#define MISSION_INSPECTION_PIN
#define SDC_LOGIC_WATCHDOG_IN_PIN
#define SDC_STATE_PIN
bool pneumatic_line_pressure
Metro watchdogTimestamp
bool watchdog_state
Mission
Definition structure.hpp:17
@ MANUAL
Definition structure.hpp:18
@ EBS_TEST
Definition structure.hpp:23
@ SKIDPAD
Definition structure.hpp:20
@ AUTOCROSS
Definition structure.hpp:21
@ ACCELERATION
Definition structure.hpp:19
@ TRACKDRIVE
Definition structure.hpp:22
@ INSPECTION
Definition structure.hpp:24