38 : hardware_data_(digital_data), mission_(mission) {
50 pinMode(
ASATS, INPUT);
55 digitalPinToInterrupt(
RR_WSS),
62 digitalPinToInterrupt(
RL_WSS),
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;
89 void read_pneumatic_line();
101 void read_asms_switch();
106 void read_asats_state();
112 void read_wheel_speed_sensors();
118 void read_bspd_sdc();
124 void read_brake_sensor();
140 void read_watchdog_ready();
149 read_pneumatic_line();
157 read_watchdog_ready();
161inline void DigitalReceiver::read_soc() {
162 const int raw_value = analogRead(
SOC);
165 hardware_data_->
soc_ =
static_cast<uint8_t
>(mapped_value);
168inline void DigitalReceiver::read_bspd_sdc() {
172inline void DigitalReceiver::read_brake_sensor() {
177inline void DigitalReceiver::read_pneumatic_line() {
183 bool latest_pneumatic_pressure = pneumatic2 && pneumatic1;
186 pneumatic_change_counter_);
189inline void DigitalReceiver::read_mission() {
190 const int raw_value = analogRead(
AMI);
194 if ((latest_mission == *mission_) && (latest_mission == last_tried_mission_)) {
195 mission_change_counter_ = 0;
197 mission_change_counter_++;
199 this->last_tried_mission_ = latest_mission;
201 *mission_ = latest_mission;
202 mission_change_counter_ = 0;
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_);
211inline void DigitalReceiver::read_asats_state() {
212 bool asats_pressed = digitalRead(
ASATS);
216inline void DigitalReceiver::read_ats() {
217 bool ats_pressed = digitalRead(
ATS);
221inline void DigitalReceiver::read_watchdog_ready() {
222 bool wd_ready = digitalRead(
WD_READY);
226inline 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
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 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
bool pneumatic_line_pressure_
bool pneumatic_line_pressure_2_
bool pneumatic_line_pressure_1_
#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)