Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Binary file added include/.DS_Store
Binary file not shown.
4 changes: 3 additions & 1 deletion include/README
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,9 @@ new version when next recompiled. The header file eliminates the labor of
finding and changing all the copies as well as the risk that a failure to
find one copy will result in inconsistencies within a program.

In C, the convention is to give header files names that end with `.h'.
In C, the usual convention is to give header files names that end with `.h'.
It is most portable to use only letters, digits, dashes, and underscores in
header file names, and at most one dot.

Read more about using header files in official GCC documentation:

Expand Down
23 changes: 23 additions & 0 deletions include/apps.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
#pragma once
//APPS = Accelerator Pedal Position Sensor
//-----------------------CONSTANTS------------------------
extern const double PEDAL_MIN;
extern const double PEDAL_MAX;

// APPS Pins
const int APPS_1_PIN = A6;
const int APPS_2_PIN = A7;

// APPS_PLAUSIBILITY_THRESHOLDS
// Brake Sensor
const int APPS_BRAKE_PLAUSIBILITY_THRESHOLD = 25; // % APPS request threshold for brake plausibility check (Rule EV.5.7)

// APPS
const float APPS_PLAUSIBILITY_THRESHOLD = 10.0f; // % difference threshold (Rule EV.5.6)

// TIMEOUTS
const unsigned long APPS_PLAUSIBILITY_TIMEOUT_MS = 100; // Max time for APPS implausibility (Rule EV.5.6.3)
const unsigned long APPS_BRAKE_PLAUSIBILITY_TIMEOUT_MS = 500; // Max time for APPS/Brake implausibility (Rule EV.2.3.1)

//-----------------------FUNCTION PROTOTYPES------------------------
double get_apps_reading(); // Returns pedal position (%) or -1.0 on implausibility
192 changes: 192 additions & 0 deletions include/bamocar-due.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,192 @@
/**
* @file bamocar-due.h
* @brief Defines the Bamocar class for interacting with the Bamocar D3
* controller. Modified to remove CAN callback registration and expose message
* handling.
* @author Shane Whelan (UCD Formula Student)
* @date 2025-04-27
*/
#pragma once

#include <Arduino.h>
#ifdef min
#undef min
#endif

#ifdef max
#undef max
#endif
#include "bamocar-registers.h"
#include "due_can.h"
#include <functional>

// #define CAN_TIMEOUT 0.01
#define TORQUE_MAX_PERCENT 1.00

// Forward declaration
class CANManager;

class M_data {
public:
// --- Constructor Overloads (Unchanged) ---
M_data(uint8_t regID, uint16_t m_data16) {
data.bytes[0] = regID;
data.bytes[1] = m_data16 & 0xFF;
data.bytes[2] = m_data16 >> 8;
dataLength = 3;
}

M_data(uint8_t regID, int16_t m_data16) {
data.bytes[0] = regID;
data.bytes[1] = m_data16 & 0xFF;
data.bytes[2] = m_data16 >> 8;
dataLength = 3;
}

M_data(uint8_t regID, uint32_t m_data32) {
data.bytes[0] = regID;
data.bytes[1] = m_data32 & 0xFF;
data.bytes[2] = (m_data32 >> 8) & 0xFF;
data.bytes[3] = (m_data32 >> 16) & 0xFF;
data.bytes[4] = (m_data32 >> 24) & 0xFF;
dataLength = 5;
}

M_data(uint8_t regID, int32_t m_data32) {
data.bytes[0] = regID;
data.bytes[1] = m_data32 & 0xFF;
data.bytes[2] = (m_data32 >> 8) & 0xFF;
data.bytes[3] = (m_data32 >> 16) & 0xFF;
data.bytes[4] = (m_data32 >> 24) & 0xFF;
dataLength = 5;
}

M_data(uint8_t regID, uint8_t requestedRegID, uint8_t interval) {
data.bytes[0] = regID;
data.bytes[1] = requestedRegID;
data.bytes[2] = interval;
dataLength = 3;
}
// --- End Constructor Overloads ---

BytesUnion getData() { return data; }

uint8_t length() { return dataLength; }

protected:
BytesUnion data;
uint8_t dataLength;
};

// -------------------------------------

class Bamocar {
public:
/**
* @brief Constructor for Bamocar.
* Removed mailbox parameter as callbacks are no longer used here.
* Initializes default CAN IDs.
*/
Bamocar() {
// instance = this; // Keep if static instance is needed elsewhere
_rxID = STD_RX_ID; // ID we send commands TO
_txID = STD_TX_ID; // ID we receive responses FROM
}

// --- Public Interface Functions (Unchanged signatures) ---
float getSpeed();
bool setSpeed(int16_t speed);
bool requestSpeed(uint8_t interval = INTVL_IMMEDIATE);

bool setAccel(int16_t accel);
bool setDecel(int16_t decel);

float getTorque();
bool setTorque(float torque);
bool requestTorque(uint8_t interval = INTVL_IMMEDIATE);
float getMaxTorqueNm(); // Helper function for regen scaling

float getCurrent(); // Remember to fix implementation (2.0/10.0)
bool requestCurrent(uint8_t interval = INTVL_IMMEDIATE);

uint16_t getMotorTemp();
uint16_t getControllerTemp();
uint16_t getAirTemp();
bool requestMotorTemp(uint8_t interval = INTVL_IMMEDIATE);
bool requestControllerTemp(uint8_t interval = INTVL_IMMEDIATE);
bool requestAirTemp(uint8_t interval = INTVL_IMMEDIATE);

uint32_t getStatus(); // Changed return type to match _rcvd.STATUS
bool requestStatus(uint8_t interval = INTVL_IMMEDIATE);

void setSoftEnable(bool enable);
bool getHardEnable();
bool requestHardEnabled(uint8_t interval = INTVL_IMMEDIATE);

void setRxID(uint16_t rxID); // ID to send commands TO
void setTxID(uint16_t txID); // ID to receive responses FROM
uint16_t getTxID() const {
return _txID;
} // Getter for CANManager filter setup
uint16_t getRxID() const { return _rxID; } // Getter

/**
* @brief Public function to handle incoming CAN frames intended for this
* Bamocar instance. Called by CANManager.
* @param msg The received CAN_FRAME.
*/
void handle_incoming_frame(const CAN_FRAME &msg);

protected:
// static Bamocar *instance; // Keep if needed
uint16_t _rxID; // ID we send commands TO
uint16_t _txID; // ID we receive responses FROM

// Structure to hold received data (Unchanged)
struct _rcvd {
int16_t N_ACTUAL = 0, N_MAX = 0, TORQUE = 0;
uint16_t READY = 0, I_ACTUAL = 0, I_DEVICE = 0, I_200PC = 0, RAMP_ACC = 0,
RAMP_DEC = 0, TEMP_MOTOR = 0, TEMP_IGBT = 0, TEMP_AIR = 0,
HARD_ENABLED = 0;
uint32_t STATUS = 0; // Ensure this is uint32_t
} _rcvd;

/**
* @brief Sends a command/request to the Bamocar via the CANManager.
* @param m_data The M_data object containing the command.
* @return True if the message was successfully sent by CANManager, false
* otherwise.
*/
bool _sendCAN(M_data m_data);

/**
* @brief Sends a request for data transmission from the Bamocar.
* @param requestedRegID The register ID to request.
* @param interval The requested transmission interval code.
* @return True if the request message was successfully sent, false otherwise.
*/
bool _requestData(uint8_t requestedRegID, uint8_t interval = INTVL_IMMEDIATE);

// Removed _forwardFrame as it's no longer needed for callbacks

/**
* @brief Parses a received CAN message and updates the internal state
* (_rcvd). Now called by the public handle_incoming_frame.
* @param msg The received CAN_FRAME.
*/
void _parseMessage(const CAN_FRAME &msg); // Made const reference

/**
* @brief Extracts 16-bit data from a received CAN frame.
* @param msg The received CAN_FRAME.
* @return The extracted 16-bit value.
*/
int16_t _getReceived16Bit(const CAN_FRAME &msg); // Made const reference

/**
* @brief Extracts 32-bit data from a received CAN frame.
* @param msg The received CAN_FRAME.
* @return The extracted 32-bit value.
*/
int32_t _getReceived32Bit(const CAN_FRAME &msg); // Made const reference
};
50 changes: 50 additions & 0 deletions include/bamocar-registers.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,50 @@
/*

bamocar-registers.h

*/

#ifndef Bamocar_registers_h
#define Bamocar_registers_h

// CAN-Relevant settings
#define STD_RX_ID 0x201 //The ID the MC will listen on
#define STD_TX_ID 0x181 //The ID the MC will answer with
#define STD_BAUD_RATE 500000 //Standard Baudrate


// Control Registers
#define REG_ENABLE 0x51 //Disable or Enable transmission
#define REG_REQUEST 0x3D //Transmission request

// Data Registers
#define REG_STATUS 0x40 //Status of device
#define REG_READY 0xE2 //State of the device

#define REG_N_ACTUAL 0x30 //RPM actual
#define REG_N_CMD 0x31 //RPM command
#define REG_N_MAX 0xC8 //(SPEED_RPMMAX) Maximum rotation speed in turns per minute (Servo)

#define REG_I_ACTUAL 0x20 //Current actual
#define REG_I_DEVICE 0xC6 //Current device
#define REG_I_200PC 0xD9 //Current 200 PC

#define REG_TORQUE 0x90 //Torque reference

#define REG_RAMP_ACC 0x35 //Ramp Acceleration command
#define REG_RAMP_DEC 0xED //Ramp Deceleration command

#define REG_TEMP_MOTOR 0x49 //Active motor temperature
#define REG_TEMP_IGBT 0x4A //Active output stage temperature
#define REG_TEMP_AIR 0x4B //Air temperature in the servo

#define REG_HARD_ENABLED 0xE8 //Hard Enabled State

// Request interval Pre-settings
#define INTVL_IMMEDIATE 0x00
#define INTVL_SUSPEND 0xFF
#define INTVL_100MS 0x64
#define INTVL_200MS 0xC8
#define INTVL_250MS 0xFA

#endif
49 changes: 49 additions & 0 deletions include/bpps.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,49 @@
#ifndef BPPS_H
#define BPPS_H
/**
* @file bpps.h
* @brief Handles reading brake pressure sensors, MPU6050 tilt sensor, and controls brake light
* @author Muhammad Ibrahim Mansoor (UCD Formula Student)
* @date 2025-10-9
*/

//BPPS = Brake Pedal Position Sensor
//----------------- CONSTANTS ------------------
//PINS
// Analog Pins (INPUT)
const int BRAKE_PRESSURE_SENSOR_PIN_FRONT = A0;
const int BRAKE_PRESSURE_SENSOR_PIN_REAR = A1;

// Digital Pins (OUTPUT)
const int BRAKE_LIGHT_PIN = 7;

//GYRO
extern bool mpuInitialized;
const float TILT_THRESHOLD_DEG = 5.8; // For MPU6050 brake light activation

// Brake Light calibration constants
const int BRAKE_LIGHT_THRESHOLD = 109; // Calibrated
const int BRAKE_LIGHT_HYSTERESIS = 2; // Calibrated

//--------------- GLOBAL VARIABLES --------------------

//BRAKE PRESSURE VARIABLES
extern int brakePressureFront;
extern int brakePressureRear;
extern int brakePressureCombined;
//BRAKE IDLE VALUES
extern int brakeIdleValueFront;
extern int brakeIdleValueRear;
extern int brakeIdleValueCombined;

extern int dynamicBrakeThreshold;
extern bool brakeInitialized;

//------------ GLOBAL OBJECTS ---------------
extern Adafruit_MPU6050 mpu;
#endif // BPPS_H

//------------ FUNCTION PROTOTYPES -----------
bool initializeMPU(); // Initialize MPU6050 sensor
void brake_light(); // Reads brake pressure, MPU, controls brake light
void recalibrate_brake_idle(); // Recalibrate brake idle values
9 changes: 9 additions & 0 deletions include/dashboard.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
#ifndef DASHBOARD_H
#define DASHBOARD_H

// ------------ FUNCTION PROTOTYPES ------------
void dash_setup(); // Setup for Nextion display
void dash_loop(); // Update loop for Nextion display
void sendPlottableData(); // Send data for plotting

#endif // DASHBOARD_H
23 changes: 23 additions & 0 deletions include/error_monitor.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
#ifndef ERROR_MONITOR_H
#define ERROR_MONITOR_H
// ------------ CONSTANTS ------------
// --- Debug ---
const int DEBUG_MODE = 4; // 0=Off, 1=Essential, 2=Verbose, 3=Very Verbose, 4=Max Debug

// VCU-HACK: Set to true to bypass BMS checks for bench testing without a BMS.
// TODO: MUST BE FALSE FOR VEHICLE OPERATION.
const bool BENCH_TESTING_MODE = true;

// --- Pins ---
const int ERROR_PIN_START = 22; // Start pin for error monitoring
const int ERROR_PIN_END = 37; // End pin for error monitoring

// ------------ FUNCTION PROTOTYPES ------------
void monitor_errors_setup(); // Setup error monitoring
void monitor_errors_loop(); // Error monitoring loop
void checkCriticalSystems(); // Check critical systems and update warnings
const char* getErrorString(int errorCode); // Get error string from error code



#endif // ERROR_MONITOR_H
Loading