From 5a70f3983eca64443d30115dd711191fe1d75a9f Mon Sep 17 00:00:00 2001 From: Justin Hwang Date: Thu, 8 Aug 2024 07:10:20 -0700 Subject: [PATCH] Updated documentation/comments/style for Dashboard --- lib/interfaces/include/AMSInterface.h | 2 +- lib/interfaces/include/DashboardInterface.h | 207 ++++++++++++++------ lib/interfaces/src/DashboardInterface.cpp | 108 +++++----- src/main.cpp | 2 +- 4 files changed, 198 insertions(+), 121 deletions(-) diff --git a/lib/interfaces/include/AMSInterface.h b/lib/interfaces/include/AMSInterface.h index 5d0d3e4ef..afddedfdd 100644 --- a/lib/interfaces/include/AMSInterface.h +++ b/lib/interfaces/include/AMSInterface.h @@ -1,7 +1,7 @@ #ifndef __AMSINTERFACE_H__ #define __AMSINTERFACE_H__ -/* Library Include s*/ +/* Library Includes */ #include "FlexCAN_T4.h" #include "HyTech_CAN.h" #include "SysClock.h" diff --git a/lib/interfaces/include/DashboardInterface.h b/lib/interfaces/include/DashboardInterface.h index 494e83384..b6667fd48 100644 --- a/lib/interfaces/include/DashboardInterface.h +++ b/lib/interfaces/include/DashboardInterface.h @@ -1,19 +1,23 @@ #ifndef __DASHBOARDINTERFACE_H__ #define __DASHBOARDINTERFACE_H__ -#include "MessageQueueDefine.h" +/* Library Includes */ #include "FlexCAN_T4.h" #include "hytech.h" + +/* Interface Includes */ #include "MCUInterface.h" #include "InverterInterface.h" +/* System Includes */ +#include "MessageQueueDefine.h" #include "TorqueControllers.h" -/* - Enum for the car's torque limits - MOVE ME! - ideally into a TorqueControllerDefs.h file - to prevent circular dependencies -*/ +/** + * Enum for the car's torque limits. + * MOVE ME! - ideally into a TorqueControllerDefs.h file + * to prevent circular dependencies + */ enum class TorqueLimit_e { TCMUX_LOW_TORQUE = 0, @@ -22,7 +26,9 @@ enum class TorqueLimit_e TCMUX_NUM_TORQUE_LIMITS = 3, }; -/* Enum for the modes on the dial, corresponds directly to dial index pos. */ +/** + * Enum for the modes on the dial, corresponds directly to dial index pos. + */ enum class DialMode_e { /* No torque vectoring */ @@ -37,7 +43,9 @@ enum class DialMode_e MODE_5, }; -/* Enum for defined LED colors. ON will be LED's default color on dashboard*/ +/** + * Enum for defined LED colors. ON will be LED's default color on dashboard + */ enum class LEDColors_e { OFF, @@ -46,7 +54,10 @@ enum class LEDColors_e RED, }; -/* Enum to index the LED array. Each LED in the CAN message is represented in no particular order. */ +/** + * Enum to index the LED array. Each LED in the CAN message is represented in + * no particular order. + */ enum class DashLED_e { BOTS_LED, @@ -63,7 +74,9 @@ enum class DashLED_e AMS_LED, }; -/* Struct holding the state of Dashboard buttons */ +/** + * Struct holding the state of Dashboard buttons + */ struct DashButtons_s { bool start; @@ -77,14 +90,14 @@ struct DashButtons_s bool right_shifter; }; -/* Struct holding all data for the DashboardInterface (inputs and outputs) */ +/** + * Struct holding all data for the DashboardInterface (inputs and outputs) + */ struct DashComponentInterface_s { /* READ DATA */ - // enum for dial position read by controller mux DialMode_e dial_mode; DialMode_e cur_dial_mode; - // Buttons struct for better naming DashButtons_s button; bool ssok; // safety system OK (IMD?) RENAME bool shutdown; @@ -97,47 +110,58 @@ struct DashComponentInterface_s uint8_t LED[12] = {}; }; -/* - The DashboardInterface is an interface that handles all data to and from the dashboard. - Through a set of setters and getters (not explicitly named set/get) the state machine, - other interfaces, and systems can update the information on the dashboard. - Currently this is written to be a 1 to 1 representation of the current state of the dashboard, - almost no display logic for the below basic components is handled by the dash. -*/ +/** + * The DashboardInterface is an interface that handles all data to and from the dashboard. + * Through a set of setters and getters (not explicitly named set/get) the state machine, + * other interfaces, and systems can update the information on the dashboard. + * Currently this is written to be a 1 to 1 representation of the current state of the dashboard, + * almost no display logic for the below basic components is handled by the dash. + */ class DashboardInterface { private: - /* Pointer to the circular buffer to write new messages */ + /** + * Pointer to the circular buffer to write new messages. + */ CANBufferType *msg_queue_; - /* The instantiated data struct used to access data by member functions */ - DashComponentInterface_s _data; -public: - /*! - Constructor for new DashboardInterface, All that it is inited with - is the pointer to the telem circular buffer that is used to write new messages + /** + * The instantiated data struct used to access data by member function + */ + DashComponentInterface_s data_; - @param msg_output_queue Pointer to the telem CAN circular buffer - */ +public: + /** + * Constructor for new DashboardInterface. The Dashboard is only initialized with + * a the pointer to the telem CAN buffer to write new messages. + * + * @param msg_output_queue Pointer to the telem CAN circular buffer + */ DashboardInterface(CANBufferType *msg_output_queue) { msg_queue_ = msg_output_queue; }; - /*! - read function will take in a reference to a new CAN message, unpack it, - and will store all of the information into the DashComponentInterface for later access - @param can_msg is the reference to a new CAN message CAN_message_t - */ + /** + * This read() function takes in a reference to a new CAN message, unpack it and + * stores all of the information into the DashComponentInterface for later access. + * + * @param can_msg is the reference to a new CAN message CAN_message_t + */ void read(const CAN_message_t &can_msg); - /* write function will Pack a message based on the current data in the interface and push it to the tx buffer */ + /** + * Write function packs a message based on the current data in the interface and + * pushes it to the TX buffer. + * + * @return The CAN message that the write() function just pushed to the buffer. + */ CAN_message_t write(); - /* - Tick DashboardInterface at 10hz to gather data and send CAN message - */ - void tick10(MCUInterface* mcu, + /** + * Tick DashboardInterface at 10hz to gather data and send a new CAN message. + */ + void tick(MCUInterface* mcu, int car_state, bool buzzer, bool drivetrain_error, @@ -147,46 +171,107 @@ class DashboardInterface int launch_state, DialMode_e dial_mode); - /*! - getter for the dashboard's current dial position (drive profile) - @return returns a DialMode_e enum with the current dial position - */ + /** + * Getter for the dashboard's current dial position (drive profile). + * @return returns a DialMode_e enum with the current dial position. + */ DialMode_e getDialMode(); - /* gets whether the safety system is ok (wtf is a safety system - rename this)*/ + /** + * Returns whether the safety system is OK. + * Note: I don't think this is currently used, as it is never set in Dashboard code. + */ bool safetySystemOK(); - /* getter for the start button */ + /** + * Getter for the start button. + * @return True if the button is currently pressed, false otherwise. + */ bool startButtonPressed(); - /* getter for the mark button */ + + /** + * Getter for the mark button. + * @return True if the button is currently pressed, false otherwise. + */ bool specialButtonPressed(); - /* getter for the torque button (does not currently exist on dash ) */ + + /** + * Getter for the torque button. + * @return True if the button is currently pressed, false otherwise. + */ bool torqueModeButtonPressed(); - /* getter for the inverter reset button (clears error codes ) */ + + /** + * Getter for the inverter reset button (clears error codes). + * @return True if the button is currently pressed, false otherwise. + */ bool inverterResetButtonPressed(); - /* getter for the launch control button */ + + /** + * Getter for the launch control button. + * Note: I don't think this is currently used, as it is never set in Dashboard code. + * @return True if the button is currently pressed, false otherwise. + */ bool launchControlButtonPressed(); - /* getter for the torque mode/level button */ + + /** + * Getter for the torque mode/level button. + * @return True if the button is currently pressed, false otherwise. + */ bool torqueLoadingButtonPressed(); - /* getter for the dimmer button (this logic handled on dash ) */ + + /** + * Getter for the dimmer button (this logic handled on dash). + * @return True if the button is currently pressed, false otherwise. + */ bool nightModeButtonPressed(); + + /** + * Getter for the left paddle shifter. + * @return True if the button is currently pressed, false otherwise. + */ bool leftShifterButtonPressed(); + + /** + * Getter for the right paddle shifter. + * @return True if the button is currently pressed, false otherwise. + */ bool rightShifterButtonPressed(); - /* getter for the current shutdown threshold on the dashboard*/ + + /** + * Getter for the current shutdown threshold on the dashboard. + * Note: I don't think this is currently used, as it is never set in Dashboard code. + * that sets this bit. + */ bool shutdownHAboveThreshold(); - /* setter for the buzzer */ + + /** + * Setter for the buzzer. The Dashboard itself handles the timer code, so even if + * the soundBuzzer(true) function is only called for one CAN frame, the Dashboard + * will still ensure that the buzzer sounds for the full duration. + * + * @param s True to start the buzzer, false otherwise. + */ void soundBuzzer(bool s); - /* getter for the buzzer */ - bool checkBuzzer(); - // LEDs in same order as dash rev. 7 placement + /** + * Getter for the current buzzer state. Notably, even if soundBuzzer(false) is called, + * the Dashboard ensures that the buzzer sounds for the full duration. In that state, + * even though soundBuzzer(false) is sent over CAN, checkBuzzer() will still return + * true if the buzzer is currently sounding. + * + * @return True if the buzzer is currently sounding, according to the Dash. False otherwise. + */ + bool checkBuzzer(); - /*! - setter for the dash LEDs - @param led DashLED_e enum that corresponds to the LED's value in the LED array - @param color LEDColors_e enum that corresponds to the color/state of the set LED - */ + /** + * Setter for the dash LEDs . + * + * @param led DashLED_e enum that corresponds to the LED's value in the LED array + * @param color LEDColors_e enum that corresponds to the color/state of the set LED + */ void setLED(DashLED_e led, LEDColors_e color); + }; #endif /* __DASHBOARDINTERFACE_H__ */ diff --git a/lib/interfaces/src/DashboardInterface.cpp b/lib/interfaces/src/DashboardInterface.cpp index de22b7c1b..abeedd456 100644 --- a/lib/interfaces/src/DashboardInterface.cpp +++ b/lib/interfaces/src/DashboardInterface.cpp @@ -3,57 +3,56 @@ void DashboardInterface::read(const CAN_message_t &can_msg) { + // Reads the current dashboard from the CAN buffer DASHBOARD_STATE_t dash_state; Unpack_DASHBOARD_STATE_hytech(&dash_state, can_msg.buf, can_msg.len); - _data.dial_mode = static_cast(dash_state.dial_state); + // Writes the data from the CAN buffer into the local struct. + data_.dial_mode = static_cast(dash_state.dial_state); - _data.ssok = dash_state.ssok_above_threshold; - _data.shutdown = dash_state.shutdown_h_above_threshold; + data_.ssok = dash_state.ssok_above_threshold; //not set in Dashboard code + data_.shutdown = dash_state.shutdown_h_above_threshold; //not set in Dashboard code - _data.button.start = dash_state.start_button; - _data.button.mark = dash_state.mark_button; - _data.button.mode = dash_state.mode_button; - _data.button.mc_cycle = dash_state.motor_controller_cycle_button; - _data.button.launch_ctrl = dash_state.launch_ctrl_button; - _data.button.torque_mode = dash_state.torque_mode_button; - _data.button.led_dimmer = dash_state.led_dimmer_button; - _data.button.left_shifter = dash_state.left_shifter_button; - _data.button.right_shifter = dash_state.right_shifter_button; + data_.button.start = dash_state.start_button; + data_.button.mark = dash_state.mark_button; + data_.button.mode = dash_state.mode_button; //not set in Dashboard code + data_.button.mc_cycle = dash_state.motor_controller_cycle_button; + data_.button.launch_ctrl = dash_state.launch_ctrl_button; //not set in Dashboard code + data_.button.torque_mode = dash_state.torque_mode_button; + data_.button.led_dimmer = dash_state.led_dimmer_button; + data_.button.left_shifter = dash_state.left_shifter_button; + data_.button.right_shifter = dash_state.right_shifter_button; - _data.buzzer_state = dash_state.drive_buzzer; + data_.buzzer_state = dash_state.drive_buzzer; } CAN_message_t DashboardInterface::write() { + // Creating struct to populate with data DASHBOARD_MCU_STATE_t dash_mcu_state; - dash_mcu_state.drive_buzzer = _data.buzzer_cmd; - - dash_mcu_state.dial_state = static_cast(_data.cur_dial_mode); - - // TODO: use logic as to not write data for LEDs that have not changed - dash_mcu_state.launch_control_led = _data.LED[static_cast(DashLED_e::LAUNCH_CONTROL_LED)]; - dash_mcu_state.mode_led = _data.LED[static_cast(DashLED_e::MODE_LED)]; - dash_mcu_state.mechanical_brake_led = _data.LED[static_cast(DashLED_e::MECH_BRAKE_LED)]; - dash_mcu_state.cockpit_brb_led = _data.LED[static_cast(DashLED_e::COCKPIT_BRB_LED)]; - dash_mcu_state.inertia_status_led = _data.LED[static_cast(DashLED_e::INERTIA_LED)]; - dash_mcu_state.start_status_led = _data.LED[static_cast(DashLED_e::START_LED)]; - dash_mcu_state.motor_controller_error_led = _data.LED[static_cast(DashLED_e::MC_ERROR_LED)]; - - dash_mcu_state.bots_led = _data.LED[static_cast(DashLED_e::BOTS_LED)]; - dash_mcu_state.imd_led = _data.LED[static_cast(DashLED_e::IMD_LED)]; - dash_mcu_state.ams_led = _data.LED[static_cast(DashLED_e::AMS_LED)]; - - dash_mcu_state.glv_led = _data.LED[static_cast(DashLED_e::GLV_LED)]; - dash_mcu_state.pack_charge_led = _data.LED[static_cast(DashLED_e::CRIT_CHARGE_LED)]; + + dash_mcu_state.drive_buzzer = data_.buzzer_cmd; + dash_mcu_state.dial_state = static_cast(data_.cur_dial_mode); + + // Writing LEDs + dash_mcu_state.launch_control_led = data_.LED[static_cast(DashLED_e::LAUNCH_CONTROL_LED)]; + dash_mcu_state.mode_led = data_.LED[static_cast(DashLED_e::MODE_LED)]; + dash_mcu_state.mechanical_brake_led = data_.LED[static_cast(DashLED_e::MECH_BRAKE_LED)]; + dash_mcu_state.cockpit_brb_led = data_.LED[static_cast(DashLED_e::COCKPIT_BRB_LED)]; + dash_mcu_state.inertia_status_led = data_.LED[static_cast(DashLED_e::INERTIA_LED)]; + dash_mcu_state.start_status_led = data_.LED[static_cast(DashLED_e::START_LED)]; + dash_mcu_state.motor_controller_error_led = data_.LED[static_cast(DashLED_e::MC_ERROR_LED)]; + dash_mcu_state.bots_led = data_.LED[static_cast(DashLED_e::BOTS_LED)]; + dash_mcu_state.imd_led = data_.LED[static_cast(DashLED_e::IMD_LED)]; + dash_mcu_state.ams_led = data_.LED[static_cast(DashLED_e::AMS_LED)]; + dash_mcu_state.glv_led = data_.LED[static_cast(DashLED_e::GLV_LED)]; + dash_mcu_state.pack_charge_led = data_.LED[static_cast(DashLED_e::CRIT_CHARGE_LED)]; CAN_message_t can_msg; auto id = Pack_DASHBOARD_MCU_STATE_hytech(&dash_mcu_state, can_msg.buf, &can_msg.len, (uint8_t*) &can_msg.flags.extended); can_msg.id = id; - // this circular buffer implementation requires that you push your data in a array buffer - // all this does is put the msg into a uint8_t buffer and pushes it onto the queue uint8_t buf[sizeof(CAN_message_t)] = {}; memmove(buf, &can_msg, sizeof(CAN_message_t)); msg_queue_->push_back(buf, sizeof(CAN_message_t)); @@ -62,14 +61,12 @@ CAN_message_t DashboardInterface::write() } -//figure out how to set enumed led colors or send (0,255 value) void DashboardInterface::setLED(DashLED_e led, LEDColors_e color) { - - _data.LED[static_cast(led)] = static_cast(color); + data_.LED[static_cast(led)] = static_cast(color); } -void DashboardInterface::tick10(MCUInterface* mcu, +void DashboardInterface::tick(MCUInterface* mcu, int car_state, bool buzzer, bool drivetrain_error, @@ -80,7 +77,7 @@ void DashboardInterface::tick10(MCUInterface* mcu, DialMode_e dial_mode) { - _data.cur_dial_mode = dial_mode; + data_.cur_dial_mode = dial_mode; soundBuzzer(buzzer); @@ -122,26 +119,21 @@ void DashboardInterface::tick10(MCUInterface* mcu, } uint16_t scaled_cell_voltage = (uint16_t)map((uint32_t)(min_cell_voltage*1000), 3300, 4200, 0, 255);// scale voltage - _data.LED[static_cast(DashLED_e::CRIT_CHARGE_LED)] = std::max(0, std::min((int)scaled_cell_voltage, 255));// clamp voltage - // _data.LED[DashLED_e::GLV_LED] = (uint8_t)map(glv_voltage.raw) + data_.LED[static_cast(DashLED_e::CRIT_CHARGE_LED)] = std::max(0, std::min((int)scaled_cell_voltage, 255));// clamp voltage write(); } -DialMode_e DashboardInterface::getDialMode() {return _data.dial_mode;} - -bool DashboardInterface::startButtonPressed() {return _data.button.start;} -bool DashboardInterface::specialButtonPressed() {return _data.button.mark;} -bool DashboardInterface::torqueModeButtonPressed() {return _data.button.torque_mode;} -bool DashboardInterface::inverterResetButtonPressed() {return _data.button.mc_cycle;} -bool DashboardInterface::launchControlButtonPressed() {return _data.button.launch_ctrl;} -bool DashboardInterface::nightModeButtonPressed() {return _data.button.led_dimmer;} -bool DashboardInterface::leftShifterButtonPressed() {return _data.button.left_shifter;} -bool DashboardInterface::rightShifterButtonPressed() {return _data.button.right_shifter;} - -bool DashboardInterface::safetySystemOK() {return _data.ssok;} -bool DashboardInterface::shutdownHAboveThreshold() {return _data.shutdown;} - -void DashboardInterface::soundBuzzer(bool state) {_data.buzzer_cmd = state;} -bool DashboardInterface::checkBuzzer() {return _data.buzzer_state;} - +DialMode_e DashboardInterface::getDialMode() {return data_.dial_mode;} +bool DashboardInterface::startButtonPressed() {return data_.button.start;} +bool DashboardInterface::specialButtonPressed() {return data_.button.mark;} +bool DashboardInterface::torqueModeButtonPressed() {return data_.button.torque_mode;} +bool DashboardInterface::inverterResetButtonPressed() {return data_.button.mc_cycle;} +bool DashboardInterface::launchControlButtonPressed() {return data_.button.launch_ctrl;} +bool DashboardInterface::nightModeButtonPressed() {return data_.button.led_dimmer;} +bool DashboardInterface::leftShifterButtonPressed() {return data_.button.left_shifter;} +bool DashboardInterface::rightShifterButtonPressed() {return data_.button.right_shifter;} +bool DashboardInterface::safetySystemOK() {return data_.ssok;} +bool DashboardInterface::shutdownHAboveThreshold() {return data_.shutdown;} +void DashboardInterface::soundBuzzer(bool state) {data_.buzzer_cmd = state;} +bool DashboardInterface::checkBuzzer() {return data_.buzzer_state;} \ No newline at end of file diff --git a/src/main.cpp b/src/main.cpp index bbb8100ae..df415a608 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -592,7 +592,7 @@ void tick_all_interfaces(const SysTick_s ¤t_system_tick) if (t.trigger10) // 10Hz { - dashboard.tick10( + dashboard.tick( &main_ecu, int(fsm.get_state()), buzzer.buzzer_is_on(),