![]() |
N4 Flight Software N4
Flight software used for the N4 flight computers
|
This contains the main driver code for the flight computer. More...
#include <Arduino.h>
#include <Wire.h>
#include <WiFi.h>
#include <PubSubClient.h>
#include <TinyGPSPlus.h>
#include <SFE_BMP180.h>
#include <FS.h>
#include <SD.h>
#include <SPIFFS.h>
#include "defs.h"
#include "mpu.h"
#include "SerialFlash.h"
#include "logger.h"
#include "data_types.h"
#include "states.h"
#include "system_logger.h"
#include "system_log_levels.h"
#include "wifi-config.h"
#include "kalman_filter.h"
#include "ring_buffer.h"
Macros | |
#define | BMP_CHECK_BIT 0 |
#define | IMU_CHECK_BIT 1 |
#define | FLASH_CHECK_BIT 2 |
#define | GPS_CHECK_BIT 3 |
#define | SD_CHECK_BIT 4 |
#define | SPIFFS_CHECK_BIT 5 |
#define | TEST_HARDWARE_CHECK_BIT 6 |
Enumerations | |
enum | OPERATION_MODE { SAFE_MODE = 0 , ARMED_MODE } |
enum | BUZZ_INTERVALS { SETUP_INIT = 200 , ARMING_PROCEDURE = 500 } |
enum | BLINK_INTERVALS { SAFE_BLINK = 400 , ARMED_BLINK = 100 } |
Functions | |
void | initDynamicWIFI () |
create dynamic WIFI | |
void | drogueChuteDeploy () |
fires the pyro-charge to deploy the drogue chute Turn on the drogue chute ejection circuit by running the GPIO HIGH for a preset No. of seconds. Default no. of seconds to remain HIGH is 5 | |
void | mainChuteDeploy () |
fires the pyro-charge to deploy the main chute Turn on the main chute ejection circuit by running the GPIO HIGH for a preset No. of seconds Default no. of seconds to remain HIGH is 5 | |
float | kalmanFilter (float z) |
Kalman filter estimated value calculation. | |
void | checkRunTestToggle () |
void | non_blocking_buzz (uint16_t interval) |
| |
void | blocking_buzz (uint16_t interval) |
blocking buzz | |
double | altimeter_get_pressure () |
Read the raw pressure from the altimeter. | |
void | mqtt_command_processor (const char *topic, const char *command) |
process commands sent from the base station | |
void | arm_pyros () |
void | disarm_pyros () |
HardwareSerial | gpsSerial (2) |
PubSubClient | client (wifi_client) |
uint8_t | MQTTInit (const char *broker_IP, uint16_t broker_port) |
void | buzzerInit () |
initialize Buzzer | |
void | LED_init () |
uint8_t | InitSPIFFS () |
initialize SPIFFS for event logging during flight | |
uint8_t | initSD () |
initilize SD card | |
uint8_t | BMPInit () |
Initialize BMP180 barometric sensor. | |
uint8_t | GPSInit () |
Initialize the GPS connected on Serial2. | |
void | readAccelerationTask (void *pvParameter) |
Read acceleration data from the accelerometer. | |
void | readAltimeterTask (void *pvParameters) |
Read atm pressure data from the barometric sensor onboard. | |
void | readGPSTask (void *pvParameters) |
Read the GPS location data and altitude and append to telemetry packet for transmission. | |
void | kalmanFilterTask (void *pvParameters) |
Filter data using the Kalman Filter. | |
void | checkFlightState (void *pvParameters) |
check various condition from flight data to change the flight state | |
void | flightStateCallback (void *pvParameters) |
performs flight actions based on the current flight state | |
void | debugToTerminalTask (void *pvParameters) |
debug flight/test data to terminal, this task is called if the DEBUG_TO_TERMINAL is set to 1 (see defs.h) | |
void | logToMemory (void *pvParameter) |
log the data to the external flash memory | |
void | MQTT_TransmitTelemetry (void *pvParameters) |
send flight data to ground | |
void | MQTT_Reconnect () |
Try reconnecting to MQTT if connection is lost. | |
void | mqtt_Callback (char *topic, byte *payload, unsigned int length) |
void | MQTTInit (const char *broker_IP, int broker_port) |
Initialize MQTT. | |
void | xOperationModeIndicateTask (void *pvParameters) |
blinks green LED for safe mode and red LED for armed mode | |
void | xCreateAllTasks () |
void | setup () |
Setup - perform initialization of all hardware subsystems, create queues, create queue handles initialize system check table. | |
void | loop () |
Main loop. | |
Variables | |
uint8_t | operation_mode = 0 |
uint8_t | current_state = ARMED_FLIGHT_STATE::PRE_FLIGHT_GROUND |
uint8_t | STATE_BIT_MASK = 0 |
TinyGPSPlus | gps |
char | gps_buffer [20] |
gps_type_t | gps_packet |
SystemLogger | SYSTEM_LOGGER |
const char * | system_log_file = "/event_log.txt" |
LOG_LEVEL | level = INFO |
const char * | rocket_ID = "FC1" |
uint8_t | is_safe_mode = OPERATION_MODE::SAFE_MODE |
unsigned long | current_non_block_time = 0 |
unsigned long | last_non_block_time = 0 |
bool | buzz_state = 0 |
uint8_t | mqtt_connect_flag |
uint8_t | SUBSYSTEM_INIT_MASK = 0b00000000 |
WiFiClient | wifi_client |
WIFIConfig | wifi_config |
uint8_t | drogue_pyro = 25 |
uint8_t | main_pyro = 12 |
uint8_t | flash_cs_pin = 5 |
uint8_t | remote_switch = 27 |
uint8_t | flash_led_pin = 32 |
char | filename [] = "flight_data.txt" |
uint32_t | FILE_SIZE_512K = 524288L |
uint32_t | FILE_SIZE_1M = 1048576L |
uint32_t | FILE_SIZE_4M = 4194304L |
SerialFlashFile | file |
unsigned long long | previous_log_time = 0 |
unsigned long long | current_log_time = 0 |
uint16_t | log_sample_interval = 5 |
DataLogger | data_logger (flash_cs_pin, RED_LED_PIN, filename, file, FILE_SIZE_4M) |
long long | current_time = 0 |
long long | previous_time = 0 |
char | telemetry_packet_buffer [256] |
ring_buffer | altitude_ring_buffer |
double | baseline = 0.0 |
float | curr_val |
float | oldest_val |
uint8_t | apogee_flag =0 |
uint8_t | main_eject_flag = 0 |
TaskHandle_t | readAccelerationTaskHandle |
TaskHandle_t | readAltimeterTaskHandle |
TaskHandle_t | readGPSTaskHandle |
TaskHandle_t | clearTelemetryQueueTaskHandle |
TaskHandle_t | checkFlightStateTaskHandle |
TaskHandle_t | flightStateCallbackTaskHandle |
TaskHandle_t | MQTT_TransmitTelemetryTaskHandle |
TaskHandle_t | kalmanFilterTaskHandle |
TaskHandle_t | debugToTerminalTaskHandle |
TaskHandle_t | logToMemoryTaskHandle |
TaskHandle_t | opModeIndicateTaskHandle |
accel_type_t | acc_data |
gyro_type_t | gyro_data |
gps_type_t | gps_data |
altimeter_type_t | altimeter_data |
telemetry_type_t | telemetry_packet |
MPU6050 | imu (MPU_ADDRESS, MPU_ACCEL_RANGE, GYRO_RANGE) |
SFE_BMP180 | altimeter |
double | altimeter_temperature = 0.0 |
altimeter_type_t | altimeter_packet |
QueueHandle_t | telemetry_data_queue_handle |
QueueHandle_t | log_to_mem_queue_handle |
QueueHandle_t | check_state_queue_handle |
QueueHandle_t | debug_to_term_queue_handle |
QueueHandle_t | kalman_filter_queue_handle |
This contains the main driver code for the flight computer.
0x5765206D6179206D616B65206F757220706C616E73202C 0x62757420476F642068617320746865206C61737420776F7264
enum OPERATION_MODE |
flight states these states are to be used for flight
double altimeter_get_pressure | ( | ) |
Read the raw pressure from the altimeter.
uint8_t BMPInit | ( | ) |
Initialize BMP180 barometric sensor.
void checkFlightState | ( | void * | pvParameters | ) |
void checkRunTestToggle | ( | ) |
Check the toggle pin for TESTING or RUN mode
void debugToTerminalTask | ( | void * | pvParameters | ) |
debug flight/test data to terminal, this task is called if the DEBUG_TO_TERMINAL is set to 1 (see defs.h)
pvParameter | - A value that is passed as the parameter to the created task. If pvParameter is set to the address of a variable then the variable must still exist when the created task executes - so it is not valid to pass the address of a stack variable. |
record number operation_mode state ax ay az pitch roll gx gy gz latitude longitude gps_altitude pressure temperature altitude_agl velocity
void drogueChuteDeploy | ( | ) |
fires the pyro-charge to deploy the drogue chute Turn on the drogue chute ejection circuit by running the GPIO HIGH for a preset No. of seconds.
Default no. of seconds to remain HIGH is 5
void flightStateCallback | ( | void * | pvParameters | ) |
performs flight actions based on the current flight state
If the flight state requires an action, we perform it here For example if the flight state is apogee, we perform MAIN_CHUTE ejection
uint8_t GPSInit | ( | ) |
Initialize the GPS connected on Serial2.
FIXME: Proper GPS init check! Look into if the GPS has acquired a LOCK on satelites Only if it has a lock then can we return a 1
void kalmanFilterTask | ( | void * | pvParameters | ) |
Filter data using the Kalman Filter.
void logToMemory | ( | void * | pvParameter | ) |
log the data to the external flash memory
pvParameter | - A value that is passed as the paramater to the created task. If pvParameter is set to the address of a variable then the variable must still exist when the created task executes - so it is not valid to pass the address of a stack variable. |
void loop | ( | ) |
Main loop.
void mainChuteDeploy | ( | ) |
fires the pyro-charge to deploy the main chute Turn on the main chute ejection circuit by running the GPIO HIGH for a preset No. of seconds Default no. of seconds to remain HIGH is 5
void mqtt_command_processor | ( | const char * | topic, |
const char * | command ) |
process commands sent from the base station
command | ARM DISARM RESET |
void MQTT_TransmitTelemetry | ( | void * | pvParameters | ) |
send flight data to ground
pvParameter | - A value that is passed as the parameter to the created task. If pvParameter is set to the address of a variable then the variable must still exist when the created task executes - so it is not valid to pass the address of a stack variable. |
PACKAGE TELEMETRY PACKET
record number operation_mode state ax ay az pitch roll gx gy gz latitude longitude gps_altitude pressure temperature relative_altitude
void MQTTInit | ( | const char * | broker_IP, |
int | broker_port ) |
Initialize MQTT.
void readAccelerationTask | ( | void * | pvParameter | ) |
Read acceleration data from the accelerometer.
pvParameters | - A value that is passed as the paramater to the created task. If pvParameters is set to the address of a variable then the variable must still exist when the created task executes - so it is not valid to pass the address of a stack variable. |
void readAltimeterTask | ( | void * | pvParameters | ) |
Read atm pressure data from the barometric sensor onboard.
void readGPSTask | ( | void * | pvParameters | ) |
Read the GPS location data and altitude and append to telemetry packet for transmission.
pvParameters | - A value that is passed as the paramater to the created task. If pvParameters is set to the address of a variable then the variable must still exist when the created task executes - so it is not valid to pass the address of a stack variable. |
void setup | ( | ) |
Setup - perform initialization of all hardware subsystems, create queues, create queue handles initialize system check table.
void xOperationModeIndicateTask | ( | void * | pvParameters | ) |
blinks green LED for safe mode and red LED for armed mode
accel_type_t acc_data |
///////////////////////// DATA TYPES /////////////////////////
unsigned long long current_log_time = 0 |
What is the processor time right now?
uint8_t current_state = ARMED_FLIGHT_STATE::PRE_FLIGHT_GROUND |
The starting state - we start at PRE_FLIGHT_GROUND state
SerialFlashFile file |
object representing file object for flash memory
uint32_t FILE_SIZE_1M = 1048576L |
1MB
uint32_t FILE_SIZE_4M = 4194304L |
4MB
uint32_t FILE_SIZE_512K = 524288L |
512KB
char filename[] = "flight_data.txt" |
data log filename - Filename must be less than 20 chars, including the file extension
uint8_t flash_cs_pin = 5 |
External flash memory chip select pin
uint8_t flash_led_pin = 32 |
LED pin connected to indicate flash memory formatting
MPU6050 imu(MPU_ADDRESS, MPU_ACCEL_RANGE, GYRO_RANGE) | ( | MPU_ADDRESS | , |
MPU_ACCEL_RANGE | , | ||
GYRO_RANGE | ) |
///////////////////////// END OF DATA VARIABLES ///////////////////////// create an MPU6050 object 0x68 is the address of the MPU set gyro to max deg to 1000 deg/sec set accel fs reading to 16g
uint16_t log_sample_interval = 5 |
After how long should we sample and log data to flash memory?
uint8_t operation_mode = 0 |
Tells whether software is in safe or flight mode - FLIGHT_MODE=1, SAFE_MODE=0
unsigned long long previous_log_time = 0 |
The last time we logged data to memory
TaskHandle_t readAccelerationTaskHandle |
Task creation handles
const char* rocket_ID = "FC1" |
Unique ID of the rocket. Change to the needed rocket name before uploading
QueueHandle_t telemetry_data_queue_handle |
///////////////////////// END OF PERIPHERALS INIT /////////////////////////
WiFiClient wifi_client |
MQTT helper instances, if using MQTT to transmit telemetry