diff --git a/include/VCF_Constants.h b/include/VCF_Constants.h index a25ab7a..1ee9c2f 100644 --- a/include/VCF_Constants.h +++ b/include/VCF_Constants.h @@ -8,7 +8,7 @@ namespace VCFInterfaceConstants { /* Teensy 4.1 GPIO pins */ /* Not on Schematic - // constexpr int BTN_DIM_READ = 28; + // constexpr int BTN_DIM_READ = 28; // Currently used for steering system recalibration TODO: change pin // constexpr int BTN_PRESET_READ = 31; // constexpr int BTN_MODE_READ = 27; // USED TO BE 26. */ @@ -93,9 +93,9 @@ namespace VCFInterfaceConstants { constexpr float FL_LOADCELL_OFFSET = 0.0; constexpr float FR_LOADCELL_SCALE = 1.0; //Values constexpr float FR_LOADCELL_OFFSET = 0.0; - + constexpr float FR_SUS_POT_SCALE = 0.01396; // Calibrated for mm between mounting bolts - constexpr float FR_SUS_POT_OFFSET = 150.8; // Can change offset once car is on ground to center at zero + constexpr float FR_SUS_POT_OFFSET = 150.8; constexpr float FL_SUS_POT_SCALE = 0.01396; // Same as FR constexpr float FL_SUS_POT_OFFSET = 150.8; @@ -125,7 +125,7 @@ namespace VCFSystemConstants { constexpr uint32_t ACCEL_MAX_SENSOR_PEDAL_2 = 4000; constexpr float ACCEL_DEADZONE_MARGIN = 0.03f; constexpr float ACCEL_MECHANICAL_ACTIVATION_PERCENTAGE = 0.05f; - + constexpr uint32_t BRAKE_1_MIN_ADDR = 16; constexpr uint32_t BRAKE_2_MIN_ADDR = 20; constexpr uint32_t BRAKE_1_MAX_ADDR = 24; @@ -137,6 +137,30 @@ namespace VCFSystemConstants { constexpr uint32_t BRAKE_MAX_SENSOR_PEDAL_2 = 4000; constexpr float BRAKE_DEADZONE_MARGIN = 0.04f; constexpr float BRAKE_MECHANICAL_ACTIVATION_PERCENTAGE = 0.5f; + + // Steering System Constants + constexpr uint32_t MIN_STEERING_SIGNAL_ANALOG_ADDR = 56; //Raw ADC value from analog sensor at minimum (left) steering angle (calibration) + constexpr uint32_t MAX_STEERING_SIGNAL_ANALOG_ADDR = 60; //Raw ADC value from analog sensor at maximum (right) steering angle + constexpr uint32_t MIN_STEERING_SIGNAL_DIGITAL_ADDR = 32; //Raw ADC value from digital sensor at minimum (left) steering angle + constexpr uint32_t MAX_STEERING_SIGNAL_DIGITAL_ADDR = 36; //Raw ADC value from digital sensor at maximum (right) steering angle + + constexpr int32_t ANALOG_MIN_WITH_MARGINS_ADDR = 40; + constexpr int32_t ANALOG_MAX_WITH_MARGINS_ADDR = 44; + constexpr int32_t DIGITAL_MIN_WITH_MARGINS_ADDR = 48; + constexpr int32_t DIGITAL_MAX_WITH_MARGINS_ADDR = 52; + + + // implausibility values + constexpr float ANALOG_TOLERANCE = 0.05f; //+- 0.5% error (analog sensor tolerance according to datasheet) + constexpr float DIGITAL_TOLERANCE = 0.05f; // +- 0.2 degrees error + constexpr float ERROR_BETWEEN_SENSORS_TOLERANCE = 5.0f; + + // rate of angle change + constexpr float MAX_DTHETA_THRESHOLD = 50.0f; //maximum change in angle since last reading to consider the reading valid + + // degrees per bit + constexpr float DEG_PER_COUNT_DIGITAL = 360.0f / 16384.0f; + constexpr float DEG_PER_COUNT_ANALOG = 360.0f / 3686.4f; } // software configuration constants @@ -150,40 +174,47 @@ namespace VCFTaskConstants { constexpr unsigned long CAN_SEND_PRIORITY = 10; constexpr unsigned long CAN_SEND_PERIOD = 2000; // 2 000 us = 500 Hz - constexpr unsigned long PEDALS_PRIORITY = 5; - constexpr unsigned long PEDALS_SEND_PERIOD = 4000; // 4 000 us = 250 Hz - constexpr unsigned long PEDALS_SAMPLE_PERIOD = 500; // 500 us = 2 kHz - - constexpr unsigned long PEDALS_RECALIBRATION_PRIORITY = 150; - constexpr unsigned long PEDALS_RECALIBRATION_PERIOD = 100000; // 100 000 us = 10 Hz - + constexpr unsigned long BUZZER_PRIORITY = 20; constexpr unsigned long BUZZER_WRITE_PERIOD = 100000; // 100 000 us = 10 Hz - + constexpr unsigned long DASH_SAMPLE_PRIORITY = 21; constexpr unsigned long DASH_SAMPLE_PERIOD = 100000; // 100 000 us = 10 Hz - + constexpr unsigned long DASH_SEND_PRIORITY = 7; constexpr unsigned long DASH_SEND_PERIOD = 100000; // 100 000 us = 10 Hz - + constexpr unsigned long DEBUG_PRIORITY = 100; constexpr unsigned long DEBUG_PERIOD = 10000; // 10 000 us = 2 Hz - + constexpr unsigned long NEOPIXEL_UPDATE_PRIORITY = 90; constexpr unsigned long NEOPIXEL_UPDATE_PERIOD = 100000; // 100 000 us = 10 Hz - - constexpr unsigned long STEERING_SEND_PRIORITY = 25; - constexpr unsigned long STEERING_SEND_PERIOD = 4000; // 4 000 us = 250 Hz - + + constexpr unsigned long LOADCELL_SAMPLE_PRIORITY = 24; constexpr unsigned long LOADCELL_SAMPLE_PERIOD = 250; // 250 us = 4 kHz - + constexpr unsigned long LOADCELL_SEND_PRIORITY = 25; + constexpr unsigned long LOADCELL_SEND_PERIOD = 4000; // 4 000 us = 250 Hz + constexpr unsigned long ETHERNET_SEND_PRIORITY = 20; constexpr unsigned long ETHERNET_SEND_PERIOD = 100000; // 100 000 us = 10Hz + + constexpr unsigned long PEDALS_PRIORITY = 5; + constexpr unsigned long PEDALS_SEND_PERIOD = 4000; // 4 000 us = 250 Hz + constexpr unsigned long PEDALS_SAMPLE_PERIOD = 500; // 500 us = 2 kHz + + constexpr unsigned long PEDALS_RECALIBRATION_PRIORITY = 150; + constexpr unsigned long PEDALS_RECALIBRATION_PERIOD = 100000; // 100 000 us = 10 Hz - constexpr unsigned long LOADCELL_SEND_PRIORITY = 25; - constexpr unsigned long LOADCELL_SEND_PERIOD = 4000; // 4 000 us = 250 Hz + constexpr unsigned long STEERING_SEND_PRIORITY = 25; + constexpr unsigned long STEERING_SEND_PERIOD = 4000; // 4 000 us = 250 Hz + constexpr unsigned long STEERING_SAMPLE_PERIOD = 1000; // 2000 us = 500 Hz + constexpr unsigned long STEERING_SAMPLE_PRIORITY = 10; + + constexpr unsigned long STEERING_RECALIBRATION_PRIORITY = 150; + constexpr unsigned long STEERING_RECALIBRATION_PERIOD = 100000; + // IIR filter alphas constexpr float LOADCELL_IIR_FILTER_ALPHA = 0.01f; @@ -191,4 +222,4 @@ namespace VCFTaskConstants { constexpr unsigned long WATCHDOG_KICK_PERIOD = 10000; // 10 000 us = 100 Hz } -#endif /* VCF_CONSTANTS */ \ No newline at end of file +#endif /* VCF_CONSTANTS */ diff --git a/include/VCF_Tasks.h b/include/VCF_Tasks.h index 6228bad..5803ec4 100644 --- a/include/VCF_Tasks.h +++ b/include/VCF_Tasks.h @@ -34,6 +34,7 @@ #include "VCFCANInterfaceImpl.h" #include "VCFEthernetInterface.h" #include "PedalsSystem.h" +#include "SteeringSystem.h" #include "ht_sched.hpp" #include "ht_task.hpp" #include "BuzzerController.h" @@ -42,6 +43,7 @@ #include "WatchdogSystem.h" #include "ADCInterface.h" #include "CANInterface.h" +#include "SteeringEncoderInterface.h" /** * The read_adc0 task will command the ADCInterface to sample, convert, and store @@ -60,6 +62,7 @@ HT_TASK::TaskResponse run_kick_watchdog(const unsigned long& sysMicros, const HT HT_TASK::TaskResponse update_pedals_calibration_task(const unsigned long& sysMicros, const HT_TASK::TaskInfo& taskInfo); +HT_TASK::TaskResponse update_steering_calibration_task(const unsigned long& sysMicros, const HT_TASK::TaskInfo& taskInfo); /** * The buzzer_control task will control the buzzer control pin. This function * relies on the buzzer_control pin definition in VCF_Constants.h; @@ -77,20 +80,9 @@ HT_TASK::TaskResponse run_buzzer_control_task(const unsigned long& sysMicros, co HT_TASK::TaskResponse init_handle_send_vcf_ethernet_data(const unsigned long& sysMicros, const HT_TASK::TaskInfo& taskInfo); HT_TASK::TaskResponse run_handle_send_vcf_ethernet_data(const unsigned long& sysMicros, const HT_TASK::TaskInfo& taskInfo); -/** - * The handle_receive_VCR_ethernet_data task will receive a protobuf message - * from VCR. This function relies on the VCF (receiving) socket and vcf_data - * defined in VCFGlobals.h, and Ethernet constants defined in - * EthernetAddressDefs.h. - * - */ -HT_TASK::TaskResponse init_handle_receive_vcr_ethernet_data(const unsigned long& sysMicros, const HT_TASK::TaskInfo& taskInfo); -HT_TASK::TaskResponse run_handle_receive_vcr_ethernet_data(const unsigned long& sysMicros, const HT_TASK::TaskInfo& taskInfo); - // this task attempts to send any data that is enqueued at 250hz. this will be the max rate that you can send over the CAN bus. // you dont have to enqeue at this rate, but this allows us to have 2 layers of rate limiting on CAN sending HT_TASK::TaskResponse handle_CAN_send(const unsigned long &sysMicros, const HT_TASK::TaskInfo &taskInfo); // NOLINT (capitalization of CAN) -HT_TASK::TaskResponse handle_CAN_receive(const unsigned long& sysMicros, const HT_TASK::TaskInfo& taskInfo); // NOLINT (capitalization of CAN) HT_TASK::TaskResponse run_dash_GPIOs_task(const unsigned long& sys_micros, const HT_TASK::TaskInfo& task_info); // NOLINT (capitalization of GPIOs) HT_TASK::TaskResponse send_dash_data(const unsigned long &sysMicros, const HT_TASK::TaskInfo &taskInfo); diff --git a/lib/interfaces/include/NeopixelController.h b/lib/interfaces/include/NeopixelController.h index 916f821..ffcb3f9 100644 --- a/lib/interfaces/include/NeopixelController.h +++ b/lib/interfaces/include/NeopixelController.h @@ -18,7 +18,6 @@ #include "etl/singleton.h" #include "VCFCANInterfaceImpl.h" - struct MinCellMonitoringThresholds_s { float max_level = 3.85; diff --git a/lib/interfaces/include/SteeringEncoderInterface.h b/lib/interfaces/include/SteeringEncoderInterface.h index 8c2733d..f65ef2b 100644 --- a/lib/interfaces/include/SteeringEncoderInterface.h +++ b/lib/interfaces/include/SteeringEncoderInterface.h @@ -1,32 +1,6 @@ #ifndef STEERING_ENCODER_INTERFACE_H #define STEERING_ENCODER_INTERFACE_H - -#include - -enum class SteeringEncoderStatus_e -{ - NOMINAL = 0, - ERROR = 1, -}; - -/// @brief Error and warning flags from the encoder. -/// @note Specific encoders may populate only a subset of these flags. -struct EncoderErrorFlags_s -{ - bool dataInvalid = false; - bool operatingLimit = false; - bool noData = false; -}; - -/// @brief Complete steering angle measurement with status and error flags. -/// @note This struct is transmitted across the CAN bus to other vehicle systems. -struct SteeringEncoderReading_s -{ - float angle = 0.0f; - int rawValue = 0; - SteeringEncoderStatus_e status = SteeringEncoderStatus_e::NOMINAL; - EncoderErrorFlags_s errors; -}; +#include "SharedFirmwareTypes.h" class SteeringEncoderInterface { @@ -40,4 +14,4 @@ class SteeringEncoderInterface virtual SteeringEncoderReading_s getLastReading() = 0; }; -#endif /* STEERING_ENCODER_INTERFACE_H */ \ No newline at end of file +#endif /* STEERING_ENCODER_INTERFACE_H */ diff --git a/lib/interfaces/include/VCFEthernetInterface.h b/lib/interfaces/include/VCFEthernetInterface.h index 3bb32ce..2bbe727 100644 --- a/lib/interfaces/include/VCFEthernetInterface.h +++ b/lib/interfaces/include/VCFEthernetInterface.h @@ -7,6 +7,7 @@ #include "ADCInterface.h" #include "DashboardInterface.h" #include "PedalsSystem.h" +#include "SteeringSystem.h" namespace VCFEthernetInterface { @@ -17,7 +18,7 @@ namespace VCFEthernetInterface * @return A populated instance of the outgoing protoc struct. */ // hytech_msgs_VCFData_s make_vcf_data_msg(VCFData_s &shared_state); - hytech_msgs_VCFData_s make_vcf_data_msg(ADCInterface &ADCInterfaceInstance, DashboardInterface &dashInstance, PedalsSystem &pedalsInstance); + hytech_msgs_VCFData_s make_vcf_data_msg(ADCInterface &ADCInterfaceInstance, DashboardInterface &dashInstance, PedalsSystem &pedalsInstance, SteeringSystem &steeringInstance); /** * Function to take a populated protoc struct from VCR and update the VCF state. This is ONLY critical diff --git a/lib/interfaces/include/VCRInterface.h b/lib/interfaces/include/VCRInterface.h index 9a97f2d..ed58411 100644 --- a/lib/interfaces/include/VCRInterface.h +++ b/lib/interfaces/include/VCRInterface.h @@ -8,7 +8,6 @@ #include "hytech.h" #include "FlexCAN_T4.h" - struct InverterErrorFlags_s{ veh_vec error; @@ -16,7 +15,6 @@ struct InverterErrorFlags_s{ }; struct InverterBusVolts_s{ - veh_vec voltage; }; @@ -26,11 +24,15 @@ class VCRInterface bool is_in_pedals_calibration_state() {return _is_in_pedals_calibration_state;} TorqueLimit_e get_torque_limit_mode() {return _torque_limit;} + + bool is_in_steering_calibration_state() {return _is_in_steering_calibration_state;} //steering and pedals calibration states are the same, so we can use the same variable for both void receive_dash_control_data(const CAN_message_t &can_msg); void disable_calibration_state() {_is_in_pedals_calibration_state = false;} + void disable_steering_calibration_state() {_is_in_steering_calibration_state = false;} + void receive_car_states_data(const CAN_message_t &can_msg); void receive_inverter_status_1(const CAN_message_t &can_msg); @@ -45,22 +47,22 @@ class VCRInterface VehicleState_e get_vehicle_state() {return _vehicle_state_value;} DrivetrainState_e get_drivetrain_state() {return _drivetrain_state_value;} InverterBusVolts_s get_dc_bus_voltage() {return _bus_voltages;} - bool get_db_in_ctrl() {return _is_db_in_ctrl;} bool get_inverter_error(); private: bool _is_in_pedals_calibration_state = false; + bool _is_in_steering_calibration_state = false; VehicleState_e _vehicle_state_value; DrivetrainState_e _drivetrain_state_value; bool _is_db_in_ctrl; TorqueLimit_e _torque_limit = TorqueLimit_e::TCMUX_LOW_TORQUE; InverterErrorFlags_s _inv_error_status; //creates object that reflects the inverter error status...the object //holds the error flags for each inverter, the getter above returns True if there's an error in any of the 4 - InverterBusVolts_s _bus_voltages; + InverterBusVolts_s _bus_voltages; }; using VCRInterfaceInstance = etl::singleton; -#endif /* VCR_INTERFACE_H */ \ No newline at end of file +#endif /* VCR_INTERFACE_H */ diff --git a/lib/interfaces/src/ACUInterface.cpp b/lib/interfaces/src/ACUInterface.cpp index 94316d8..2f29225 100644 --- a/lib/interfaces/src/ACUInterface.cpp +++ b/lib/interfaces/src/ACUInterface.cpp @@ -4,6 +4,5 @@ void ACUInterface::receive_ACU_voltages(const CAN_message_t &can_msg) { BMS_VOLTAGES_t unpacked_msg; Unpack_BMS_VOLTAGES_hytech(&unpacked_msg, can_msg.buf, can_msg.len); // NOLINT (implicitly decay pointer) - _min_cell_voltage = HYTECH_min_cell_voltage_ro_fromS(unpacked_msg.min_cell_voltage_ro); } diff --git a/lib/interfaces/src/ADCInterface.cpp b/lib/interfaces/src/ADCInterface.cpp index 16509e2..51cb744 100644 --- a/lib/interfaces/src/ADCInterface.cpp +++ b/lib/interfaces/src/ADCInterface.cpp @@ -172,4 +172,4 @@ AnalogConversion_s ADCInterface::get_brake_pressure_front() { AnalogConversion_s ADCInterface::get_brake_pressure_rear() { return _adc1.data.conversions[_adc_parameters.channels.brake_pressure_rear_channel]; -} \ No newline at end of file +} diff --git a/lib/interfaces/src/NeopixelController.cpp b/lib/interfaces/src/NeopixelController.cpp index 9723e01..eb0e203 100644 --- a/lib/interfaces/src/NeopixelController.cpp +++ b/lib/interfaces/src/NeopixelController.cpp @@ -36,7 +36,7 @@ void NeopixelController::set_neopixel(uint16_t id, uint32_t c) void NeopixelController::refresh_neopixels(const PedalsSystemData_s &pedals_data, CANInterfaces &interfaces) { // If we are in pedals recalibration state, LIGHT UP DASHBOARD ALL RED. - if (interfaces.vcr_interface.is_in_pedals_calibration_state()) { + if (interfaces.vcr_interface.is_in_pedals_calibration_state() || interfaces.vcr_interface.is_in_steering_calibration_state()) { set_neopixel_color(LED_ID_e::BRAKE, LED_color_e::RED); set_neopixel_color(LED_ID_e::TORQUE_MODE, LED_color_e::RED); set_neopixel_color(LED_ID_e::LATCH, LED_color_e::RED); @@ -136,10 +136,11 @@ void NeopixelController::refresh_neopixels(const PedalsSystemData_s &pedals_data interfaces.vcr_interface.get_dc_bus_voltage().voltage.RL > _hv_threshold_voltage || interfaces.vcr_interface.get_dc_bus_voltage().voltage.RR > _hv_threshold_voltage; + constexpr float glv_critical_voltage = 22.0f; /* SHUTDOWN LEDS */ - set_neopixel_color(LED_ID_e::LATCH, hv_present ? LED_color_e::PURPLE : LED_color_e::GREEN); // Unused for now + set_neopixel_color(LED_ID_e::LATCH, hv_present ? LED_color_e::PURPLE : LED_color_e::GREEN); set_neopixel_color(LED_ID_e::IMD, interfaces.dash_interface.imd_ok ? LED_color_e::GREEN : LED_color_e::RED); set_neopixel_color(LED_ID_e::BMS, interfaces.dash_interface.bms_ok ? LED_color_e::GREEN : LED_color_e::RED); set_neopixel_color(LED_ID_e::SHUTDOWN, LED_color_e::OFF); // Unused for now diff --git a/lib/interfaces/src/VCFEthernetInterface.cpp b/lib/interfaces/src/VCFEthernetInterface.cpp index fb8105e..6edb648 100644 --- a/lib/interfaces/src/VCFEthernetInterface.cpp +++ b/lib/interfaces/src/VCFEthernetInterface.cpp @@ -4,7 +4,7 @@ #include "hytech_msgs_version.h" #include "device_fw_version.h" -hytech_msgs_VCFData_s VCFEthernetInterface::make_vcf_data_msg(ADCInterface &ADCInterfaceInstance, DashboardInterface &dashInstance, PedalsSystem &pedalsInstance) +hytech_msgs_VCFData_s VCFEthernetInterface::make_vcf_data_msg(ADCInterface &ADCInterfaceInstance, DashboardInterface &dashInstance, PedalsSystem &pedalsInstance, SteeringSystem &steeringInstance) { hytech_msgs_VCFData_s out; @@ -14,6 +14,7 @@ hytech_msgs_VCFData_s VCFEthernetInterface::make_vcf_data_msg(ADCInterface &ADCI out.has_front_suspot_data = true; out.has_pedals_system_data = true; out.has_steering_data = true; + out.has_steering_system_data = true; out.has_vcf_ethernet_link_data = true; out.has_vcf_shutdown_data = true; out.has_brake_pressure_data = true; @@ -30,6 +31,22 @@ hytech_msgs_VCFData_s VCFEthernetInterface::make_vcf_data_msg(ADCInterface &ADCI out.steering_data.analog_steering_degrees = ADCInterfaceInstance.get_steering_degrees_cw().conversion; out.steering_data.digital_steering_analog = ADCInterfaceInstance.get_steering_degrees_ccw().conversion; + //SteeringSystem + out.steering_system_data.analog_raw = steeringInstance.get_steering_system_data().analog_raw; + out.steering_system_data.digital_raw = steeringInstance.get_steering_system_data().digital_raw; + out.steering_system_data.analog_steering_angle = steeringInstance.get_steering_system_data().analog_steering_angle; + out.steering_system_data.digital_steering_angle = steeringInstance.get_steering_system_data().digital_steering_angle; + out.steering_system_data.output_steering_angle = steeringInstance.get_steering_system_data().output_steering_angle; + out.steering_system_data.analog_steering_velocity_deg_s = steeringInstance.get_steering_system_data().analog_steering_velocity_deg_s; + out.steering_system_data.digital_steering_velocity_deg_s = steeringInstance.get_steering_system_data().digital_steering_velocity_deg_s; + out.steering_system_data.digital_oor_implausibility = steeringInstance.get_steering_system_data().digital_oor_implausibility; + out.steering_system_data.analog_oor_implausibility = steeringInstance.get_steering_system_data().analog_oor_implausibility; + out.steering_system_data.sensor_disagreement_implausibility = steeringInstance.get_steering_system_data().sensor_disagreement_implausibility; + out.steering_system_data.dtheta_exceeded_analog = steeringInstance.get_steering_system_data().dtheta_exceeded_analog; + out.steering_system_data.dtheta_exceeded_digital = steeringInstance.get_steering_system_data().dtheta_exceeded_digital; + out.steering_system_data.both_sensors_fail = steeringInstance.get_steering_system_data().both_sensors_fail; + out.steering_system_data.interface_sensor_error = steeringInstance.get_steering_system_data().interface_sensor_error; + //TODO: MODIFY ETH STRUCT // Dash out.dash_input_state.dim_btn_is_pressed = dashInstance.get_dashboard_outputs().brightness_ctrl_btn_is_pressed; diff --git a/lib/interfaces/src/VCRInterface.cpp b/lib/interfaces/src/VCRInterface.cpp index 9865192..85b80d5 100644 --- a/lib/interfaces/src/VCRInterface.cpp +++ b/lib/interfaces/src/VCRInterface.cpp @@ -10,6 +10,7 @@ void VCRInterface::receive_dash_control_data(const CAN_message_t &can_msg) } _is_in_pedals_calibration_state = unpacked_msg.in_pedal_calibration_state; + _is_in_steering_calibration_state = unpacked_msg.in_steering_calibration_state; if (unpacked_msg.torque_limit_enum_value < ((int) TorqueLimit_e::TCMUX_NUM_TORQUE_LIMITS)) // check for validity { @@ -39,14 +40,13 @@ void VCRInterface::receive_inverter_status_2(const CAN_message_t &can_msg) Unpack_INV2_STATUS_hytech(&unpacked_msg, can_msg.buf, can_msg.len); //NOLINT _inv_error_status.error.FR = unpacked_msg.error; _bus_voltages.voltage.FR = unpacked_msg.dc_bus_voltage; - } void VCRInterface::receive_inverter_status_3(const CAN_message_t &can_msg) { INV3_STATUS_t unpacked_msg; Unpack_INV3_STATUS_hytech(&unpacked_msg, can_msg.buf, can_msg.len); //NOLINT _inv_error_status.error.RL = unpacked_msg.error; - _bus_voltages.voltage.RL = unpacked_msg.dc_bus_voltage; + _bus_voltages.voltage.RL = unpacked_msg.dc_bus_voltage; } void VCRInterface::receive_inverter_status_4(const CAN_message_t &can_msg) { diff --git a/lib/systems/include/SteeringSystem.h b/lib/systems/include/SteeringSystem.h new file mode 100644 index 0000000..e2cf992 --- /dev/null +++ b/lib/systems/include/SteeringSystem.h @@ -0,0 +1,126 @@ +#ifndef STEERING_SYSTEM_H +#define STEERING_SYSTEM_H + +#include +#include + +#include "SharedFirmwareTypes.h" + +struct SteeringParams_s { + // raw ADC input signals + uint32_t min_steering_signal_analog; //Raw ADC value from analog sensor at minimum (left) steering angle (calibration) + uint32_t max_steering_signal_analog; //Raw ADC value from analog sensor at maximum (right) steering angle + uint32_t min_steering_signal_digital; //Raw ADC value from digital sensor at minimum (left) steering angle + uint32_t max_steering_signal_digital; //Raw ADC value from digital sensor at maximum (right) steering angle + + int32_t analog_min_with_margins; // Added margins to min raw value + int32_t analog_max_with_margins; // Added margins to max raw value + int32_t digital_min_with_margins; // Added margins to min raw value + int32_t digital_max_with_margins; // Added margins to max raw value + + uint32_t span_signal_analog; // range of the analog sensor in counts + uint32_t span_signal_digital; // range of the digital sensor in counts + uint32_t digital_midpoint; // midpoint of raw values + uint32_t analog_midpoint; // midpoint of raw values + + // conversion rates + // float deg_per_count_analog = 0.0439f; //hard coded for analog (180) + float deg_per_count_analog; + float deg_per_count_digital; //based on digital readings + + // implausibility values + float analog_tolerance; //+- 0.5% error + float digital_tolerance; // +- 0.2 degrees error + float analog_tol_deg; + float digital_tol_deg; // +- 0.2 degrees error + + // rate of angle change + float max_dtheta_threshold; //maximum change in angle since last reading to consider the reading valid + + // difference rating + float error_between_sensors_tolerance; //maximum difference between digital and analog sensor allowed +}; + +class SteeringSystem { +public: + SteeringSystem(const SteeringParams_s &steeringParams) : _steeringParams(steeringParams) {} + + // Functions + void recalibrate_steering_digital(); + + void evaluate_steering(const uint32_t analog_raw, const SteeringEncoderReading_s digital_data, const uint32_t current_millis); + + // Getters + const SteeringParams_s &get_steering_params() const { + return _steeringParams; + } + + const SteeringSystemData_s &get_steering_system_data() const { + return _steeringSystemData; + } + + float get_unfiltered_analog_steering_deg() const { + return _analog_angle_unfiltered; + } + + // Setters + void set_steering_params(const SteeringParams_s &steeringParams) { + _steeringParams = steeringParams; + } + + void set_steering_system_data(const SteeringSystemData_s &steeringSystemData) { + _steeringSystemData = steeringSystemData; + } + void update_observed_steering_limits(const uint32_t analog_raw, const uint32_t digital_raw); + + //DELETE + const uint32_t get_min_observed_analog() const { + return min_observed_analog; + } + const uint32_t get_max_observed_analog() const { + return max_observed_analog; + } +private: + float _convert_digital_sensor(const uint32_t digital_raw); + + float _convert_analog_sensor(const uint32_t analog_raw); + + //returns true if steering_analog is outside of the range defined by min and max sensor values + bool _evaluate_steering_oor_analog(const uint32_t steering_analog); + + //returns true if steering_digital is outside the range defined by min and max sensor values + bool _evaluate_steering_oor_digital(const uint32_t steering_digital); + + //returns true if change in angle exceeds maximum change per reading ( max_dtheta_threshold ) + bool _evaluate_steering_dtheta_exceeded(float dtheta); + + SteeringSystemData_s _steeringSystemData {}; + SteeringParams_s _steeringParams; + //track the state of our system from the previous tick to compare against current state for implausibility checks + float _analog_angle_unfiltered = 0.0f; + float _prev_analog_angle = 0.0f; + float _prev_digital_angle = 0.0f; + float _prev_digital_vel_angle = 0.0f; + float _prev_analog_vel_angle = 0.0f; + uint32_t _prev_timestamp = 0; + bool _calibrating = false; + bool _finished_calibrating = false; + bool _first_run = true; // skip dTheta check on the very first tick + uint32_t min_observed_analog = UINT32_MAX; + uint32_t max_observed_analog = 0; + uint32_t min_observed_digital = UINT32_MAX; + uint32_t max_observed_digital = 0; + + // 2nd-order Butterworth IIR low-pass on the analog angle. + // Designed for fc = 8 Hz at fs = 500 Hz. Direct Form II Transposed. + float _filter_analog_angle(float x); + float _bw_z1 = 0.0f; + float _bw_z2 = 0.0f; + bool _bw_initialized = false; + float _last_filtered_analog_angle = 0.0f; +}; +using SteeringSystemInstance = etl::singleton; + + +#endif + diff --git a/lib/systems/src/SteeringSystem.cpp b/lib/systems/src/SteeringSystem.cpp new file mode 100644 index 0000000..a25a081 --- /dev/null +++ b/lib/systems/src/SteeringSystem.cpp @@ -0,0 +1,200 @@ +#include + +#include "SteeringSystem.h" + +constexpr float kBwB0 = 0.00235721f; +constexpr float kBwB1 = 0.00471442f; +constexpr float kBwB2 = 0.00235721f; +constexpr float kBwA1 = -1.85804330f; +constexpr float kBwA2 = 0.86747213f; + +void SteeringSystem::recalibrate_steering_digital() { + _steeringParams.min_steering_signal_analog = min_observed_analog; + _steeringParams.max_steering_signal_analog = max_observed_analog; + _steeringParams.min_steering_signal_digital = min_observed_digital; + _steeringParams.max_steering_signal_digital = max_observed_digital; + // swaps min & max in the params if sensor is flipped + if (_steeringParams.min_steering_signal_digital > _steeringParams.max_steering_signal_digital) { + std::swap(_steeringParams.min_steering_signal_digital, _steeringParams.max_steering_signal_digital); + } + if (_steeringParams.min_steering_signal_analog > _steeringParams.max_steering_signal_analog) { + std::swap(_steeringParams.min_steering_signal_analog, _steeringParams.max_steering_signal_analog); + } + _steeringParams.span_signal_digital = _steeringParams.max_steering_signal_digital-_steeringParams.min_steering_signal_digital; + _steeringParams.analog_tol_deg = static_cast(_steeringParams.span_signal_analog) * _steeringParams.analog_tolerance * _steeringParams.deg_per_count_analog; + _steeringParams.digital_tol_deg = static_cast(_steeringParams.span_signal_digital) *_steeringParams.digital_tolerance * _steeringParams.deg_per_count_digital; + _steeringParams.digital_midpoint = (_steeringParams.max_steering_signal_digital + _steeringParams.min_steering_signal_digital) / 2; + _steeringParams.analog_midpoint = (_steeringParams.max_steering_signal_analog + _steeringParams.min_steering_signal_analog) / 2; + _steeringParams.analog_min_with_margins = static_cast(_steeringParams.min_steering_signal_analog - _steeringParams.analog_tol_deg); // NOLINT + _steeringParams.analog_max_with_margins = static_cast(_steeringParams.max_steering_signal_analog + _steeringParams.analog_tol_deg); // NOLINT + _steeringParams.digital_min_with_margins = static_cast(_steeringParams.min_steering_signal_digital - _steeringParams.digital_tol_deg); // NOLINT + _steeringParams.digital_max_with_margins = static_cast(_steeringParams.max_steering_signal_digital + _steeringParams.digital_tol_deg); // NOLINT + + if (max_observed_analog > min_observed_analog && _steeringParams.span_signal_analog > 2500) // NOLINT with 360 deg analog sensor, typical span is about 2000 + { + min_observed_analog = UINT32_MAX; // after calculating params, if the range is marginally greater than half the steering wheel adc, likely the min and max are clinging to a prior run that is not applicable, meaning we will need to reset the boundaries. + max_observed_analog = 0; + } + if (max_observed_digital > min_observed_digital && _steeringParams.span_signal_digital > 9000) // NOLINT with digital sensor, typical span is about 9000 + { + min_observed_digital = UINT32_MAX; + max_observed_digital = 0; + } + +} + +void SteeringSystem::evaluate_steering(const uint32_t analog_raw, const SteeringEncoderReading_s digital_data, const uint32_t current_millis) { + // Reset flags + _steeringSystemData.digital_oor_implausibility = false; + _steeringSystemData.analog_oor_implausibility = false; + _steeringSystemData.sensor_disagreement_implausibility = false; + _steeringSystemData.dtheta_exceeded_analog = false; + _steeringSystemData.dtheta_exceeded_digital = false; + _steeringSystemData.both_sensors_fail = false; + + const uint32_t digital_raw = digital_data.rawValue; + + SteeringEncoderStatus_e digital_status = digital_data.status; + bool digital_fault = (digital_status == SteeringEncoderStatus_e::ERROR); + _steeringSystemData.interface_sensor_error = digital_fault; + _steeringSystemData.digital_raw = digital_raw; + + _steeringSystemData.analog_raw = analog_raw; + _analog_angle_unfiltered = _convert_analog_sensor(analog_raw); + + //Conversion from raw ADC to degrees + _steeringSystemData.digital_steering_angle = _convert_digital_sensor(digital_raw); + + uint32_t dt = 0; + if (current_millis - _prev_timestamp > 2) { + dt = current_millis - _prev_timestamp; //current_millis is seperate data input   + } + + if (!_first_run) { //check that we not on the first run which would mean no previous data + + + if (dt >= 2) { + float filtered_analog_angle = _filter_analog_angle(_analog_angle_unfiltered); + _steeringSystemData.analog_steering_angle = filtered_analog_angle; // update the angle to the filtered value for downstream use and velocity calculation + float dtheta_analog = filtered_analog_angle - _prev_analog_vel_angle; + float dtheta_digital = _steeringSystemData.digital_steering_angle - _prev_digital_vel_angle; + + _steeringSystemData.analog_steering_velocity_deg_s = (dtheta_analog / static_cast(dt)) * 1000.0f; // NOLINT 1000.0f is result of converting dt in millis to seconds + + _steeringSystemData.digital_steering_velocity_deg_s = (dtheta_digital / static_cast(dt)) * 1000.0f; // NOLINT 1000.0f is result of converting dt in millis to seconds + + _last_filtered_analog_angle = filtered_analog_angle; + } else { + _steeringSystemData.analog_steering_angle = _last_filtered_analog_angle; + } + + + //Check if either sensor moved too much in one tick + _steeringSystemData.dtheta_exceeded_analog = _evaluate_steering_dtheta_exceeded(_steeringSystemData.analog_steering_velocity_deg_s); + _steeringSystemData.dtheta_exceeded_digital = _evaluate_steering_dtheta_exceeded(_steeringSystemData.digital_steering_velocity_deg_s); // use digital velocity for dtheta check since it's more precise and we are concerned about large changes in angle that could be caused by noise in the analog sensor + + //Check if either sensor is out of range (pass in raw) + _steeringSystemData.analog_oor_implausibility = _evaluate_steering_oor_analog(static_cast(analog_raw)); + _steeringSystemData.digital_oor_implausibility = _evaluate_steering_oor_digital(static_cast(digital_raw)); + + //Check if there is too much of a difference between sensor values + float sensor_difference = std::fabs(_steeringSystemData.analog_steering_angle - _steeringSystemData.digital_steering_angle); + bool sensors_agree = (sensor_difference <= _steeringParams.error_between_sensors_tolerance); //steeringParams.error + _steeringSystemData.sensor_disagreement_implausibility = !sensors_agree; + + //create an algorithm/ checklist to determine which sensor we trust more, + //or, if we should have an algorithm to have a weighted calculation based on both values + bool analog_valid = !_steeringSystemData.analog_oor_implausibility && !_steeringSystemData.dtheta_exceeded_analog; + bool digital_valid = !_steeringSystemData.digital_oor_implausibility && !_steeringSystemData.dtheta_exceeded_digital && !_steeringSystemData.interface_sensor_error; + + if (analog_valid && digital_valid) { + //if sensors have acceptable difference, use digital as steering angle + if (sensors_agree) { + _steeringSystemData.output_steering_angle = _steeringSystemData.digital_steering_angle; + } else { + _steeringSystemData.output_steering_angle = _steeringSystemData.digital_steering_angle; //default to original, but we need to consider what we really want to put here + } + } else if (analog_valid) { + _steeringSystemData.output_steering_angle = _steeringSystemData.analog_steering_angle; + } else if (digital_valid) { + _steeringSystemData.output_steering_angle = _steeringSystemData.digital_steering_angle; + } else { // if both sensors fail + _steeringSystemData.output_steering_angle = _prev_digital_angle; + _steeringSystemData.both_sensors_fail = true; + } + } + //Update states + if (dt >= 2) { // update at 500Hz + _prev_timestamp = current_millis; + _prev_analog_vel_angle = _steeringSystemData.analog_steering_angle; + _prev_digital_vel_angle = _steeringSystemData.digital_steering_angle; + } + + _prev_analog_angle = _steeringSystemData.analog_steering_angle; + _prev_digital_angle = _steeringSystemData.digital_steering_angle; + _first_run = false; +} + +void SteeringSystem::update_observed_steering_limits(const uint32_t analog_raw, const uint32_t digital_raw) { + + min_observed_analog = std::min(min_observed_analog, static_cast(analog_raw)); + max_observed_analog = std::max(max_observed_analog, static_cast(analog_raw)); + min_observed_digital = std::min(min_observed_digital, static_cast(digital_raw)); //NOLINT should both be uint32_t + max_observed_digital = std::max(max_observed_digital, static_cast(digital_raw)); //NOLINT ^ + if (min_observed_analog < 5) // NOLINT want to prevent sticking at 0 or clipping with small value + { + min_observed_analog = UINT32_MAX; // clipping if it is at 0, it is likely sensor is clipping or clipped in past and reading is holding the 0 value. + } + if (max_observed_analog > 3675) // NOLINT prevents clipping, this is slightly less than calculated value of actual max output of sensor with current resistor divider on VCF's ADC + { + max_observed_analog = 0; // clipping + } + if (min_observed_digital < 10) // NOLINT want to prevent sticking at 0 or clipping + { + min_observed_digital = UINT32_MAX; // clipping on prior run. + } + if (max_observed_digital > 16374) // NOLINT 16374 = 2^14 - 10 to prevent clipping with 14 bit resolution on sensor + { + max_observed_digital = 0; // clipping + } +} + +float SteeringSystem::_convert_digital_sensor(const uint32_t digital_raw) { + // Same logic for digital + const int32_t offset = _steeringParams.digital_midpoint-static_cast(digital_raw); //NOLINT + return static_cast(offset) * _steeringParams.deg_per_count_digital; // bc diital sensor is flipped +} + +float SteeringSystem::_convert_analog_sensor(const uint32_t analog_raw) { + // Get the raw value + const int32_t offset = static_cast(analog_raw) - _steeringParams.analog_midpoint; //NOLINT + return static_cast(offset) * _steeringParams.deg_per_count_analog; +} + +bool SteeringSystem::_evaluate_steering_oor_analog(const uint32_t steering_analog_raw) { // RAW + return (static_cast(steering_analog_raw) < _steeringParams.analog_min_with_margins || static_cast(steering_analog_raw) > _steeringParams.analog_max_with_margins); +} + +bool SteeringSystem::_evaluate_steering_oor_digital(const uint32_t steering_digital_raw) {// RAW + return (static_cast(steering_digital_raw) < _steeringParams.digital_min_with_margins || static_cast(steering_digital_raw) > _steeringParams.digital_max_with_margins); +} + +bool SteeringSystem::_evaluate_steering_dtheta_exceeded(float steering_velocity_deg_s) { + return (fabs(steering_velocity_deg_s) > _steeringParams.max_dtheta_threshold); +} + +float SteeringSystem::_filter_analog_angle(float x) { + // First sample: pre-load the state so the output starts at x and + // there is no startup transient (otherwise the filter would ramp + // from 0 up to the first real value over ~50 ms). + if (!_bw_initialized) { + _bw_z1 = (1.0f - kBwB0) * x; + _bw_z2 = (kBwB2 - kBwA2) * x; + _bw_initialized = true; + } + // Direct Form II Transposed biquad: 5 multiplies, 4 adds, 2 floats of state. + float y = kBwB0 * x + _bw_z1; + _bw_z1 = kBwB1 * x - kBwA1 * y + _bw_z2; + _bw_z2 = kBwB2 * x - kBwA2 * y; + return y; +} diff --git a/platformio.ini b/platformio.ini index b265965..2047844 100644 --- a/platformio.ini +++ b/platformio.ini @@ -7,10 +7,10 @@ lib_deps_shared = nanopb/Nanopb@0.4.91 https://github.com/hytech-racing/shared_firmware_systems.git - https://github.com/hytech-racing/shared_firmware_types.git + https://github.com/hytech-racing/shared_firmware_types.git#d9818df40287f21524de7e4b8558ced2023bd705 https://github.com/hytech-racing/HT_SCHED#c13cff762c59dd82a8c273e3e98fd1a80622656d - https://github.com/hytech-racing/HT_proto/releases/download/2026-04-02T21_09_09/hytech_msgs_pb_lib.tar.gz - https://github.com/hytech-racing/HT_CAN/releases/download/250/can_lib.tar.gz + https://github.com/hytech-racing/HT_proto/releases/download/2026-04-19T22_02_36/hytech_msgs_pb_lib.tar.gz + https://github.com/hytech-racing/HT_CAN/releases/download/251/can_lib.tar.gz etlcpp/Embedded Template Library @@ -111,7 +111,7 @@ build_flags = -std=c++17 -g -D TESTING_SYSTEMS -lib_ignore = +lib_ignore= test_ignore= test_interfaces* lib_deps = @@ -226,4 +226,4 @@ lib_deps = https://github.com/ssilverman/QNEthernet#v0.26.0 blemasle/MCP23017@^2.0.0 https://github.com/hytech-racing/shared_firmware_interfaces.git#29a9cb09f91b684382e897de780d8d52a14659a7 - https://github.com/KSU-MS/pio-git-hash-gen#7998b5b3f8a2464209b0e73338717998bcf511ee \ No newline at end of file + https://github.com/KSU-MS/pio-git-hash-gen#7998b5b3f8a2464209b0e73338717998bcf511ee diff --git a/src/VCF_Tasks.cpp b/src/VCF_Tasks.cpp index ef6c2d5..841059d 100644 --- a/src/VCF_Tasks.cpp +++ b/src/VCF_Tasks.cpp @@ -13,6 +13,7 @@ #include "VCRInterface.h" #include "SystemTimeInterface.h" #include "PedalsSystem.h" +#include "SteeringSystem.h" #include "WatchdogSystem.h" #include "DashboardInterface.h" #include "VCFEthernetInterface.h" @@ -20,6 +21,7 @@ #include #include "FlexCAN_T4.h" #include "Orbis_BR.h" +#include "SteeringEncoderInterface.h" #include "WatchdogSystem.h" #include "Arduino.h" @@ -28,15 +30,14 @@ HT_TASK::TaskResponse run_read_adc0_task(const unsigned long& sysMicros, const H { // Updates all eight channels. ADCInterfaceInstance::instance().adc0_tick(); + OrbisBRInstance::instance().sample(); PedalsSystemInstance::instance().set_pedals_sensor_data(PedalSensorData_s{ .accel_1 = static_cast(ADCInterfaceInstance::instance().acceleration_1().conversion), .accel_2 = static_cast(ADCInterfaceInstance::instance().acceleration_2().conversion), .brake_1 = static_cast(ADCInterfaceInstance::instance().brake_1().conversion), .brake_2 = static_cast(ADCInterfaceInstance::instance().brake_2().conversion) }); - - // sample digital steering too TODO: move this to its own task maybe? - OrbisBRInstance::instance().sample(); + return HT_TASK::TaskResponse::YIELD; } @@ -57,7 +58,7 @@ HT_TASK::TaskResponse init_kick_watchdog(const unsigned long& sysMicros, const H } HT_TASK::TaskResponse run_kick_watchdog(const unsigned long& sysMicros, const HT_TASK::TaskInfo& taskInfo) { - digitalWrite(VCFInterfaceConstants::SOFTWARE_OK_PIN , HIGH); + digitalWrite(VCFInterfaceConstants::SOFTWARE_OK_PIN, HIGH); digitalWrite(VCFInterfaceConstants::WATCHDOG_PIN, WatchdogInstance::instance().get_watchdog_state(sys_time::hal_millis())); return HT_TASK::TaskResponse::YIELD; } @@ -85,6 +86,28 @@ HT_TASK::TaskResponse update_pedals_calibration_task(const unsigned long& sysMic return HT_TASK::TaskResponse::YIELD; } +HT_TASK::TaskResponse update_steering_calibration_task(const unsigned long& sysMicros, const HT_TASK::TaskInfo& taskInfo) { + const uint32_t analog_raw = SteeringSystemInstance::instance().get_steering_system_data().analog_raw; // NOLINT thinks this is not initialized + const uint32_t digital_raw = SteeringSystemInstance::instance().get_steering_system_data().digital_raw; // NOLINT thinks this is not initialized + + SteeringSystemInstance::instance().update_observed_steering_limits(analog_raw, digital_raw); + + + if (VCRInterfaceInstance::instance().is_in_steering_calibration_state()) { + + SteeringSystemInstance::instance().recalibrate_steering_digital(); + EEPROMUtilities::write_eeprom_32bit(VCFSystemConstants::MIN_STEERING_SIGNAL_ANALOG_ADDR, SteeringSystemInstance::instance().get_steering_params().min_steering_signal_analog); + EEPROMUtilities::write_eeprom_32bit(VCFSystemConstants::MAX_STEERING_SIGNAL_ANALOG_ADDR, SteeringSystemInstance::instance().get_steering_params().max_steering_signal_analog); + EEPROMUtilities::write_eeprom_32bit(VCFSystemConstants::MIN_STEERING_SIGNAL_DIGITAL_ADDR, SteeringSystemInstance::instance().get_steering_params().min_steering_signal_digital); + EEPROMUtilities::write_eeprom_32bit(VCFSystemConstants::MAX_STEERING_SIGNAL_DIGITAL_ADDR, SteeringSystemInstance::instance().get_steering_params().max_steering_signal_digital); + EEPROMUtilities::write_eeprom_32bit(VCFSystemConstants::ANALOG_MIN_WITH_MARGINS_ADDR, SteeringSystemInstance::instance().get_steering_params().analog_min_with_margins); + EEPROMUtilities::write_eeprom_32bit(VCFSystemConstants::ANALOG_MAX_WITH_MARGINS_ADDR, SteeringSystemInstance::instance().get_steering_params().analog_max_with_margins); + EEPROMUtilities::write_eeprom_32bit(VCFSystemConstants::DIGITAL_MIN_WITH_MARGINS_ADDR, SteeringSystemInstance::instance().get_steering_params().digital_min_with_margins); + EEPROMUtilities::write_eeprom_32bit(VCFSystemConstants::DIGITAL_MAX_WITH_MARGINS_ADDR, SteeringSystemInstance::instance().get_steering_params().digital_max_with_margins); + } + + return HT_TASK::TaskResponse::YIELD; +} // bool init_read_gpio_task() // { // // Setting digital/analog buttons D10-D6, A8 as inputs @@ -130,7 +153,6 @@ HT_TASK::TaskResponse run_buzzer_control_task(const unsigned long& sysMicros, co bool buzzer_is_active = BuzzerController::getInstance().buzzer_is_active(sys_time::hal_millis()); //NOLINT digitalWrite(VCFInterfaceConstants::BUZZER_CONTROL_PIN, buzzer_is_active); - return HT_TASK::TaskResponse::YIELD; } @@ -149,9 +171,9 @@ HT_TASK::TaskResponse send_dash_data(const unsigned long& sysMicros, const HT_TA DASH_INPUT_t msg_out; + msg_out.dim_button = dash_outputs.btn_dim_read_is_pressed; msg_out.preset_button = dash_outputs.preset_btn_is_pressed; msg_out.mode_button = 0; // dont exist but i dont wanna bother changing can msgs - msg_out.motor_controller_cycle_button = dash_outputs.mc_reset_btn_is_pressed; msg_out.start_button = dash_outputs.start_btn_is_pressed; msg_out.data_button_is_pressed = dash_outputs.data_btn_is_pressed; @@ -181,19 +203,19 @@ HT_TASK::TaskResponse enqueue_front_suspension_data(const unsigned long& sysMicr HT_TASK::TaskResponse enqueue_steering_data(const unsigned long& sysMicros, const HT_TASK::TaskInfo& taskInfo) { - STEERING_DATA_t msg_out = {}; - - // TODO: change these to actually grab values from steering system - msg_out.steering_analog_oor = 0; - msg_out.steering_analog_raw = ADCInterfaceInstance::instance().get_steering_degrees_cw().raw; - msg_out.steering_both_sensors_fail = 0; - msg_out.steering_digital_oor = 0; - msg_out.steering_digital_raw = OrbisBRInstance::instance().getLastReading().rawValue; - msg_out.steering_dtheta_exceeded_analog = 0; - msg_out.steering_dtheta_exceeded_digital = 0; - msg_out.steering_interface_sensor_error = 0; - msg_out.steering_output_steering_angle_ro = 0; - msg_out.steering_sensor_disagreement = 0; + STEERING_DATA_t msg_out; + SteeringSystemData_s steering_system_data = SteeringSystemInstance::instance().get_steering_system_data(); + + msg_out.steering_analog_oor = steering_system_data.analog_oor_implausibility; + msg_out.steering_both_sensors_fail = steering_system_data.both_sensors_fail; + msg_out.steering_digital_oor = steering_system_data.digital_oor_implausibility; + msg_out.steering_dtheta_exceeded_analog = steering_system_data.dtheta_exceeded_analog; + msg_out.steering_dtheta_exceeded_digital = steering_system_data.dtheta_exceeded_digital; + msg_out.steering_interface_sensor_error = steering_system_data.interface_sensor_error; + msg_out.steering_output_steering_angle_ro = HYTECH_steering_output_steering_angle_ro_toS(steering_system_data.output_steering_angle); + msg_out.steering_sensor_disagreement = steering_system_data.sensor_disagreement_implausibility; + msg_out.steering_analog_raw = steering_system_data.analog_raw; + msg_out.steering_digital_raw = steering_system_data.digital_raw; CAN_util::enqueue_msg(&msg_out, &Pack_STEERING_DATA_hytech, VCFCANInterfaceInstance::instance().telem_can_tx_buffer); return HT_TASK::TaskResponse::YIELD; @@ -207,7 +229,7 @@ HT_TASK::TaskResponse init_handle_send_vcf_ethernet_data(const unsigned long& sy } HT_TASK::TaskResponse run_handle_send_vcf_ethernet_data(const unsigned long& sysMicros, const HT_TASK::TaskInfo& taskInfo) { - hytech_msgs_VCFData_s msg = VCFEthernetInterface::make_vcf_data_msg(ADCInterfaceInstance::instance(), DashboardInterfaceInstance::instance(), PedalsSystemInstance::instance()); + hytech_msgs_VCFData_s msg = VCFEthernetInterface::make_vcf_data_msg(ADCInterfaceInstance::instance(), DashboardInterfaceInstance::instance(), PedalsSystemInstance::instance(), SteeringSystemInstance::instance()); if(handle_ethernet_socket_send_pb (EthernetIPDefsInstance::instance().drivebrain_ip, EthernetIPDefsInstance::instance().VCFData_port, @@ -256,10 +278,15 @@ HT_TASK::TaskResponse run_dash_GPIOs_task(const unsigned long& sys_micros, const bool was_dim_btn_pressed = DashboardInterfaceInstance::instance().get_dashboard_stored_state().brightness_ctrl_btn_is_pressed; //NOLINT (linter thinks variable uninitialized) DashInputState_s current_state = DashboardInterfaceInstance::instance().get_dashboard_outputs(); - if (!current_state.preset_btn_is_pressed) //preset_btn_is_pressed doesnt exist anymore + if (!current_state.preset_btn_is_pressed) //preset btn tied to brightness control on schematic { VCRInterfaceInstance::instance().disable_calibration_state(); } + + if (!current_state.data_btn_is_pressed) + { + VCRInterfaceInstance::instance().disable_steering_calibration_state(); + } // Checks if dim btn has been clicked (falling edge) if (was_dim_btn_pressed && !current_state.brightness_ctrl_btn_is_pressed) @@ -299,13 +326,20 @@ namespace async_tasks void handle_async_recvs() { // ethernet, etc... - + handle_async_CAN_receive(); } HT_TASK::TaskResponse handle_async_main(const unsigned long& sys_micros, const HT_TASK::TaskInfo& task_info) { handle_async_recvs(); + + SteeringSystemInstance::instance().evaluate_steering( + ADCInterfaceInstance::instance().get_steering_degrees_cw().conversion, + OrbisBRInstance::instance().getLastReading(), + sys_time::hal_millis() + ); + PedalsSystemInstance::instance().evaluate_pedals( PedalsSystemInstance::instance().get_pedals_sensor_data(), sys_time::hal_millis() @@ -314,6 +348,7 @@ namespace async_tasks } }; + HT_TASK::TaskResponse debug_print(const unsigned long& sysMicros, const HT_TASK::TaskInfo& taskInfo) { /* Pedals Info */ @@ -337,7 +372,52 @@ HT_TASK::TaskResponse debug_print(const unsigned long& sysMicros, const HT_TASK: Serial.print(PedalsSystemInstance::instance().get_brake_params().max_pedal_1); Serial.print("\t"); Serial.print(PedalsSystemInstance::instance().get_brake_params().min_pedal_2); Serial.print("\t"); Serial.println(PedalsSystemInstance::instance().get_brake_params().max_pedal_2); - + + /* Steering System Data */ + Serial.println("Steering Sensor Data: "); + Serial.print("analog adc: "); + Serial.print(SteeringSystemInstance::instance().get_steering_system_data().analog_raw); Serial.print(" "); + Serial.print(ADCInterfaceInstance::instance().get_steering_degrees_cw().raw); + Serial.print("|"); + Serial.println(SteeringSystemInstance::instance().get_steering_system_data().analog_steering_angle); + Serial.print("digital adc: "); + Serial.print(SteeringSystemInstance::instance().get_steering_system_data().digital_raw); + Serial.print("|"); + Serial.println(SteeringSystemInstance::instance().get_steering_system_data().digital_steering_angle); + Serial.print("min_observed_analog: "); + Serial.println(SteeringSystemInstance::instance().get_min_observed_analog()); + Serial.print("max_observed_analog: "); + Serial.println(SteeringSystemInstance::instance().get_max_observed_analog()); + Serial.print("analog_steering_angle: "); + Serial.println(SteeringSystemInstance::instance().get_steering_system_data().analog_steering_angle); + Serial.print("digital_steering_angle: "); + Serial.println(SteeringSystemInstance::instance().get_steering_system_data().digital_steering_angle); + Serial.print("time: "); + Serial.println(sys_time::hal_millis()); + + Serial.print("output_steering_angle: "); + Serial.println(SteeringSystemInstance::instance().get_steering_system_data().output_steering_angle); + + Serial.print("analog_steering_velocity_deg_s: "); + Serial.println(SteeringSystemInstance::instance().get_steering_system_data().analog_steering_velocity_deg_s); + Serial.print("digital_steering_velocity_deg_s: "); + Serial.println(SteeringSystemInstance::instance().get_steering_system_data().digital_steering_velocity_deg_s); + + Serial.print("digital_oor_implausibility: "); + Serial.println(SteeringSystemInstance::instance().get_steering_system_data().digital_oor_implausibility); + Serial.print("analog_oor_implausibility: "); + Serial.println(SteeringSystemInstance::instance().get_steering_system_data().analog_oor_implausibility); + Serial.print("sensor_disagreement_implausibility: "); + Serial.println(SteeringSystemInstance::instance().get_steering_system_data().sensor_disagreement_implausibility); + Serial.print("dtheta_exceeded_analog: "); + Serial.println(SteeringSystemInstance::instance().get_steering_system_data().dtheta_exceeded_analog); + Serial.print("dtheta_exceeded_digital: "); + Serial.println(SteeringSystemInstance::instance().get_steering_system_data().dtheta_exceeded_digital); + Serial.print("both_sensors_fail: "); + Serial.println(SteeringSystemInstance::instance().get_steering_system_data().both_sensors_fail); + Serial.print("interface_sensor_error: "); + Serial.println(SteeringSystemInstance::instance().get_steering_system_data().interface_sensor_error); + /* ADC Values */ Serial.println("\nADC Vals:"); // ADC 0 @@ -395,9 +475,6 @@ HT_TASK::TaskResponse debug_print(const unsigned long& sysMicros, const HT_TASK: Serial.print(DashboardInterfaceInstance::instance().get_dashboard_outputs().data_btn_is_pressed); Serial.print("\t"); Serial.println(BuzzerController::getInstance().buzzer_is_active(sys_time::hal_millis())); - Serial.println("Digital Steering:"); - Serial.println(OrbisBRInstance::instance().getLastReading().rawValue); - return HT_TASK::TaskResponse::YIELD; } @@ -498,9 +575,32 @@ void setup_all_interfaces() { }; PedalsSystemInstance::create(accel_params, brake_params); //pass in the two different params + SteeringParams_s steering_params = { + .min_steering_signal_analog = EEPROMUtilities::read_eeprom_32bit(VCFSystemConstants::MIN_STEERING_SIGNAL_ANALOG_ADDR), + .max_steering_signal_analog = EEPROMUtilities::read_eeprom_32bit(VCFSystemConstants::MAX_STEERING_SIGNAL_ANALOG_ADDR), + .min_steering_signal_digital = EEPROMUtilities::read_eeprom_32bit(VCFSystemConstants::MIN_STEERING_SIGNAL_DIGITAL_ADDR), + .max_steering_signal_digital = EEPROMUtilities::read_eeprom_32bit(VCFSystemConstants::MAX_STEERING_SIGNAL_DIGITAL_ADDR), + .analog_min_with_margins = EEPROMUtilities::read_eeprom_32bit(VCFSystemConstants::ANALOG_MIN_WITH_MARGINS_ADDR), // NOLINT this is prev saved value so it is ok + .analog_max_with_margins = EEPROMUtilities::read_eeprom_32bit(VCFSystemConstants::ANALOG_MAX_WITH_MARGINS_ADDR), // NOLINT this is prev saved value so it is ok + .digital_min_with_margins = EEPROMUtilities::read_eeprom_32bit(VCFSystemConstants::DIGITAL_MIN_WITH_MARGINS_ADDR), // NOLINT this is prev saved value so it is ok + .digital_max_with_margins = EEPROMUtilities::read_eeprom_32bit(VCFSystemConstants::DIGITAL_MAX_WITH_MARGINS_ADDR), // NOLINT this is prev saved value so it is ok + .deg_per_count_analog = VCFSystemConstants::DEG_PER_COUNT_ANALOG, + .deg_per_count_digital = VCFSystemConstants::DEG_PER_COUNT_DIGITAL, + .analog_tolerance = VCFSystemConstants::ANALOG_TOLERANCE, + .digital_tolerance = VCFSystemConstants::DIGITAL_TOLERANCE, + .max_dtheta_threshold = VCFSystemConstants::MAX_DTHETA_THRESHOLD, + .error_between_sensors_tolerance = VCFSystemConstants::ERROR_BETWEEN_SENSORS_TOLERANCE + + }; + steering_params.span_signal_analog = steering_params.max_steering_signal_analog - steering_params.min_steering_signal_analog; + steering_params.analog_midpoint = (steering_params.max_steering_signal_analog + steering_params.min_steering_signal_analog) / 2; + steering_params.span_signal_digital = steering_params.max_steering_signal_digital - steering_params.min_steering_signal_digital; + steering_params.digital_midpoint = (steering_params.min_steering_signal_digital + steering_params.max_steering_signal_digital) / 2; + SteeringSystemInstance::create(steering_params); // NOLINT thinks steering params is not initialized + // Create Digital Steering Sensor singleton OrbisBRInstance::create(&Serial2); - + // Create dashboard singleton DashboardGPIOs_s dashboard_gpios = { .BRIGHTNESS_CONTROL_PIN = VCFInterfaceConstants::BRIGHTNESS_CONTROL_PIN, @@ -525,5 +625,4 @@ void setup_all_interfaces() { uint8_t mac[6]; // NOLINT (mac addresses are always 6 bytes) qindesign::network::Ethernet.macAddress(&mac[0]); qindesign::network::Ethernet.begin(mac, EthernetIPDefsInstance::instance().vcf_ip, EthernetIPDefsInstance::instance().default_dns, EthernetIPDefsInstance::instance().default_gateway, EthernetIPDefsInstance::instance().car_subnet); - -} \ No newline at end of file +} diff --git a/src/main.cpp b/src/main.cpp index 3148850..f23b1de 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -23,6 +23,7 @@ #include "VCF_Constants.h" #include "VCF_Tasks.h" #include "PedalsSystem.h" +#include "SteeringSystem.h" #include "DashboardInterface.h" #include "VCFEthernetInterface.h" #include "WatchdogSystem.h" @@ -55,8 +56,9 @@ HT_TASK::Task ethernet_send_task(init_handle_send_vcf_ethernet_data, run_handle_ HT_TASK::Task steering_message_enqueue(HT_TASK::DUMMY_FUNCTION, &enqueue_steering_data, VCFTaskConstants::STEERING_SEND_PRIORITY, VCFTaskConstants::STEERING_SEND_PERIOD); HT_TASK::Task front_suspension_message_enqueue(HT_TASK::DUMMY_FUNCTION, &enqueue_front_suspension_data, VCFTaskConstants::LOADCELL_SEND_PRIORITY, VCFTaskConstants::LOADCELL_SEND_PERIOD); -HT_TASK::Task kick_watchdog_task(&init_kick_watchdog, &run_kick_watchdog, VCFTaskConstants::WATCHDOG_PRIORITY, VCFTaskConstants::WATCHDOG_KICK_PERIOD); -HT_TASK::Task pedals_calibration_task(HT_TASK::DUMMY_FUNCTION, &update_pedals_calibration_task, VCFTaskConstants::PEDALS_RECALIBRATION_PRIORITY, VCFTaskConstants::PEDALS_RECALIBRATION_PERIOD); +HT_TASK::Task kick_watchdog_task(&init_kick_watchdog, &run_kick_watchdog, VCFTaskConstants::WATCHDOG_PRIORITY, VCFTaskConstants::WATCHDOG_KICK_PERIOD); +HT_TASK::Task pedals_calibration_task(HT_TASK::DUMMY_FUNCTION, &update_pedals_calibration_task, VCFTaskConstants::PEDALS_RECALIBRATION_PRIORITY, VCFTaskConstants::PEDALS_RECALIBRATION_PERIOD); +HT_TASK::Task steering_calibration_task(HT_TASK::DUMMY_FUNCTION, &update_steering_calibration_task, VCFTaskConstants::STEERING_RECALIBRATION_PRIORITY, VCFTaskConstants::STEERING_RECALIBRATION_PERIOD); HT_TASK::Task debug_state_print_task(HT_TASK::DUMMY_FUNCTION, &debug_print, VCFTaskConstants::DEBUG_PRIORITY, VCFTaskConstants::DEBUG_PERIOD); @@ -80,6 +82,7 @@ void setup() { HT_SCHED::Scheduler::getInstance().schedule(steering_message_enqueue); HT_SCHED::Scheduler::getInstance().schedule(front_suspension_message_enqueue); HT_SCHED::Scheduler::getInstance().schedule(pedals_calibration_task); + HT_SCHED::Scheduler::getInstance().schedule(steering_calibration_task); HT_SCHED::Scheduler::getInstance().schedule(ethernet_send_task); HT_SCHED::Scheduler::getInstance().schedule(debug_state_print_task); @@ -87,4 +90,4 @@ void setup() { void loop() { HT_SCHED::Scheduler::getInstance().run(); -} \ No newline at end of file +} diff --git a/src/test_orbis.cpp b/src/test_orbis.cpp index 695c1a5..7d071f7 100644 --- a/src/test_orbis.cpp +++ b/src/test_orbis.cpp @@ -32,7 +32,7 @@ void setup() // OrbisBRInstance::instance().sample(); // Serial.print("\n\n"); - // SteeringEncoderConversion_s result = OrbisBRInstance::instance().convert(); + // SteeringEncoderReading_s result = OrbisBRInstance::instance().convert(); // if (result.errors.generalError) { Serial.println("General error"); } // if (result.errors.generalWarning) { Serial.println("General warning"); } // if (result.errors.noData) { Serial.println("No data"); } @@ -70,4 +70,4 @@ void loop() if (orbisErrors.calibration_parameter) { Serial.println("Calibration parameter error"); } } -} \ No newline at end of file +} diff --git a/src/test_steering.cpp b/src/test_steering.cpp new file mode 100644 index 0000000..e69de29 diff --git a/test/test_systems/main.cpp b/test/test_systems/main.cpp index 812379c..0be3f13 100644 --- a/test/test_systems/main.cpp +++ b/test/test_systems/main.cpp @@ -2,6 +2,7 @@ #include #include "pedals_system_test.h" #include "test_buzzer.h" +#include "steering_system_test.h" int main(int argc, char **argv) { diff --git a/test/test_systems/steering_system_test.h b/test/test_systems/steering_system_test.h new file mode 100644 index 0000000..c472bad --- /dev/null +++ b/test/test_systems/steering_system_test.h @@ -0,0 +1,402 @@ +#define STEERING_SYSTEM_TEST +#include +#include +#include "SteeringSystem.h" +#include "SharedFirmwareTypes.h" +#include + +#include + +SteeringParams_s gen_default_params(){ + SteeringParams_s params{}; + //hard code the parmas for sensors + params.min_steering_signal_analog = 1024; + params.max_steering_signal_analog = 3071;//actual hard coded + + params.min_steering_signal_digital = 25; + params.max_steering_signal_digital = 8000; //testing values + + params.span_signal_analog = 3071; + params.span_signal_digital = 8000; + + + params.deg_per_count_analog = 0.087890625f; + params.deg_per_count_digital = 0.02197265625f; + + // params.analog_tol = 0.005f; + params.analog_tol_deg = 0.11377778f; + params.digital_tol_deg = 0.2f; + + params.max_dtheta_threshold = 50.0f;//change + params.error_between_sensors_tolerance = 0.31377778f; + + params.digital_midpoint = (params.min_steering_signal_digital + params.max_steering_signal_digital) / 2; + params.analog_midpoint = (params.min_steering_signal_analog + params.max_steering_signal_analog) / 2; + + + const int32_t analog_margin_counts = static_cast(params.analog_tol_deg / params.deg_per_count_analog); + const int32_t digital_margin_counts = static_cast(params.digital_tol_deg / params.deg_per_count_digital); + + params.analog_min_with_margins = static_cast(params.min_steering_signal_analog) - analog_margin_counts; + params.analog_max_with_margins = static_cast(params.max_steering_signal_analog) + analog_margin_counts; + params.digital_min_with_margins = static_cast(params.min_steering_signal_digital) - digital_margin_counts; + params.digital_max_with_margins = static_cast(params.max_steering_signal_digital) + digital_margin_counts; + return params; + +} + + +void debug_print_steering(const SteeringSystemData_s& data){ + std::cout<<"analog_steering_angle: "<(params.min_steering_signal_analog) - static_cast(analog_mid)) * params.deg_per_count_analog; + float expected_digital_min = -1 * (static_cast(params.min_steering_signal_digital) - static_cast(digital_mid)) * params.deg_per_count_digital; + + // debug_print_steering(data); + // std::printf("Exp A Min: %.1f\n Exp D Min: %.1f\nMin A: %d\n Min D: %d\n\n", expected_analog_min, expected_digital_min, params.min_steering_signal_analog, params.min_steering_signal_digital); + EXPECT_NEAR(data.analog_steering_angle, expected_analog_min, 0.001f); + EXPECT_NEAR(data.digital_steering_angle, expected_digital_min, 0.001f); + + //max values + analog_raw = params.max_steering_signal_analog; + std::printf("Analog Raw: %d\n", analog_raw); + digital_data = hardcode_digital_data(params.max_steering_signal_digital); + + steering.evaluate_steering(analog_raw, digital_data, 1020); + data = steering.get_steering_system_data(); + data.analog_steering_angle = steering.get_unfiltered_analog_steering_deg(); + + float expected_analog_max = (static_cast(params.max_steering_signal_analog) - static_cast(analog_mid)) * params.deg_per_count_analog; + float expected_digital_max = -1 * (static_cast(params.max_steering_signal_digital) - static_cast(digital_mid)) * params.deg_per_count_digital; + + // debug_print_steering(data); + // std::printf("Exp A Max: %.1f\nExp D Max: %.1f\nMax A: %d\nMax D: %d\n\n", expected_analog_max, expected_digital_max, params.max_steering_signal_analog, params.max_steering_signal_digital); + EXPECT_NEAR(data.analog_steering_angle, expected_analog_max, 0.001f); + EXPECT_NEAR(data.digital_steering_angle, expected_digital_max, 0.001f); +} + +//FIXED +TEST(SteeringSystemTesting, test_out_of_bounds_raw_signals){ + auto params = gen_default_params(); + uint32_t analog_mid = (params.min_steering_signal_analog + params.max_steering_signal_analog) / 2; + uint32_t digital_mid = (params.min_steering_signal_digital + params.max_steering_signal_digital) / 2; + + + SteeringSystem steering(params); + + //Check for known valid values first + uint32_t analog_raw = analog_mid; + auto digital_data = hardcode_digital_data(digital_mid); + steering.evaluate_steering(analog_raw, digital_data, 1000); + auto data = steering.get_steering_system_data(); + EXPECT_FALSE(data.analog_oor_implausibility); + EXPECT_FALSE(data.digital_oor_implausibility); + + //OOR High + analog_raw = 5000; + digital_data = hardcode_digital_data(9000); + steering.evaluate_steering(analog_raw, digital_data, 1010); + data = steering.get_steering_system_data(); + EXPECT_TRUE(data.analog_oor_implausibility); + EXPECT_TRUE(data.digital_oor_implausibility); + + //OOR Low + + analog_raw = static_cast(params.min_steering_signal_analog) - 50; + digital_data = hardcode_digital_data(static_cast(params.min_steering_signal_digital) - 10); + steering.evaluate_steering(analog_raw, digital_data, 1020); + steering.evaluate_steering(analog_raw, digital_data, 1030); + //data = steering.evaluate_steering(low_val, 1030); + data = steering.get_steering_system_data(); + EXPECT_TRUE(data.analog_oor_implausibility); + EXPECT_TRUE(data.digital_oor_implausibility); + +} + +TEST(SteeringSystemTesting, test_detect_jumps_dtheta){ + auto params = gen_default_params(); + SteeringSystem steering(params); + + uint32_t analog_raw = 2048; + auto digital_data = hardcode_digital_data(4000); + + //First run (just to verify that we don't get a dtheta exceeded on the first run since we have no previous data to compare to) + steering.evaluate_steering(analog_raw, digital_data, 1000); + auto data = steering.get_steering_system_data(); + EXPECT_FALSE(data.dtheta_exceeded_analog); + EXPECT_FALSE(data.dtheta_exceeded_digital); + + analog_raw = 4096; + digital_data = hardcode_digital_data(8000); + steering.evaluate_steering(analog_raw, digital_data, 1005); + data = steering.get_steering_system_data(); + EXPECT_TRUE(data.dtheta_exceeded_analog); + EXPECT_TRUE(data.dtheta_exceeded_digital); + + + // Reset the last value of evaluate steering to baseline + analog_raw = 2048; + digital_data = hardcode_digital_data(4000); + steering.evaluate_steering(analog_raw, digital_data, 1010); + data = steering.get_steering_system_data(); + + std::cout << "\n angle1: " << data.digital_steering_angle; + //Small motion valid + analog_raw = 2060; + digital_data = hardcode_digital_data(4050); + steering.evaluate_steering(analog_raw, digital_data, 1120); //advance time by 110 ms + + data = steering.get_steering_system_data(); + + std::cout << "\n angle2: " << data.digital_steering_angle; + std::cout << "\n Velocity:" << data.digital_steering_velocity_deg_s << '\n'; + + EXPECT_FALSE(data.dtheta_exceeded_analog); + EXPECT_FALSE(data.dtheta_exceeded_digital); + + //Big motion NOT valid + analog_raw = 4096; + digital_data = hardcode_digital_data(8000); + steering.evaluate_steering(analog_raw, digital_data, 1130); //advance time by another 10 ms + + data = steering.get_steering_system_data(); + EXPECT_TRUE(data.dtheta_exceeded_analog); + EXPECT_TRUE(data.dtheta_exceeded_digital); +} + + +TEST(SteeringSystemTesting, test_sensor_disagreement) +{ + auto params = gen_default_params(); + SteeringSystem steering(params); + + uint32_t analog_raw = 2000; + auto digital_data = hardcode_digital_data(4000); + + steering.evaluate_steering(analog_raw, digital_data, 1000); + + //create disagreement between sensors to test + digital_data = hardcode_digital_data(7000); //large offset from analog + + steering.evaluate_steering(analog_raw, digital_data, 1100); + auto data = steering.get_steering_system_data(); + EXPECT_TRUE(data.sensor_disagreement_implausibility); +} + +TEST(SteeringSystemTesting,test_sensor_output_logic){ + auto params = gen_default_params(); + + + uint32_t analog_mid = (params.min_steering_signal_analog + params.max_steering_signal_analog) / 2; + uint32_t digital_mid = (params.min_steering_signal_digital + params.max_steering_signal_digital) / 2; + +{ + //When both valid and agreeing, we default to digital + SteeringSystem steering(params); + uint32_t analog_raw = analog_mid; + auto digital_data = hardcode_digital_data(digital_mid); + steering.evaluate_steering(analog_raw, digital_data, 1000); + steering.evaluate_steering(analog_raw, digital_data, 1100); + + auto data = steering.get_steering_system_data(); + EXPECT_NEAR(data.output_steering_angle, data.digital_steering_angle, 0.001f); //probably same problem, recheck after fix + EXPECT_FALSE(data.both_sensors_fail); //fail + EXPECT_FALSE(data.sensor_disagreement_implausibility); +} + // Prevent dtheta exceeded for the next test + +{ + //When both valid but disagreeing, we default to digital + SteeringSystem steering(params); + uint32_t analog_raw = analog_mid; + auto digital_data = hardcode_digital_data(digital_mid + 3000); //large offset from analog + steering.evaluate_steering(analog_raw, digital_data, 1000); + steering.evaluate_steering(analog_raw, digital_data, 1100); + auto data = steering.get_steering_system_data(); + + EXPECT_TRUE(data.sensor_disagreement_implausibility); + EXPECT_FALSE(data.analog_oor_implausibility); //actual true, expected false + EXPECT_FALSE(data.digital_oor_implausibility); //actual true, expected false + EXPECT_NEAR(data.output_steering_angle, data.digital_steering_angle, 0.001f); +} +{ + //When analog is good but digital is bad, we put analog + SteeringSystem steering(params); + uint32_t analog_raw = analog_mid; + auto digital_data = hardcode_digital_data(params.max_steering_signal_digital + 1000); //bad digital + steering.evaluate_steering(analog_raw, digital_data, 1000); + steering.evaluate_steering(analog_raw, digital_data, 1100); + auto data = steering.get_steering_system_data(); + EXPECT_TRUE(data.digital_oor_implausibility); + EXPECT_FALSE(data.analog_oor_implausibility); //actual true, expected false + EXPECT_NEAR(data.output_steering_angle, data.analog_steering_angle, 0.001f); //propgated +} +{ + //When digital is good but analog is bad, we put digital + SteeringSystem steering(params); + uint32_t analog_raw = params.max_steering_signal_analog + 1000; + auto digital_data = hardcode_digital_data(digital_mid); + steering.evaluate_steering(analog_raw, digital_data, 1000); + steering.evaluate_steering(analog_raw, digital_data, 1005); + auto data = steering.get_steering_system_data(); + EXPECT_TRUE(data.analog_oor_implausibility); + EXPECT_FALSE(data.digital_oor_implausibility); //actual true, expected false + EXPECT_NEAR(data.output_steering_angle, data.digital_steering_angle, 0.001f); //propagated from 253 +} +{ + //When both bad, we flagging that error + SteeringSystem steering(params); + uint32_t analog_raw = params.max_steering_signal_analog + 1000; + auto digital_data = hardcode_digital_data(params.max_steering_signal_digital + 1000); + steering.evaluate_steering(analog_raw, digital_data, 1000); + steering.evaluate_steering(analog_raw, digital_data, 1005); + auto data = steering.get_steering_system_data(); + EXPECT_TRUE(data.analog_oor_implausibility); + EXPECT_TRUE(data.digital_oor_implausibility); + EXPECT_TRUE(data.both_sensors_fail); +} + + +} + + + + +//REWRITE THIS WHOLE THING + +// TEST(SteeringSystemTesting, test_recalibrate_steering_digital) +// { +// auto params = gen_default_params(); +// SteeringSystem steering(params); + +// // Build calibration samples from the original digital range +// const uint32_t original_digital_min = params.min_steering_signal_digital; +// const uint32_t original_digital_max = params.max_steering_signal_digital; +// const uint32_t original_digital_mid = params.digital_midpoint; + +// // Pick values inside the original range so calibration observes a new min/max +// const uint32_t observed_low = original_digital_min + (original_digital_mid - original_digital_min) / 2; +// const uint32_t observed_high = original_digital_mid + (original_digital_max - original_digital_mid) / 2; + +// const uint32_t analog_mid_raw = static_cast(params.analog_midpoint); + +// // Start calibration: first sample should seed both observed min and max +// steering.recalibrate_steering_digital(analog_mid_raw, observed_high, true); +// auto updated_params = steering.get_steering_params(); + +// EXPECT_EQ(updated_params.min_observed_digital, observed_high); +// EXPECT_EQ(updated_params.max_observed_digital, observed_high); + +// // Feed lower value -> updates min only +// steering.recalibrate_steering_digital(analog_mid_raw, observed_low, true); +// updated_params = steering.get_steering_params(); + +// EXPECT_EQ(updated_params.min_observed_digital, observed_low); +// EXPECT_EQ(updated_params.max_observed_digital, observed_high); + +// // Feed high value again -> max remains high +// steering.recalibrate_steering_digital(analog_mid_raw, observed_high, true); +// updated_params = steering.get_steering_params(); + +// EXPECT_EQ(updated_params.min_observed_digital, observed_low); +// EXPECT_EQ(updated_params.max_observed_digital, observed_high); + +// // End calibration and commit recalculated values +// steering.recalibrate_steering_digital(analog_mid_raw, observed_high, false); +// updated_params = steering.get_steering_params(); + +// // Expected committed digital range +// const uint32_t expected_min_digital = observed_low; +// const uint32_t expected_max_digital = observed_high; +// const uint32_t expected_span_digital = expected_max_digital - expected_min_digital; +// const int32_t expected_digital_midpoint = static_cast((expected_max_digital + expected_min_digital) / 2); + +// // Analog values should remain based on the original analog params +// const uint32_t expected_span_analog = params.max_steering_signal_analog - params.min_steering_signal_analog; +// const int32_t expected_analog_midpoint = static_cast((params.max_steering_signal_analog + params.min_steering_signal_analog) / 2); + +// const float expected_analog_tol_deg = static_cast(params.span_signal_analog) *params.analog_tol * +// params.deg_per_count_analog; + +// const int32_t expected_analog_margin_counts = +// static_cast(params.analog_tol * static_cast(params.span_signal_analog)); + +// const int32_t expected_digital_margin_counts = static_cast(params.digital_tol_deg / params.deg_per_count_digital); + +// const int32_t expected_analog_min_with_margins = static_cast(params.min_steering_signal_analog) - expected_analog_margin_counts; +// const int32_t expected_analog_max_with_margins = static_cast(params.max_steering_signal_analog) + expected_analog_margin_counts; + +// const int32_t expected_digital_min_with_margins = static_cast(expected_min_digital) - expected_digital_margin_counts; +// const int32_t expected_digital_max_with_margins = static_cast(expected_max_digital) + expected_digital_margin_counts; + +// const float expected_error_between_sensors_tolerance = expected_analog_tol_deg + params.digital_tol_deg; + +// // Check committed digital calibration +// EXPECT_EQ(updated_params.min_steering_signal_digital, expected_min_digital); +// EXPECT_EQ(updated_params.max_steering_signal_digital, expected_max_digital); +// EXPECT_EQ(updated_params.span_signal_digital, expected_span_digital); +// EXPECT_EQ(updated_params.digital_midpoint, expected_digital_midpoint); + +// // Check analog-derived values that get recomputed +// EXPECT_EQ(updated_params.analog_midpoint, expected_analog_midpoint); +// EXPECT_FLOAT_EQ(updated_params.analog_tol_deg, expected_analog_tol_deg); + +// // Check margins +// EXPECT_EQ(updated_params.analog_min_with_margins, expected_analog_min_with_margins); +// EXPECT_EQ(updated_params.analog_max_with_margins, expected_analog_max_with_margins); +// EXPECT_EQ(updated_params.digital_min_with_margins, expected_digital_min_with_margins); +// EXPECT_EQ(updated_params.digital_max_with_margins, expected_digital_max_with_margins); + +// // Check combined disagreement tolerance +// EXPECT_FLOAT_EQ(updated_params.error_between_sensors_tolerance, +// expected_error_between_sensors_tolerance); +// } +