GCS_MAVLink: make rally/fence item conversion methods public

This commit is contained in:
Peter Barker 2024-01-23 15:23:15 +11:00
parent c6e7ba8131
commit 3b715ade6b
3 changed files with 9 additions and 5 deletions

View File

@ -95,7 +95,7 @@ uint16_t MissionItemProtocol_Fence::item_count() const
return _fence.polyfence().num_stored_items();
}
static MAV_MISSION_RESULT convert_MISSION_ITEM_INT_to_AC_PolyFenceItem(const mavlink_mission_item_int_t &mission_item_int, AC_PolyFenceItem &ret)
MAV_MISSION_RESULT MissionItemProtocol_Fence::convert_MISSION_ITEM_INT_to_AC_PolyFenceItem(const mavlink_mission_item_int_t &mission_item_int, AC_PolyFenceItem &ret)
{
if (mission_item_int.frame != MAV_FRAME_GLOBAL &&
mission_item_int.frame != MAV_FRAME_GLOBAL_INT &&

View File

@ -2,6 +2,8 @@
#include "MissionItemProtocol.h"
#include <AC_Fence/AC_Fence.h>
class AC_PolyFence_loader;
class MissionItemProtocol_Fence : public MissionItemProtocol {
@ -22,6 +24,8 @@ public:
*/
static bool get_item_as_mission_item(uint16_t seq, mavlink_mission_item_int_t &ret_packet);
static MAV_MISSION_RESULT convert_MISSION_ITEM_INT_to_AC_PolyFenceItem(const mavlink_mission_item_int_t &mission_item_int, class AC_PolyFenceItem &ret);
protected:
ap_message next_item_ap_message_id() const override {

View File

@ -21,6 +21,8 @@ public:
*/
static bool get_item_as_mission_item(uint16_t seq, mavlink_mission_item_int_t &ret_packet);
static MAV_MISSION_RESULT convert_MISSION_ITEM_INT_to_RallyLocation(const mavlink_mission_item_int_t &cmd, class RallyLocation &ret) WARN_IF_UNUSED;
protected:
ap_message next_item_ap_message_id() const override {
@ -42,8 +44,6 @@ private:
const mavlink_mission_request_int_t &packet,
mavlink_mission_item_int_t &ret_packet) override WARN_IF_UNUSED;
static MAV_MISSION_RESULT convert_MISSION_ITEM_INT_to_RallyLocation(const mavlink_mission_item_int_t &cmd, class RallyLocation &ret) WARN_IF_UNUSED;
};
#endif // HAL_RALLY_ENABLED