Skip to content

Commit

Permalink
Added Task Trampoline Logic
Browse files Browse the repository at this point in the history
  • Loading branch information
Yaremadzulynsky committed Mar 11, 2024
1 parent acfb908 commit 60b2b39
Show file tree
Hide file tree
Showing 4 changed files with 158 additions and 107 deletions.
64 changes: 34 additions & 30 deletions TelemetryManager/Inc/TM.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,77 +7,81 @@
* @version 1.0
* @date 2023-08-24
* @author Yarema Dzulynsky: initial structure & Implementation
*
*
* @warning Any issues you think are important/foresee in the future?
*/

#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) { \
auto* tmInstance = static_cast<TelemetryManager*>(pvParameters); \
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 -
*/
TelemetryManager();
~TelemetryManager();

public:
GroundStationComms GSC;
MavlinkTranslator MT;
TimerInterrupt TI;

/**
* @brief Allows access to the TelemetryManager instance statically. This can be done because
* we will only ever have one instance of the TelemetryManager. This is a singleton pattern.
*
* @return TelemetryManager& Reference to the static TelemetryManager instance.
*/
static TelemetryManager &getInstance() {
static TelemetryManager instance;
return instance;
}

TelemetryManager(const TelemetryManager &) = delete; // Prevent copying
TelemetryManager &operator=(const TelemetryManager &) = delete; // Prevent assignment


/**
* @brief Initialize TM threads and timer interrupts.
*
*/
static void init();
void init();

/**
* @brief This thread is responsible for taking the bytes from the GSC.DMAReceiveBuffer and
* converting them to Mavlink messages/triggering the callbacks associated with each Mavlink
* message.
*/
static void translateToMavlinkThread(void *pvParameters);
void translateToMavlinkThread();
// 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.
*/
static void mavlinkToBytesThread(void *pvParameters);
void 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 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.
*
*/
static void TimerISR1000ms();

/**
* @brief This method is responsible for
* sending non routine data to the ground station. Such as arm disarmed message status,
* fulfilling data requests from the ground station etc. This is the lowest priority data
* in the GSC.lowPriorityTransmitBuffer.
*/
static void sendLowPriorityData();
void sendLowPriorityData();

void createTimerInterrupts();
};

#endif
59 changes: 47 additions & 12 deletions TelemetryManager/Inc/TimerInterrupt.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,37 +3,72 @@
* @brief What does this file do?
*
* @note Anything future maintainers should know about this file?
* - Don't touch TaskTrampoline. Took a while to get right and is confusing.
*
* @version 1.0
* @date 2023-08-24
* @author Yarema Dzulynsky: initial structure
* @author Yarema Dzulynsky: initial structure & implementation
* @author Rahul Ramkumar: implementation
* @author Derek Tang: implementation
*
* @warning Any issues you think are important/foresee in the future?
*/

#include <functional>

#include "FreeRTOS.h"
#include "TM.hpp"
#include "task.h"
#ifndef TIMERINTURUPT_H
#define TIMERINTURUPT_H

class TimerInterrupt {
// Simple alias for a lambda function that takes a TelemetryManager reference as an argument.
using Callback = std::function<void(TelemetryManager&)>;

public:
TimerInterrupt();

//TM instance reference to be used in the callback.
TelemetryManager& tm;
//Callback function to be called when the timer interrupt is triggered.
Callback cbLambda;
//Handle to the task. Or should this be something else? Since we are doing a timer interrupt?
TaskHandle_t xHandle;

/**
* @brief Construct a new Timer Interrupt object which will call the given lambda function
* at the given interval. This is an abstraction of the software timer interrupt functionality
* in FreeRTOS. This will allow easier scheduling of data transfer or any TM tasks which need
* to happen at a regular interval.
*
* @param taskName - The name of the task.
* @param stackSize - The size of the stack for the task.
* @param uxPriority - The priority of the task.
* @param intervalMs - The time interval in milliseconds at which the interrupt should be
* triggered.
* @param tm - The TelemetryManager object.
* @param cbLambda - The callback function to be called when the timer interrupt is triggered.
*/
TimerInterrupt(const char* taskName, int stackSize, UBaseType_t uxPriority,
TickType_t intervalMs, TelemetryManager& tm, Callback cbLambda);

/**
* @brief Destroy the Timer Interrupt object.
*
*/
~TimerInterrupt();

public:
/**
* @brief This function allows us to "register" a timer interrupt when the program starts.
* The function will be called every time the timer interrupt is triggered. This is
* simply an abstraction of the timer interrupt functionality on the STM32 and will allow
* easier scheduling of data transfer or any TM tasks which need to happen at a regular
* interval.
* @brief This is essentially a compatibility/wrapper function that allows us to use a lambda
* function which has a class instance as an argument as a callback for the timer interrupt.
* This allows us to access TM within the lambda function.
*
* @param timeIntervalMs The time interval in milliseconds at which the interrupt should
* be triggered and function should be called.
* @param function The function to be called when the timer interrupt is triggered.
* @param pvParameters - The TimerInterrupt object.
*/
void registerTimerInterrupt(int timeIntervalMs, void (*function)());
static void TaskTrampoline(void* pvParameters) {
auto* context = static_cast<TimerInterrupt*>(pvParameters);
context->cbLambda(context->tm);
}
};

#endif
115 changes: 63 additions & 52 deletions TelemetryManager/Src/TM.cpp
Original file line number Diff line number Diff line change
@@ -1,90 +1,101 @@
#include "TM.hpp"

#include "GroundStationComms.hpp"
#include "MavlinkTranslator.hpp"
#include "TimerInterrupt.hpp"
#include "FreeRTOS.h"
// #include "task.h"// for some reason this is causing an error during complilation??
#include "task.h"

TelemetryManager::TelemetryManager() {
// Constructor
}
TelemetryManager::~TelemetryManager() {
// Destructor
this->MT = MavlinkTranslator();
this->GSC = GroundStationComms();
}

/**
* @brief Initialize TM threads and timer interrupts.
*
*/
void TelemetryManager::init() {
GroundStationComms GSC = getInstance().GSC;
TimerInterrupt TI = getInstance().TI;
MavlinkTranslator MT = getInstance().MT;

// initialize the timer interrupts
TI.registerTimerInterrupt(1000, TimerISR1000ms);
createTimerInterrupts();

// Initialize translateToMavlinkThread as a FreeRTOS task

/* task.h is causing errors during compilation says it is not found. Just uncomment this once
fixed xTaskCreate(mavlinkToBytesThread, // Task function "translateToMavlinkThread", //
Task name configMINIMAL_STACK_SIZE, // Stack size NULL, // Task
parameters tskIDLE_PRIORITY + 1, // Task priority NULL // Task
handle
xTaskCreate(TelemetryManager::translateToMavlinkThreadStatic, // Task function
"translateToMavlinkThread", // Task name
configMINIMAL_STACK_SIZE, // Stack size
this, // Task parameters
tskIDLE_PRIORITY + 1, // Task priority
NULL // Task handle
);

// Initialize mavlinkToBytesThread as a FreeRTOS task
xTaskCreate(mavlinkToBytesThread, // Task function
"mavlinkToBytesThread", // Task name
configMINIMAL_STACK_SIZE, // Stack size
NULL, // Task parameters
tskIDLE_PRIORITY + 1, // Task priority
NULL // Task handle
xTaskCreate(TelemetryManager::mavlinkToBytesThreadStatic, // Task function
"mavlinkToBytesThread", // Task name
configMINIMAL_STACK_SIZE, // Stack size
this, // Task parameters
tskIDLE_PRIORITY + 1, // Task priority
NULL // Task handle
);

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

void TelemetryManager::translateToMavlinkThread(void *pvParameters) {
// give access to any of the TM's members statically
MavlinkTranslator MT = getInstance().MT;
GroundStationComms GSC = getInstance().GSC;

/**
* @brief This thread is responsible for taking the bytes from the GSC.DMAReceiveBuffer and
* converting them to Mavlink messages/triggering the callbacks associated with each Mavlink
* message.
*/
void TelemetryManager::translateToMavlinkThread() {
while (true) {
MT.bytesToMavlinkMsg(GSC.DMAReceiveBuffer);

/* task.h is causing errors during compilation says it is not found. Just uncomment this
once fixed
vTaskDelay(pdMS_TO_TICKS(10)); // Adjust the delay as necessary
*/
vTaskDelay(pdMS_TO_TICKS(10)); // Adjust the delay as necessary
}
}

void TelemetryManager::mavlinkToBytesThread(void *pvParameters) {
/**
* @brief This thread is responsible for taking data from other managers and converting
* them to Mavlink bytes, then putting them into GSC.lowPriorityTransmitBuffer.
*/
void TelemetryManager::mavlinkToBytesThread() {
while (true) {
// START: fill GSC.lowPriorityTransmitBuffer with data to transmit

// END: fill GSC.lowPriorityTransmitBuffer with data to transmit

/* task.h is causing errors during compilation says it is not found. Just uncomment this
once fixed vTaskDelay(pdMS_TO_TICKS(10)); // Adjust the delay as necessary
*/
vTaskDelay(pdMS_TO_TICKS(10)); // Adjust the delay as necessary
}
}

/**
* @brief This function is responsible for
* sending non routine data to the ground station. Such as arm disarmed message status,
* fulfilling data requests from the ground station etc. This is the lowest priority data
* in the GSC.lowPriorityTransmitBuffer.
*/
void TelemetryManager::sendLowPriorityData() {
// there will be some kind of trigger for this function to be called. not sure what it is yet.

GroundStationComms GSC = getInstance().GSC;
// transmit low priority the data via GSC.sendToGroundStation(); function
GSC.sendToGroundStation(GSC.lowPriorityTransmitBuffer);
}

void TelemetryManager::TimerISR1000ms() {
// give access to any of the TM's members statically
GroundStationComms GSC = getInstance().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::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);
});
}
27 changes: 14 additions & 13 deletions TelemetryManager/Src/TimerInterrupt.cpp
Original file line number Diff line number Diff line change
@@ -1,20 +1,21 @@

#include "TimerInterrupt.hpp"

TimerInterrupt::TimerInterrupt()
{
// Constructor
}
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.
xTaskCreate(&TimerInterrupt::TaskTrampoline, taskName, stackSize, this, uxPriority, &xHandle);

TimerInterrupt::~TimerInterrupt()
{
// Destructor
// START: Implement the actual timer interrupt and call the callback function every intervalMs

// END: Implement the actual timer interrupt and call the callback function every intervalMs
}

TimerInterrupt::~TimerInterrupt() {
if (eTaskGetState(xHandle) != eDeleted) {
vTaskDelete(xHandle);
}
}

void TimerInterrupt::registerTimerInterrupt(int timeIntervalMs, void (*function)())
{
// execute the function every timeIntervalMs using a timer interrupt on the STM32
//likely some STM32 specific code here or FreeRTOS code. Not 100% sure what the best way to do this is.
function();
}

0 comments on commit 60b2b39

Please sign in to comment.