Skip to content

Commit

Permalink
merging with master
Browse files Browse the repository at this point in the history
  • Loading branch information
RCMast3r committed Oct 18, 2024
2 parents 2c78972 + 6c80919 commit 8b90cd4
Show file tree
Hide file tree
Showing 31 changed files with 317 additions and 246 deletions.
4 changes: 4 additions & 0 deletions .github/workflows/docs.yml
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,10 @@ jobs:
uses: mattnotmitt/[email protected]
with:
doxyfile-path: 'Doxyfile'


- name: Install dependencies
run: sudo apt-get update && sudo apt-get install -y graphviz

- name: Deploy to GitHub Pages
uses: peaceiris/actions-gh-pages@v3
Expand Down
4 changes: 2 additions & 2 deletions Doxyfile
Original file line number Diff line number Diff line change
Expand Up @@ -2481,7 +2481,7 @@ HIDE_UNDOC_RELATIONS = YES
# set to NO
# The default value is: NO.

HAVE_DOT = NO
HAVE_DOT = YES

# The DOT_NUM_THREADS specifies the number of dot invocations doxygen is allowed
# to run in parallel. When set to 0 doxygen will base this on the number of
Expand Down Expand Up @@ -2565,7 +2565,7 @@ GROUP_GRAPHS = YES
# The default value is: NO.
# This tag requires that the tag HAVE_DOT is set to YES.

UML_LOOK = NO
UML_LOOK = YES

# If the UML_LOOK tag is enabled, the fields and methods are shown inside the
# class node. If there are many fields or methods and many nodes the graph may
Expand Down
35 changes: 19 additions & 16 deletions lib/interfaces/include/MCUInterface.h
Original file line number Diff line number Diff line change
Expand Up @@ -7,18 +7,20 @@
#include "hytech.h"
#include "MessageQueueDefine.h"
#include "PedalsSystem.h"

const int DEFAULT_BMS_OK_READ = 17; // SHDN_D_READ
const int DEFAULT_BMS_SENSE_PIN = 16; // BMS_OK_SENSE
const int DEFAULT_IMD_OK_READ = 10; // SHDN_C_READ
const int DEFAULT_IMD_SENSE_PIN = 18; // OKHS_SENSE
const int DEFAULT_BSPD_OK_READ = 39; // SHDN_E_READ
const int DEFAULT_SOFTWARE_OK_READ = 25; // SHDN_F_READ Watchdog Combined
const int DEFAULT_BOTS_OK_READ = 24; // SHDN_B_READ
const int DEFAULT_BRB_OK_READ = 26; // SHDN_G_READ
const int DEFAULT_BRAKE_LIGHT_CTRL = 6;
const int DEFAULT_INVERTER_ENABLE = 9;
const int DEFAULT_INVERTER_24V_ENABLE = 7;
#include "SharedDataTypes.h"

const int DEFAULT_BMS_OK_READ = 17; // SHDN_D_READ
const int DEFAULT_BMS_SENSE_PIN = 16; // BMS_OK_SENSE
const int DEFAULT_IMD_OK_READ = 10; // SHDN_C_READ
const int DEFAULT_IMD_SENSE_PIN = 18; // OKHS_SENSE
const int DEFAULT_BSPD_OK_READ = 39; // SHDN_E_READ
const int DEFAULT_SOFTWARE_OK_READ = 25; // SHDN_F_READ Watchdog Combined
const int DEFAULT_BOTS_OK_READ = 24; // SHDN_B_READ
const int DEFAULT_BRB_OK_READ = 26; // SHDN_G_READ
const int DEFAULT_BRAKE_LIGHT_CTRL = 6;
const int DEFAULT_INVERTER_ENABLE = 9;
const int DEFAULT_INVERTER_24V_ENABLE = 7;
const int DEFAULT_BRAKE_PRESSURE_SENSOR_READ = 27; // Read pin for brake pressure sensor.

/// @brief specifically designed so that Walker would be happy
struct MainECUHardwareReadPins
Expand All @@ -35,10 +37,12 @@ struct MainECUHardwareReadPins
// inverter enable pins
int pin_inv_en;
int pin_inv_24V_en;
int pin_brake_pressure_sensor_read;
};

static const MainECUHardwareReadPins DEFAULT_PINS = {DEFAULT_BMS_OK_READ,DEFAULT_IMD_OK_READ, DEFAULT_BSPD_OK_READ, DEFAULT_SOFTWARE_OK_READ,
DEFAULT_BOTS_OK_READ, DEFAULT_BRB_OK_READ, DEFAULT_BRAKE_LIGHT_CTRL, DEFAULT_INVERTER_ENABLE, DEFAULT_INVERTER_24V_ENABLE};
DEFAULT_BOTS_OK_READ, DEFAULT_BRB_OK_READ, DEFAULT_BRAKE_LIGHT_CTRL, DEFAULT_INVERTER_ENABLE,
DEFAULT_INVERTER_24V_ENABLE, DEFAULT_BRAKE_PRESSURE_SENSOR_READ};

class MCUInterface
{
Expand Down Expand Up @@ -114,6 +118,7 @@ class MCUInterface
// Interfaces
void update_mcu_status_CAN_ams(bool is_critical);
void update_mcu_status_CAN_dashboard(bool is_active);
void update_brake_pressure_CAN();

/* Enqueue MCU_status CAN */
void enqueue_CAN_mcu_status();
Expand All @@ -123,9 +128,7 @@ class MCUInterface
int fsm_state,
bool inv_has_error,
bool software_is_ok,
int drive_mode,
int torque_mode,
float max_torque,
const TorqueControllerMuxStatus& tc_mux_status,
bool buzzer_is_on,
const PedalsSystemData_s &pedals_data,
bool pack_charge_is_critical,
Expand Down
24 changes: 21 additions & 3 deletions lib/interfaces/src/MCUInterface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -182,13 +182,25 @@ void MCUInterface::update_mcu_status_CAN_pedals(const PedalsSystemData_s &pedals
mcu_status_.no_brake_implausibility = !pedals.brakeImplausible;
mcu_status_.no_accel_or_brake_implausibility = !(pedals.brakeAndAccelPressedImplausibility);
}
void MCUInterface::update_brake_pressure_CAN()
{
BRAKE_PRESSURE_SENSOR_t brake_sensor_msg;
brake_sensor_msg.brake_sensor_analog_read = analogRead(pins_.pin_brake_pressure_sensor_read);

CAN_message_t msg;

msg.id = Pack_BRAKE_PRESSURE_SENSOR_hytech(&brake_sensor_msg, msg.buf, &msg.len, (uint8_t*) &msg.flags.extended);

uint8_t buf[sizeof(CAN_message_t)] = {};
memmove(buf, &msg, sizeof(CAN_message_t));
msg_queue_->push_back(buf, sizeof(CAN_message_t));
}

void MCUInterface::tick(int fsm_state,
bool inv_has_error,
bool software_is_ok,
int drive_mode,
int torque_mode,
float max_torque,

const TorqueControllerMuxStatus& tc_mux_status,
bool buzzer_is_on,
const PedalsSystemData_s &pedals_data,
bool pack_charge_is_critical,
Expand All @@ -199,12 +211,18 @@ void MCUInterface::tick(int fsm_state,
// Systems
update_mcu_status_CAN_drivetrain(inv_has_error);
update_mcu_status_CAN_safety(software_is_ok);

auto drive_mode = static_cast<int>(tc_mux_status.active_controller_mode);
auto torque_mode = static_cast<int>(tc_mux_status.active_torque_limit_enum);
auto max_torque = tc_mux_status.active_torque_limit_value;

update_mcu_status_CAN_TCMux(drive_mode, torque_mode, max_torque);
update_mcu_status_CAN_buzzer(buzzer_is_on);
update_mcu_status_CAN_pedals(pedals_data);
// External Interfaces
update_mcu_status_CAN_ams(pack_charge_is_critical);
update_mcu_status_CAN_dashboard(button_is_pressed);
update_brake_pressure_CAN();
// Internal values
update_mcu_status_CAN();
// Push into buffer
Expand Down
46 changes: 0 additions & 46 deletions lib/mock_interfaces/ParameterInterface.h

This file was deleted.

21 changes: 16 additions & 5 deletions lib/shared_data/include/SharedDataTypes.h
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@
using speed_rpm = float;
using torque_nm = float;

/// @brief Defines modes of torque limit to be processed in torque limit map for exact values.
enum class TorqueLimit_e
{
TCMUX_FULL_TORQUE = 0,
Expand Down Expand Up @@ -53,17 +54,25 @@ struct DrivetrainDynamicReport_s
float measuredTorqueCurrents[NUM_MOTORS];
float measuredMagnetizingCurrents[NUM_MOTORS];
};
/// @brief Stores setpoints for a command to the Drivetrain, containing speed and torque setpoints for each motor. These setpoints are defined in the torque controllers cycled by the TC Muxer.
/// The Speeds unit is rpm and are the targeted speeds for each wheel of the car.
/// The torques unit is nm and is the max torque requested from the inverter to reach such speeds.
/// One can use the arrays with FR(Front Left), FL(Front Left), RL(Rear Left), RR(Rear Right) to access or modify the respective set points. eg. speeds_rpm[FR] = 0.0;
/// Their indexes are defined in utility.h as follows: FL = 0, FR = 1, RL = 2, RR = 3.
struct DrivetrainCommand_s
{
float speeds_rpm[NUM_MOTORS];
float torqueSetpoints[NUM_MOTORS]; // FIXME: misnomer. This represents the magnitude of the torque the inverter can command to reach the commanded speed setpoint
float inverter_torque_limit[NUM_MOTORS];
};

/// @brief Packages drivetrain command with ready boolean to give feedback on controller successfully evaluating
/// @note returned by all car controllers evaluate method
struct TorqueControllerOutput_s
{
DrivetrainCommand_s command;
bool ready;
};

struct VectornavData_s
{
float velocity_x;
Expand All @@ -84,6 +93,7 @@ struct VectornavData_s
xyz_vec<float> angular_rates;
};

/// @brief Defines errors for TC Mux to use to maintain system safety
enum class TorqueControllerMuxError
{
NO_ERROR = 0,
Expand All @@ -93,12 +103,13 @@ enum class TorqueControllerMuxError
ERROR_CONTROLLER_NULL_POINTER =4
};

/// @brief packages TC Mux indicators: errors, mode, torque limit, bypass
struct TorqueControllerMuxStatus
{
TorqueControllerMuxError current_error;
ControllerMode_e current_controller_mode_;
TorqueLimit_e current_torque_limit_enum;
float current_torque_limit_value;
TorqueControllerMuxError active_error;
ControllerMode_e active_controller_mode;
TorqueLimit_e active_torque_limit_enum;
float active_torque_limit_value;
bool output_is_bypassing_limits;
};

Expand Down
12 changes: 11 additions & 1 deletion lib/systems/include/BaseController.h
Original file line number Diff line number Diff line change
@@ -1,16 +1,26 @@
#ifndef BASECONTROLLER
#define BASECONTROLLER
#include "SharedDataTypes.h"

/// @brief defines namespace for definition of a drivetrain command with no torque for clearer code in the Muxer
/// This can be used to define other specific car states in the future
namespace BaseControllerParams
{
const DrivetrainCommand_s TC_COMMAND_NO_TORQUE = {
.speeds_rpm = {0.0, 0.0, 0.0, 0.0},
.torqueSetpoints = {0.0, 0.0, 0.0, 0.0}};
.inverter_torque_limit = {0.0, 0.0, 0.0, 0.0}};

}
/// @brief Base class for all controllers, which define drivetrain command containing different variations of
/// speed set points and necessary torque set points to be requested from the motors in order to achieve said speeds.
/// required method(s): evaluate
class Controller
{
public:
/// @brief This mehod must be implemented by every controller in the Tc Muxer. This is called in the Muxer whenever the drivetrain command is obtained.
/// @ref TorqueControllerMux.cpp to see that in every tick of the system, the active controller must be ticked through this method
/// @param state with all sensor information to properly define torque set points
/// @return TorqueControllerOutput_s This is a Drivetrain command passed along with a state boolean to ensure car controllers are working properly
virtual TorqueControllerOutput_s evaluate(const SharedCarState_s &state) = 0;
};

Expand Down
26 changes: 26 additions & 0 deletions lib/systems/include/BaseLaunchController.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,15 @@
#include "BaseController.h"
#include <algorithm>
#include <math.h>

/// @brief Modes to define launch behavior, where each one waits for acceleration request threshold to move to next mode
/// LAUNCH_NOT_READY keeps speed at 0 and makes sure pedals are not pressed, the launch controller begins in this state
/// From this state the launch can only progress forwards to LAUNCH_READY
/// LAUNCH_READY keeps speed at 0, below the speed threshold(5 m/s) and makes sure brake is not pressed harder than the threshold of .2(20% pushed)
/// From this state the launch can progress forwards to LAUNCHING according to the two conditions defined above or backwards to LAUNCH_NOT_READY if those conditions are not met
/// LAUNCHING uses respective algorithm to set speed set point and requests torque from motors to reach it
/// From this state the launch can fully begin and set speed set points above 0.0 m/s and the maximum available torque can be requested from the inverters
/// This launch state can be terminated if the brake is pressed above the threshold(.2(20% pushed)) or if the accelerator is not pressed enough (<= .5(50% pushed))
enum class LaunchStates_e
{
NO_LAUNCH_MODE,
Expand All @@ -12,6 +21,7 @@ enum class LaunchStates_e
LAUNCHING
};

/// @brief contains constants for tick behavior/progression(_threshold variables used to determine when to move to the next step) and defaults(DEFAULT_LAUNCH_SPEED_TARGET)
namespace BaseLaunchControllerParams
{
const int16_t DEFAULT_LAUNCH_SPEED_TARGET = 1500;
Expand All @@ -37,19 +47,35 @@ class BaseLaunchController : public virtual Controller
int16_t init_speed_target_ = 0;

public:
/// @brief Constructor for parent launch controller
/// @param initial_speed_target used only in simple launch controller algorithm
/// @note requires one method: calc_launch_algo
BaseLaunchController(int16_t initial_speed_target)
: init_speed_target_(initial_speed_target)
{
writeout_.command = BaseControllerParams::TC_COMMAND_NO_TORQUE;
writeout_.ready = true;
}

/// @brief ticks launch controller to progress through launch states when conditions are met. The conditions are explained above the launch states enum.
/// all launch controllers use this class' implementation of tick.
/// tick conatains the current system tick controlled by main.cpp
/// pedalsData conatins the brake and accelerator values
/// wheel_rpms[] contains how fast each wheel is spinning, order of wheels in this array is defined in SharedDataTypes.h and Utility.h
/// vn_data contains vector states of the car that will be provided to the calc_launch_algo method called in the LAUNCHING state of this set of modes
void tick(const SysTick_s &tick,
const PedalsSystemData_s &pedalsData,
const float wheel_rpms[],
const VectornavData_s &vn_data);
LaunchStates_e get_launch_state() { return launch_state_; }
/// @brief calculates how speed target (the speed the car is trying to achieve during launch) is set and/or increased during launch
/// This updates internal speed target variable launch_speed_target_
/// @param vn_data vector data needed for calulations eg. speed and coordinates
/// @note defines important variation in launch controller tick/evaluation as the launch controllers share a tick method defined in this parent class implementation
/// @note all launch algorithms are implemented in LaunchControllerAlgos.cpp
virtual void calc_launch_algo(const VectornavData_s &vn_data) = 0;
/// @brief all launch controllers share the same evaluate method implemented in this class implementation.
/// @note refer to parent class for function documentation
TorqueControllerOutput_s evaluate(const SharedCarState_s &state) override;
};
#endif // __BASELAUNCHCONTROLLER_H__
12 changes: 10 additions & 2 deletions lib/systems/include/CASESystem.h
Original file line number Diff line number Diff line change
Expand Up @@ -148,10 +148,18 @@ class CASESystem

DrivetrainCommand_s get_current_drive_command() { return current_command_; }

/// @brief uses pedal data to determine the torque to be requested from the motors
/// pedals_data.accelPercent - pedals_data.regenPercent -> where accelpercent is to what percent the acellerator is pushed and the regen percent is the amount of regenerative braking currently applied
/// @param pedals_data has accel and regen percent
/// @param max_torque not used right now
/// @param max_regen_torque used for calculation of torque request
/// @param max_rpm not used right now
/// @return float representing the calculated request
float calculate_torque_request(const PedalsSystemData_s &pedals_data, float max_torque, float max_regen_torque, float max_rpm);
/// @brief configuration function to determine what CASE is using / turn on and off different features within CASE
/// @param config the configuration struct we will be setting

/// @brief retrieves rpm setpoint based on final torque value
/// @param float final_torque
/// @return The maximum RPM from the case configuration if torque is positive, otherwise 0.
float get_rpm_setpoint(float final_torque)
{
if (final_torque > 0)
Expand Down
8 changes: 4 additions & 4 deletions lib/systems/include/CASESystem.tpp
Original file line number Diff line number Diff line change
Expand Up @@ -268,10 +268,10 @@ DrivetrainCommand_s CASESystem<message_queue>::evaluate(

DrivetrainCommand_s command;

command.torqueSetpoints[0] = res.FinalTorqueFL;
command.torqueSetpoints[1] = res.FinalTorqueFR;
command.torqueSetpoints[2] = res.FinalTorqueRL;
command.torqueSetpoints[3] = res.FinalTorqueRR;
command.inverter_torque_limit[0] = res.FinalTorqueFL;
command.inverter_torque_limit[1] = res.FinalTorqueFR;
command.inverter_torque_limit[2] = res.FinalTorqueRL;
command.inverter_torque_limit[3] = res.FinalTorqueRR;

command.speeds_rpm[0] = get_rpm_setpoint(res.FinalTorqueFL);
command.speeds_rpm[1] = get_rpm_setpoint(res.FinalTorqueFR);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,14 +5,18 @@
#include "CASESystem.h"

template <typename message_queue>
/// @brief makes CASE system a part of Controller hierarchy for use in TC Mux
class TorqueControllerCASEWrapper : public virtual Controller
{
public:
TorqueControllerCASEWrapper() = delete;

/// @param case_instance requires current state estimator instance to give access of the CASE instance to this specific controller so that it can update/control it.
/// @note This also ensures there are not duplicates of this system for safety.
TorqueControllerCASEWrapper(CASESystem<message_queue> *case_instance) : case_instance_(case_instance)
{
}
/// @brief packages CASE system command into Torque Controller Output
/// @param state this state is updated by the CASE system in main repeatedly
TorqueControllerOutput_s evaluate(const SharedCarState_s &state) override
{
DrivetrainCommand_s curr_cmd = case_instance_->get_current_drive_command();
Expand Down
Loading

0 comments on commit 8b90cd4

Please sign in to comment.