Skip to content

Commit

Permalink
Updated documentation/comments/style for Dashboard
Browse files Browse the repository at this point in the history
  • Loading branch information
jhwang04 committed Aug 8, 2024
1 parent fc58ada commit 5a70f39
Show file tree
Hide file tree
Showing 4 changed files with 198 additions and 121 deletions.
2 changes: 1 addition & 1 deletion lib/interfaces/include/AMSInterface.h
Original file line number Diff line number Diff line change
@@ -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"
Expand Down
207 changes: 146 additions & 61 deletions lib/interfaces/include/DashboardInterface.h
Original file line number Diff line number Diff line change
@@ -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,
Expand All @@ -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 */
Expand All @@ -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,
Expand All @@ -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,
Expand All @@ -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;
Expand All @@ -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;
Expand All @@ -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,
Expand All @@ -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__ */
Loading

0 comments on commit 5a70f39

Please sign in to comment.