Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Tc mux docs #106

Open
wants to merge 12 commits into
base: master
Choose a base branch
from
6 changes: 3 additions & 3 deletions lib/interfaces/src/MCUInterface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -212,9 +212,9 @@ void MCUInterface::tick(int fsm_state,
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.current_controller_mode);
auto torque_mode = static_cast<int>(tc_mux_status.current_torque_limit_enum);
auto max_torque = tc_mux_status.current_torque_limit_value;
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);
Expand Down
21 changes: 16 additions & 5 deletions lib/shared_data/include/SharedDataTypes.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
#include "SysClock.h"
#include "SharedFirmwareTypes.h"

/// @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 @@ -49,17 +50,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 @@ -80,6 +89,7 @@ struct VectornavData_s
xyz_vec<float> angular_rates;
};

/// @brief Defines errors for TC Mux to use to maintain system safety
Comerm28 marked this conversation as resolved.
Show resolved Hide resolved
enum class TorqueControllerMuxError
{
NO_ERROR = 0,
Expand All @@ -89,12 +99,13 @@ enum class TorqueControllerMuxError
ERROR_CONTROLLER_NULL_POINTER =4
};

/// @brief packages TC Mux indicators: errors, mode, torque limit, bypass
Comerm28 marked this conversation as resolved.
Show resolved Hide resolved
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
Comerm28 marked this conversation as resolved.
Show resolved Hide resolved
/// 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
Comerm28 marked this conversation as resolved.
Show resolved Hide resolved
/// 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;
Comerm28 marked this conversation as resolved.
Show resolved Hide resolved
/// @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
Comerm28 marked this conversation as resolved.
Show resolved Hide resolved
/// 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
6 changes: 5 additions & 1 deletion lib/systems/include/Controllers/CASEControllerWrapper.h
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
6 changes: 6 additions & 0 deletions lib/systems/include/Controllers/LoadCellVectoringController.h
Original file line number Diff line number Diff line change
Expand Up @@ -57,12 +57,18 @@ class TorqueControllerLoadCellVectoring : public virtual Controller
writeout_.command = BaseControllerParams::TC_COMMAND_NO_TORQUE;
writeout_.ready = false;
}
/// @brief default contructor with balanced default values: rearTorqueScale = 1.0, regenTorqueScale = 1.0
TorqueControllerLoadCellVectoring() : TorqueControllerLoadCellVectoring(1.0, 1.0) {}

/// @brief Calculates speed set point based on normal force applied to wheels individually
/// @param SysTick_s &tick
/// @param PedalsSystemData_s &pedalsData
/// @param LoadCellInterfaceOutput_s &loadCellData
void tick(
const SysTick_s &tick,
const PedalsSystemData_s &pedalsData,
const LoadCellInterfaceOutput_s &loadCellData);
/// @note refer to parent class for function documentation
TorqueControllerOutput_s evaluate(const SharedCarState_s &state) override;
};

Expand Down
4 changes: 2 additions & 2 deletions lib/systems/include/Controllers/LookupLaunchController.h
Original file line number Diff line number Diff line change
Expand Up @@ -22,9 +22,9 @@ class TorqueControllerLookupLaunch : public virtual BaseLaunchController
*/
Comerm28 marked this conversation as resolved.
Show resolved Hide resolved
TorqueControllerLookupLaunch(int16_t initial_speed_target)
: BaseLaunchController(initial_speed_target) {}

/// @brief default constructor for slip launch controller: DEFAULT_LAUNCH_SPEED_TARGET = 1500(rpm)
TorqueControllerLookupLaunch() : TorqueControllerLookupLaunch(LookupLaunchControllerParams::DEFAULT_LAUNCH_SPEED_TARGET) {}

/// @brief increases speed target based on distance from start to ensure the speed target is progressing as the car begins to move
void calc_launch_algo(const VectornavData_s &vn_data) override;
};

Expand Down
4 changes: 3 additions & 1 deletion lib/systems/include/Controllers/SimpleController.h
Original file line number Diff line number Diff line change
Expand Up @@ -28,8 +28,10 @@ class TorqueControllerSimple : public Controller
writeout_.command = BaseControllerParams::TC_COMMAND_NO_TORQUE;
writeout_.ready = true;
}

/// @brief calculates torque output based off max torque and simple torque scaling metric defined in constructor and adjusts writeout_ accordingly
/// @param pedalsData controller calculates acceleration request from the pedals based off of this data
void tick(const PedalsSystemData_s &pedalsData);
/// @note refer to parent class for function documentation
TorqueControllerOutput_s evaluate(const SharedCarState_s &state) override;
};

Expand Down
9 changes: 5 additions & 4 deletions lib/systems/include/Controllers/SimpleLaunchController.h
Original file line number Diff line number Diff line change
Expand Up @@ -19,18 +19,19 @@ class TorqueControllerSimpleLaunch : public virtual BaseLaunchController
public:
/*!
SIMPLE LAUNCH CONTROLLER
This launch controller is based off of a specified launch rate and an initial speed target
It will ramp up the speed target linearlly over time to accelerate
@brief this launch controller is based off of a specified launch rate and an initial speed target
It will ramp up the speed target linearly over time to accelerate
@param launch_rate specified launch rate in m/s^2
@param initial_speed_target the initial speed commanded to the wheels
*/
TorqueControllerSimpleLaunch(float launch_rate, int16_t initial_speed_target)
: BaseLaunchController(initial_speed_target),
launch_rate_target_(launch_rate) {}


/// @brief base constructor with default values: Default_Launch_Rate = 11.76, DEFAULT_LAUNCH_SPEED_TARGET = 1500(rpm)
TorqueControllerSimpleLaunch() : TorqueControllerSimpleLaunch(SLParams::DEFAULT_LAUNCH_RATE, SLParams::DEFAULT_LAUNCH_SPEED_TARGET) {}

/// @brief Increases speed target during launch linearly based off launch rate provided in the constructor
/// @param vn_data this data is not necessary for this controller but is supplied according to the interface
void calc_launch_algo(const VectornavData_s &vn_data) override;
};
#endif // __SIMPLELAUNCHCONTROLLER_H__
5 changes: 3 additions & 2 deletions lib/systems/include/Controllers/SlipLaunchController.h
Original file line number Diff line number Diff line change
Expand Up @@ -24,9 +24,10 @@ class TorqueControllerSlipLaunch : public virtual BaseLaunchController
TorqueControllerSlipLaunch(float slip_ratio, int16_t initial_speed_target)
: BaseLaunchController(initial_speed_target),
slip_ratio_(slip_ratio) {}

/// @brief default constructor for slip launch controller: DEFAULT_SLIP_RATIO = 0.2, DEFAULT_LAUNCH_SPEED_TARGET = 1500(rpm)
TorqueControllerSlipLaunch() : TorqueControllerSlipLaunch(SlipLaunchControllerParams::DEFAULT_SLIP_RATIO, SlipLaunchControllerParams::DEFAULT_LAUNCH_SPEED_TARGET) {}

/// @brief Increases speed target during launch linearly according to slip ratio to keep the cars wheels spinning faster than the velocity for increased traction
/// @param vn_data This controller needs velocity data for to keep updating increasing the speed according to the slip ratio
void calc_launch_algo(const VectornavData_s &vn_data) override;
};
#endif // __SLIPLAUNCHCONTROLLER_H__
2 changes: 1 addition & 1 deletion lib/systems/include/DrivetrainSystem.tpp
Original file line number Diff line number Diff line change
Expand Up @@ -148,7 +148,7 @@ void DrivetrainSystem<InverterType>::command_drivetrain(const DrivetrainCommand_
int index = 0;
for (auto inv_pointer : inverters_)
{
inv_pointer->handle_command({data.torqueSetpoints[index], data.speeds_rpm[index]});
inv_pointer->handle_command({data.inverter_torque_limit[index], data.speeds_rpm[index]});
index++;
}
// last_general_cmd_time_ = curr_system_millis_;
Expand Down
Loading
Loading