APM:Libraries
AP_GPS_MAV.cpp
Go to the documentation of this file.
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 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
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 
16 //
17 // MAVLINK GPS driver
18 //
19 #include "AP_GPS_MAV.h"
20 #include <stdint.h>
21 
23  AP_GPS_Backend(_gps, _state, _port)
24 {
25 }
26 
27 // Reading does nothing in this class; we simply return whether or not
28 // the latest reading has been consumed. By calling this function we assume
29 // the caller is consuming the new data;
30 bool AP_GPS_MAV::read(void)
31 {
32  if (_new_data) {
33  _new_data = false;
34  return true;
35  }
36 
37  return false;
38 }
39 
40 // handles an incoming mavlink message (HIL_GPS) and sets
41 // corresponding gps data appropriately;
42 void AP_GPS_MAV::handle_msg(const mavlink_message_t *msg)
43 {
44  switch (msg->msgid) {
45 
46  case MAVLINK_MSG_ID_GPS_INPUT: {
47  mavlink_gps_input_t packet;
48  mavlink_msg_gps_input_decode(msg, &packet);
49 
50  bool have_alt = ((packet.ignore_flags & GPS_INPUT_IGNORE_FLAG_ALT) == 0);
51  bool have_hdop = ((packet.ignore_flags & GPS_INPUT_IGNORE_FLAG_HDOP) == 0);
52  bool have_vdop = ((packet.ignore_flags & GPS_INPUT_IGNORE_FLAG_VDOP) == 0);
53  bool have_vel_h = ((packet.ignore_flags & GPS_INPUT_IGNORE_FLAG_VEL_HORIZ) == 0);
54  bool have_vel_v = ((packet.ignore_flags & GPS_INPUT_IGNORE_FLAG_VEL_VERT) == 0);
55  bool have_sa = ((packet.ignore_flags & GPS_INPUT_IGNORE_FLAG_SPEED_ACCURACY) == 0);
56  bool have_ha = ((packet.ignore_flags & GPS_INPUT_IGNORE_FLAG_HORIZONTAL_ACCURACY) == 0);
57  bool have_va = ((packet.ignore_flags & GPS_INPUT_IGNORE_FLAG_VERTICAL_ACCURACY) == 0);
58 
59  state.time_week = packet.time_week;
60  state.time_week_ms = packet.time_week_ms;
61  state.status = (AP_GPS::GPS_Status)packet.fix_type;
62 
63  Location loc = {};
64  loc.lat = packet.lat;
65  loc.lng = packet.lon;
66  if (have_alt) {
67  loc.alt = packet.alt * 100; // convert to centimeters
68  }
69  state.location = loc;
71 
72  if (have_hdop) {
73  state.hdop = packet.hdop * 100; // convert to centimeters
74  }
75 
76  if (have_vdop) {
77  state.vdop = packet.vdop * 100; // convert to centimeters
78  }
79 
80  if (have_vel_h) {
81  Vector3f vel(packet.vn, packet.ve, 0);
82  if (have_vel_v) {
83  vel.z = packet.vd;
85  }
86 
87  state.velocity = vel;
88  state.ground_course = wrap_360(degrees(atan2f(vel.y, vel.x)));
89  state.ground_speed = norm(vel.x, vel.y);
90  }
91 
92  if (have_sa) {
93  state.speed_accuracy = packet.speed_accuracy;
95  }
96 
97  if (have_ha) {
98  state.horizontal_accuracy = packet.horiz_accuracy;
100  }
101 
102  if (have_va) {
103  state.vertical_accuracy = packet.vert_accuracy;
105  }
106 
107  state.num_sats = packet.satellites_visible;
109  _new_data = true;
110  break;
111  }
112 
113  case MAVLINK_MSG_ID_HIL_GPS: {
114  mavlink_hil_gps_t packet;
115  mavlink_msg_hil_gps_decode(msg, &packet);
116 
117  state.time_week = 0;
118  state.time_week_ms = packet.time_usec/1000;
119  state.status = (AP_GPS::GPS_Status)packet.fix_type;
120 
121  Location loc = {};
122  loc.lat = packet.lat;
123  loc.lng = packet.lon;
124  loc.alt = packet.alt * 0.1f;
125  state.location = loc;
126  state.location.options = 0;
127  state.hdop = MIN(packet.eph, GPS_UNKNOWN_DOP);
128  state.vdop = MIN(packet.epv, GPS_UNKNOWN_DOP);
129  if (packet.vel < 65535) {
130  state.ground_speed = packet.vel / 100.0f;
131  }
132  Vector3f vel(packet.vn/100.0f, packet.ve/100.0f, packet.vd/100.0f);
133  state.velocity = vel;
134  if (packet.vd != 0) {
136  }
137  if (packet.cog < 36000) {
138  state.ground_course = packet.cog / 100.0f;
139  }
140  state.have_speed_accuracy = false;
143  if (packet.satellites_visible < 255) {
144  state.num_sats = packet.satellites_visible;
145  }
147  _new_data = true;
148  break;
149  }
150  default:
151  // ignore all other messages
152  break;
153  }
154 }
float norm(const T first, const U second, const Params... parameters)
Definition: AP_Math.h:190
Definition: AP_GPS.h:48
uint32_t time_week_ms
GPS time (milliseconds from start of GPS week)
Definition: AP_GPS.h:133
uint32_t last_gps_time_ms
the system time we got the last GPS timestamp, milliseconds
Definition: AP_GPS.h:149
GPS_Status status
driver fix status
Definition: AP_GPS.h:132
bool have_vertical_velocity
does GPS give vertical velocity? Set to true only once available.
Definition: AP_GPS.h:145
Vector3f velocity
3D velocity in m/s, in NED format
Definition: AP_GPS.h:141
void handle_msg(const mavlink_message_t *msg)
Definition: AP_GPS_MAV.cpp:42
bool _new_data
Definition: AP_GPS_MAV.h:41
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
#define MIN(a, b)
Definition: usb_conf.h:215
GPS_Status
GPS status codes.
Definition: AP_GPS.h:96
AP_GPS_MAV(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port)
Definition: AP_GPS_MAV.cpp:22
float wrap_360(const T angle, float unit_mod)
Definition: AP_Math.cpp:123
bool read()
Definition: AP_GPS_MAV.cpp:30
T y
Definition: vector3.h:67
uint32_t millis()
Definition: system.cpp:157
T z
Definition: vector3.h:67
uint16_t time_week
GPS week number.
Definition: AP_GPS.h:134
AP_GPS::GPS_State & state
public state for this instance
Definition: GPS_Backend.h:71
#define GPS_UNKNOWN_DOP
Definition: AP_GPS.h:35
uint16_t vdop
vertical dilution of precision in cm
Definition: AP_GPS.h:139
Location location
last fix location
Definition: AP_GPS.h:135
bool have_vertical_accuracy
does GPS give vertical position accuracy? Set to true only once available.
Definition: AP_GPS.h:148
float speed_accuracy
3D velocity RMS accuracy estimate in m/s
Definition: AP_GPS.h:142
bool have_horizontal_accuracy
does GPS give horizontal position accuracy? Set to true only once available.
Definition: AP_GPS.h:147
float horizontal_accuracy
horizontal RMS accuracy estimate in m
Definition: AP_GPS.h:143
float ground_speed
ground speed in m/sec
Definition: AP_GPS.h:136
#define degrees(x)
Definition: moduletest.c:23
float vertical_accuracy
vertical RMS accuracy estimate in m
Definition: AP_GPS.h:144
uint16_t hdop
horizontal dilution of precision in cm
Definition: AP_GPS.h:138
T x
Definition: vector3.h:67
uint8_t options
Definition: AP_Common.h:136
uint8_t num_sats
Number of visible satellites.
Definition: AP_GPS.h:140
bool have_speed_accuracy
does GPS give speed accuracy? Set to true only once available.
Definition: AP_GPS.h:146
float ground_course
ground course in degrees
Definition: AP_GPS.h:137