Skip to content

Commit

Permalink
Small Stuff
Browse files Browse the repository at this point in the history
  • Loading branch information
Yaremadzulynsky committed Mar 11, 2024
1 parent 60b2b39 commit dfce61c
Show file tree
Hide file tree
Showing 3 changed files with 76 additions and 55 deletions.
60 changes: 36 additions & 24 deletions TelemetryManager/Inc/TM.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,34 +14,29 @@
#ifndef TM_H
#define TM_H

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

#include "GroundStationComms.hpp"
#include "MavlinkTranslator.hpp"
#include "TimerInterrupt.hpp"

class TelemetryManager {

/**
* @brief Construct a new Telemetry Manager object. Does not initialize the threads or timer interrupts.
* To do so call the init() method.
*
* @param GSC - The GroundStationComms object.
* @param MT - The MavlinkTranslator object.
* @param TI -
*/
/**
* @brief Construct a new Telemetry Manager object. Does not initialize the threads or timer
* interrupts. To do so call the init() method.
*/
TelemetryManager();
~TelemetryManager();

Expand All @@ -61,17 +56,24 @@ class TelemetryManager {
* message.
*/
void translateToMavlinkThread();
// Create a static version of the translateToMavlinkThread function to be used as a callback for the FreeRTOS task.

/*
Create a static version of the translateToMavlinkThread function to be used as a callback for
the FreeRTOS task.
*/
TRANSLATE_TO_STATIC(translateToMavlinkThread);

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

/*
Create a static version of the mavlinkToBytesThread function to be used as a callback for the
FreeRTOS task.
*/
TRANSLATE_TO_STATIC(mavlinkToBytesThread);

/**
* @brief This method is responsible for
Expand All @@ -81,7 +83,17 @@ class TelemetryManager {
*/
void sendLowPriorityData();

void createTimerInterrupts();
/**
* @brief Create the timer interrupts for the TelemetryManager.
*
*/
void initTimerInterrupts();

/**
* @brief Create and configure the threads for the TelemetryManager.
*
*/
void initTasks();
};

#endif
65 changes: 37 additions & 28 deletions TelemetryManager/Src/TM.cpp
Original file line number Diff line number Diff line change
@@ -1,22 +1,57 @@
#include "FreeRTOS.h"
#include "GroundStationComms.hpp"
#include "MavlinkTranslator.hpp"
#include "TimerInterrupt.hpp"
#include "FreeRTOS.h"
#include "task.h"

TelemetryManager::TelemetryManager() {
this->MT = MavlinkTranslator();
this->GSC = GroundStationComms();
}

TelemetryManager::~TelemetryManager() {
// Destructor
}

/**
* @brief Initialize TM threads and timer interrupts.
*
*/
void TelemetryManager::init() {
// initialize the timer interrupts
createTimerInterrupts();
initTimerInterrupts();

// Init TM tasks
initTasks();

// Start the scheduler
vTaskStartScheduler(); // should this be in system manager instead?
}

void TelemetryManager::initTimerInterrupts() {
/**
* @brief This interrupt service routine is called every 1000ms. It is responsible for
* sending the highest priority drone "state" data to the ground station. Data such as
* heartbeat message, altitude, attitude, latitude, longitude... And anything else deemed
* important enough to be transmitted at a regular interval. This is the highest priority
* data in the GSC.highPriorityTransmitBuffer.
*
*/
TimerInterrupt dispatchHighPriorityInterrupt1000Ms(
"dispatchHighPriority1000Ms", configMINIMAL_STACK_SIZE, tskIDLE_PRIORITY, 500, *this,
[](TelemetryManager& tm) -> void {
auto GSC = tm.GSC;

// START: ingest drone state data and pack bytes into GSC.highPriorityTransmitBuffer

// END: ingest drone state data and pack bytes into GSC.highPriorityTransmitBuffer

// transmit the data via GSC.sendToGroundStation(); function
GSC.sendToGroundStation(GSC.highPriorityTransmitBuffer);
});
}

void TelemetryManager::initTasks() {
// Initialize translateToMavlinkThread as a FreeRTOS task
xTaskCreate(TelemetryManager::translateToMavlinkThreadStatic, // Task function
"translateToMavlinkThread", // Task name
Expand All @@ -34,9 +69,6 @@ void TelemetryManager::init() {
tskIDLE_PRIORITY + 1, // Task priority
NULL // Task handle
);

// Start the scheduler
vTaskStartScheduler(); // should this be in system manager instead?
}

/**
Expand Down Expand Up @@ -76,26 +108,3 @@ void TelemetryManager::sendLowPriorityData() {
// transmit low priority the data via GSC.sendToGroundStation(); function
GSC.sendToGroundStation(GSC.lowPriorityTransmitBuffer);
}

void TelemetryManager::createTimerInterrupts() {
/**
* @brief This interrupt service routine is called every 1000ms. It is responsible for
* sending the highest priority drone "state" data to the ground station. Data such as
* heartbeat message, altitude, attitude, latitude, longitude... And anything else deemed
* important enough to be transmitted at a regular interval. This is the highest priority
* data in the GSC.highPriorityTransmitBuffer.
*
*/
TimerInterrupt dispatchHighPriorityInterrupt1000Ms(
"dispatchHighPriority1000Ms", configMINIMAL_STACK_SIZE, tskIDLE_PRIORITY, 500, *this,
[](TelemetryManager& tm) -> void {
auto GSC = tm.GSC;

// START: ingest drone state data and pack bytes into GSC.highPriorityTransmitBuffer

// END: ingest drone state data and pack bytes into GSC.highPriorityTransmitBuffer

// transmit the data via GSC.sendToGroundStation(); function
GSC.sendToGroundStation(GSC.highPriorityTransmitBuffer);
});
}
6 changes: 3 additions & 3 deletions TelemetryManager/Src/TimerInterrupt.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,9 @@
TimerInterrupt::TimerInterrupt(const char *taskName, int stackSize, UBaseType_t uxPriority,
TickType_t intervalMs, TelemetryManager &tm, Callback cbLambda)
: tm(tm), cbLambda(cbLambda), xHandle(nullptr) {

// Below is just an example of creating a task with the TaskTrampoline. This is not the actual implementation.

// Below is just an example of creating a task with the TaskTrampoline. This is not the actual
// implementation. Delete it and implement the actual timer interrupt.
xTaskCreate(&TimerInterrupt::TaskTrampoline, taskName, stackSize, this, uxPriority, &xHandle);

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

0 comments on commit dfce61c

Please sign in to comment.