AP_GPS_MAV.cpp 5.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158
  1. /*
  2. This program is free software: you can redistribute it and/or modify
  3. it under the terms of the GNU General Public License as published by
  4. the Free Software Foundation, either version 3 of the License, or
  5. (at your option) any later version.
  6. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. //
  14. // MAVLINK GPS driver
  15. //
  16. #include "AP_GPS_MAV.h"
  17. #include <stdint.h>
  18. AP_GPS_MAV::AP_GPS_MAV(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port) :
  19. AP_GPS_Backend(_gps, _state, _port)
  20. {
  21. }
  22. // Reading does nothing in this class; we simply return whether or not
  23. // the latest reading has been consumed. By calling this function we assume
  24. // the caller is consuming the new data;
  25. bool AP_GPS_MAV::read(void)
  26. {
  27. if (_new_data) {
  28. _new_data = false;
  29. return true;
  30. }
  31. return false;
  32. }
  33. // handles an incoming mavlink message (HIL_GPS) and sets
  34. // corresponding gps data appropriately;
  35. void AP_GPS_MAV::handle_msg(const mavlink_message_t &msg)
  36. {
  37. switch (msg.msgid) {
  38. case MAVLINK_MSG_ID_GPS_INPUT: {
  39. mavlink_gps_input_t packet;
  40. mavlink_msg_gps_input_decode(&msg, &packet);
  41. bool have_alt = ((packet.ignore_flags & GPS_INPUT_IGNORE_FLAG_ALT) == 0);
  42. bool have_hdop = ((packet.ignore_flags & GPS_INPUT_IGNORE_FLAG_HDOP) == 0);
  43. bool have_vdop = ((packet.ignore_flags & GPS_INPUT_IGNORE_FLAG_VDOP) == 0);
  44. bool have_vel_h = ((packet.ignore_flags & GPS_INPUT_IGNORE_FLAG_VEL_HORIZ) == 0);
  45. bool have_vel_v = ((packet.ignore_flags & GPS_INPUT_IGNORE_FLAG_VEL_VERT) == 0);
  46. bool have_sa = ((packet.ignore_flags & GPS_INPUT_IGNORE_FLAG_SPEED_ACCURACY) == 0);
  47. bool have_ha = ((packet.ignore_flags & GPS_INPUT_IGNORE_FLAG_HORIZONTAL_ACCURACY) == 0);
  48. bool have_va = ((packet.ignore_flags & GPS_INPUT_IGNORE_FLAG_VERTICAL_ACCURACY) == 0);
  49. bool have_yaw = (packet.yaw != 0);
  50. state.time_week = packet.time_week;
  51. state.time_week_ms = packet.time_week_ms;
  52. state.status = (AP_GPS::GPS_Status)packet.fix_type;
  53. Location loc = {};
  54. loc.lat = packet.lat;
  55. loc.lng = packet.lon;
  56. if (have_alt) {
  57. loc.alt = packet.alt * 100; // convert to centimeters
  58. }
  59. state.location = loc;
  60. if (have_hdop) {
  61. state.hdop = packet.hdop * 100; // convert to centimeters
  62. }
  63. if (have_vdop) {
  64. state.vdop = packet.vdop * 100; // convert to centimeters
  65. }
  66. if (have_vel_h) {
  67. Vector3f vel(packet.vn, packet.ve, 0);
  68. if (have_vel_v) {
  69. vel.z = packet.vd;
  70. state.have_vertical_velocity = true;
  71. }
  72. state.velocity = vel;
  73. state.ground_course = wrap_360(degrees(atan2f(vel.y, vel.x)));
  74. state.ground_speed = norm(vel.x, vel.y);
  75. }
  76. if (have_sa) {
  77. state.speed_accuracy = packet.speed_accuracy;
  78. state.have_speed_accuracy = true;
  79. }
  80. if (have_ha) {
  81. state.horizontal_accuracy = packet.horiz_accuracy;
  82. state.have_horizontal_accuracy = true;
  83. }
  84. if (have_va) {
  85. state.vertical_accuracy = packet.vert_accuracy;
  86. state.have_vertical_accuracy = true;
  87. }
  88. if (have_yaw) {
  89. state.gps_yaw = wrap_360(packet.yaw*0.01);
  90. state.have_gps_yaw = true;
  91. }
  92. state.num_sats = packet.satellites_visible;
  93. state.last_gps_time_ms = AP_HAL::millis();
  94. _new_data = true;
  95. break;
  96. }
  97. case MAVLINK_MSG_ID_HIL_GPS: {
  98. mavlink_hil_gps_t packet;
  99. mavlink_msg_hil_gps_decode(&msg, &packet);
  100. state.time_week = 0;
  101. state.time_week_ms = packet.time_usec/1000;
  102. state.status = (AP_GPS::GPS_Status)packet.fix_type;
  103. Location loc = {};
  104. loc.lat = packet.lat;
  105. loc.lng = packet.lon;
  106. loc.alt = packet.alt * 0.1f;
  107. state.location = loc;
  108. state.hdop = MIN(packet.eph, GPS_UNKNOWN_DOP);
  109. state.vdop = MIN(packet.epv, GPS_UNKNOWN_DOP);
  110. if (packet.vel < 65535) {
  111. state.ground_speed = packet.vel / 100.0f;
  112. }
  113. Vector3f vel(packet.vn/100.0f, packet.ve/100.0f, packet.vd/100.0f);
  114. state.velocity = vel;
  115. if (packet.vd != 0) {
  116. state.have_vertical_velocity = true;
  117. }
  118. if (packet.cog < 36000) {
  119. state.ground_course = packet.cog / 100.0f;
  120. }
  121. state.have_speed_accuracy = false;
  122. state.have_horizontal_accuracy = false;
  123. state.have_vertical_accuracy = false;
  124. if (packet.satellites_visible < 255) {
  125. state.num_sats = packet.satellites_visible;
  126. }
  127. state.last_gps_time_ms = AP_HAL::millis();
  128. _new_data = true;
  129. break;
  130. }
  131. default:
  132. // ignore all other messages
  133. break;
  134. }
  135. }