Skip to content
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
45 commits
Select commit Hold shift + click to select a range
3e1befc
Merge pull request #6 from Pioneer-Rocketry/main
CSutter5 Oct 27, 2025
bab484e
Created basic Sensor and Navigation classes
Oct 27, 2025
d1f04dc
Created basic I2C Device, and SPI Device classes
Oct 30, 2025
5d6e518
Created LSM6DSV320 driver
Oct 30, 2025
55b04c7
Added more docstrings
Oct 30, 2025
9d0d0c4
Added updateDevice method to I2C and SPI devices
Oct 30, 2025
d27c345
Created basic Sensor and Navigation classes
Oct 27, 2025
8603a6a
Created basic I2C Device, and SPI Device classes
Oct 30, 2025
911278b
Created LSM6DSV320 driver
Oct 30, 2025
8efdecb
Added more docstrings
Oct 30, 2025
9528d5d
Added updateDevice method to I2C and SPI devices
Oct 30, 2025
03fbd6b
Merge branch 'feature/navigation' of github.com:Pioneer-Rocketry/Flig…
Nov 4, 2025
ddcd04a
Added IMU device to nav class
Nov 7, 2025
4cf9012
Wrote basic MS560702BA03 driver
Nov 14, 2025
0385aa4
Finished writing IMU Driver
Nov 22, 2025
b9d2271
Created Barometer Driver (not fully tested)
Nov 22, 2025
2ee27c5
Added Quaternion Type
Nov 22, 2025
1d11602
Test Barometer driver and it works
Nov 23, 2025
7505aab
Implementated basic sensor fusion using quaternion intergration, and …
Nov 23, 2025
567c672
Added Kalman Filter data to DataContainer
Nov 23, 2025
ee96fa0
Added Doc Strings to KF Init
Nov 23, 2025
bb7c022
Designed and implemented the State Transition Matrix for the KF
Nov 23, 2025
ab9b4bd
Designed and implemented Observation Matrix
Nov 23, 2025
82cb55c
Designed and implemented the Process Noise, and Measurement Noise Mat…
Nov 23, 2025
68ac013
Create Kalman Filter update, and run functions
Nov 23, 2025
5d39829
Fix some of the math errors in the Quaterion intergration, and Kalman…
Nov 25, 2025
70fb00b
Switch from custom quat to Eigen quat
Nov 25, 2025
4a51754
Added pointer to the uart in GPS
Nov 25, 2025
799808d
Added a basic gyro bias
Nov 25, 2025
8a8b400
Recored how long each KF operation took
Nov 25, 2025
b16843e
Added functions for working with microseconds
CSutter5 Dec 2, 2025
af67ebc
Merge remote-tracking branch 'origin/main' into feature/navigation
CSutter5 Dec 7, 2025
ed1ee12
Setup error message for when the navigation subsystem doesn't init co…
CSutter5 Dec 7, 2025
f4bbbf3
Merge remote-tracking branch 'origin/main' into feature/navigation
CSutter5 Dec 15, 2025
36b7e45
Pulled main to here
CSutter5 Dec 15, 2025
5e18a6b
Switch to a custom matrix implemations that is faster
CSutter5 Dec 23, 2025
0841942
Rewrote quaterion intergration to not use Eigen
CSutter5 Dec 27, 2025
4b81c0d
Removed Eigen as it's no longer needed
CSutter5 Dec 27, 2025
428be3b
Merge branch 'main' into feature/navigation
Jan 7, 2026
fcbc983
fixed build script
Jan 7, 2026
dac4543
removed unneeded build files
Jan 7, 2026
a555a6d
fixed compiler error
Jan 7, 2026
9056b9e
Merge branch 'main' into feature/navigation
Jan 7, 2026
e354bfd
Modifed vscode settings
Jan 8, 2026
d63e06e
Implement a GPS driver
Jan 8, 2026
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
11 changes: 11 additions & 0 deletions .project
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
<?xml version="1.0" encoding="UTF-8"?>
<projectDescription>
<name>Flight-Computer</name>
<comment></comment>
<projects>
</projects>
<buildSpec>
</buildSpec>
<natures>
</natures>
</projectDescription>
2 changes: 1 addition & 1 deletion .vscode/launch.json
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
"device": "STM32F411RE",
"interface": "swd",
"runToEntryPoint": "main",
"preLaunchTask": "Build",
// "preLaunchTask": "Build",
}

]
Expand Down
3 changes: 2 additions & 1 deletion .vscode/settings.json
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
{
"cortex-debug.gdbPath.linux": "/usr/bin/arm-none-eabi-gdb",
"cortex-debug.stutilPath.linux": "/usr/bin/st-util"
"cortex-debug.stutilPath.linux": "/usr/bin/st-util",
"cortex-debug.variableUseNaturalFormat": true
}
4 changes: 2 additions & 2 deletions .vscode/tasks.json
Original file line number Diff line number Diff line change
Expand Up @@ -10,11 +10,11 @@
"detail": "Build"
},
{
"label": "Clean Build",
"label": "Clean",
"group": "build",
"type": "shell",
"command": "make",
"args": [ "-j", "-C", "./Code/", "cleanbuild"],
"args": [ "-j", "-C", "./Code/", "clean"],
"detail": "Do a clean build"
},
{
Expand Down
138 changes: 138 additions & 0 deletions Code/.cproject

Large diffs are not rendered by default.

4 changes: 2 additions & 2 deletions Code/.mxproject

Large diffs are not rendered by default.

51 changes: 35 additions & 16 deletions Code/Code.ioc
Original file line number Diff line number Diff line change
Expand Up @@ -8,19 +8,32 @@ ADC1.master=1
CAD.formats=
CAD.pinconfig=
CAD.provider=
Dma.Request0=UART4_RX
Dma.RequestsNb=1
Dma.UART4_RX.0.Direction=DMA_PERIPH_TO_MEMORY
Dma.UART4_RX.0.FIFOMode=DMA_FIFOMODE_DISABLE
Dma.UART4_RX.0.Instance=DMA1_Stream2
Dma.UART4_RX.0.MemDataAlignment=DMA_MDATAALIGN_BYTE
Dma.UART4_RX.0.MemInc=DMA_MINC_ENABLE
Dma.UART4_RX.0.Mode=DMA_CIRCULAR
Dma.UART4_RX.0.PeriphDataAlignment=DMA_PDATAALIGN_BYTE
Dma.UART4_RX.0.PeriphInc=DMA_PINC_DISABLE
Dma.UART4_RX.0.Priority=DMA_PRIORITY_LOW
Dma.UART4_RX.0.RequestParameters=Instance,Direction,PeriphInc,MemInc,PeriphDataAlignment,MemDataAlignment,Mode,Priority,FIFOMode
File.Version=6
KeepUserPlacement=false
Mcu.CPN=STM32F446RET6
Mcu.Family=STM32F4
Mcu.IP0=ADC1
Mcu.IP1=I2C2
Mcu.IP2=NVIC
Mcu.IP3=RCC
Mcu.IP4=SPI1
Mcu.IP5=SYS
Mcu.IP6=UART4
Mcu.IP7=USB_OTG_FS
Mcu.IPNb=8
Mcu.IP1=DMA
Mcu.IP2=I2C2
Mcu.IP3=NVIC
Mcu.IP4=RCC
Mcu.IP5=SPI1
Mcu.IP6=SYS
Mcu.IP7=UART4
Mcu.IP8=USB_OTG_FS
Mcu.IPNb=9
Mcu.Name=STM32F446R(C-E)Tx
Mcu.Package=LQFP64
Mcu.Pin0=PC13
Expand Down Expand Up @@ -67,6 +80,7 @@ Mcu.UserName=STM32F446RETx
MxCube.Version=6.16.1
MxDb.Version=DB.6.0.161
NVIC.BusFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
NVIC.DMA1_Stream2_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true
NVIC.DebugMonitor_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
NVIC.ForceEnableDMAVector=true
NVIC.HardFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
Expand Down Expand Up @@ -140,9 +154,10 @@ PB4.GPIOParameters=GPIO_Label
PB4.GPIO_Label=LORA_CS
PB4.Locked=true
PB4.Signal=GPIO_Output
PB5.GPIOParameters=GPIO_Label
PB5.GPIOParameters=PinState,GPIO_Label
PB5.GPIO_Label=BARO_CS
PB5.Locked=true
PB5.PinState=GPIO_PIN_SET
PB5.Signal=GPIO_Output
PB6.GPIOParameters=GPIO_Label
PB6.GPIO_Label=FLASH_CS
Expand Down Expand Up @@ -235,7 +250,7 @@ ProjectManager.LastFirmware=true
ProjectManager.LibraryCopy=1
ProjectManager.MainLocation=Core/Src
ProjectManager.NoMain=false
ProjectManager.PreviousToolchain=
ProjectManager.PreviousToolchain=STM32CubeIDE
ProjectManager.ProjectBuild=false
ProjectManager.ProjectFileName=Code.ioc
ProjectManager.ProjectName=Code
Expand All @@ -246,8 +261,9 @@ ProjectManager.TargetToolchain=Makefile
ProjectManager.ToolChainLocation=
ProjectManager.UAScriptAfterPath=
ProjectManager.UAScriptBeforePath=
ProjectManager.UnderRoot=false
ProjectManager.functionlistsort=1-SystemClock_Config-RCC-false-HAL-false,2-MX_GPIO_Init-GPIO-false-HAL-true,3-MX_ADC1_Init-ADC1-false-HAL-true,4-MX_I2C2_Init-I2C2-false-HAL-true,5-MX_SPI1_Init-SPI1-false-HAL-true,6-MX_UART4_Init-UART4-false-HAL-true,7-MX_USB_OTG_FS_PCD_Init-USB_OTG_FS-false-HAL-true
<<<<<<< HEAD
ProjectManager.UnderRoot=true
ProjectManager.functionlistsort=1-SystemClock_Config-RCC-false-HAL-false,2-MX_GPIO_Init-GPIO-false-HAL-true,3-MX_DMA_Init-DMA-false-HAL-true,4-MX_ADC1_Init-ADC1-false-HAL-true,5-MX_I2C2_Init-I2C2-false-HAL-true,6-MX_SPI1_Init-SPI1-false-HAL-true,7-MX_UART4_Init-UART4-false-HAL-true,8-MX_USB_OTG_FS_PCD_Init-USB_OTG_FS-false-HAL-true
RCC.AHBFreq_Value=180000000
RCC.APB1CLKDivider=RCC_HCLK_DIV4
RCC.APB1Freq_Value=45000000
Expand Down Expand Up @@ -319,13 +335,16 @@ SH.S_TIM1_CH2.0=TIM1_CH2
SH.S_TIM1_CH2.ConfNb=1
SH.S_TIM1_CH3.0=TIM1_CH3
SH.S_TIM1_CH3.ConfNb=1
SPI1.BaudRatePrescaler=SPI_BAUDRATEPRESCALER_2
SPI1.CalculateBaudRate=45.0 MBits/s
SPI1.BaudRatePrescaler=SPI_BAUDRATEPRESCALER_16
SPI1.CLKPhase=SPI_PHASE_1EDGE
SPI1.CLKPolarity=SPI_POLARITY_LOW
SPI1.CalculateBaudRate=5.625 MBits/s
SPI1.Direction=SPI_DIRECTION_2LINES
SPI1.IPParameters=VirtualType,Mode,Direction,CalculateBaudRate,BaudRatePrescaler
SPI1.IPParameters=VirtualType,Mode,Direction,CalculateBaudRate,BaudRatePrescaler,CLKPhase,CLKPolarity
SPI1.Mode=SPI_MODE_MASTER
SPI1.VirtualType=VM_MASTER
UART4.IPParameters=VirtualMode
UART4.BaudRate=9600
UART4.IPParameters=VirtualMode,BaudRate
UART4.VirtualMode=Asynchronous
USB_OTG_FS.IPParameters=VirtualMode
USB_OTG_FS.VirtualMode=Device_Only
Expand Down
62 changes: 60 additions & 2 deletions Code/Core/Inc/DataContainer.h
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,8 @@
#ifndef INC_DATACONTAINER_H_
#define INC_DATACONTAINER_H_

#include <cstdint>

/**
* @class DataContainer
* @brief Central data storage and communication hub for all subsystems.
Expand All @@ -29,10 +31,66 @@
class DataContainer {
private:


public:
/* IMU Data*/
float LSM6DSV320GyroX_dps;
float LSM6DSV320GyroY_dps;
float LSM6DSV320GyroZ_dps;

float LSM6DSV320LowGAccelX_mps2;
float LSM6DSV320LowGAccelY_mps2;
float LSM6DSV320LowGAccelZ_mps2;

float LSM6DSV320HighGAccelX_mps2;
float LSM6DSV320HighGAccelY_mps2;
float LSM6DSV320HighGAccelZ_mps2;

/* Barometer Data*/
float MS560702BA03Temperature_C;
float MS560702BA03Pressure_hPA;
float MS560702BA03Altitude_m;

/* GPS Data */
// Latitude in decimal degrees (+N, -S)
float GPSLatitude;
// Longitude in decimal degrees (+E, -W)
float GPSLongitude;
// Altitude in meters (from GPS)
float GPSAltitude_m;
// GPS fix status: 0 = invalid, 1 = GPS fix, 2 = DGPS
int GPSFix;
// Number of satellites used in fix
int GPSNumSatellites;
// UTC time string from GPS (hhmmss.sss)
char GPSUTCTime[16];

/* Quaternion Data */
float quaternionW;
float quaternionX;
float quaternionY;
float quaternionZ;

float quaternionNorm;

/* Euler Angles */
float roll;
float pitch;
float yaw;

/* Kalman Filter Data */
float KalmanFilterPositionX_m;
float KalmanFilterPositionY_m;
float KalmanFilterPositionZ_m;

float KalmanFilterVelocityX_mps;
float KalmanFilterVelocityY_mps;
float KalmanFilterVelocityZ_mps;

float KalmanFilterAccelerationX_mps2;
float KalmanFilterAccelerationY_mps2;
float KalmanFilterAccelerationZ_mps2;
};



#endif /* INC_DATACONTAINER_H_ */
#endif /* INC_DATACONTAINER_H_ */
102 changes: 102 additions & 0 deletions Code/Core/Inc/Devices/GPS.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,102 @@
/*
* GPS.h
*
* Created on: Jan 08, 2026
* Author: colin
*/

#ifndef SRC_DEVICES_GPS_H_
#define SRC_DEVICES_GPS_H_

#include "main.h"
#include "DataContainer.h"
#include <string.h>

#define GPS_DMA_BUFFER_SIZE 512
#define GPS_UBX_MAX_PAYLOAD 256

class GPS {
public:
GPS(DataContainer* data, UART_HandleTypeDef* uart, uint8_t* dmaBuffer);

int deviceInit();
int updateDevice();

private:
DataContainer* data;
UART_HandleTypeDef* uart;
uint8_t* dmaBuffer;

uint16_t currentBufferPos;
uint16_t lastDmaBufferPos;

// UBX message buffer
uint8_t ubxBuffer[GPS_UBX_MAX_PAYLOAD];
uint16_t ubxIndex;

// UBX-NAV-PVT structure (92 bytes payload)
struct __attribute__((packed)) UBX_NAV_PVT {
uint32_t iTOW; // GPS time of week (ms)
uint16_t year; // Year (UTC)
uint8_t month; // Month (1-12)
uint8_t day; // Day (1-31)
uint8_t hour; // Hour (0-23)
uint8_t min; // Minute (0-59)
uint8_t sec; // Second (0-60)
uint8_t valid; // Validity flags
uint32_t tAcc; // Time accuracy estimate (ns)
int32_t nano; // Fraction of second (-1e9 to 1e9)
uint8_t fixType; // GPS fix type (0=none, 3=3D fix)
uint8_t flags; // Fix status flags
uint8_t flags2; // Additional flags
uint8_t numSV; // Number of satellites
int32_t lon; // Longitude (1e-7 deg)
int32_t lat; // Latitude (1e-7 deg)
int32_t height; // Height above ellipsoid (mm)
int32_t hMSL; // Height above MSL (mm)
uint32_t hAcc; // Horizontal accuracy (mm)
uint32_t vAcc; // Vertical accuracy (mm)
int32_t velN; // North velocity (mm/s)
int32_t velE; // East velocity (mm/s)
int32_t velD; // Down velocity (mm/s)
int32_t gSpeed; // Ground speed (mm/s)
int32_t headMot; // Heading of motion (1e-5 deg)
uint32_t sAcc; // Speed accuracy (mm/s)
uint32_t headAcc; // Heading accuracy (1e-5 deg)
uint16_t pDOP; // Position DOP (0.01)
uint8_t reserved1[6]; // Reserved
int32_t headVeh; // Heading of vehicle (1e-5 deg)
int16_t magDec; // Magnetic declination (1e-2 deg)
uint16_t magAcc; // Magnetic declination accuracy (1e-2 deg)
};

// UBX parser state machine
enum UBXParseState {
WAIT_SYNC1,
WAIT_SYNC2,
GET_CLASS,
GET_ID,
GET_LENGTH1,
GET_LENGTH2,
GET_PAYLOAD,
GET_CHECKSUM1,
GET_CHECKSUM2
};

UBXParseState parseState;
uint8_t msgClass;
uint8_t msgId;
uint16_t payloadLength;
uint16_t payloadIndex;
uint8_t ckA, ckB;

// Private methods
void processDMAData();
bool parseUBXByte(uint8_t byte);
void processUBXMessage();
void sendUBXCommand(const uint8_t* cmd, uint16_t len);
void calculateChecksum(const uint8_t* data, uint16_t len, uint8_t* ckA, uint8_t* ckB);
void configureGPS();
};

#endif /* SRC_DEVICES_GPS_H_ */
Loading