34 : digitalData(digitalData), mission(mission) {
56 unsigned int asms_change_counter = 0;
57 unsigned int aats_change_counter = 0;
58 unsigned int pneumatic_change_counter = 0;
59 unsigned int mission_change_counter = 0;
66 void readPneumaticLine();
78 void readAsmsSwitch();
115inline void DigitalReceiver::readPneumaticLine() {
118 if (pneumatic1 == 0) {
121 if (pneumatic2 == 0) {
124 bool temp_res = pneumatic1 && pneumatic2;
127 pneumatic_change_counter = temp_res == digitalData->
pneumatic_line_pressure ? 0 : pneumatic_change_counter + 1;
130 pneumatic_change_counter = 0;
136inline void DigitalReceiver::readMission() {
147 mission_change_counter = (temp_res == *mission) &&
148 (temp_res == last_tried_mission_) ?
149 0 : mission_change_counter + 1;
150 this->last_tried_mission_ = temp_res;
153 mission_change_counter = 0;
158inline void DigitalReceiver::readAsmsSwitch() {
162 asms_change_counter = temp_res == digitalData->
asms_on ? 0 : asms_change_counter + 1;
164 digitalData->
asms_on = temp_res;
165 asms_change_counter = 0;
169inline void DigitalReceiver::readAatsState() {
173 aats_change_counter = temp_res == digitalData->
sdcState_OPEN ? 0 : aats_change_counter + 1;
176 aats_change_counter = 0;
181inline void DigitalReceiver::readWatchdog() {
Class responsible for the reading of the digital inputs into the Master teensy.
static void updateLeftWheelRpm()
callback to update rl wheel rpm
static double _current_left_wheel_rpm
DigitalReceiver(DigitalData *digitalData, Mission *mission)
Constructor for the class, sets pintmodes and buttons.
void digitalReads()
read all digital inputs
static unsigned long last_wheel_pulse_ts
void reset()
Resets the timer to the current time.
#define MISSION_EBSTEST_PIN
#define SENSOR_PRESSURE_2_PIN
#define MISSION_ACCELERATION_PIN
#define DIGITAL_INPUT_COUNTER_LIMIT
#define SDC_LOGIC_WATCHDOG_OUT_PIN
#define MISSION_MANUAL_PIN
#define MISSION_SKIDPAD_PIN
#define MISSION_AUTOCROSS_PIN
#define SENSOR_PRESSURE_1_PIN
#define MISSION_TRACKDRIVE_PIN
#define MISSION_INSPECTION_PIN
#define SDC_LOGIC_WATCHDOG_IN_PIN
bool pneumatic_line_pressure