-
Notifications
You must be signed in to change notification settings - Fork 9
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
- Loading branch information
1 parent
acfb908
commit 60b2b39
Showing
4 changed files
with
158 additions
and
107 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
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); | ||
}); | ||
} |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
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(); | ||
} |