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 "utils.hpp"
12
18public:
19 inline static uint32_t last_wheel_pulse_rl =
20 0; // Timestamp of the last pulse for left wheel RPM calculation
21 inline static uint32_t second_to_last_wheel_pulse_rl = 0; // Timestamp of the second to last
22 // pulse for left wheel RPM calculation
23 inline static uint32_t last_wheel_pulse_rr =
24 0; // Timestamp of the last pulse for right wheel RPM calculation
25 inline static uint32_t second_to_last_wheel_pulse_rr =
26 0; // Timestamp of the second to last pulse for right
27 // wheel RPM calculation
28
32 void digital_reads();
33
38 pinMode(SDC_BSPD_STATE_PIN, INPUT);
39 pinMode(AMI, INPUT);
40 pinMode(ASMS_IN_PIN, INPUT);
41 pinMode(EBS_SENSOR2, INPUT);
42 pinMode(EBS_SENSOR1, INPUT);
43
44 pinMode(RL_WSS, INPUT);
45 pinMode(RR_WSS, INPUT);
46 pinMode(BRAKE_SENSOR, INPUT);
47 pinMode(SOC, INPUT);
48 pinMode(ATS, INPUT);
49 pinMode(ASATS, INPUT);
50 pinMode(WD_READY, INPUT);
51 pinMode(WD_SDC_RELAY, INPUT);
52
53 attachInterrupt(
54 digitalPinToInterrupt(RR_WSS),
55 []() {
57 last_wheel_pulse_rr = micros();
58 },
59 RISING);
60 attachInterrupt(
61 digitalPinToInterrupt(RL_WSS),
62 []() {
64 last_wheel_pulse_rl = micros();
65 },
66 RISING);
67 }
68
69private:
70 SystemData* system_data_;
71
72 std::deque<int> brake_readings;
73 unsigned int asms_change_counter_ = 0;
74 unsigned int aats_change_counter_ = 0;
75 unsigned int sdc_change_counter_ = 0;
76 unsigned int pneumatic_change_counter_ = 0;
77 unsigned int mission_change_counter_ = 0;
78 unsigned int sdc_bspd_change_counter_ = 0;
79 unsigned int ats_change_counter_ = 0;
80 unsigned int wd_ready_change_counter_ = 0;
81 Mission last_tried_mission_ = Mission::MANUAL;
82
87 void read_pneumatic_line();
88
93 void read_mission();
94
99 void read_asms_switch();
104 void read_asats_state();
105
110 void read_wheel_speed_sensors();
111
116 void read_bspd_sdc();
117
122 void read_brake_sensor();
123
127 void read_soc();
128
133 void read_ats();
134
138 void read_watchdog_ready();
139
143 void read_rpm();
144};
145
147 read_pneumatic_line();
148 read_mission();
149 read_asms_switch();
150 read_asats_state();
151 read_soc();
152 read_brake_sensor();
153 read_ats();
154 read_bspd_sdc();
155 read_watchdog_ready();
156 read_rpm();
157}
158
159inline void DigitalReceiver::read_soc() {
160 const int raw_value = analogRead(SOC);
161 int mapped_value = map(raw_value, 0, ADC_MAX_VALUE, 0, SOC_PERCENT_MAX);
162 mapped_value = constrain(mapped_value, 0, SOC_PERCENT_MAX); // constrain to 0-100, just in case
163 system_data_->hardware_data_.soc_ = static_cast<uint8_t>(mapped_value);
164}
165
166inline void DigitalReceiver::read_bspd_sdc() {
167 bool is_sdc_open = (0 == digitalRead(SDC_BSPD_STATE_PIN)); // low when sdc/bspd open
168 debounce(is_sdc_open, system_data_->hardware_data_.bspd_sdc_open_, sdc_bspd_change_counter_);
169}
170inline void DigitalReceiver::read_brake_sensor() {
171 int hydraulic_pressure = analogRead(BRAKE_SENSOR);
172 insert_value_queue(hydraulic_pressure, brake_readings);
173 system_data_->hardware_data_._hydraulic_line_pressure = average_queue(brake_readings);
174}
175inline void DigitalReceiver::read_pneumatic_line() {
176 bool pneumatic1 = digitalRead(EBS_SENSOR2);
177 bool pneumatic2 = digitalRead(EBS_SENSOR1);
178
179 system_data_->hardware_data_.pneumatic_line_pressure_1_ = pneumatic1;
180 system_data_->hardware_data_.pneumatic_line_pressure_2_ = pneumatic2;
181 bool latest_pneumatic_pressure = pneumatic1 && pneumatic2;
182
183 debounce(latest_pneumatic_pressure, system_data_->hardware_data_.pneumatic_line_pressure_,
184 pneumatic_change_counter_);
185}
186
187inline void DigitalReceiver::read_mission() {
188 int raw_value = analogRead(AMI);
189 int mapped_value = map(constrain(raw_value, 0, ADC_MAX_VALUE), 0, ADC_MAX_VALUE, 0, MAX_MISSION); // constrain just in case
190 Mission latest_mission = static_cast<Mission>(mapped_value);
191
192 if ((latest_mission == system_data_->mission_) && (latest_mission == last_tried_mission_)) {
193 mission_change_counter_ = 0;
194 } else {
195 mission_change_counter_++;
196 }
197 this->last_tried_mission_ = latest_mission;
198 if (mission_change_counter_ >= CHANGE_COUNTER_LIMIT) {
199 system_data_->mission_ = latest_mission;
200 mission_change_counter_ = 0;
201 }
202 system_data_->mission_ = Mission::MANUAL;
203}
204
205inline void DigitalReceiver::read_asms_switch() {
206 bool latest_asms_status = digitalRead(ASMS_IN_PIN);
207 debounce(latest_asms_status, system_data_->hardware_data_.asms_on_, asms_change_counter_);
208}
209
210inline void DigitalReceiver::read_asats_state() {
211 bool asats_pressed = !digitalRead(ASATS);
212 debounce(asats_pressed, system_data_->hardware_data_.asats_pressed_, aats_change_counter_);
213 if (system_data_->hardware_data_.asats_pressed_) { // TODO: remove this, shitty workaround
214 system_data_->failure_detection_.emergency_signal_ = false;
215 }
216}
217
218inline void DigitalReceiver::read_ats() {
219 bool ats_pressed = digitalRead(ATS);
220 // DEBUG_PRINT_VAR(ats_pressed);
221 debounce(ats_pressed, system_data_->hardware_data_.ats_pressed_, ats_change_counter_);
222}
223
224inline void DigitalReceiver::read_watchdog_ready() {
225 bool wd_ready = digitalRead(WD_READY);
226 debounce(wd_ready, system_data_->hardware_data_.wd_ready_, wd_ready_change_counter_);
227}
228
229inline void DigitalReceiver::read_rpm() {
230 unsigned long time_interval_rr = (last_wheel_pulse_rr - second_to_last_wheel_pulse_rr);
231 unsigned long time_interval_rl = (last_wheel_pulse_rl - second_to_last_wheel_pulse_rl);
232 if (micros() - last_wheel_pulse_rr > LIMIT_RPM_INTERVAL) {
233 system_data_->hardware_data_.rr_wheel_rpm = 0.0;
234 } else {
235 system_data_->hardware_data_.rr_wheel_rpm =
236 1 / (time_interval_rr * MICRO_TO_SECONDS * PULSES_PER_ROTATION) * SECONDS_IN_MINUTE;
237 }
238 if (micros() - last_wheel_pulse_rl > LIMIT_RPM_INTERVAL) {
239 system_data_->hardware_data_.rl_wheel_rpm = 0.0;
240 } else {
241 system_data_->hardware_data_.rl_wheel_rpm =
242 1 / (time_interval_rl * MICRO_TO_SECONDS * PULSES_PER_ROTATION) * SECONDS_IN_MINUTE;
243 }
244}
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 MAX_MISSION
constexpr int EBS_SENSOR1
constexpr int ASATS
constexpr int ATS
constexpr int AMI
constexpr int SOC_PERCENT_MAX
constexpr int BRAKE_SENSOR
constexpr int SDC_BSPD_STATE_PIN
SystemData system_data
Definition main.cpp:11
int _hydraulic_line_pressure
bool pneumatic_line_pressure_
bool pneumatic_line_pressure_2_
bool pneumatic_line_pressure_1_
The whole model of the system: holds all the data necessary.
Mission mission_
FailureDetection failure_detection_
HardwareData hardware_data_
Mission
Definition structure.hpp:10
#define ASMS_IN_PIN
#define PULSES_PER_ROTATION
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:58
void insert_value_queue(const int value, std::deque< int > &queue)
Definition utils.hpp:6
int average_queue(const std::deque< int > &queue)
Definition utils.hpp:14