Skip to content
This repository was archived by the owner on Jun 28, 2025. It is now read-only.

Commit dfce61c

Browse files
Small Stuff
1 parent 60b2b39 commit dfce61c

File tree

3 files changed

+76
-55
lines changed

3 files changed

+76
-55
lines changed

TelemetryManager/Inc/TM.hpp

Lines changed: 36 additions & 24 deletions
Original file line numberDiff line numberDiff line change
@@ -14,34 +14,29 @@
1414
#ifndef TM_H
1515
#define TM_H
1616

17-
/**
18-
* @brief This is essentially a compatibility/wrapper function that allows us to turn
19-
* a member function into a static function. This is necessary because FreeRTOS tasks
20-
* can only take static functions as arguments.
21-
* @param memberFunction - The member function to be turned into a static function.
22-
* Note that the Macro simply takes the name in ANSI text of the member function and
23-
* appends "Static" to it. All you need to do is pass the name of the member function.
24-
*/
25-
#define TRANSLATE_TO_STATIC(memberFunction) \
26-
static void memberFunction##Static(void* pvParameters) { \
17+
/**
18+
* @brief This is essentially a compatibility/wrapper function that allows us to turn
19+
* a member function into a static function. This is necessary because FreeRTOS tasks
20+
* can only take static functions as arguments.
21+
* @param memberFunction - The member function to be turned into a static function.
22+
* Note that the Macro simply takes the name in ANSI text of the member function and
23+
* appends "Static" to it. All you need to do is pass the name of the member function.
24+
*/
25+
#define TRANSLATE_TO_STATIC(memberFunction) \
26+
static void memberFunction##Static(void* pvParameters) { \
2727
auto* tmInstance = static_cast<TelemetryManager*>(pvParameters); \
28-
tmInstance->memberFunction(); \
28+
tmInstance->memberFunction(); \
2929
}
3030

3131
#include "GroundStationComms.hpp"
3232
#include "MavlinkTranslator.hpp"
3333
#include "TimerInterrupt.hpp"
3434

3535
class TelemetryManager {
36-
37-
/**
38-
* @brief Construct a new Telemetry Manager object. Does not initialize the threads or timer interrupts.
39-
* To do so call the init() method.
40-
*
41-
* @param GSC - The GroundStationComms object.
42-
* @param MT - The MavlinkTranslator object.
43-
* @param TI -
44-
*/
36+
/**
37+
* @brief Construct a new Telemetry Manager object. Does not initialize the threads or timer
38+
* interrupts. To do so call the init() method.
39+
*/
4540
TelemetryManager();
4641
~TelemetryManager();
4742

@@ -61,17 +56,24 @@ class TelemetryManager {
6156
* message.
6257
*/
6358
void translateToMavlinkThread();
64-
// Create a static version of the translateToMavlinkThread function to be used as a callback for the FreeRTOS task.
59+
60+
/*
61+
Create a static version of the translateToMavlinkThread function to be used as a callback for
62+
the FreeRTOS task.
63+
*/
6564
TRANSLATE_TO_STATIC(translateToMavlinkThread);
6665

6766
/**
6867
* @brief This thread is responsible for taking data from other managers and converting
6968
* them to Mavlink bytes, then putting them into GSC.lowPriorityTransmitBuffer.
7069
*/
7170
void mavlinkToBytesThread();
72-
// Create a static version of the mavlinkToBytesThread function to be used as a callback for the FreeRTOS task.
73-
TRANSLATE_TO_STATIC(mavlinkToBytesThread);
7471

72+
/*
73+
Create a static version of the mavlinkToBytesThread function to be used as a callback for the
74+
FreeRTOS task.
75+
*/
76+
TRANSLATE_TO_STATIC(mavlinkToBytesThread);
7577

7678
/**
7779
* @brief This method is responsible for
@@ -81,7 +83,17 @@ class TelemetryManager {
8183
*/
8284
void sendLowPriorityData();
8385

84-
void createTimerInterrupts();
86+
/**
87+
* @brief Create the timer interrupts for the TelemetryManager.
88+
*
89+
*/
90+
void initTimerInterrupts();
91+
92+
/**
93+
* @brief Create and configure the threads for the TelemetryManager.
94+
*
95+
*/
96+
void initTasks();
8597
};
8698

8799
#endif

TelemetryManager/Src/TM.cpp

Lines changed: 37 additions & 28 deletions
Original file line numberDiff line numberDiff line change
@@ -1,22 +1,57 @@
1+
#include "FreeRTOS.h"
12
#include "GroundStationComms.hpp"
23
#include "MavlinkTranslator.hpp"
34
#include "TimerInterrupt.hpp"
4-
#include "FreeRTOS.h"
55
#include "task.h"
66

77
TelemetryManager::TelemetryManager() {
88
this->MT = MavlinkTranslator();
99
this->GSC = GroundStationComms();
1010
}
1111

12+
TelemetryManager::~TelemetryManager() {
13+
// Destructor
14+
}
15+
1216
/**
1317
* @brief Initialize TM threads and timer interrupts.
1418
*
1519
*/
1620
void TelemetryManager::init() {
1721
// initialize the timer interrupts
18-
createTimerInterrupts();
22+
initTimerInterrupts();
23+
24+
// Init TM tasks
25+
initTasks();
26+
27+
// Start the scheduler
28+
vTaskStartScheduler(); // should this be in system manager instead?
29+
}
30+
31+
void TelemetryManager::initTimerInterrupts() {
32+
/**
33+
* @brief This interrupt service routine is called every 1000ms. It is responsible for
34+
* sending the highest priority drone "state" data to the ground station. Data such as
35+
* heartbeat message, altitude, attitude, latitude, longitude... And anything else deemed
36+
* important enough to be transmitted at a regular interval. This is the highest priority
37+
* data in the GSC.highPriorityTransmitBuffer.
38+
*
39+
*/
40+
TimerInterrupt dispatchHighPriorityInterrupt1000Ms(
41+
"dispatchHighPriority1000Ms", configMINIMAL_STACK_SIZE, tskIDLE_PRIORITY, 500, *this,
42+
[](TelemetryManager& tm) -> void {
43+
auto GSC = tm.GSC;
44+
45+
// START: ingest drone state data and pack bytes into GSC.highPriorityTransmitBuffer
1946

47+
// END: ingest drone state data and pack bytes into GSC.highPriorityTransmitBuffer
48+
49+
// transmit the data via GSC.sendToGroundStation(); function
50+
GSC.sendToGroundStation(GSC.highPriorityTransmitBuffer);
51+
});
52+
}
53+
54+
void TelemetryManager::initTasks() {
2055
// Initialize translateToMavlinkThread as a FreeRTOS task
2156
xTaskCreate(TelemetryManager::translateToMavlinkThreadStatic, // Task function
2257
"translateToMavlinkThread", // Task name
@@ -34,9 +69,6 @@ void TelemetryManager::init() {
3469
tskIDLE_PRIORITY + 1, // Task priority
3570
NULL // Task handle
3671
);
37-
38-
// Start the scheduler
39-
vTaskStartScheduler(); // should this be in system manager instead?
4072
}
4173

4274
/**
@@ -76,26 +108,3 @@ void TelemetryManager::sendLowPriorityData() {
76108
// transmit low priority the data via GSC.sendToGroundStation(); function
77109
GSC.sendToGroundStation(GSC.lowPriorityTransmitBuffer);
78110
}
79-
80-
void TelemetryManager::createTimerInterrupts() {
81-
/**
82-
* @brief This interrupt service routine is called every 1000ms. It is responsible for
83-
* sending the highest priority drone "state" data to the ground station. Data such as
84-
* heartbeat message, altitude, attitude, latitude, longitude... And anything else deemed
85-
* important enough to be transmitted at a regular interval. This is the highest priority
86-
* data in the GSC.highPriorityTransmitBuffer.
87-
*
88-
*/
89-
TimerInterrupt dispatchHighPriorityInterrupt1000Ms(
90-
"dispatchHighPriority1000Ms", configMINIMAL_STACK_SIZE, tskIDLE_PRIORITY, 500, *this,
91-
[](TelemetryManager& tm) -> void {
92-
auto GSC = tm.GSC;
93-
94-
// START: ingest drone state data and pack bytes into GSC.highPriorityTransmitBuffer
95-
96-
// END: ingest drone state data and pack bytes into GSC.highPriorityTransmitBuffer
97-
98-
// transmit the data via GSC.sendToGroundStation(); function
99-
GSC.sendToGroundStation(GSC.highPriorityTransmitBuffer);
100-
});
101-
}

TelemetryManager/Src/TimerInterrupt.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -4,8 +4,9 @@
44
TimerInterrupt::TimerInterrupt(const char *taskName, int stackSize, UBaseType_t uxPriority,
55
TickType_t intervalMs, TelemetryManager &tm, Callback cbLambda)
66
: tm(tm), cbLambda(cbLambda), xHandle(nullptr) {
7-
8-
// Below is just an example of creating a task with the TaskTrampoline. This is not the actual implementation.
7+
8+
// Below is just an example of creating a task with the TaskTrampoline. This is not the actual
9+
// implementation. Delete it and implement the actual timer interrupt.
910
xTaskCreate(&TimerInterrupt::TaskTrampoline, taskName, stackSize, this, uxPriority, &xHandle);
1011

1112
// START: Implement the actual timer interrupt and call the callback function every intervalMs
@@ -18,4 +19,3 @@ TimerInterrupt::~TimerInterrupt() {
1819
vTaskDelete(xHandle);
1920
}
2021
}
21-

0 commit comments

Comments
 (0)