mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: make rally/fence item conversion methods public
This commit is contained in:
parent
3ef2139f4b
commit
c33d665906
|
@ -95,7 +95,7 @@ uint16_t MissionItemProtocol_Fence::item_count() const
|
||||||
return _fence.polyfence().num_stored_items();
|
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 &&
|
if (mission_item_int.frame != MAV_FRAME_GLOBAL &&
|
||||||
mission_item_int.frame != MAV_FRAME_GLOBAL_INT &&
|
mission_item_int.frame != MAV_FRAME_GLOBAL_INT &&
|
||||||
|
|
|
@ -2,6 +2,8 @@
|
||||||
|
|
||||||
#include "MissionItemProtocol.h"
|
#include "MissionItemProtocol.h"
|
||||||
|
|
||||||
|
#include <AC_Fence/AC_Fence.h>
|
||||||
|
|
||||||
class AC_PolyFence_loader;
|
class AC_PolyFence_loader;
|
||||||
|
|
||||||
class MissionItemProtocol_Fence : public MissionItemProtocol {
|
class MissionItemProtocol_Fence : public MissionItemProtocol {
|
||||||
|
@ -21,7 +23,9 @@ public:
|
||||||
static function to format mission item as mavlink_mission_item_int_t
|
static function to format mission item as mavlink_mission_item_int_t
|
||||||
*/
|
*/
|
||||||
static bool get_item_as_mission_item(uint16_t seq, mavlink_mission_item_int_t &ret_packet);
|
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:
|
protected:
|
||||||
|
|
||||||
ap_message next_item_ap_message_id() const override {
|
ap_message next_item_ap_message_id() const override {
|
||||||
|
|
|
@ -20,7 +20,9 @@ public:
|
||||||
static function to get rally item as mavlink_mission_item_int_t
|
static function to get rally item as mavlink_mission_item_int_t
|
||||||
*/
|
*/
|
||||||
static bool get_item_as_mission_item(uint16_t seq, mavlink_mission_item_int_t &ret_packet);
|
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:
|
protected:
|
||||||
|
|
||||||
ap_message next_item_ap_message_id() const override {
|
ap_message next_item_ap_message_id() const override {
|
||||||
|
@ -42,8 +44,6 @@ private:
|
||||||
const mavlink_mission_request_int_t &packet,
|
const mavlink_mission_request_int_t &packet,
|
||||||
mavlink_mission_item_int_t &ret_packet) override WARN_IF_UNUSED;
|
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
|
#endif // HAL_RALLY_ENABLED
|
||||||
|
|
Loading…
Reference in New Issue