49 pinMode(
ASATS, INPUT);
54 digitalPinToInterrupt(
RR_WSS),
61 digitalPinToInterrupt(
RL_WSS),
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;
87 void read_pneumatic_line();
99 void read_asms_switch();
104 void read_asats_state();
110 void read_wheel_speed_sensors();
116 void read_bspd_sdc();
122 void read_brake_sensor();
138 void read_watchdog_ready();
147 read_pneumatic_line();
155 read_watchdog_ready();
159inline void DigitalReceiver::read_soc() {
160 const int raw_value = analogRead(
SOC);
166inline void DigitalReceiver::read_bspd_sdc() {
170inline void DigitalReceiver::read_brake_sensor() {
175inline void DigitalReceiver::read_pneumatic_line() {
181 bool latest_pneumatic_pressure = pneumatic1 && pneumatic2;
184 pneumatic_change_counter_);
187inline void DigitalReceiver::read_mission() {
188 int raw_value = analogRead(
AMI);
192 if ((latest_mission == system_data_->
mission_) && (latest_mission == last_tried_mission_)) {
193 mission_change_counter_ = 0;
195 mission_change_counter_++;
197 this->last_tried_mission_ = latest_mission;
199 system_data_->
mission_ = latest_mission;
200 mission_change_counter_ = 0;
205inline void DigitalReceiver::read_asms_switch() {
206 bool latest_asms_status = digitalRead(
ASMS_IN_PIN);
210inline void DigitalReceiver::read_asats_state() {
211 bool asats_pressed = !digitalRead(
ASATS);
218inline void DigitalReceiver::read_ats() {
219 bool ats_pressed = digitalRead(
ATS);
224inline void DigitalReceiver::read_watchdog_ready() {
225 bool wd_ready = digitalRead(
WD_READY);
229inline void DigitalReceiver::read_rpm() {
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 LIMIT_RPM_INTERVAL
constexpr int SECONDS_IN_MINUTE
constexpr int WD_SDC_RELAY
constexpr int CHANGE_COUNTER_LIMIT
constexpr int EBS_SENSOR2
constexpr int MAX_MISSION
constexpr int EBS_SENSOR1
constexpr int SOC_PERCENT_MAX
constexpr int BRAKE_SENSOR
constexpr int SDC_BSPD_STATE_PIN
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.
FailureDetection failure_detection_
HardwareData hardware_data_
#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)
void insert_value_queue(const int value, std::deque< int > &queue)
int average_queue(const std::deque< int > &queue)