Skip to content
Open
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
228 changes: 228 additions & 0 deletions intro_projects/RussellTabata/intro_project.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,228 @@
#include <arduino_freertos.h>
#include <stdint.h>

/*
The car has three possible functional states:
1. Low Voltage (LV)
2. Tractive System (TS)
3. Ready to Drive (RTD)

When in LV, the car cannot drive. When in TS, the car is energized, but still
cannot drive. When in RTD, the car is energized and able to drive.

There are two Accumulator Isolation Relays (AIRs) that connect the high voltage
(HV) battery to the rest of the car. One is on the positive terminal, and the
other on the negative terminal (AIR+ and AIR-). That is to say, the battery is
disconnected unless we energize both relays, which is important for safety.
Whenever we have a critical error, we can open these relays / de-energize them
to make sure there is no HV outside the accumulator.

When we go from LV -> TS, we cannot simply energize the relays (ask an
electrical lead why!). Instead we first close AIR-, then another relay called
the "Precharge Relay". After ~5 seconds we close AIR+ and open the precharge
relay.

There is a TS On button and an RTD button on the dash that move the cars into
those states. ie. When you press TS On the car goes TS, and when you press RTD,
it goes to RTD. They are both active low, meaning when the button's are pressed,
the voltage goes low.

We also have a few sensors that we need to be able to calculate how much torque
to command:

1. Current sensor (How much current there is in the HV path)
2. Wheelspeeds
3. Steering Angle Sensor

The current sensor is a Hall Effect sensor read by an ADC through GPIO pins. The
conversion is: 1 amp per 10mV

Wheelspeeds are a bit tricky. The sensor is routed to a GPIO pin, and is
normally high. However, the wheels have a gear looking thing with 17 teeth --
everytime one of the teeth passes the sensor, the voltage at the GPIO pin goes
low. You can derive the RPM of the wheel from how often the voltage goes low.

The steering angle sensor comes to us via CAN.

We also have to monitor our battery to make sure nothing explodes or catches on
fire... Thankfully we have a Battery Management System (BMS) that monitors cell
voltages and temperatures and can send them to us. It sends this info via SPI.
If any cell voltage goes below 2.8V or above 4.3V, de-energize the car. Also, if
any temperature exceeds 60 degrees, de-energize.

Finally, we have an LCD on the dash which is useful to display information. You
should print all relevant info to the screen so we know what's going on with the
car. This also operates via SPI.

Mock library functions have been provided where necessary (marked with extern).

NOTE - EXTREMELY IMPORTANT: the CAN methods `can_send` and `can_receive` are NOT
thread safe.

Also think about the implications of having two peripherals on one SPI bus.

----------------------------

Requirements:

1. Command each motor with an appropriate torque every 1ms
2. Print sensor values and torque values to the LCD every 100ms
3. Monitor the highest/lowest voltage and highest temperature from the BMS and
shutdown the car if there is any unsafe condition

----------------------------

Pins:

TS On: 12
RTD: 13
Current Sensor: 19
CAN RX: 2
CAN TX: 3
MOSI: 5
MISO: 6
SCK: 7
LCD_CS: 8
BMS_CS: 9
AIR+: 22
Precharge: 23
AIR-: 10

----------------------------

"Submission" instructions. I want you all to get familiar with git, so we will
do this project with git. The repo is
https://github.com/UTFR/firmware-tutorials.

If you still haven't joined the github organization, let me know and i'll add
you. Clone the repository, and make a branch called `<your name>/intro_project`.
Copy this file into the directory `intro_projects/<your name>` and make all your
changes there.

Whenever you add a feature, `git add` the files, and `git commit -m "..."` with
a useful/descriptive message. Whenver you want your changes to be public, do
`git push origin <your name>/intro_project`.

Also, I won't enforce it for this project, but for the actual firmware repo we
have a code formatter (clang-format). It means that everyone's code will look
exactly the same, in terms of how much whitespace there is and other aesthetics
like that. It's not there for aesthetics, but moreso so that you when people
make changes you can see exactly what they changed, whereas without a formatter,
you end up with lots of useless formatting changes. You should install
clang-format as soon as possible and set it up :)
*/

/*
Initialize the CAN peripheral with given RX and TX pins at a given baudrate.
*/
extern void can_init(uint8_t rx, uint8_t tx, uint32_t baudrate);
/*
Send a CAN message with a given id.
The 8 byte payload is encoded as a uint64_t
*/
extern void can_send(uint8_t id, uint64_t payload);

/*
Receive a CAN message with a given id into a uint64_t
*/
extern void can_receive(uint64_t* payload, uint8_t id);

/*
Calculates four torques, in order, for the Front Left, Front Right, Rear Left,
and Rear Right motors given current, wheelspeeds (in the same order), and a
steering angle.
*/
extern void calculate_torque_cmd(
float* torques, float current, float* wheelspeeds, float steering_angle);

/*
Initialize the LCD peripheral
*/
extern void lcd_init(uint8_t mosi, uint8_t miso, uint8_t sck, uint8_t lcs_cs);

/*
Print something to the LCD
*/
extern void lcd_printf(const char* fmt, ...);

/*
Initialize the BMS
*/
extern void bms_init(uint8_t mosi, uint8_t miso, uint8_t sck, uint8_t lcs_cs);

/*
Get voltage of the nth cell in the battery
*/
extern float bms_get_voltage(uint8_t n);

/*
Get temperature of the nth cell in the battery
*/
extern float bms_get_temperature(uint8_t n);

/*
Requirements:

1. Command each motor with an appropriate torque every 1ms
2. Print sensor values and torque values to the LCD every 100ms
3. Monitor the highest/lowest voltage and highest temperature from the BMS and
shutdown the car if there is any unsafe condition
*/

/*
If any cell voltage goes below 2.8V or above 4.3V, de-energize the car. Also, if
any temperature exceeds 60 degrees, de-energize.
*/

void deenergize_car()
{
digitalWrite(AIR_POS, LOW);
digitalWrite(PRECHARGE, LOW);
digitalWrite(AIR_NEG, LOW);
}

void setup(void)
{
can_init(2, 3, 1000000);
lcd_init(5, 6, 7, 8);
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I would define macros for all your pins, for example #define LCD_CS 8, but that's a very small thing, otherwise correct

Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Both the LCD and BMS are using the same SPI pins / peripheral (5 and 6). If you have an interrupt configured (which you should for the wheelspeed), one device could try to talk while the other was trying to transmit information and that's how you result with a race condition.

A mutex would be helpful to use here

You can define a mutex like this: SemaphoreHandle_t spi_mutex;

bms_init(5, 6, 7, 9);

pinMode(AIR_POS, OUTPUT);
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

For the precharge setup we cannot immediately close the relays when we go from LV -> TS

As it says in the top of the file

"When we go from LV -> TS, we cannot simply energize the relays (ask an
electrical lead why!). Instead we first close AIR-, then another relay called
the "Precharge Relay". After ~5 seconds we close AIR+ and open the pre-charge
relay"

The reason for this is because I believe the high voltage system specifically the inverter contains high capacitance. Empty capacitors act as shorts so a massive spike of current rushes from the battery into those empty capacitors and its so much to the point that arcing occurs and they literally weld shut the AIRs (accumulator isolation relays).

To get the delay you use vTaskDelay("put time in milliseconds here), but make sure you don't block the CPU

pinMode(PRECHARGE, OUTPUT);
pinMode(AIR_NEG, OUTPUT);
deenergize_car(); // start safe

loop();
}

#define CURRENT_GPIO 12
#define WHEELSPEED_GPIO 11
#define STEERING_CAN_ID 0
#define NUM_BATTERIES 3

#define AIR_POS 22
#define PRECHARGE 23
#define AIR_NEG 10

void loop(void)
{
while (true) {

float torques[4];
float current = analogRead(CURRENT_GPIO);
float wheelspeeds = analogRead(WHEELSPEED_GPIO);
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

You cannot do an analog read on the wheelspeed pin, sorry I didn't realize this earlier, but it is a digital input (from the perspective of the MCU).

You can reference this in the project:

"Wheelspeeds are a bit tricky. The sensor is routed to a GPIO pin, and is
normally high. However, the wheels have a gear looking thing with 17 teeth --
everytime one of the teeth passes the sensor, the voltage at the GPIO pin goes
low. You can derive the RPM of the wheel from how often the voltage goes low"

float steering_angle;
can_receive(&steering_angle, STEERING_CAN_ID);

calculate_torque_cmd(&torques, current, wheelspeeds, steering_angle);
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

You should send torque on CAN

lcd_printf("torque values: %f, %f, %f, %f, wheelspeeds: %f, %f, %f, %f, current: %f, steering angle: %f",
torques[0], torques[1], torques[2], torques[3], wheelspeeds[0], wheelspeeds[1], wheelspeeds[2], wheelspeeds[3], current, steering_angle);

for (int i = 0; i < NUM_BATTERIES; i++) {
if (bms_get_temperature(i) > 60 || bms_get_voltage(i) < 2.8 || bms_get_voltage(i) > 4.3) {
deenergize_car();
return;
}
}
}
}