APM:Libraries
GCS_Rally.cpp
Go to the documentation of this file.
1 /*
2  GCS MAVLink functions related to rally points
3 
4  This program is free software: you can redistribute it and/or modify
5  it under the terms of the GNU General Public License as published by
6  the Free Software Foundation, either version 3 of the License, or
7  (at your option) any later version.
8 
9  This program is distributed in the hope that it will be useful,
10  but WITHOUT ANY WARRANTY; without even the implied warranty of
11  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12  GNU General Public License for more details.
13 
14  You should have received a copy of the GNU General Public License
15  along with this program. If not, see <http://www.gnu.org/licenses/>.
16  */
17 
18 #include "GCS.h"
19 
20 void GCS_MAVLINK::handle_rally_point(mavlink_message_t *msg)
21 {
22  AP_Rally *r = get_rally();
23  if (r == nullptr) {
24  return;
25  }
26 
27  mavlink_rally_point_t packet;
28  mavlink_msg_rally_point_decode(msg, &packet);
29 
30  if (packet.idx >= r->get_rally_total() ||
31  packet.idx >= r->get_rally_max()) {
32  send_text(MAV_SEVERITY_WARNING,"Bad rally point ID");
33  return;
34  }
35 
36  if (packet.count != r->get_rally_total()) {
37  send_text(MAV_SEVERITY_WARNING,"Bad rally point count");
38  return;
39  }
40 
41  // sanity check location
42  if (!check_latlng(packet.lat, packet.lng)) {
43  return;
44  }
45 
46  RallyLocation rally_point;
47  rally_point.lat = packet.lat;
48  rally_point.lng = packet.lng;
49  rally_point.alt = packet.alt;
50  rally_point.break_alt = packet.break_alt;
51  rally_point.land_dir = packet.land_dir;
52  rally_point.flags = packet.flags;
53 
54  if (!r->set_rally_point_with_index(packet.idx, rally_point)) {
55  send_text(MAV_SEVERITY_CRITICAL, "Error setting rally point");
56  }
57 }
58 
59 void GCS_MAVLINK::handle_rally_fetch_point(mavlink_message_t *msg)
60 {
61  AP_Rally *r = get_rally();
62  if (r == nullptr) {
63  return;
64  }
65 
66  mavlink_rally_fetch_point_t packet;
67  mavlink_msg_rally_fetch_point_decode(msg, &packet);
68 
69  if (packet.idx > r->get_rally_total()) {
70  send_text(MAV_SEVERITY_WARNING, "Bad rally point ID");
71  return;
72  }
73 
74  RallyLocation rally_point;
75  if (!r->get_rally_point_with_index(packet.idx, rally_point)) {
76  send_text(MAV_SEVERITY_WARNING, "Failed to get rally point");
77  return;
78  }
79 
80  mavlink_msg_rally_point_send_buf(msg,
81  chan, msg->sysid, msg->compid, packet.idx,
82  r->get_rally_total(), rally_point.lat, rally_point.lng,
83  rally_point.alt, rally_point.break_alt, rally_point.land_dir,
84  rally_point.flags);
85 }
86 
87 void GCS_MAVLINK::handle_common_rally_message(mavlink_message_t *msg)
88 {
89  switch (msg->msgid) {
90  case MAVLINK_MSG_ID_RALLY_POINT:
91  handle_rally_point(msg);
92  break;
93  case MAVLINK_MSG_ID_RALLY_FETCH_POINT:
95  break;
96  default:
97  break;
98  }
99 }
100 
int32_t lng
Definition: AP_Rally.h:26
uint8_t get_rally_total() const
Definition: AP_Rally.h:48
Object managing Rally Points.
Definition: AP_Rally.h:37
Interface definition for the various Ground Control System.
uint8_t flags
Definition: AP_Rally.h:30
uint8_t get_rally_max(void) const
Definition: AP_Rally.h:49
uint16_t land_dir
Definition: AP_Rally.h:29
bool set_rally_point_with_index(uint8_t i, const RallyLocation &rallyLoc)
Definition: AP_Rally.cpp:75
int16_t alt
Definition: AP_Rally.h:27
int16_t break_alt
Definition: AP_Rally.h:28
bool check_latlng(float lat, float lng)
Definition: location.cpp:231
bool get_rally_point_with_index(uint8_t i, RallyLocation &ret) const
Definition: AP_Rally.cpp:59
int32_t lat
Definition: AP_Rally.h:25