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
37 DigitalReceiver(HardwareData *digital_data, Mission *mission)
38 : hardware_data_(digital_data), mission_(mission) {
39 pinMode(SDC_BSPD_STATE_PIN, INPUT);
40 pinMode(AMI, INPUT);
41 pinMode(ASMS_IN_PIN, INPUT);
42 pinMode(EBS_SENSOR2, INPUT);
43 pinMode(EBS_SENSOR1, INPUT);
44
45 pinMode(RL_WSS, INPUT);
46 pinMode(RR_WSS, INPUT);
47 pinMode(BRAKE_SENSOR, INPUT);
48 pinMode(SOC, INPUT);
49 pinMode(ATS, INPUT);
50 pinMode(ASATS, INPUT);
51 pinMode(WD_READY, INPUT);
52 pinMode(WD_SDC_RELAY, INPUT);
53
54 attachInterrupt(
55 digitalPinToInterrupt(RR_WSS),
56 []() {
58 last_wheel_pulse_rr = micros();
59 },
60 RISING);
61 attachInterrupt(
62 digitalPinToInterrupt(RL_WSS),
63 []() {
65 last_wheel_pulse_rl = micros();
66 },
67 RISING);
68 }
69
70private:
71 HardwareData *hardware_data_;
72 Mission *mission_;
73
74 std::deque<int> brake_readings;
75 unsigned int asms_change_counter_ = 0;
76 unsigned int aats_change_counter_ = 0;
77 unsigned int sdc_change_counter_ = 0;
78 unsigned int pneumatic_change_counter_ = 0;
79 unsigned int mission_change_counter_ = 0;
80 unsigned int sdc_bspd_change_counter_ = 0;
81 unsigned int ats_change_counter_ = 0;
82 unsigned int wd_ready_change_counter_ = 0;
83 Mission last_tried_mission_ = Mission::MANUAL;
84
89 void read_pneumatic_line();
90
95 void read_mission();
96
101 void read_asms_switch();
106 void read_asats_state();
107
112 void read_wheel_speed_sensors();
113
118 void read_bspd_sdc();
119
124 void read_brake_sensor();
125
129 void read_soc();
130
135 void read_ats();
136
140 void read_watchdog_ready();
141
145 void read_rpm();
146};
147
149 read_pneumatic_line();
150 read_mission();
151 read_asms_switch();
152 read_asats_state();
153 read_soc();
154 read_brake_sensor();
155 read_ats();
156 read_bspd_sdc();
157 read_watchdog_ready();
158 read_rpm();
159}
160
161inline void DigitalReceiver::read_soc() {
162 const int raw_value = analogRead(SOC);
163 int mapped_value = map(raw_value, 0, ADC_MAX_VALUE, 0, SOC_PERCENT_MAX);
164 mapped_value = constrain(mapped_value, 0, SOC_PERCENT_MAX); // constrain to 0-100, just in case
165 hardware_data_->soc_ = static_cast<uint8_t>(mapped_value);
166}
167
168inline void DigitalReceiver::read_bspd_sdc() {
169 bool is_sdc_open = (0 == digitalRead(SDC_BSPD_STATE_PIN)); // low when sdc/bspd open
170 debounce(is_sdc_open, hardware_data_->bspd_sdc_open_, sdc_bspd_change_counter_);
171}
172inline void DigitalReceiver::read_brake_sensor() {
173 int hydraulic_pressure = analogRead(BRAKE_SENSOR);
174 insert_value_queue(hydraulic_pressure, brake_readings);
175 hardware_data_->hydraulic_pressure_ = average_queue(brake_readings);
176}
177inline void DigitalReceiver::read_pneumatic_line() {
178 bool pneumatic1 = digitalRead(EBS_SENSOR2);
179 bool pneumatic2 = digitalRead(EBS_SENSOR1);
180
181 hardware_data_->pneumatic_line_pressure_1_ = pneumatic1;
182 hardware_data_->pneumatic_line_pressure_2_ = pneumatic2;
183 bool latest_pneumatic_pressure = pneumatic2 && pneumatic1;
184
185 debounce(latest_pneumatic_pressure, hardware_data_->pneumatic_line_pressure_,
186 pneumatic_change_counter_);
187}
188
189inline void DigitalReceiver::read_mission() {
190 const int raw_value = analogRead(AMI);
191 int mapped_value = map(constrain(raw_value, 0, ADC_MAX_VALUE), 0, ADC_MAX_VALUE, 0, MAX_MISSION); // constrain just in case
192 Mission latest_mission = static_cast<Mission>(mapped_value);
193
194 if ((latest_mission == *mission_) && (latest_mission == last_tried_mission_)) {
195 mission_change_counter_ = 0;
196 } else {
197 mission_change_counter_++;
198 }
199 this->last_tried_mission_ = latest_mission;
200 if (mission_change_counter_ >= CHANGE_COUNTER_LIMIT) {
201 *mission_ = latest_mission;
202 mission_change_counter_ = 0;
203 }
204}
205
206inline void DigitalReceiver::read_asms_switch() {
207 bool latest_asms_status = digitalRead(ASMS_IN_PIN);
208 debounce(latest_asms_status, hardware_data_->asms_on_, asms_change_counter_);
209}
210
211inline void DigitalReceiver::read_asats_state() {
212 bool asats_pressed = digitalRead(ASATS);
213 debounce(asats_pressed, hardware_data_->asats_pressed_, aats_change_counter_);
214}
215
216inline void DigitalReceiver::read_ats() {
217 bool ats_pressed = digitalRead(ATS);
218 debounce(ats_pressed, hardware_data_->ats_pressed_, ats_change_counter_);
219}
220
221inline void DigitalReceiver::read_watchdog_ready() {
222 bool wd_ready = digitalRead(WD_READY);
223 debounce(wd_ready, hardware_data_->wd_ready_, wd_ready_change_counter_);
224}
225
226inline void DigitalReceiver::read_rpm() {
227 unsigned long time_interval_rr = (last_wheel_pulse_rr - second_to_last_wheel_pulse_rr);
228 unsigned long time_interval_rl = (last_wheel_pulse_rl - second_to_last_wheel_pulse_rl);
229 if (micros() - last_wheel_pulse_rr > LIMIT_RPM_INTERVAL) {
230 hardware_data_->rr_wheel_rpm = 0.0;
231 } else {
232 hardware_data_->rr_wheel_rpm =
233 1 / (time_interval_rr * MICRO_TO_SECONDS * PULSES_PER_ROTATION) * SECONDS_IN_MINUTE;
234 }
235 if (micros() - last_wheel_pulse_rl > LIMIT_RPM_INTERVAL) {
236 hardware_data_->rl_wheel_rpm = 0.0;
237 } else {
238 hardware_data_->rl_wheel_rpm =
239 1 / (time_interval_rl * MICRO_TO_SECONDS * PULSES_PER_ROTATION) * SECONDS_IN_MINUTE;
240 }
241}
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
DigitalReceiver(HardwareData *digital_data, Mission *mission)
Constructor for the class, sets pintmodes and buttons.
static uint32_t second_to_last_wheel_pulse_rr
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
bool pneumatic_line_pressure_
bool pneumatic_line_pressure_2_
bool pneumatic_line_pressure_1_
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