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 "digitalSettings.hpp"
11
17public:
18 static double _current_left_wheel_rpm; // Class variable to store the left wheel RPM (non-static)
19 static unsigned long last_wheel_pulse_ts; // Timestamp of the last pulse for RPM calculation
20
24 void digital_reads();
25
29 static void updateLeftWheelRpm();
30
34 DigitalReceiver(DigitalData *digital_data, Mission *mission)
35 : digital_data_(digital_data), mission_(mission) {
36 pinMode(SDC_STATE_PIN, INPUT);
37 pinMode(MISSION_ACCELERATION_PIN, INPUT);
38 pinMode(MISSION_AUTOCROSS_PIN, INPUT);
39 pinMode(MISSION_EBSTEST_PIN, INPUT);
40 pinMode(MISSION_INSPECTION_PIN, INPUT);
41 pinMode(MISSION_MANUAL_PIN, INPUT);
42 pinMode(MISSION_SKIDPAD_PIN, INPUT);
43 pinMode(MISSION_TRACKDRIVE_PIN, INPUT);
44 pinMode(ASMS_IN_PIN, INPUT);
45 pinMode(SENSOR_PRESSURE_1_PIN, INPUT);
46 // pinMode(SENSOR_PRESSURE_2_PIN, INPUT);
47 }
48
49private:
50 DigitalData *digital_data_;
51 Mission *mission_;
52
53 unsigned int asms_change_counter_ = 0;
54 unsigned int aats_change_counter_ = 0;
55 unsigned int pneumatic_change_counter_ = 0;
56 unsigned int mission_change_counter_ = 0;
57 Mission last_tried_mission_ = Mission::MANUAL;
58
63 void read_pneumatic_line();
64
69 void read_mission();
70
75 void read_asms_switch();
76
81 void read_aats_state();
82};
83
85 read_pneumatic_line();
86 read_mission();
87 read_asms_switch();
88 read_aats_state();
89}
90
91inline void DigitalReceiver::read_pneumatic_line() {
92 // bool pneumatic1 = digitalRead(SENSOR_PRESSURE_1_PIN);
93 bool pneumatic2 = digitalRead(SENSOR_PRESSURE_2_PIN); // TODO: maybe poorly read
94
95 // digital_data_->pneumatic_line_pressure_1_ = pneumatic1;
96 digital_data_->pneumatic_line_pressure_2_ = pneumatic2;
97 bool temp_res = pneumatic2;
98
99 // Only change the value if it has been different 5 times in a row
100 pneumatic_change_counter_ =
101 temp_res == digital_data_->pneumatic_line_pressure_ ? 0 : pneumatic_change_counter_ + 1;
102 if (pneumatic_change_counter_ >= DIGITAL_INPUT_COUNTER_LIMIT) {
103 digital_data_->pneumatic_line_pressure_ = temp_res; // both need to be True
104 pneumatic_change_counter_ = 0;
105 }
106}
107
108inline void DigitalReceiver::read_mission() {
109 Mission temp_res = static_cast<Mission>(
117
118 mission_change_counter_ = (temp_res == *mission_) && (temp_res == last_tried_mission_)
119 ? 0
120 : mission_change_counter_ + 1;
121 this->last_tried_mission_ = temp_res;
122 if (mission_change_counter_ >= DIGITAL_INPUT_COUNTER_LIMIT) {
123 *mission_ = temp_res;
124 mission_change_counter_ = 0;
125 }
126}
127
128inline void DigitalReceiver::read_asms_switch() {
129 bool temp_res = digitalRead(ASMS_IN_PIN);
130
131 // Only change the value if it has been different 5 times in a row
132 asms_change_counter_ = temp_res == digital_data_->asms_on_ ? 0 : asms_change_counter_ + 1;
133 if (asms_change_counter_ >= DIGITAL_INPUT_COUNTER_LIMIT) {
134 digital_data_->asms_on_ = temp_res;
135 asms_change_counter_ = 0;
136 }
137}
138
139inline void DigitalReceiver::read_aats_state() {
140 // AATS is on if SDC is closed (SDC STATE PIN AS HIGH)
141 bool is_sdc_closed = !digitalRead(SDC_STATE_PIN);
142 // Only change the value if it has been different 5 times in a row
143 aats_change_counter_ = is_sdc_closed == digital_data_->sdc_open_ ? 0 : aats_change_counter_ + 1;
144 if (aats_change_counter_ >= DIGITAL_INPUT_COUNTER_LIMIT) {
145 digital_data_->sdc_open_ = is_sdc_closed; // both need to be True
146 aats_change_counter_ = 0;
147 }
148}
Class responsible for the reading of the digital inputs into the Master teensy.
DigitalReceiver(DigitalData *digital_data, Mission *mission)
Constructor for the class, sets pintmodes and buttons.
static void updateLeftWheelRpm()
callback to update rl wheel rpm
static double _current_left_wheel_rpm
void digital_reads()
read all digital inputs
static unsigned long last_wheel_pulse_ts
constexpr int MISSION_TRACKDRIVE_PIN
constexpr int MISSION_INSPECTION_PIN
constexpr int MISSION_SKIDPAD_PIN
constexpr int MISSION_EBSTEST_PIN
constexpr int DIGITAL_INPUT_COUNTER_LIMIT
constexpr int MISSION_AUTOCROSS_PIN
constexpr int MISSION_MANUAL_PIN
constexpr int MISSION_ACCELERATION_PIN
constexpr auto to_underlying(Enum e) noexcept
Definition enum_utils.hpp:4
bool pneumatic_line_pressure_
bool pneumatic_line_pressure_2_
Mission
Definition structure.hpp:10
@ ACCELERATION
#define ASMS_IN_PIN
#define SENSOR_PRESSURE_2_PIN
#define SENSOR_PRESSURE_1_PIN
#define SDC_STATE_PIN