16 unsigned long timer_ = 0;
23 if (millis() - timer_ > 10000) {
27 return true & tsms_activated;
31 if (millis() - timer_ > 50) {
47 unsigned long tsms_timer_ = 0;
82 pinMode(
ASATS, INPUT);
85 digitalPinToInterrupt(
RR_WSS),
92 digitalPinToInterrupt(
RL_WSS),
103 std::deque<int> brake_readings;
104 unsigned int asms_change_counter_ = 0;
105 unsigned int aats_change_counter_ = 0;
106 unsigned int sdc_change_counter_ = 0;
107 unsigned int pneumatic_change_counter_ = 0;
108 unsigned int mission_change_counter_ = 0;
109 unsigned int sdc_tsms_change_counter_ = 0;
110 unsigned int ats_change_counter_ = 0;
111 unsigned int wd_ready_change_counter_ = 0;
118 void read_pneumatic_line();
130 void read_asms_switch();
135 void read_asats_state();
141 void read_wheel_speed_sensors();
147 void read_tsms_sdc();
153 void read_brake_sensor();
169 void read_watchdog_ready();
178 read_pneumatic_line();
186 read_watchdog_ready();
190inline void DigitalReceiver::read_soc() {
191 const int raw_value = analogRead(
SOC);
197inline void DigitalReceiver::read_tsms_sdc() {
201 this->sdc_tsms_change_counter_, 1000);
205inline void DigitalReceiver::read_brake_sensor() {
210inline void DigitalReceiver::read_pneumatic_line() {
216 bool latest_pneumatic_pressure = pneumatic1 && pneumatic2;
224 pneumatic_change_counter_);
227inline void DigitalReceiver::read_mission() {
228 int raw_value = analogRead(
AMI);
229 int contrained_value = constrain(raw_value, 0, 600);
233 if (contrained_value < 60) {
235 }
else if (contrained_value < 220) {
237 }
else if (contrained_value < 330) {
239 }
else if (contrained_value < 420) {
241 }
else if (contrained_value < 475) {
243 }
else if (contrained_value < 540) {
250 if ((latest_mission == system_data_->
mission_) && (latest_mission == last_tried_mission_)) {
251 mission_change_counter_ = 0;
253 mission_change_counter_++;
255 this->last_tried_mission_ = latest_mission;
257 system_data_->
mission_ = latest_mission;
258 mission_change_counter_ = 0;
262inline void DigitalReceiver::read_asms_switch() {
263 bool latest_asms_status = digitalRead(
ASMS_IN_PIN);
267inline void DigitalReceiver::read_asats_state() {
272inline void DigitalReceiver::read_ats() {
273 bool ats_pressed = digitalRead(
ATS);
278inline void DigitalReceiver::read_watchdog_ready() {
279 bool wd_ready = digitalRead(
WD_READY);
283inline 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 EBS_SENSOR1
constexpr int SOC_PERCENT_MAX
constexpr int SDC_TSMS_STATE_PIN
constexpr int BRAKE_SENSOR
int _hydraulic_line_pressure
bool pneumatic_line_pressure_
bool pneumatic_line_pressure_2_
bool pneumatic_line_pressure_1_
bool activate_shit(bool tsms_activated)
The whole model of the system: holds all the data necessary.
HardwareData hardware_data_
#define PULSES_PER_ROTATION
void insert_value_queue(const int value, std::deque< int > &queue, const unsigned int max_queue_size)
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)
int average_queue(const std::deque< int > &queue)