Skip to content

Commit

Permalink
Develop/fsae (#186)
Browse files Browse the repository at this point in the history
* switch to pca9539 (untested) (#175)

* switch to pca9539 (untested)

* update pdu to improved api

* fix addr

* new reg name

* disable shutdown

* removed debugging stuff

* bump

---------

Co-authored-by: Scott A <[email protected]>

* Feature/pedal tune (#180)

* prepped for pedal tuning + added break check when going to drive mode

* added Scott's implementation for bspd pre check

* added defcon 5 fault

* fuck

* remoced torque send

* pedals calibrated

* fix bit

* im stupid

* new pedals

* added debug

* poop farty

* Auto stash before merge of "feature/pedal-tune" and "origin/feature/pedal-tune"

* move tsms status

* reset queuue

* fixed stuff

---------

Co-authored-by: Jack Rubacha <[email protected]>

* Finally get mph working! (#183)

* dti back and mph calcs

* queue fixes and got a backwards erpm reading

* use correct units

* fix up mph, tested recieve and send, not validated connection

---------

Co-authored-by: Scott A <[email protected]>

* Monitor fixes (#181)

* add lv monitor again

* remove bad line

* fix missed line in rebase

* fix up math

* regen fix issue

* fix send torque

* Bms fault fixes (#182)

* fix bms fault, get rid of write fan battbox

* add note

* fix bspd prefault

* adjust value for proper scale

* fix mph, bspd prefault

* fix nero

* add brake filter

* Debounce tsms (#178)

* tsms debounce with nertimer

* you saw nothing

* tsms debounce with nertimer

* you saw nothing

* add tsms debounce

---------

Co-authored-by: Jack Rubacha <[email protected]>

---------

Co-authored-by: Jack Rubacha <[email protected]>
Co-authored-by: Scott A <[email protected]>
  • Loading branch information
3 people committed Jun 17, 2024
1 parent 1b6b5b1 commit 4210c9c
Show file tree
Hide file tree
Showing 24 changed files with 664 additions and 405 deletions.
2 changes: 1 addition & 1 deletion .mxproject

Large diffs are not rendered by default.

19 changes: 11 additions & 8 deletions Core/Inc/cerberus_conf.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,20 +5,22 @@
#define FUSES_SAMPLE_DELAY 1000 /* ms */
#define SHUTDOWN_MONITOR_DELAY 500 /* ms */
#define NERO_DELAY_TIME 100 /* ms*/
#define LV_READ_DELAY 1000
#define SERIAL_MONITOR_DELAY
#define CAN_ROUTER_DELAY
#define CAN_DISPATCH_DELAY 5
#define BMS_CAN_MONITOR_DELAY 7000
#define BMS_CAN_MONITOR_DELAY 4000
#define STATE_MACHINE_DELAY
#define TORQUE_CALC_DELAY
#define FAULT_HANDLE_DELAY

/* Pedal tuning */
#define PEDALS_SAMPLE_DELAY 20 /* ms */
#define ACCEL1_OFFSET 2767
#define ACCEL1_MAX_VAL 3319
#define ACCEL2_OFFSET 1920
#define ACCEL2_MAX_VAL 3382
#define ACCEL1_OFFSET 980
#define ACCEL1_MAX_VAL 1866
#define ACCEL2_OFFSET 1780
#define ACCEL2_MAX_VAL 3365
#define PEDAL_BRAKE_THRESH 650

/* Torque Tuning */
#define MAX_TORQUE 220 /* Nm * 10 */
Expand Down Expand Up @@ -50,16 +52,17 @@
#define WATCHDOG_Pin GPIO_PIN_15
#define WATCHDOG_GPIO_Port GPIOB

#define CANID_PEDAL_SENSOR 0x002
// TODO: GET CORRECT CAN ID
#define CANID_IMU 0x003

#define CANID_TEMP_SENSOR 0x004
#define CANID_TORQUE_MSG 0x005
#define CANID_OUTBOUND_MSG 0xA55
#define CANID_FUSE 0x111
#define CANID_SHUTDOWN_LOOP 0x123
#define CANID_IMU_ACCEL 0x506
#define CANID_IMU_GYRO 0x507
#define CANID_NERO_MSG 0x501
#define CANID_FAULT_MSG 0x502
#define CANID_LV_MONITOR 0x503
#define CANID_PEDALS_ACCEL_MSG 0x504
#define CANID_PEDALS_BRAKE_MSG 0x505
#define CANID_EXTRA_MSG 0x701 // Reserved for MPU debug message, see yaml for format
15 changes: 8 additions & 7 deletions Core/Inc/dti.h
Original file line number Diff line number Diff line change
Expand Up @@ -22,9 +22,10 @@
#define DTI_CANID_TEMPS_FAULT 0x456 /* Controller Temp, Motor Temp, Faults */
#define DTI_CANID_ID_IQ 0x476 /* Id, Iq values */
#define DTI_CANID_SIGNALS 0x496 /* Throttle signal, Brake signal, IO, Drive enable */
#define DTI_QUEUE_SIZE 5

#define WHEEL_CIRCUMFERENCE 1.2767 /* meters */
#define GEAR_RATIO 4.3 /* unitless */
#define TIRE_DIAMETER 16 /* inches */
#define GEAR_RATIO 47 / 13.0 /* unitless */
#define POLE_PAIRS 10 /* unitless */

typedef struct
Expand All @@ -44,13 +45,13 @@ typedef struct
} dti_t;

// TODO: Expand GET interface
uint32_t dti_get_rpm(dti_t* dti);
int32_t dti_get_rpm(dti_t* dti);

/* Utilities for Decoding CAN message */
// extern osThreadId_t dti_router_handle;
// extern const osThreadAttr_t dti_router_attributes;
// extern osMessageQueueId_t dti_router_queue;
// void vDTIRouter(void* pv_params);
extern osThreadId_t dti_router_handle;
extern const osThreadAttr_t dti_router_attributes;
extern osMessageQueueId_t dti_router_queue;
void vDTIRouter(void* pv_params);

dti_t* dti_init();

Expand Down
2 changes: 2 additions & 0 deletions Core/Inc/fault.h
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,8 @@ typedef enum {
INVALID_TRANSITION_FAULT = 0x400,
BMS_CAN_MONITOR_FAULT = 0x800,
BUTTONS_MONITOR_FAULT = 0xF00,
BSPD_PREFAULT = 0x1000,
LV_MONITOR_FAULT = 0x2000,
MAX_FAULTS
} fault_code_t;

Expand Down
9 changes: 9 additions & 0 deletions Core/Inc/monitor.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,10 @@
#include "stm32f4xx_hal.h"
#include "stdbool.h"

void vLVMonitor(void* pv_params);
extern osThreadId lv_monitor_handle;
extern const osThreadAttr_t lv_monitor_attributes;

/* Defining Temperature Monitor Task */
void vTempMonitor(void* pv_params);
extern osThreadId_t temp_monitor_handle;
Expand All @@ -25,6 +29,11 @@ void vIMUMonitor(void* pv_params);
extern osThreadId_t imu_monitor_handle;
extern const osThreadAttr_t imu_monitor_attributes;

/* Task for Monitoring the TSMS sense on PDU CTRL expander*/
void vTsmsMonitor(void* pv_params);
extern osThreadId_t tsms_monitor_handle;
extern const osThreadAttr_t tsms_monitor_attributes;

/* Task for Monitoring the Fuses on PDU */
void vFusingMonitor(void* pv_params);
extern osThreadId_t fusing_monitor_handle;
Expand Down
8 changes: 7 additions & 1 deletion Core/Inc/mpu.h
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,10 @@ typedef struct {
ADC_HandleTypeDef* pedals_adc;
uint32_t pedal_dma_buf[4];


ADC_HandleTypeDef* lv_adc;
uint32_t lv_dma_buf;

GPIO_TypeDef* led_gpio;
GPIO_TypeDef* watchdog_gpio;
sht30_t* temp_sensor;
Expand All @@ -29,7 +33,7 @@ typedef struct
} brake_adc_channels_t;


mpu_t* init_mpu(I2C_HandleTypeDef* hi2c, ADC_HandleTypeDef* pedals_adc, GPIO_TypeDef* led_gpio,
mpu_t* init_mpu(I2C_HandleTypeDef* hi2c, ADC_HandleTypeDef* pedals_adc, ADC_HandleTypeDef* lv_adc, GPIO_TypeDef* led_gpio,
GPIO_TypeDef* watchdog_gpio);

int8_t write_rled(mpu_t* mpu, bool status);
Expand All @@ -44,6 +48,8 @@ int8_t pet_watchdog(mpu_t* mpu);

void read_pedals(mpu_t* mpu, uint32_t pedal_buf[4]);

void read_lv_voltage(mpu_t* mpu, uint32_t *lv_buf);

int8_t read_temp_sensor(mpu_t* mpu, uint16_t* temp, uint16_t* humidity);

int8_t read_accel(mpu_t* mpu, uint16_t accel[3]);
Expand Down
2 changes: 2 additions & 0 deletions Core/Inc/nero.h
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,8 @@ void select_nero_index();
*/
void set_mph(int8_t new_mph);

void set_nero_home_mode();

/*
* Emits the state of NERO
*/
Expand Down
11 changes: 5 additions & 6 deletions Core/Inc/pdu.h
Original file line number Diff line number Diff line change
Expand Up @@ -2,16 +2,15 @@
#define PDU_H

#include "cmsis_os.h"
#include "pi4ioe.h"
#include "max7314.h"
#include "pca9539.h"
#include <stdbool.h>
#include <stdint.h>

typedef struct {
I2C_HandleTypeDef* hi2c;
osMutexId_t* mutex;
max7314_t* shutdown_expander;
max7314_t* ctrl_expander;
pca9539_t* shutdown_expander;
pca9539_t* ctrl_expander;
osTimerId rtds_timer;
} pdu_t;

Expand Down Expand Up @@ -40,7 +39,7 @@ typedef enum {
MAX_FUSES
} fuse_t;

int8_t read_fuse(pdu_t* pdu, fuse_t fuse, bool* status);
int8_t read_fuses(pdu_t* pdu, bool status[MAX_FUSES]);

int8_t read_tsms_sense(pdu_t* pdu, bool* status);

Expand All @@ -60,6 +59,6 @@ typedef enum {
MAX_SHUTDOWN_STAGES
} shutdown_stage_t;

int8_t read_shutdown(pdu_t* pdu, shutdown_stage_t stage, bool* status);
int8_t read_shutdown(pdu_t* pdu, bool status[MAX_SHUTDOWN_STAGES]);

#endif /* PDU_H */
4 changes: 4 additions & 0 deletions Core/Inc/queues.h
Original file line number Diff line number Diff line change
Expand Up @@ -28,4 +28,8 @@ typedef struct {

extern osMessageQueueId_t pedal_data_queue;

extern osMessageQueueId_t break_state_queue;

bool get_brake_state();

#endif // QUEUES_H
2 changes: 1 addition & 1 deletion Core/Inc/stm32f4xx_hal_conf.h
Original file line number Diff line number Diff line change
Expand Up @@ -214,7 +214,7 @@
#define MAC_ADDR5 0U

/* Definition of the Ethernet driver buffers size and count */
#define ETH_RX_BUF_SIZE /* buffer size for receive */
#define ETH_RX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for receive */
#define ETH_TX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for transmit */
#define ETH_RXBUFNB 4U /* 4 Rx buffers of size ETH_RX_BUF_SIZE */
#define ETH_TXBUFNB 4U /* 4 Tx buffers of size ETH_TX_BUF_SIZE */
Expand Down
1 change: 1 addition & 0 deletions Core/Src/bms.c
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@ void bms_fault_callback()
{
fault_data_t fault_data = { .id = BMS_CAN_MONITOR_FAULT, .severity = DEFCON1 }; /*TO-DO: update severity*/
fault_data.diag = "Failing To Receive CAN Messages from Shepherd";
osTimerStart(bms->bms_monitor_timer, BMS_CAN_MONITOR_DELAY);
queue_fault(&fault_data);
}

Expand Down
13 changes: 8 additions & 5 deletions Core/Src/can_handler.c
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
#include <stdlib.h>
#include "stdio.h"
#include <string.h>
#include "dti.h"

#define CAN_MSG_QUEUE_SIZE 50 /* messages */
static osMessageQueueId_t can_outbound_queue;
Expand Down Expand Up @@ -75,14 +76,16 @@ void can1_callback(CAN_HandleTypeDef* hcan)
switch (new_msg.id) {
/* Messages Relevant to Motor Controller */
case DTI_CANID_ERPM:
case DTI_CANID_CURRENTS:
case DTI_CANID_TEMPS_FAULT:
case DTI_CANID_ID_IQ:
// case DTI_CANID_CURRENTS:
// case DTI_CANID_TEMPS_FAULT:
// case DTI_CANID_ID_IQ:
// case DTI_CANID_SIGNALS:
// osMessageQueuePut(dti_router_queue, &new_msg, 0U, 0U);
// break;
osMessageQueuePut(dti_router_queue, &new_msg, 0U, 0U);
break;
case BMS_DCL_MSG:
//printf("Recieved dcl");
osMessageQueuePut(bms_monitor_queue, &new_msg, 0U, 0U);
break;
default:
break;
}
Expand Down
110 changes: 53 additions & 57 deletions Core/Src/dti.c
Original file line number Diff line number Diff line change
Expand Up @@ -35,10 +35,6 @@ dti_t* dti_init()
mc->mutex = osMutexNew(&dti_mutex_attributes);
assert(mc->mutex);

/* Create Queue for CAN signaling */
// dti_router_queue = osMessageQueueNew(CAN_QUEUE_SIZE, sizeof(can_msg_t), NULL);
// assert(dti_router_queue);

return mc;
}

Expand Down Expand Up @@ -221,66 +217,66 @@ void dti_set_drive_enable(bool drive_enable)
queue_can_msg(msg);
}

uint32_t dti_get_rpm(dti_t* mc)
int32_t dti_get_rpm(dti_t* mc)
{
uint32_t rpm;
int32_t rpm;
osMutexAcquire(*mc->mutex, osWaitForever);
rpm = mc->rpm;
//printf("Rpm %ld",rpm);
osMutexRelease(*mc->mutex);

return rpm;
}

/* Inbound Task-specific Info */
// osThreadId_t dti_router_handle;
// const osThreadAttr_t dti_router_attributes
// = { .name = "DTIRouter", .stack_size = 64 * 8, .priority = (osPriority_t)osPriorityHigh };

// static void dti_set_rpm(dti_t *mc, can_msg_t msg)
// {
// /* ERPM is first four bytes of can message in big endian format */
// uint32_t erpm = 0;
// for (int i = 0; i < 4; i++) {
// erpm |= msg.data[i] << (8 * (3 - i));
// }

// uint32_t rpm = erpm / POLE_PAIRS;

// osMutexAcquire(*mc->mutex, osWaitForever);
// mc->rpm = rpm;
// osMutexRelease(*mc->mutex);
// }

// void vDTIRouter(void* pv_params)
// {
// can_msg_t message;
// osStatus_t status;
// // fault_data_t fault_data = { .id = DTI_ROUTING_FAULT, .severity = DEFCON2 };

// dti_t *mc = (dti_t *)pv_params;

// for (;;) {
// /* Wait until new CAN message comes into queue */
// status = osMessageQueueGet(dti_router_queue, &message, NULL, osWaitForever);
// if (status == osOK)
// {
// switch (message.id)
// {
// case DTI_CANID_ERPM:
// dti_set_rpm(mc, message);
// break;
// case DTI_CANID_CURRENTS:
// break;
// case DTI_CANID_TEMPS_FAULT:
// break;
// case DTI_CANID_ID_IQ:
// break;
// case DTI_CANID_SIGNALS:
// break;
// default:
// break;
// }
// }
// }
// }
osThreadId_t dti_router_handle;
const osThreadAttr_t dti_router_attributes
= { .name = "DTIRouter", .stack_size = 64 * 8, .priority = (osPriority_t)osPriorityHigh };

static void dti_record_rpm(dti_t *mc, can_msg_t msg)
{
/* ERPM is first four bytes of can message in big endian format */
int32_t erpm = (msg.data[0] << 24) + (msg.data[1] << 16) + (msg.data[2] << 8) + (msg.data[3]);

int32_t rpm = erpm / POLE_PAIRS;

//printf("\n\nRPM Rec: %ld\n\n", rpm);

osMutexAcquire(*mc->mutex, osWaitForever);
mc->rpm = rpm;
osMutexRelease(*mc->mutex);
}

void vDTIRouter(void* pv_params)
{
can_msg_t message;
osStatus_t status;
// fault_data_t fault_data = { .id = DTI_ROUTING_FAULT, .severity = DEFCON2 };

dti_t *mc = (dti_t *)pv_params;

for (;;) {
/* Wait until new CAN message comes into queue */
status = osMessageQueueGet(dti_router_queue, &message, NULL, osWaitForever);
if (status == osOK)
{
switch (message.id)
{
case DTI_CANID_ERPM:
dti_record_rpm(mc, message);
break;
case DTI_CANID_CURRENTS:
break;
case DTI_CANID_TEMPS_FAULT:
break;
case DTI_CANID_ID_IQ:
break;
case DTI_CANID_SIGNALS:
break;
default:
break;
}
}
}
}

Loading

0 comments on commit 4210c9c

Please sign in to comment.