Skip to content

Commit 0167ac3

Browse files
committed
Rename state and mode to mavState and mavMode
1 parent a5bb017 commit 0167ac3

File tree

3 files changed

+13
-13
lines changed

3 files changed

+13
-13
lines changed

SystemManager/Src/SystemManager.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -74,8 +74,8 @@ SystemManager::SystemManager()
7474
stateData.pitchspeed = &pitchspeed;
7575
stateData.yawspeed = &yawspeed;
7676

77-
MAV_STATE state = MAV_STATE::MAV_STATE_STANDBY;
78-
MAV_MODE_FLAG mode = MAV_MODE_FLAG::MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
77+
MAV_STATE mavState = MAV_STATE::MAV_STATE_STANDBY;
78+
MAV_MODE_FLAG mavMode = MAV_MODE_FLAG::MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
7979

8080
// Creating parameters for the GroundStationCommunication that will be passed to telemetryManager
8181
TMCircularBuffer DMAReceiveBuffer = *(new TMCircularBuffer(rfd900_circular_buffer));
@@ -95,7 +95,7 @@ SystemManager::SystemManager()
9595
// the buffer that stores the bytes received from the ground station.
9696
MavlinkTranslator MT;
9797

98-
this->telemetryManager = new TelemetryManager(stateData, state, mode, GSC, MT);
98+
this->telemetryManager = new TelemetryManager(stateData, mavState, mavMode, GSC, MT);
9999
this->telemetryManager->init();
100100
// IDK WHERE SM PLANS TO DO THIS, BUT telemetryManager.update() NEEDS TO BE CALLED AT A SEMI
101101
// REGULAR INTERVAL AS IT DEALS WITH MESSAGE DECODING AND LOW PRIORITY DATA TRANSMISSION

TelemetryManager/Inc/TelemetryManager.hpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -101,9 +101,9 @@ class TelemetryManager {
101101

102102

103103
// System status flag (https://mavlink.io/en/messages/minimal.html#MAV_STATE).
104-
MAV_STATE& state;
104+
MAV_STATE& mavState;
105105
// System mode bitmap (https://mavlink.io/en/messages/minimal.html#MAV_MODE_FLAG).
106-
MAV_MODE_FLAG& mode;
106+
MAV_MODE_FLAG& mavMode;
107107

108108

109109
/**
@@ -121,13 +121,13 @@ class TelemetryManager {
121121
/**
122122
* @brief Construct a new Telemetry Manager object. Does not initialize the tasks.
123123
* To do so call the init() method.
124-
* @param TM The state of the drone (lat, lng, yaw, pitch, etc..).
125-
* @param state System status flag (https://mavlink.io/en/messages/minimal.html#MAV_STATE).
126-
* @param mode System mode bitmap (https://mavlink.io/en/messages/minimal.html#MAV_MODE_FLAG).
124+
* @param stateData The state of the drone (lat, lng, yaw, pitch, etc..).
125+
* @param mav_state System status flag (https://mavlink.io/en/messages/minimal.html#MAV_STATE).
126+
* @param mav_mode System mode bitmap (https://mavlink.io/en/messages/minimal.html#MAV_MODE_FLAG).
127127
* @param GSC Object to handle communication with the groundstation
128128
* @param MT Object to translate MAVLink data
129129
*/
130-
TelemetryManager(TMStateData& stateData, MAV_STATE& state, MAV_MODE_FLAG& mode,
130+
TelemetryManager(TMStateData& stateData, MAV_STATE& mavState, MAV_MODE_FLAG& mavMode,
131131
GroundStationCommunication& GSC, MavlinkTranslator& MT);
132132

133133
/**

TelemetryManager/Src/TelemetryManager.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -4,11 +4,11 @@
44
// FreeRTOS task handle for the routineDataTransmission task
55
TaskHandle_t routineDataTransmissionH = NULL;
66

7-
TelemetryManager::TelemetryManager(TMStateData& stateData, MAV_STATE& state, MAV_MODE_FLAG& mode,
7+
TelemetryManager::TelemetryManager(TMStateData& stateData, MAV_STATE& mav_state, MAV_MODE_FLAG& mav_mode,
88
GroundStationCommunication& GSC, MavlinkTranslator& MT)
99
: stateData(stateData),
10-
state(state),
11-
mode(mode),
10+
mavState(mavState),
11+
mavMode(mavMode),
1212
GSC(GSC),
1313
MT(MT) {}
1414

@@ -93,7 +93,7 @@ void routineDataTransmission(void* pvParameters) {
9393
mavlink_message_t heartbeatMsg = {0};
9494
// Pack the message with the actual data
9595
mavlink_msg_heartbeat_pack(system_id, component_id, &heartbeatMsg, MAV_TYPE_QUADROTOR,
96-
MAV_AUTOPILOT_INVALID, tm->mode, 0, tm->state);
96+
MAV_AUTOPILOT_INVALID, tm->mavMode, 0, tm->mavState);
9797
// Add the packed message to the byte queue for later transmission
9898
tm->MT.addMavlinkMsgToByteQueue(heartbeatMsg, tm->GSC.highPriorityTransmitBuffer);
9999

0 commit comments

Comments
 (0)