From ae6df4fc0404656926683ce603fb774ee98e9d11 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 9 Jul 2017 18:32:30 +1000 Subject: [PATCH] AC_Fence: remove global static send_statustext_chan --- libraries/AC_Fence/AC_Fence.cpp | 10 +++++----- libraries/AC_Fence/AC_Fence.h | 2 +- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/libraries/AC_Fence/AC_Fence.cpp b/libraries/AC_Fence/AC_Fence.cpp index 5a252ad3d2..283f03a53b 100644 --- a/libraries/AC_Fence/AC_Fence.cpp +++ b/libraries/AC_Fence/AC_Fence.cpp @@ -355,7 +355,7 @@ bool AC_Fence::boundary_breached(const Vector2f& location, uint16_t num_points, } /// handler for polygon fence messages with GCS -void AC_Fence::handle_msg(mavlink_channel_t chan, mavlink_message_t* msg) +void AC_Fence::handle_msg(GCS_MAVLINK &link, mavlink_message_t* msg) { // exit immediately if null message if (msg == nullptr) { @@ -368,13 +368,13 @@ void AC_Fence::handle_msg(mavlink_channel_t chan, mavlink_message_t* msg) mavlink_fence_point_t packet; mavlink_msg_fence_point_decode(msg, &packet); if (!check_latlng(packet.lat,packet.lng)) { - GCS_MAVLINK::send_statustext_chan(MAV_SEVERITY_WARNING, chan, "Invalid fence point, lat or lng too large"); + link.send_text(MAV_SEVERITY_WARNING, "Invalid fence point, lat or lng too large"); } else { Vector2l point; point.x = packet.lat*1.0e7f; point.y = packet.lng*1.0e7f; if (!_poly_loader.save_point_to_eeprom(packet.idx, point)) { - GCS_MAVLINK::send_statustext_chan(MAV_SEVERITY_WARNING, chan, "Failed to save polygon point, too many points?"); + link.send_text(MAV_SEVERITY_WARNING, "Failed to save polygon point, too many points?"); } else { // trigger reload of points _boundary_loaded = false; @@ -390,9 +390,9 @@ void AC_Fence::handle_msg(mavlink_channel_t chan, mavlink_message_t* msg) // attempt to retrieve from eeprom Vector2l point; if (_poly_loader.load_point_from_eeprom(packet.idx, point)) { - mavlink_msg_fence_point_send_buf(msg, chan, msg->sysid, msg->compid, packet.idx, _total, point.x*1.0e-7f, point.y*1.0e-7f); + mavlink_msg_fence_point_send_buf(msg, link.get_chan(), msg->sysid, msg->compid, packet.idx, _total, point.x*1.0e-7f, point.y*1.0e-7f); } else { - GCS_MAVLINK::send_statustext_chan(MAV_SEVERITY_WARNING, chan, "Bad fence point"); + link.send_text(MAV_SEVERITY_WARNING, "Bad fence point"); } break; } diff --git a/libraries/AC_Fence/AC_Fence.h b/libraries/AC_Fence/AC_Fence.h index 9593052396..c6cf0bb120 100644 --- a/libraries/AC_Fence/AC_Fence.h +++ b/libraries/AC_Fence/AC_Fence.h @@ -112,7 +112,7 @@ public: bool boundary_breached(const Vector2f& location, uint16_t num_points, const Vector2f* points) const; /// handler for polygon fence messages with GCS - void handle_msg(mavlink_channel_t chan, mavlink_message_t* msg); + void handle_msg(GCS_MAVLINK &link, mavlink_message_t* msg); static const struct AP_Param::GroupInfo var_info[];