55
66#include " SystemManager.hpp"
77
8+ #include < iostream>
9+
10+ #include " FreeRTOS.h"
11+ #include " GroundStationCommunication.hpp"
12+ #include " TelemetryManager.hpp"
13+ #include " cmsis_os.h"
814#include " drivers_config.hpp"
915#include " independent_watchdog.h"
1016#include " rcreceiver_datatypes.h"
1117#include " sbus_defines.h"
1218#include " sbus_receiver.hpp"
1319#include " tim.h"
14- #include " cmsis_os.h"
15- #include " FreeRTOS.h"
16- #include < iostream>
1720
1821extern " C" {
19- #include " app_fatfs.h"
20- #include " log_util.h"
22+ #include " app_fatfs.h"
23+ #include " log_util.h"
2124}
2225
23- #define TIMEOUT_CYCLES 250000 // 25k = 1 sec fro testing 10/14/2023 => 250k = 10 sec
24- #define TIMOUT_MS 10000 // 10 sec
26+ #define TIMEOUT_CYCLES 250000 // 25k = 1 sec fro testing 10/14/2023 => 250k = 10 sec
27+ #define TIMOUT_MS 10000 // 10 sec
2528
2629// 0 - AM, 1 - TM, 2 - PM
2730static TaskHandle_t taskHandles[3 ];
@@ -43,40 +46,88 @@ SystemManager::SystemManager()
4346 // VARIABLES FOR TELEMETRY MANAGER TO HAVE AS REFERENCES THEY OBV SHOULD BE PUT SOMEWHERE ELSE,
4447 // BUT I FEEL LIKE SM PM WOULD KNOW WHERE. MAYBE IN THE HPP FILE? IDK HOW YOU ARE PLANNING ON
4548 // GATHERING THE DATA. I JUST PUT THEM HERE FOR NOW
49+
50+
51+ this ->telemetryManager = setupTM ();
52+ this ->telemetryManager ->init ();
53+
54+ // IDK WHERE SM PLANS TO DO THIS, BUT telemetryManager.update() NEEDS TO BE CALLED AT A SEMI
55+ // REGULAR INTERVAL AS IT DEALS WITH MESSAGE DECODING AND LOW PRIORITY DATA TRANSMISSION
56+ }
57+
58+ TelemetryManager* SystemManager::setupTM () {
59+
60+ // Struct containing the state of the drone
61+ TMStateData stateData;
62+
63+ // values to be assigned to stateData
64+ // THIS IS JUST A PLACEHOLDER, THE MEMORY ADDRESSES NEED TO LIVE LONGER THAN THE SM CONSTRUCTOR
65+ int32_t alt = 0 ;
4666 int32_t lat = 0 ;
4767 int32_t lon = 0 ;
48- int32_t alt = 0 ;
4968 int32_t relative_alt = 0 ;
5069 int16_t vx = 0 ;
5170 int16_t vy = 0 ;
5271 int16_t vz = 0 ;
5372 uint16_t hdg = 0 ;
5473 int32_t time_boot_ms = 0 ;
55- MAV_STATE state = MAV_STATE::MAV_STATE_STANDBY;
56- MAV_MODE_FLAG mode = MAV_MODE_FLAG::MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
5774 float roll = 0 ;
5875 float pitch = 0 ;
5976 float yaw = 0 ;
6077 float rollspeed = 0 ;
6178 float pitchspeed = 0 ;
6279 float yawspeed = 0 ;
6380
64- this ->telemetryManager =
65- new TelemetryManager (lat, lon, alt, relative_alt, vx, vy, vz, hdg, time_boot_ms, state,
66- mode, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed);
67- this ->telemetryManager ->init ();
68- // IDK WHERE SM PLANS TO DO THIS, BUT telemetryManager.update() NEEDS TO BE CALLED AT A SEMI
69- // REGULAR INTERVAL AS IT DEALS WITH MESSAGE DECODING AND LOW PRIORITY DATA TRANSMISSION
81+ // use the memory address of the above, since stateData uses pointers
82+ stateData.set_alt (&alt);
83+ stateData.set_lat (&lat);
84+ stateData.set_lon (&lon);
85+ stateData.set_relative_alt (&relative_alt);
86+ stateData.set_vx (&vx);
87+ stateData.set_vy (&vy);
88+ stateData.set_vz (&vz);
89+ stateData.set_hdg (&hdg);
90+ stateData.set_time_boot_ms (&time_boot_ms);
91+ stateData.set_roll (&roll);
92+ stateData.set_pitch (&pitch);
93+ stateData.set_yaw (&yaw);
94+ stateData.set_rollspeed (&rollspeed);
95+ stateData.set_pitchspeed (&pitchspeed);
96+ stateData.set_yawspeed (&yawspeed);
97+
98+ MAV_STATE mavState = MAV_STATE::MAV_STATE_STANDBY;
99+ MAV_MODE_FLAG mavMode = MAV_MODE_FLAG::MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
100+
101+ // Creating parameters for the GroundStationCommunication that will be passed to
102+ // telemetryManager
103+ TMCircularBuffer DMAReceiveBuffer = *(new TMCircularBuffer (rfd900_circular_buffer));
104+
105+ // the buffer that stores non_routine/low_priority bytes (ex. Battery Voltage) to be sent to the
106+ // ground station.
107+ uint8_t *lowPriorityTransmitBuffer = new uint8_t [RFD900_BUF_SIZE];
108+
109+ // the buffer that stores routine/high_priority bytes (ex. heading, general state data) to be
110+ // sent to the ground station.
111+ uint8_t *highPriorityTransmitBuffer = new uint8_t [RFD900_BUF_SIZE];
112+
113+ GroundStationCommunication GSC = *(new GroundStationCommunication (
114+ DMAReceiveBuffer, lowPriorityTransmitBuffer, highPriorityTransmitBuffer, RFD900_BUF_SIZE));
115+
116+ // the buffer that stores the bytes received from the ground station.
117+ MavlinkTranslator MT;
118+
119+
120+ return new TelemetryManager (stateData, mavState, mavMode, GSC, MT);
70121}
71122
72-
73- // wrapper functions are needed as FreeRTOS xTaskCreate function does not accept functions that have "this" pointers
74- void SystemManager::attitudeManagerTaskWrapper (void * pvParameters){
75- SystemManager *systemManagerInstance = static_cast <SystemManager *>(pvParameters);
123+ // wrapper functions are needed as FreeRTOS xTaskCreate function does not accept functions that have
124+ // "this" pointers
125+ void SystemManager::attitudeManagerTaskWrapper (void * pvParameters) {
126+ SystemManager *systemManagerInstance = static_cast <SystemManager *>(pvParameters);
76127 systemManagerInstance->attitudeManagerTask ();
77128}
78129
79- void SystemManager::telemetryManagerTaskWrapper (void * pvParameters){
130+ void SystemManager::telemetryManagerTaskWrapper (void * pvParameters) {
80131 SystemManager *systemManagerInstance = static_cast <SystemManager *>(pvParameters);
81132 systemManagerInstance->telemetryManagerTask ();
82133}
@@ -86,13 +137,13 @@ void SystemManager::pathManagerTaskWrapper(void *pvParameters) {
86137 systemManagerInstance->pathManagerTask ();
87138}
88139
89- void SystemManager::systemManagerTask (){
140+ void SystemManager::systemManagerTask () {
90141 TickType_t xNextWakeTime = xTaskGetTickCount ();
91142 uint16_t frequency = 5 ;
92143
93- for (;;){
144+ for (;;) {
94145 printf (" SM called\r\n " );
95- HAL_GPIO_TogglePin (GPIOB, GPIO_PIN_7); // toggle led light for testing
146+ HAL_GPIO_TogglePin (GPIOB, GPIO_PIN_7); // toggle led light for testing
96147
97148 this ->rcInputs_ = rcController_->GetRCControl ();
98149
@@ -134,42 +185,42 @@ void SystemManager::systemManagerTask(){
134185 this ->invertedRollMotorChannel_ .set (SBUS_MAX / 2 );
135186 }
136187
137- vTaskDelayUntil (&xNextWakeTime, 1000 / frequency);
188+ vTaskDelayUntil (&xNextWakeTime, 1000 / frequency);
138189 }
139190}
140191
141- void SystemManager::attitudeManagerTask (){
192+ void SystemManager::attitudeManagerTask () {
142193 TickType_t xNextWakeTime = xTaskGetTickCount ();
143194 uint16_t frequency = 5 ;
144195
145- for (;;){
146- // call AM
196+ for (;;) {
197+ // call AM
147198
148199 printf (" AM called\r\n " );
149- HAL_GPIO_TogglePin (GPIOC, GPIO_PIN_7); // toggle led light for testing
150- vTaskDelayUntil (&xNextWakeTime, 1000 / frequency);
200+ HAL_GPIO_TogglePin (GPIOC, GPIO_PIN_7); // toggle led light for testing
201+ vTaskDelayUntil (&xNextWakeTime, 1000 / frequency);
151202 }
152203}
153204
154- void SystemManager::telemetryManagerTask (){
205+ void SystemManager::telemetryManagerTask () {
155206 TickType_t xNextWakeTime = xTaskGetTickCount ();
156207 uint16_t frequency = 5 ;
157208
158- for (;;){
159- // call TM
209+ for (;;) {
210+ // call TM
160211
161212 printf (" TM called\r\n " );
162- HAL_GPIO_TogglePin (GPIOA, GPIO_PIN_9); // toggle led light for testing
163- vTaskDelayUntil (&xNextWakeTime, 1000 / frequency);
213+ HAL_GPIO_TogglePin (GPIOA, GPIO_PIN_9); // toggle led light for testing
214+ vTaskDelayUntil (&xNextWakeTime, 1000 / frequency);
164215 }
165216}
166217
167- void SystemManager::pathManagerTask (){
218+ void SystemManager::pathManagerTask () {
168219 TickType_t xNextWakeTime = xTaskGetTickCount ();
169220 uint16_t frequency = 5 ;
170221
171- for (;;){
172- // call PM
222+ for (;;) {
223+ // call PM
173224
174225 printf (" PM called\r\n " );
175226 vTaskDelayUntil (&xNextWakeTime, 1000 / frequency);
@@ -183,14 +234,18 @@ void SystemManager::startSystemManager() {
183234 if (MX_FATFS_Init () != APP_OK) {
184235 Error_Handler ();
185236 }
186- logInit ();
187-
188- // BaseType_t xTaskCreate( TaskFunction_t pvTaskCode, const char * const pcName, configSTACK_DEPTH_TYPE usStackDepth, void * pvParameters, UBaseType_t uxPriority, TaskHandle_t * pxCreatedTask );
189- // function's name description size of stack to allocate parameters for task priority handler
237+ logInit ();
238+
239+ // BaseType_t xTaskCreate( TaskFunction_t pvTaskCode, const char * const pcName,
240+ // configSTACK_DEPTH_TYPE usStackDepth, void * pvParameters, UBaseType_t uxPriority,
241+ // TaskHandle_t * pxCreatedTask );
242+ // function's name description size of
243+ // stack to allocate parameters for task priority
244+ // handler
190245 xTaskCreate (attitudeManagerTaskWrapper, " AM TASK" , 800U , this , osPriorityNormal, taskHandles);
191- xTaskCreate (telemetryManagerTaskWrapper, " TM TASK" , 800U , this , osPriorityNormal, taskHandles + 1 );
246+ xTaskCreate (telemetryManagerTaskWrapper, " TM TASK" , 800U , this , osPriorityNormal,
247+ taskHandles + 1 );
192248 // xTaskCreate(pathManagerTaskWrapper, "PM TASK", 800U, this, osPriorityNormal, taskHandles +2);
193249
194250 systemManagerTask ();
195-
196251}
0 commit comments