APM:Libraries
GPS_Backend.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 #include "AP_GPS.h"
17 #include "GPS_Backend.h"
18 
19 #define GPS_BACKEND_DEBUGGING 0
20 
21 #if GPS_BACKEND_DEBUGGING
22  # define Debug(fmt, args ...) do {hal.console->printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); hal.scheduler->delay(1); } while(0)
23 #else
24  # define Debug(fmt, args ...)
25 #endif
26 
27 #include <GCS_MAVLink/GCS.h>
28 
29 extern const AP_HAL::HAL& hal;
30 
32  port(_port),
33  gps(_gps),
34  state(_state)
35 {
36  state.have_speed_accuracy = false;
39 }
40 
41 int32_t AP_GPS_Backend::swap_int32(int32_t v) const
42 {
43  const uint8_t *b = (const uint8_t *)&v;
44  union {
45  int32_t v;
46  uint8_t b[4];
47  } u;
48 
49  u.b[0] = b[3];
50  u.b[1] = b[2];
51  u.b[2] = b[1];
52  u.b[3] = b[0];
53 
54  return u.v;
55 }
56 
57 int16_t AP_GPS_Backend::swap_int16(int16_t v) const
58 {
59  const uint8_t *b = (const uint8_t *)&v;
60  union {
61  int16_t v;
62  uint8_t b[2];
63  } u;
64 
65  u.b[0] = b[1];
66  u.b[1] = b[0];
67 
68  return u.v;
69 }
70 
71 
76 void AP_GPS_Backend::make_gps_time(uint32_t bcd_date, uint32_t bcd_milliseconds)
77 {
78  uint8_t year, mon, day, hour, min, sec;
79  uint16_t msec;
80 
81  year = bcd_date % 100;
82  mon = (bcd_date / 100) % 100;
83  day = bcd_date / 10000;
84 
85  uint32_t v = bcd_milliseconds;
86  msec = v % 1000; v /= 1000;
87  sec = v % 100; v /= 100;
88  min = v % 100; v /= 100;
89  hour = v % 100; v /= 100;
90 
91  int8_t rmon = mon - 2;
92  if (0 >= rmon) {
93  rmon += 12;
94  year -= 1;
95  }
96 
97  // get time in seconds since unix epoch
98  uint32_t ret = (year/4) - (GPS_LEAPSECONDS_MILLIS / 1000UL) + 367*rmon/12 + day;
99  ret += year*365 + 10501;
100  ret = ret*24 + hour;
101  ret = ret*60 + min;
102  ret = ret*60 + sec;
103 
104  // convert to time since GPS epoch
105  ret -= 272764785UL;
106 
107  // get GPS week and time
110  state.time_week_ms += msec;
111 }
112 
113 /*
114  fill in 3D velocity for a GPS that doesn't give vertical velocity numbers
115  */
117 {
118  float gps_heading = radians(state.ground_course);
119 
120  state.velocity.x = state.ground_speed * cosf(gps_heading);
121  state.velocity.y = state.ground_speed * sinf(gps_heading);
122  state.velocity.z = 0;
124 }
125 
126 void
127 AP_GPS_Backend::inject_data(const uint8_t *data, uint16_t len)
128 {
129  // not all backends have valid ports
130  if (port != nullptr) {
131  if (port->txspace() > len) {
132  port->write(data, len);
133  } else {
134  Debug("GPS %d: Not enough TXSPACE", state.instance + 1);
135  }
136  }
137 }
138 
139 void AP_GPS_Backend::_detection_message(char *buffer, const uint8_t buflen) const
140 {
141  const uint8_t instance = state.instance;
142  const struct AP_GPS::detect_state dstate = gps.detect_state[instance];
143 
144  if (dstate.auto_detected_baud) {
145  hal.util->snprintf(buffer, buflen,
146  "GPS %d: detected as %s at %d baud",
147  instance + 1,
148  name(),
149  gps._baudrates[dstate.current_baud]);
150  } else {
151  hal.util->snprintf(buffer, buflen,
152  "GPS %d: specified as %s",
153  instance + 1,
154  name());
155  }
156 }
157 
158 
160 {
161  char buffer[64];
162  _detection_message(buffer, sizeof(buffer));
163  gcs().send_text(MAV_SEVERITY_INFO, buffer);
164 }
165 
167 {
168  char buffer[64];
169  _detection_message(buffer, sizeof(buffer));
171 }
172 
174 {
175  return gps.should_df_log();
176 }
177 
178 
180 {
181  const uint8_t instance = state.instance;
182  // send status
183  switch (instance) {
184  case 0:
185  mavlink_msg_gps_rtk_send(chan,
186  0, // Not implemented yet
187  0, // Not implemented yet
190  0, // Not implemented yet
191  0, // Not implemented yet
199  break;
200  case 1:
201  mavlink_msg_gps2_rtk_send(chan,
202  0, // Not implemented yet
203  0, // Not implemented yet
206  0, // Not implemented yet
207  0, // Not implemented yet
215  break;
216  }
217 }
218 
Definition: AP_GPS.h:48
#define GPS_LEAPSECONDS_MILLIS
Definition: AP_GPS.h:40
uint32_t time_week_ms
GPS time (milliseconds from start of GPS week)
Definition: AP_GPS.h:133
bool auto_detected_baud
Definition: AP_GPS.h:481
uint16_t rtk_week_number
GPS Week Number of last baseline.
Definition: AP_GPS.h:153
uint8_t current_baud
Definition: AP_GPS.h:480
uint8_t instance
Definition: AP_GPS.h:129
#define AP_MSEC_PER_SEC
Definition: definitions.h:94
Interface definition for the various Ground Control System.
bool have_vertical_velocity
does GPS give vertical velocity? Set to true only once available.
Definition: AP_GPS.h:145
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
static uint8_t buffer[SRXL_FRAMELEN_MAX]
Definition: srxl.cpp:56
int32_t rtk_baseline_z_mm
Current baseline in ECEF z or NED down component in mm.
Definition: AP_GPS.h:159
Vector3f velocity
3D velocity in m/s, in NED format
Definition: AP_GPS.h:141
void Log_Write_Message(const char *message)
Definition: DataFlash.cpp:593
virtual void inject_data(const uint8_t *data, uint16_t len)
AP_HAL::Util * util
Definition: HAL.h:115
virtual uint32_t txspace()=0
GCS & gcs()
bool should_df_log() const
Definition: AP_GPS.cpp:579
#define Debug(fmt, args ...)
Definition: GPS_Backend.cpp:24
int32_t rtk_baseline_y_mm
Current baseline in ECEF y or NED east component in mm.
Definition: AP_GPS.h:158
int32_t swap_int32(int32_t v) const
Definition: GPS_Backend.cpp:41
AP_GPS & gps
access to frontend (for parameters)
Definition: GPS_Backend.h:70
virtual const char * name() const =0
uint8_t rtk_num_sats
Current number of satellites used for RTK calculation.
Definition: AP_GPS.h:155
T y
Definition: vector3.h:67
virtual size_t write(uint8_t)=0
virtual void send_mavlink_gps_rtk(mavlink_channel_t chan)
uint8_t rtk_baseline_coords_type
Coordinate system of baseline. 0 == ECEF, 1 == NED.
Definition: AP_GPS.h:156
int32_t rtk_iar_num_hypotheses
Current number of integer ambiguity hypotheses.
Definition: AP_GPS.h:161
static DataFlash_Class * instance(void)
Definition: DataFlash.h:62
void broadcast_gps_type() const
T z
Definition: vector3.h:67
static int state
Definition: Util.cpp:20
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
float v
Definition: Printf.cpp:15
void send_text(MAV_SEVERITY severity, const char *fmt,...)
Definition: GCS.cpp:8
bool should_df_log() const
void _detection_message(char *buffer, uint8_t buflen) const
static uint8_t buflen
Definition: srxl.cpp:57
AP_GPS_Backend(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port)
Definition: GPS_Backend.cpp:31
#define AP_SEC_PER_WEEK
Definition: definitions.h:95
uint32_t rtk_accuracy
Current estimate of 3D baseline accuracy (receiver dependent, typical 0 to 9999)
Definition: AP_GPS.h:160
static const uint32_t _baudrates[]
Definition: AP_GPS.h:499
int snprintf(char *str, size_t size, const char *format,...)
Definition: Util.cpp:44
static constexpr float radians(float deg)
Definition: AP_Math.h:158
void fill_3d_velocity(void)
int16_t swap_int16(int16_t v) const
Definition: GPS_Backend.cpp:57
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
void make_gps_time(uint32_t bcd_date, uint32_t bcd_milliseconds)
Definition: GPS_Backend.cpp:76
uint32_t rtk_time_week_ms
GPS Time of Week of last baseline in milliseconds.
Definition: AP_GPS.h:152
bool have_vertical_accuracy
does GPS give vertical position accuracy? Set to true only once available.
Definition: AP_GPS.h:148
AP_HAL::UARTDriver * port
UART we are attached to.
Definition: GPS_Backend.h:69
bool have_horizontal_accuracy
does GPS give horizontal position accuracy? Set to true only once available.
Definition: AP_GPS.h:147
float ground_speed
ground speed in m/sec
Definition: AP_GPS.h:136
virtual void Write_DataFlash_Log_Startup_messages() const
static AP_GPS gps
Definition: AHRS_Test.cpp:22
struct AP_GPS::detect_state detect_state[GPS_MAX_RECEIVERS]
T x
Definition: vector3.h:67
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
int32_t rtk_baseline_x_mm
Current baseline in ECEF x or NED north component in mm.
Definition: AP_GPS.h:157