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>
5
7#include <model/structure.hpp>
8
9#include "debugUtils.hpp"
10#include "hardwareSettings.hpp"
11#include "metro.h"
12#include "utils.hpp"
13
15private:
16 unsigned long timer_ = 0;
17 int state = 0;
18
19public:
20 bool activate_shit(bool tsms_activated) {
21 switch (state) {
22 case 0: {
23 if (millis() - timer_ > 10000) {
24 state = 1;
25 timer_ = millis();
26 }
27 return true & tsms_activated;
28 break;
29 }
30 case 1: {
31 if (millis() - timer_ > 50) {
32 timer_ = millis();
33 state = 0;
34 }
35 return false;
36 }
37 }
38 }
39};
40
47 unsigned long tsms_timer_ = 0;
48
49public:
50 inline static uint32_t last_wheel_pulse_rl =
51 0; // Timestamp of the last pulse for left wheel RPM calculation
52 inline static uint32_t second_to_last_wheel_pulse_rl = 0; // Timestamp of the second to last
53 // pulse for left wheel RPM calculation
54 inline static uint32_t last_wheel_pulse_rr =
55 0; // Timestamp of the last pulse for right wheel RPM calculation
56 inline static uint32_t second_to_last_wheel_pulse_rr =
57 0; // Timestamp of the second to last pulse for right
58 // wheel RPM calculation
59
63 void digital_reads();
64
69 pinMode(SDC_TSMS_STATE_PIN, INPUT);
70 pinMode(AMI, INPUT);
71 pinMode(ASMS_IN_PIN, INPUT);
72 pinMode(EBS_SENSOR2, INPUT);
73 pinMode(EBS_SENSOR1, INPUT);
74
75 pinMode(RL_WSS, INPUT);
76 pinMode(RR_WSS, INPUT);
77 pinMode(BRAKE_SENSOR, INPUT);
78 pinMode(SOC, INPUT);
79 pinMode(ATS, INPUT);
80 pinMode(WD_READY, INPUT);
81 pinMode(WD_SDC_RELAY, INPUT);
82 pinMode(ASATS, INPUT);
83
84 attachInterrupt(
85 digitalPinToInterrupt(RR_WSS),
86 []() {
88 last_wheel_pulse_rr = micros();
89 },
90 RISING);
91 attachInterrupt(
92 digitalPinToInterrupt(RL_WSS),
93 []() {
95 last_wheel_pulse_rl = micros();
96 },
97 RISING);
98 }
99
100private:
101 SystemData* system_data_;
102
103 std::deque<int> brake_readings;
104 unsigned int asms_change_counter_ = 0;
105 unsigned int aats_change_counter_ = 0;
106 unsigned int sdc_change_counter_ = 0;
107 unsigned int pneumatic_change_counter_ = 0;
108 unsigned int mission_change_counter_ = 0;
109 unsigned int sdc_tsms_change_counter_ = 0;
110 unsigned int ats_change_counter_ = 0;
111 unsigned int wd_ready_change_counter_ = 0;
112 Mission last_tried_mission_ = Mission::MANUAL;
113
118 void read_pneumatic_line();
119
124 void read_mission();
125
130 void read_asms_switch();
135 void read_asats_state();
136
141 void read_wheel_speed_sensors();
142
147 void read_tsms_sdc();
148
153 void read_brake_sensor();
154
158 void read_soc();
159
164 void read_ats();
165
169 void read_watchdog_ready();
170
174 void read_rpm();
175};
176
178 read_pneumatic_line();
179 read_mission();
180 read_asms_switch();
181 read_asats_state();
182 read_soc();
183 read_brake_sensor();
184 read_ats();
185 read_tsms_sdc();
186 read_watchdog_ready();
187 read_rpm();
188}
189
190inline void DigitalReceiver::read_soc() {
191 const int raw_value = analogRead(SOC);
192 int mapped_value = map(raw_value, 0, ADC_MAX_VALUE, 0, SOC_PERCENT_MAX);
193 mapped_value = constrain(mapped_value, 0, SOC_PERCENT_MAX); // constrain to 0-100, just in case
194 system_data_->hardware_data_.soc_ = static_cast<uint8_t>(mapped_value);
195}
196
197inline void DigitalReceiver::read_tsms_sdc() {
198 bool is_sdc_closed = digitalRead(SDC_TSMS_STATE_PIN); // low when sdc/bspd open
199 // is_sdc_closed = this->sim.activate_shit(is_sdc_closed);
200 debounce(is_sdc_closed, system_data_->hardware_data_.tsms_sdc_closed_,
201 this->sdc_tsms_change_counter_, 1000);
202 // DEBUG_PRINT_VAR(is_sdc_closed);
203 // DEBUG_PRINT_VAR(system_data_->hardware_data_.tsms_sdc_closed_);
204}
205inline void DigitalReceiver::read_brake_sensor() {
206 int hydraulic_pressure = analogRead(BRAKE_SENSOR);
207 insert_value_queue(hydraulic_pressure, brake_readings, 10);
208 system_data_->hardware_data_._hydraulic_line_pressure = average_queue(brake_readings);
209}
210inline void DigitalReceiver::read_pneumatic_line() {
211 bool pneumatic1 = digitalRead(EBS_SENSOR2);
212 bool pneumatic2 = digitalRead(EBS_SENSOR1);
213
214 system_data_->hardware_data_.pneumatic_line_pressure_1_ = pneumatic1;
215 system_data_->hardware_data_.pneumatic_line_pressure_2_ = pneumatic2;
216 bool latest_pneumatic_pressure = pneumatic1 && pneumatic2;
217 // print values
218 // DEBUG_PRINT_VAR(latest_pneumatic_pressure);
219 // DEBUG_PRINT_VAR(system_data_->hardware_data_.pneumatic_line_pressure_);
220 // DEBUG_PRINT_VAR(pneumatic1);
221 // DEBUG_PRINT_VAR(pneumatic2);
222
223 debounce(latest_pneumatic_pressure, system_data_->hardware_data_.pneumatic_line_pressure_,
224 pneumatic_change_counter_);
225}
226
227inline void DigitalReceiver::read_mission() {
228 int raw_value = analogRead(AMI);
229 int contrained_value = constrain(raw_value, 0, 600);
230 int mapped_value;
231 // int mapped_value = map(constrain(raw_value, 0, ADC_MAX_VALUE), 0, ADC_MAX_VALUE, 0,
232 // MAX_MISSION); // constrain just in case
233 if (contrained_value < 60) {
234 mapped_value = 0; // Manual
235 } else if (contrained_value < 220) {
236 mapped_value = 1; // Acceleration
237 } else if (contrained_value < 330) {
238 mapped_value = 2; // Skidpad
239 } else if (contrained_value < 420) {
240 mapped_value = 3; // Autocross
241 } else if (contrained_value < 475) {
242 mapped_value = 4; // Trackdrive
243 } else if (contrained_value < 540) {
244 mapped_value = 5; // EBS Test
245 } else {
246 mapped_value = 6; // Inspection
247 }
248
249 Mission latest_mission = static_cast<Mission>(mapped_value);
250 if ((latest_mission == system_data_->mission_) && (latest_mission == last_tried_mission_)) {
251 mission_change_counter_ = 0;
252 } else {
253 mission_change_counter_++;
254 }
255 this->last_tried_mission_ = latest_mission;
256 if (mission_change_counter_ >= CHANGE_COUNTER_LIMIT) {
257 system_data_->mission_ = latest_mission;
258 mission_change_counter_ = 0;
259 }
260}
261
262inline void DigitalReceiver::read_asms_switch() {
263 bool latest_asms_status = digitalRead(ASMS_IN_PIN);
264 debounce(latest_asms_status, system_data_->hardware_data_.asms_on_, asms_change_counter_, 1000);
265}
266
267inline void DigitalReceiver::read_asats_state() {
268 bool asats_pressed = !digitalRead(ASATS) && system_data_->hardware_data_.asms_on_;
269 debounce(asats_pressed, system_data_->hardware_data_.asats_pressed_, aats_change_counter_);
270}
271
272inline void DigitalReceiver::read_ats() {
273 bool ats_pressed = digitalRead(ATS);
274 // DEBUG_PRINT_VAR(ats_pressed);
275 debounce(ats_pressed, system_data_->hardware_data_.ats_pressed_, ats_change_counter_);
276}
277
278inline void DigitalReceiver::read_watchdog_ready() {
279 bool wd_ready = digitalRead(WD_READY);
280 debounce(wd_ready, system_data_->hardware_data_.wd_ready_, wd_ready_change_counter_);
281}
282
283inline void DigitalReceiver::read_rpm() {
284 unsigned long time_interval_rr = (last_wheel_pulse_rr - second_to_last_wheel_pulse_rr);
285 unsigned long time_interval_rl = (last_wheel_pulse_rl - second_to_last_wheel_pulse_rl);
286 if (micros() - last_wheel_pulse_rr > LIMIT_RPM_INTERVAL) {
287 system_data_->hardware_data_._right_wheel_rpm = 0.0;
288 } else {
289 system_data_->hardware_data_._right_wheel_rpm =
290 1 / (time_interval_rr * MICRO_TO_SECONDS * PULSES_PER_ROTATION) * SECONDS_IN_MINUTE;
291 }
292 if (micros() - last_wheel_pulse_rl > LIMIT_RPM_INTERVAL) {
293 system_data_->hardware_data_._left_wheel_rpm = 0.0;
294 } else {
295 system_data_->hardware_data_._left_wheel_rpm =
296 1 / (time_interval_rl * MICRO_TO_SECONDS * PULSES_PER_ROTATION) * SECONDS_IN_MINUTE;
297 }
298}
Class responsible for the reading of the digital inputs into the Master teensy.
static uint32_t last_wheel_pulse_rr
static uint32_t last_wheel_pulse_rl
static uint32_t second_to_last_wheel_pulse_rr
DigitalReceiver(SystemData *system_data)
Constructor for the class, sets pintmodes and buttons.
static uint32_t second_to_last_wheel_pulse_rl
void digital_reads()
read all digital inputs
constexpr int ADC_MAX_VALUE
constexpr float MICRO_TO_SECONDS
constexpr int RR_WSS
constexpr int LIMIT_RPM_INTERVAL
constexpr int SECONDS_IN_MINUTE
constexpr int WD_SDC_RELAY
constexpr int SOC
constexpr int CHANGE_COUNTER_LIMIT
constexpr int EBS_SENSOR2
constexpr int RL_WSS
constexpr int WD_READY
constexpr int EBS_SENSOR1
constexpr int ASATS
constexpr int ATS
constexpr int AMI
constexpr int SOC_PERCENT_MAX
constexpr int SDC_TSMS_STATE_PIN
constexpr int BRAKE_SENSOR
SystemData system_data
Definition main.cpp:11
int _hydraulic_line_pressure
double _right_wheel_rpm
bool pneumatic_line_pressure_
bool pneumatic_line_pressure_2_
double _left_wheel_rpm
bool pneumatic_line_pressure_1_
bool activate_shit(bool tsms_activated)
The whole model of the system: holds all the data necessary.
Mission mission_
HardwareData hardware_data_
Mission
Definition structure.hpp:10
#define ASMS_IN_PIN
#define PULSES_PER_ROTATION
void insert_value_queue(const int value, std::deque< int > &queue, const unsigned int max_queue_size)
Definition utils.hpp:7
void debounce(const bool new_value, bool &stored_value, unsigned int &counter, const unsigned int counter_limit)
debounce function to avoid sporadic changes (and repeating the code everywhere)
Definition utils.hpp:64
int average_queue(const std::deque< int > &queue)
Definition utils.hpp:20