MissionItemProtocol_Rally.cpp 3.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125
  1. /*
  2. Implementation details for transfering rally point information using
  3. the MISSION_ITEM protocol to and from a GCS.
  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. This program is distributed in the hope that it will be useful,
  9. but WITHOUT ANY WARRANTY; without even the implied warranty of
  10. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  11. GNU General Public License for more details.
  12. You should have received a copy of the GNU General Public License
  13. along with this program. If not, see <http://www.gnu.org/licenses/>.
  14. */
  15. #include "MissionItemProtocol_Rally.h"
  16. #include <AP_Logger/AP_Logger.h>
  17. #include <AP_Rally/AP_Rally.h>
  18. #include <GCS_MAVLink/GCS.h>
  19. MAV_MISSION_RESULT MissionItemProtocol_Rally::append_item(const mavlink_mission_item_int_t &cmd)
  20. {
  21. RallyLocation rallyloc;
  22. const MAV_MISSION_RESULT ret = convert_MISSION_ITEM_INT_to_RallyLocation(cmd, rallyloc);
  23. if (ret != MAV_MISSION_ACCEPTED) {
  24. return ret;
  25. }
  26. if (!rally.append(rallyloc)) {
  27. return MAV_MISSION_ERROR;
  28. }
  29. return MAV_MISSION_ACCEPTED;
  30. }
  31. MAV_MISSION_RESULT MissionItemProtocol_Rally::complete(const GCS_MAVLINK &_link)
  32. {
  33. _link.send_text(MAV_SEVERITY_INFO, "Rally points received");
  34. AP::logger().Write_Rally();
  35. return MAV_MISSION_ACCEPTED;
  36. }
  37. bool MissionItemProtocol_Rally::clear_all_items()
  38. {
  39. rally.truncate(0);
  40. return true;
  41. }
  42. MAV_MISSION_RESULT MissionItemProtocol_Rally::convert_MISSION_ITEM_INT_to_RallyLocation(const mavlink_mission_item_int_t &cmd, RallyLocation &ret)
  43. {
  44. if (cmd.command != MAV_CMD_NAV_RALLY_POINT) {
  45. return MAV_MISSION_UNSUPPORTED;
  46. }
  47. if (cmd.frame != MAV_FRAME_GLOBAL_RELATIVE_ALT_INT &&
  48. cmd.frame != MAV_FRAME_GLOBAL_RELATIVE_ALT) {
  49. return MAV_MISSION_UNSUPPORTED_FRAME;
  50. }
  51. if (!check_lat(cmd.x)) {
  52. return MAV_MISSION_INVALID_PARAM5_X;
  53. }
  54. if (!check_lng(cmd.y)) {
  55. return MAV_MISSION_INVALID_PARAM6_Y;
  56. }
  57. if (cmd.z < INT16_MIN || cmd.z > INT16_MAX) {
  58. return MAV_MISSION_INVALID_PARAM7;
  59. }
  60. ret.lat = cmd.x;
  61. ret.lng = cmd.y;
  62. ret.alt = cmd.z;
  63. return MAV_MISSION_ACCEPTED;
  64. }
  65. MAV_MISSION_RESULT MissionItemProtocol_Rally::get_item(const GCS_MAVLINK &_link,
  66. const mavlink_message_t &msg,
  67. const mavlink_mission_request_int_t &packet,
  68. mavlink_mission_item_int_t &ret_packet)
  69. {
  70. RallyLocation rallypoint;
  71. if (!rally.get_rally_point_with_index(packet.seq, rallypoint)) {
  72. return MAV_MISSION_INVALID_SEQUENCE;
  73. }
  74. ret_packet.frame = MAV_FRAME_GLOBAL_RELATIVE_ALT;
  75. ret_packet.command = MAV_CMD_NAV_RALLY_POINT;
  76. ret_packet.x = rallypoint.lat;
  77. ret_packet.y = rallypoint.lng;
  78. ret_packet.z = rallypoint.alt;
  79. return MAV_MISSION_ACCEPTED;
  80. }
  81. uint16_t MissionItemProtocol_Rally::item_count() const {
  82. return rally.get_rally_total();
  83. }
  84. uint16_t MissionItemProtocol_Rally::max_items() const {
  85. return rally.get_rally_max();
  86. }
  87. MAV_MISSION_RESULT MissionItemProtocol_Rally::replace_item(const mavlink_mission_item_int_t &cmd)
  88. {
  89. RallyLocation rallyloc;
  90. const MAV_MISSION_RESULT ret = convert_MISSION_ITEM_INT_to_RallyLocation(cmd, rallyloc);
  91. if (ret != MAV_MISSION_ACCEPTED) {
  92. return ret;
  93. }
  94. if (!rally.set_rally_point_with_index(cmd.seq, rallyloc)) {
  95. return MAV_MISSION_ERROR;
  96. }
  97. return MAV_MISSION_ACCEPTED;
  98. }
  99. void MissionItemProtocol_Rally::timeout()
  100. {
  101. link->send_text(MAV_SEVERITY_WARNING, "Rally upload timeout");
  102. }
  103. void MissionItemProtocol_Rally::truncate(const mavlink_mission_count_t &packet)
  104. {
  105. rally.truncate(packet.count);
  106. }