GCS_Rally.cpp 3.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105
  1. /*
  2. GCS MAVLink functions related to upload and download of rally
  3. points with the ArduPilot-specific protocol comprised of
  4. MAVLINK_MSG_ID_RALLY_POINT and MAVLINK_MSG_ID_RALLY_FETCH_POINT.
  5. This program is free software: you can redistribute it and/or modify
  6. it under the terms of the GNU General Public License as published by
  7. the Free Software Foundation, either version 3 of the License, or
  8. (at your option) any later version.
  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. You should have received a copy of the GNU General Public License
  14. along with this program. If not, see <http://www.gnu.org/licenses/>.
  15. */
  16. #include "GCS.h"
  17. #include <AP_Rally/AP_Rally.h>
  18. #include <AP_Logger/AP_Logger.h>
  19. void GCS_MAVLINK::handle_rally_point(const mavlink_message_t &msg)
  20. {
  21. AP_Rally *r = AP::rally();
  22. if (r == nullptr) {
  23. return;
  24. }
  25. mavlink_rally_point_t packet;
  26. mavlink_msg_rally_point_decode(&msg, &packet);
  27. if (packet.idx >= r->get_rally_total() ||
  28. packet.idx >= r->get_rally_max()) {
  29. send_text(MAV_SEVERITY_WARNING,"Bad rally point ID");
  30. return;
  31. }
  32. if (packet.count != r->get_rally_total()) {
  33. send_text(MAV_SEVERITY_WARNING,"Bad rally point count");
  34. return;
  35. }
  36. // sanity check location
  37. if (!check_latlng(packet.lat, packet.lng)) {
  38. return;
  39. }
  40. RallyLocation rally_point;
  41. rally_point.lat = packet.lat;
  42. rally_point.lng = packet.lng;
  43. rally_point.alt = packet.alt;
  44. rally_point.break_alt = packet.break_alt;
  45. rally_point.land_dir = packet.land_dir;
  46. rally_point.flags = packet.flags;
  47. if (!r->set_rally_point_with_index(packet.idx, rally_point)) {
  48. send_text(MAV_SEVERITY_CRITICAL, "Error setting rally point");
  49. }
  50. }
  51. void GCS_MAVLINK::handle_rally_fetch_point(const mavlink_message_t &msg)
  52. {
  53. AP_Rally *r = AP::rally();
  54. if (r == nullptr) {
  55. return;
  56. }
  57. mavlink_rally_fetch_point_t packet;
  58. mavlink_msg_rally_fetch_point_decode(&msg, &packet);
  59. if (packet.idx > r->get_rally_total()) {
  60. send_text(MAV_SEVERITY_WARNING, "Bad rally point ID");
  61. return;
  62. }
  63. RallyLocation rally_point;
  64. if (!r->get_rally_point_with_index(packet.idx, rally_point)) {
  65. send_text(MAV_SEVERITY_WARNING, "Failed to get rally point");
  66. return;
  67. }
  68. mavlink_msg_rally_point_send(chan, msg.sysid, msg.compid, packet.idx,
  69. r->get_rally_total(), rally_point.lat, rally_point.lng,
  70. rally_point.alt, rally_point.break_alt, rally_point.land_dir,
  71. rally_point.flags);
  72. }
  73. void GCS_MAVLINK::handle_common_rally_message(const mavlink_message_t &msg)
  74. {
  75. switch (msg.msgid) {
  76. case MAVLINK_MSG_ID_RALLY_POINT:
  77. handle_rally_point(msg);
  78. break;
  79. case MAVLINK_MSG_ID_RALLY_FETCH_POINT:
  80. handle_rally_fetch_point(msg);
  81. break;
  82. default:
  83. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  84. AP_HAL::panic("Unhandled common rally message");
  85. #endif
  86. break;
  87. }
  88. }