AC_Fence: remove global static send_statustext_chan

This commit is contained in:
Peter Barker 2017-07-09 18:32:30 +10:00 committed by Francisco Ferreira
parent 2fde428890
commit ae6df4fc04
2 changed files with 6 additions and 6 deletions

View File

@ -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;
}

View File

@ -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[];