GCS_MAVLink: remove individual static members for fence, mission and rally

This commit is contained in:
Peter Barker 2022-09-28 09:46:38 +10:00 committed by Andrew Tridgell
parent 0cd7668258
commit 0f359c6a4e
3 changed files with 23 additions and 49 deletions

View File

@ -36,17 +36,7 @@ void GCS::get_sensor_status_flags(uint32_t &present,
health = control_sensors_health; health = control_sensors_health;
} }
MissionItemProtocol_Waypoints *GCS::_missionitemprotocol_waypoints; MissionItemProtocol *GCS::missionitemprotocols[3];
MissionItemProtocol_Rally *GCS::_missionitemprotocol_rally;
#if AP_FENCE_ENABLED
MissionItemProtocol_Fence *GCS::_missionitemprotocol_fence;
#endif
const MAV_MISSION_TYPE GCS_MAVLINK::supported_mission_types[] = {
MAV_MISSION_TYPE_MISSION,
MAV_MISSION_TYPE_RALLY,
MAV_MISSION_TYPE_FENCE,
};
void GCS::init() void GCS::init()
{ {

View File

@ -180,8 +180,6 @@ public:
mission_type); mission_type);
} }
static const MAV_MISSION_TYPE supported_mission_types[3];
// packetReceived is called on any successful decode of a mavlink message // packetReceived is called on any successful decode of a mavlink message
virtual void packetReceived(const mavlink_status_t &status, virtual void packetReceived(const mavlink_status_t &status,
const mavlink_message_t &msg); const mavlink_message_t &msg);
@ -1074,11 +1072,12 @@ public:
ap_var_type param_type, ap_var_type param_type,
float param_value); float param_value);
static class MissionItemProtocol_Waypoints *_missionitemprotocol_waypoints; // an array of objects used to handle each of the different
static class MissionItemProtocol_Rally *_missionitemprotocol_rally; // protocol types we support. This is indexed by the enumeration
#if AP_FENCE_ENABLED // MAV_MISSION_TYPE, taking advantage of the fact that fence,
static class MissionItemProtocol_Fence *_missionitemprotocol_fence; // mission and rally have values 0, 1 and 2. Indexing should be via
#endif // get_prot_for_mission_type to do bounds checking.
static class MissionItemProtocol *missionitemprotocols[3];
class MissionItemProtocol *get_prot_for_mission_type(const MAV_MISSION_TYPE mission_type) const; class MissionItemProtocol *get_prot_for_mission_type(const MAV_MISSION_TYPE mission_type) const;
void try_send_queued_message_for_type(MAV_MISSION_TYPE type) const; void try_send_queued_message_for_type(MAV_MISSION_TYPE type) const;

View File

@ -556,20 +556,10 @@ void GCS_MAVLINK::send_ahrs2()
MissionItemProtocol *GCS::get_prot_for_mission_type(const MAV_MISSION_TYPE mission_type) const MissionItemProtocol *GCS::get_prot_for_mission_type(const MAV_MISSION_TYPE mission_type) const
{ {
switch (mission_type) { if (mission_type >= ARRAY_SIZE(missionitemprotocols)) {
case MAV_MISSION_TYPE_MISSION:
return _missionitemprotocol_waypoints;
#if HAL_RALLY_ENABLED
case MAV_MISSION_TYPE_RALLY:
return _missionitemprotocol_rally;
#endif
#if AP_FENCE_ENABLED
case MAV_MISSION_TYPE_FENCE:
return _missionitemprotocol_fence;
#endif
default:
return nullptr; return nullptr;
} }
return missionitemprotocols[mission_type];
} }
// handle a request for the number of items we have stored for a mission type: // handle a request for the number of items we have stored for a mission type:
@ -698,8 +688,7 @@ void GCS_MAVLINK::handle_mission_clear_all(const mavlink_message_t &msg) const
bool GCS_MAVLINK::requesting_mission_items() const bool GCS_MAVLINK::requesting_mission_items() const
{ {
for (uint8_t i=0; i<ARRAY_SIZE(supported_mission_types); i++) { for (const auto *prot : gcs().missionitemprotocols) {
MissionItemProtocol *prot = gcs().get_prot_for_mission_type(supported_mission_types[i]);
if (prot && prot->receiving && prot->active_link_is(this)) { if (prot && prot->receiving && prot->active_link_is(this)) {
return true; return true;
} }
@ -2201,41 +2190,37 @@ void GCS::send_message(enum ap_message id)
void GCS::update_send() void GCS::update_send()
{ {
update_send_has_been_called = true; update_send_has_been_called = true;
#if !defined(HAL_BUILD_AP_PERIPH) && AP_FENCE_ENABLED
if (!initialised_missionitemprotocol_objects) { if (!initialised_missionitemprotocol_objects) {
initialised_missionitemprotocol_objects = true; initialised_missionitemprotocol_objects = true;
// once-only initialisation of MissionItemProtocol objects: // once-only initialisation of MissionItemProtocol objects:
#if AP_MISSION_ENABLED
AP_Mission *mission = AP::mission(); AP_Mission *mission = AP::mission();
if (mission != nullptr) { if (mission != nullptr) {
_missionitemprotocol_waypoints = new MissionItemProtocol_Waypoints(*mission); missionitemprotocols[MAV_MISSION_TYPE_MISSION] = new MissionItemProtocol_Waypoints(*mission);
} }
#endif
#if HAL_RALLY_ENABLED #if HAL_RALLY_ENABLED
AP_Rally *rally = AP::rally(); AP_Rally *rally = AP::rally();
if (rally != nullptr) { if (rally != nullptr) {
_missionitemprotocol_rally = new MissionItemProtocol_Rally(*rally); missionitemprotocols[MAV_MISSION_TYPE_RALLY] = new MissionItemProtocol_Rally(*rally);
} }
#endif #endif
#if AP_FENCE_ENABLED #if AP_FENCE_ENABLED
AC_Fence *fence = AP::fence(); AC_Fence *fence = AP::fence();
if (fence != nullptr) { if (fence != nullptr) {
_missionitemprotocol_fence = new MissionItemProtocol_Fence(*fence); missionitemprotocols[MAV_MISSION_TYPE_FENCE] = new MissionItemProtocol_Fence(*fence);
} }
}
#endif #endif
if (_missionitemprotocol_waypoints != nullptr) {
_missionitemprotocol_waypoints->update();
} }
#if HAL_RALLY_ENABLED
if (_missionitemprotocol_rally != nullptr) { for (auto *prot : missionitemprotocols) {
_missionitemprotocol_rally->update(); if (prot == nullptr) {
continue;
}
prot->update();
} }
#endif
#if AP_FENCE_ENABLED
if (_missionitemprotocol_fence != nullptr) {
_missionitemprotocol_fence->update();
}
#endif
#endif // HAL_BUILD_AP_PERIPH
// round-robin the GCS_MAVLINK backend that gets to go first so // round-robin the GCS_MAVLINK backend that gets to go first so
// one backend doesn't monopolise all of the time allowed for sending // one backend doesn't monopolise all of the time allowed for sending
// messages // messages