35 : digital_data_(digital_data), mission_(mission) {
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;
63 void read_pneumatic_line();
75 void read_asms_switch();
81 void read_aats_state();
85 read_pneumatic_line();
91inline void DigitalReceiver::read_pneumatic_line() {
97 bool temp_res = pneumatic2;
100 pneumatic_change_counter_ =
104 pneumatic_change_counter_ = 0;
108inline void DigitalReceiver::read_mission() {
118 mission_change_counter_ = (temp_res == *mission_) && (temp_res == last_tried_mission_)
120 : mission_change_counter_ + 1;
121 this->last_tried_mission_ = temp_res;
123 *mission_ = temp_res;
124 mission_change_counter_ = 0;
128inline void DigitalReceiver::read_asms_switch() {
132 asms_change_counter_ = temp_res == digital_data_->
asms_on_ ? 0 : asms_change_counter_ + 1;
135 asms_change_counter_ = 0;
139inline void DigitalReceiver::read_aats_state() {
143 aats_change_counter_ = is_sdc_closed == digital_data_->
sdc_open_ ? 0 : aats_change_counter_ + 1;
145 digital_data_->
sdc_open_ = is_sdc_closed;
146 aats_change_counter_ = 0;
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
bool pneumatic_line_pressure_
bool pneumatic_line_pressure_2_
#define SENSOR_PRESSURE_2_PIN
#define SENSOR_PRESSURE_1_PIN