|
|
@ -2,20 +2,25 @@ |
|
|
|
|
|
|
|
|
|
|
|
#include <AC_Fence/AC_Fence.h> |
|
|
|
#include <AC_Fence/AC_Fence.h> |
|
|
|
|
|
|
|
|
|
|
|
MAV_MISSION_RESULT MissionItemProtocol_Fence::get_item(const GCS_MAVLINK &_link, |
|
|
|
/*
|
|
|
|
const mavlink_message_t &msg, |
|
|
|
public function to format mission item as mavlink_mission_item_int_t |
|
|
|
const mavlink_mission_request_int_t &packet, |
|
|
|
*/ |
|
|
|
mavlink_mission_item_int_t &ret_packet) |
|
|
|
bool MissionItemProtocol_Fence::get_item_as_mission_item(uint16_t seq, |
|
|
|
|
|
|
|
mavlink_mission_item_int_t &ret_packet) |
|
|
|
{ |
|
|
|
{ |
|
|
|
const uint8_t num_stored_items = _fence.polyfence().num_stored_items(); |
|
|
|
AC_Fence *fence = AP::fence(); |
|
|
|
if (packet.seq > num_stored_items) { |
|
|
|
if (fence == nullptr) { |
|
|
|
return MAV_MISSION_INVALID_SEQUENCE; |
|
|
|
return false; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
const uint8_t num_stored_items = fence->polyfence().num_stored_items(); |
|
|
|
|
|
|
|
if (seq > num_stored_items) { |
|
|
|
|
|
|
|
return false; |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
AC_PolyFenceItem fenceitem; |
|
|
|
AC_PolyFenceItem fenceitem; |
|
|
|
|
|
|
|
|
|
|
|
if (!_fence.polyfence().get_item(packet.seq, fenceitem)) { |
|
|
|
if (!fence->polyfence().get_item(seq, fenceitem)) { |
|
|
|
return MAV_MISSION_ERROR; |
|
|
|
return false; |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
MAV_CMD ret_cmd = MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION; // initialised to avoid compiler warning
|
|
|
|
MAV_CMD ret_cmd = MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION; // initialised to avoid compiler warning
|
|
|
@ -41,7 +46,7 @@ MAV_MISSION_RESULT MissionItemProtocol_Fence::get_item(const GCS_MAVLINK &_link, |
|
|
|
p1 = fenceitem.radius; |
|
|
|
p1 = fenceitem.radius; |
|
|
|
break; |
|
|
|
break; |
|
|
|
case AC_PolyFenceType::END_OF_STORAGE: |
|
|
|
case AC_PolyFenceType::END_OF_STORAGE: |
|
|
|
return MAV_MISSION_ERROR; |
|
|
|
return false; |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
ret_packet.command = ret_cmd; |
|
|
|
ret_packet.command = ret_cmd; |
|
|
@ -50,6 +55,23 @@ MAV_MISSION_RESULT MissionItemProtocol_Fence::get_item(const GCS_MAVLINK &_link, |
|
|
|
ret_packet.y = fenceitem.loc.y; |
|
|
|
ret_packet.y = fenceitem.loc.y; |
|
|
|
ret_packet.z = 0; |
|
|
|
ret_packet.z = 0; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
return true; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
MAV_MISSION_RESULT MissionItemProtocol_Fence::get_item(const GCS_MAVLINK &_link, |
|
|
|
|
|
|
|
const mavlink_message_t &msg, |
|
|
|
|
|
|
|
const mavlink_mission_request_int_t &packet, |
|
|
|
|
|
|
|
mavlink_mission_item_int_t &ret_packet) |
|
|
|
|
|
|
|
{ |
|
|
|
|
|
|
|
const uint8_t num_stored_items = _fence.polyfence().num_stored_items(); |
|
|
|
|
|
|
|
if (packet.seq > num_stored_items) { |
|
|
|
|
|
|
|
return MAV_MISSION_INVALID_SEQUENCE; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
if (!get_item_as_mission_item(packet.seq, ret_packet)) { |
|
|
|
|
|
|
|
return MAV_MISSION_ERROR; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
return MAV_MISSION_ACCEPTED; |
|
|
|
return MAV_MISSION_ACCEPTED; |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|