Skip to content

Commit

Permalink
Worked on improving clarity via naming & small updates
Browse files Browse the repository at this point in the history
  • Loading branch information
Yaremadzulynsky committed Mar 19, 2024
1 parent d19c039 commit 3fe46ab
Show file tree
Hide file tree
Showing 13 changed files with 223 additions and 278 deletions.
11 changes: 5 additions & 6 deletions TelemetryManager/Inc/CircularBuffer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,27 +32,26 @@ class CircularBuffer {
*/
~CircularBuffer();

public:
/**
* @brief Provides the number of bytes available in the queue
*
* @return int The number of bytes available in the queue.
*/
virtual int remainingMemory();
int remainingMemory();

/**
* @brief Dequeue a byte from the queue
*
* @return MAVLinkByte The byte that was dequeued
*/
virtual MAVLinkByte dequeue();
MAVLinkByte dequeue();

/**
* @brief Enqueue a byte into the queue
*
* @param byte The byte to be enqueued
*/
virtual void enqueue(MAVLinkByte byte);
void enqueue(MAVLinkByte byte);

/**
* @brief Get the index of the last full message in the queue determined by the end flag
Expand All @@ -65,7 +64,7 @@ class CircularBuffer {
* in the MAVLink message.
*
*/
virtual int lastFullMessageEndIndex();
int lastFullMessageEndIndex();

/**
* @brief Returns the index of the current byte in the queue. This is useful for when we want to
Expand All @@ -75,7 +74,7 @@ class CircularBuffer {
*
* @return int The index of the current byte in the queue.
*/
virtual int currentIndex();
int currentIndex();
};

#endif
Original file line number Diff line number Diff line change
@@ -1,20 +1,20 @@
/**
* @file GroundStationComms.hpp
* @file GroundStationCommunication.hpp
* @brief What does this file do?
*
* @note Anything future maintainers should know about this file?
*
* @version 1.0
* @date 2023-08-24
* @author Yarema Dzulynsky: initial structure
* @author Hunter Adams: implementation
* @author Roni Kant: implementation
*
* @warning Any issues you think are important/foresee in the future?
*/

#include "CircularBuffer.hpp"
#ifndef GROUNDSTATIONCOMMS_H
#define GROUNDSTATIONCOMMS_H
#ifndef GROUNDSTATIONCOMMUNICATION_H
#define GROUNDSTATIONCOMMUNICATION_H

/**
* @brief This class is responsible for handling the communication between the ground station
Expand All @@ -23,26 +23,25 @@
* because it allows us to define the behaviour of the RFD 900 send/receive function before its
* implementation.
*/
class GroundStationComms {
class GroundStationCommunication {
public:
/**
* @brief Construct a new Ground Station Comms object. Do whatever needs to be done here.
* @brief Construct a new Ground Station Communication object. Do whatever needs to be done here.
*
*/
GroundStationComms();
~GroundStationComms();
GroundStationCommunication();
~GroundStationCommunication();

public:
/*
* When the DMA interrupt is triggered the data should be stored in the DMAReceiveBuffer
* IF there is space.
*/
CircularBuffer DMAReceiveBuffer;

// low priority Mavlink bytes to be sent to the ground station.
// low priority/Non routine Mavlink bytes to be sent to the ground station.
CircularBuffer lowPriorityTransmitBuffer;

// high priority Mavlink bytes to be sent to the ground station.
// high priority/Routine Mavlink bytes to be sent to the ground station.
CircularBuffer highPriorityTransmitBuffer;

/**
Expand All @@ -57,14 +56,14 @@ class GroundStationComms {
* @param transmissionBuffer A CircularBuffer containing the data/MAVLink bytes to be sent
* to the ground station
*/
virtual void sendToGroundStation(CircularBuffer &transmissionBuffer);
void transmit(CircularBuffer &transmissionBuffer);

/**
* @brief This is the Interrupt Service Routine (ISR) for when the RFD 900 receives data from
* the ground station and stores bytes from the transmission into the GSC.DMAReceiveBuffer if
* there is space. Otherwise the data is discarded.
*/
virtual void receiveFromGroundStationISR();
void receiveInterruptServiceRoutine();
};

#endif // GROUNDSTATIONCOMMS_H
File renamed without changes.
5 changes: 2 additions & 3 deletions TelemetryManager/Inc/MavlinkTranslator.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,15 +31,14 @@ class MavlinkTranslator {
*/
~MavlinkTranslator();

public:
/**
* @brief Ingests bytes from the rxFromGroundByteQueue and converts them to Mavlink messages.
* The Mavlink message, associated callbacks are then triggered.
*
* @param rxFromGroundByteQueue The CircularBuffer containing the bytes received from the ground
* station. waiting to be decoded.
*/
virtual void bytesToMavlinkMsg(CircularBuffer &rxFromGroundByteQueue);
void bytesToMavlinkMsg(CircularBuffer &rxFromGroundByteQueue);

/**
* @brief Converts Mavlink messages to bytes and adds them to the txToGroundByteQueue.
Expand All @@ -48,7 +47,7 @@ class MavlinkTranslator {
* @param txToGroundByteQueue The CircularBuffer containing the bytes to be sent to the ground
* station.
*/
virtual void addMavlinkMsgToByteQueue(mavlink_message_t &msg,
void addMavlinkMsgToByteQueue(mavlink_message_t &msg,
CircularBuffer &txToGroundByteQueue);
};

Expand Down
101 changes: 0 additions & 101 deletions TelemetryManager/Inc/TM.hpp

This file was deleted.

61 changes: 61 additions & 0 deletions TelemetryManager/Inc/TelemetryManager.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,61 @@
/**
* @file TelemetryManager.hpp
* @brief What does this file do?
*
* @note Anything future maintainers should know about this file?
*
* @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 TELEMETRYMANAGER_H
#define TELEMETRYMANAGER_H

#include "GroundStationCommunication.hpp"
#include "MavlinkTranslator.hpp"
#include "TelemetryTask.hpp"

class TelemetryManager {

public:
/**
* @brief Construct a new Telemetry Manager object. Does not initialize the tasks.
* To do so call the init() method.
*/
TelemetryManager();
~TelemetryManager();

GroundStationCommunication GSC;
MavlinkTranslator MT;

/**
* @brief Initialize TM.
*
*/
void init();

/**
* @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.
*/
void transmitNonRoutineData();

/**
* @brief Create and configure FreeRTOS tasks.
*
*/
void spinUpTasks();

/**
* @brief Destroy FreeRTOS tasks and free up memory.
*
*/
void teardownTasks();
};

#endif
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
/**
* @file TimerInterrupt.hpp
* @file TelemetryTask.hpp
* @brief What does this file do?
*
* @note Anything future maintainers should know about this file?
Expand All @@ -8,21 +8,20 @@
* @version 1.0
* @date 2023-08-24
* @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 "TelemetryManager.hpp"
#include <functional>
#include "FreeRTOS.h"
#include "TM.hpp"
#include "task.h"
#ifndef TIMERINTURUPT_H
#define TIMERINTURUPT_H
#ifndef TELEMETRYTASK_H
#define TELEMETRYTASK_H

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

Expand All @@ -36,39 +35,32 @@ class TimerInterrupt {
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.
* @brief Construct a new Timer TelemetryTask object which will call the given lambda function
* at the given interval. This will allow easier scheduling of data transfer or any TM tasks which need
* to happen at a regular interval with FreeRTOS.
*
* @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);
TelemetryTask(const char* taskName, int stackSize, UBaseType_t uxPriority, TelemetryManager& tm, Callback cbLambda);

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

/**
* @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 pvParameters - The TimerInterrupt object.
* @param pvParameters - The TelemetryTask object.
*/
static void TaskTrampoline(void* pvParameters) {
auto* context = static_cast<TimerInterrupt*>(pvParameters);
context->cbLambda(context->tm);
}
static void TaskTrampoline(void* pvParameters);
};

#endif
Loading

0 comments on commit 3fe46ab

Please sign in to comment.