Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_GPS/GPS_Backend.cpp
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/1415#include "AP_GPS_config.h"1617#if AP_GPS_ENABLED1819#include "AP_GPS.h"20#include "GPS_Backend.h"21#include <AP_Logger/AP_Logger.h>22#include <time.h>23#include <AP_Common/time.h>24#include <AP_InternalError/AP_InternalError.h>25#include <AP_AHRS/AP_AHRS.h>2627#define GPS_BACKEND_DEBUGGING 02829#if GPS_BACKEND_DEBUGGING30# define Debug(fmt, args ...) do {hal.console->printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); hal.scheduler->delay(1); } while(0)31#else32# define Debug(fmt, args ...)33#endif3435#include <GCS_MAVLink/GCS.h>3637#if AP_GPS_DEBUG_LOGGING_ENABLED38#include <AP_Filesystem/AP_Filesystem.h>39#endif4041extern const AP_HAL::HAL& hal;4243AP_GPS_Backend::AP_GPS_Backend(AP_GPS &_gps, AP_GPS::Params &_params, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port) :44port(_port),45gps(_gps),46state(_state),47params(_params)48{49state.have_speed_accuracy = false;50state.have_horizontal_accuracy = false;51state.have_vertical_accuracy = false;52}5354/**55fill in time_week_ms and time_week from BCD date and time components56assumes MTK19 millisecond form of bcd_time57*/58void AP_GPS_Backend::make_gps_time(uint32_t bcd_date, uint32_t bcd_milliseconds)59{60struct tm tm {};6162tm.tm_year = 100U + bcd_date % 100U;63tm.tm_mon = ((bcd_date / 100U) % 100U)-1;64tm.tm_mday = bcd_date / 10000U;6566uint32_t v = bcd_milliseconds;67uint16_t msec = v % 1000U; v /= 1000U;68tm.tm_sec = v % 100U; v /= 100U;69tm.tm_min = v % 100U; v /= 100U;70tm.tm_hour = v % 100U;7172// convert from time structure to unix time73time_t unix_time = ap_mktime(&tm);7475// convert to time since GPS epoch76const uint32_t unix_to_GPS_secs = 315964800UL;77const uint16_t leap_seconds_unix = GPS_LEAPSECONDS_MILLIS/1000U;78uint32_t ret = unix_time + leap_seconds_unix - unix_to_GPS_secs;7980// get GPS week and time81state.time_week = ret / AP_SEC_PER_WEEK;82state.time_week_ms = (ret % AP_SEC_PER_WEEK) * AP_MSEC_PER_SEC;83state.time_week_ms += msec;84}8586/*87get the last time of week in ms88*/89uint32_t AP_GPS_Backend::get_last_itow_ms(void) const90{91if (!_have_itow) {92return state.time_week_ms;93}94return (_pseudo_itow_delta_ms == 0)?(_last_itow_ms):((_pseudo_itow/1000ULL) + _pseudo_itow_delta_ms);95}9697/*98fill in 3D velocity for a GPS that doesn't give vertical velocity numbers99*/100void AP_GPS_Backend::fill_3d_velocity(void)101{102float gps_heading = radians(state.ground_course);103104state.velocity.x = state.ground_speed * cosf(gps_heading);105state.velocity.y = state.ground_speed * sinf(gps_heading);106state.velocity.z = 0;107state.have_vertical_velocity = false;108}109110/*111fill in 3D velocity for a GPS that doesn't give vertical velocity numbers112*/113void AP_GPS_Backend::velocity_to_speed_course(AP_GPS::GPS_State &s)114{115s.ground_course = wrap_360(degrees(atan2f(s.velocity.y, s.velocity.x)));116s.ground_speed = s.velocity.xy().length();117}118119void120AP_GPS_Backend::inject_data(const uint8_t *data, uint16_t len)121{122// not all backends have valid ports123if (port != nullptr) {124if (port->txspace() > len) {125port->write(data, len);126} else {127Debug("GPS %d: Not enough TXSPACE", state.instance + 1);128}129}130}131132void AP_GPS_Backend::_detection_message(char *buffer, const uint8_t buflen) const133{134const uint8_t instance = state.instance;135const struct AP_GPS::detect_state dstate = gps.detect_state[instance];136137if (dstate.auto_detected_baud) {138hal.util->snprintf(buffer, buflen,139"GPS %d: probing for %s at %d baud",140instance + 1,141name(),142int(dstate.probe_baud));143} else {144hal.util->snprintf(buffer, buflen,145"GPS %d: specified as %s",146instance + 1,147name());148}149}150151152void AP_GPS_Backend::broadcast_gps_type() const153{154char buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];155_detection_message(buffer, sizeof(buffer));156GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s", buffer);157}158159#if HAL_LOGGING_ENABLED160void AP_GPS_Backend::Write_AP_Logger_Log_Startup_messages() const161{162char buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];163_detection_message(buffer, sizeof(buffer));164AP::logger().Write_Message(buffer);165}166167bool AP_GPS_Backend::should_log() const168{169return gps.should_log();170}171#endif172173174#if AP_GPS_GPS_RTK_SENDING_ENABLED || AP_GPS_GPS2_RTK_SENDING_ENABLED175void AP_GPS_Backend::send_mavlink_gps_rtk(mavlink_channel_t chan)176{177const uint8_t instance = state.instance;178// send status179switch (instance) {180case 0:181mavlink_msg_gps_rtk_send(chan,1820, // Not implemented yet1830, // Not implemented yet184state.rtk_week_number,185state.rtk_time_week_ms,1860, // Not implemented yet1870, // Not implemented yet188state.rtk_num_sats,189state.rtk_baseline_coords_type,190state.rtk_baseline_x_mm,191state.rtk_baseline_y_mm,192state.rtk_baseline_z_mm,193state.rtk_accuracy,194state.rtk_iar_num_hypotheses);195break;196case 1:197mavlink_msg_gps2_rtk_send(chan,1980, // Not implemented yet1990, // Not implemented yet200state.rtk_week_number,201state.rtk_time_week_ms,2020, // Not implemented yet2030, // Not implemented yet204state.rtk_num_sats,205state.rtk_baseline_coords_type,206state.rtk_baseline_x_mm,207state.rtk_baseline_y_mm,208state.rtk_baseline_z_mm,209state.rtk_accuracy,210state.rtk_iar_num_hypotheses);211break;212}213}214#endif // AP_GPS_GPS_RTK_SENDING_ENABLED || AP_GPS_GPS2_RTK_SENDING_ENABLED215216217218/*219set a timestamp based on arrival time on uart at current byte,220assuming the message started nbytes ago221*/222void AP_GPS_Backend::set_uart_timestamp(uint16_t nbytes)223{224if (port) {225state.last_corrected_gps_time_us = port->receive_time_constraint_us(nbytes);226state.corrected_timestamp_updated = true;227}228}229230231void AP_GPS_Backend::check_new_itow(uint32_t itow, uint32_t msg_length)232{233if (itow != _last_itow_ms) {234_last_itow_ms = itow;235_have_itow = true;236237/*238we need to calculate a pseudo-itow, which copes with the239iTow from the GPS changing in unexpected ways. We assume240that timestamps from the GPS are always in multiples of24150ms. That means we can't handle a GPS with an update rate242of more than 20Hz. We could do more, but we'd need the GPS243poll time to be higher244*/245const uint32_t gps_min_period_ms = 50;246247// get the time the packet arrived on the UART248uint64_t uart_us;249if (_last_pps_time_us != 0 && (state.status >= AP_GPS::GPS_OK_FIX_2D)) {250// pps is only reliable when we have some sort of GPS fix251uart_us = _last_pps_time_us;252_last_pps_time_us = 0;253} else if (port) {254uart_us = port->receive_time_constraint_us(msg_length);255} else {256uart_us = AP_HAL::micros64();257}258259uint32_t now = AP_HAL::millis();260uint32_t dt_ms = now - _last_ms;261_last_ms = now;262263// round to nearest 50ms period264dt_ms = ((dt_ms + (gps_min_period_ms/2)) / gps_min_period_ms) * gps_min_period_ms;265266// work out an actual message rate. If we get 5 messages in a267// row with a new rate we switch rate268if (_last_rate_ms == dt_ms) {269if (_rate_counter < 5) {270_rate_counter++;271} else if (_rate_ms != dt_ms) {272_rate_ms = dt_ms;273}274} else {275_rate_counter = 0;276_last_rate_ms = dt_ms;277if (_rate_ms != 0) {278set_pps_desired_freq(1000/_rate_ms);279}280}281if (_rate_ms == 0) {282// only allow 5Hz to 20Hz in user config283_rate_ms = constrain_int16(gps.get_rate_ms(state.instance), 50, 200);284}285286// round to calculated message rate287dt_ms = ((dt_ms + (_rate_ms/2)) / _rate_ms) * _rate_ms;288289// calculate pseudo-itow290_pseudo_itow += dt_ms * 1000U;291292// use msg arrival time, and correct for jitter293uint64_t local_us = jitter_correction.correct_offboard_timestamp_usec(_pseudo_itow, uart_us);294state.last_corrected_gps_time_us = local_us;295state.corrected_timestamp_updated = true;296297#ifndef HAL_BUILD_AP_PERIPH298// look for lagged data from the GPS. This is meant to detect299// the case that the GPS is trying to push more data into the300// UART than can fit (eg. with GPS_RAW_DATA at 115200).301// This is disabled on AP_Periph as it is better to catch missed packet rate at the flight302// controller level303float expected_lag;304if (gps.get_lag(state.instance, expected_lag)) {305float lag_s = (now - (state.last_corrected_gps_time_us/1000U)) * 0.001;306if (lag_s > expected_lag+0.05) {307// more than 50ms over expected lag, increment lag counter308state.lagged_sample_count++;309} else {310state.lagged_sample_count = 0;311}312}313#endif // HAL_BUILD_AP_PERIPH314315if (state.status >= AP_GPS::GPS_OK_FIX_2D) {316// we must have a decent fix to calculate difference between itow and pseudo-itow317_pseudo_itow_delta_ms = itow - (_pseudo_itow/1000ULL);318}319}320}321322#if GPS_MOVING_BASELINE323bool AP_GPS_Backend::calculate_moving_base_yaw(float reported_heading_deg, const float reported_distance, const float reported_D) {324return calculate_moving_base_yaw(state, reported_heading_deg, reported_distance, reported_D);325}326327bool AP_GPS_Backend::calculate_moving_base_yaw(AP_GPS::GPS_State &interim_state, const float reported_heading_deg, const float reported_distance, const float reported_D) {328constexpr float minimum_antenna_seperation = 0.05; // meters329constexpr float permitted_error_length_pct = 0.2; // percentage330#if HAL_LOGGING_ENABLED || AP_AHRS_ENABLED331float min_D = 0.0f;332float max_D = 0.0f;333#endif334bool selectedOffset = false;335Vector3f offset;336switch (MovingBase::Type(gps.params[interim_state.instance].mb_params.type)) {337case MovingBase::Type::RelativeToAlternateInstance:338offset = gps.params[interim_state.instance^1].antenna_offset.get() - gps.params[interim_state.instance].antenna_offset.get();339selectedOffset = true;340break;341case MovingBase::Type::RelativeToCustomBase:342offset = gps.params[interim_state.instance].mb_params.base_offset.get();343selectedOffset = true;344break;345}346347if (!selectedOffset) {348// invalid type, let's throw up a flag349INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);350goto bad_yaw;351}352353{354const float offset_dist = offset.length();355const float min_dist = MIN(offset_dist, reported_distance);356357if (offset_dist < minimum_antenna_seperation) {358// offsets have to be sufficiently large to get a meaningful angle off of them359Debug("Insufficent antenna offset (%f, %f, %f)", (double)offset.x, (double)offset.y, (double)offset.z);360goto bad_yaw;361}362363if (reported_distance < minimum_antenna_seperation) {364// if the reported distance is less then the minimum separation it's not sufficiently robust365Debug("Reported baseline distance (%f) was less then the minimum antenna separation (%f)",366(double)reported_distance, (double)minimum_antenna_seperation);367goto bad_yaw;368}369370371if (fabsf(offset_dist - reported_distance) > (min_dist * permitted_error_length_pct)) {372// the magnitude of the vector is much further then we were expecting373Debug("Offset=%.2f vs reported-distance=%.2f (max-delta=%.2f)",374offset_dist, reported_distance, (double)(min_dist * permitted_error_length_pct));375goto bad_yaw;376}377378#if AP_AHRS_ENABLED379{380// get vehicle rotation, projected back in time using the gyro381// this is not 100% accurate, but it is good enough for382// this test. To do it completely accurately we'd need an383// interface into DCM, EKF2 and EKF3 to ask for a384// historical attitude. That is far too complex to justify385// for this use case386const auto &ahrs = AP::ahrs();387const Vector3f &gyro = ahrs.get_gyro();388Matrix3f rot_body_to_ned_min_lag = ahrs.get_rotation_body_to_ned();389rot_body_to_ned_min_lag.rotate(gyro * -AP_GPS_MB_MIN_LAG);390Matrix3f rot_body_to_ned_max_lag = ahrs.get_rotation_body_to_ned();391rot_body_to_ned_max_lag.rotate(gyro * -AP_GPS_MB_MAX_LAG);392393// apply rotation to the offset to get the Z offset in NED394const Vector3f antenna_tilt_min_lag = rot_body_to_ned_min_lag * offset;395const Vector3f antenna_tilt_max_lag = rot_body_to_ned_max_lag * offset;396min_D = MIN(-antenna_tilt_min_lag.z, -antenna_tilt_max_lag.z);397max_D = MAX(-antenna_tilt_min_lag.z, -antenna_tilt_max_lag.z);398min_D -= permitted_error_length_pct * min_dist;399max_D += permitted_error_length_pct * min_dist;400if (reported_D < min_D || reported_D > max_D) {401// the vertical component is out of range, reject it402Debug("bad alt_err %f < %f < %f", (double)min_D, (double)reported_D, (double)max_D);403goto bad_yaw;404}405}406#endif // AP_AHRS_ENABLED407408{409// at this point the offsets are looking okay, go ahead and actually calculate a useful heading410const float rotation_offset_rad = Vector2f(-offset.x, -offset.y).angle();411interim_state.gps_yaw = wrap_360(reported_heading_deg - degrees(rotation_offset_rad));412interim_state.have_gps_yaw = true;413interim_state.gps_yaw_time_ms = AP_HAL::millis();414}415goto good_yaw;416}417418bad_yaw:419interim_state.have_gps_yaw = false;420421good_yaw:422423#if HAL_LOGGING_ENABLED424// this log message helps diagnose GPS yaw issues425// @LoggerMessage: GPYW426// @Description: GPS Yaw427// @Field: TimeUS: Time since system startup428// @Field: Id: instance429// @Field: RHD: reported heading,deg430// @Field: RDist: antenna separation,m431// @Field: RDown: vertical antenna separation,m432// @Field: MinCDown: minimum tolerable vertical antenna separation,m433// @Field: MaxCDown: maximum tolerable vertical antenna separation,m434// @Field: OK: 1 if have yaw435AP::logger().WriteStreaming("GPYW", "TimeUS,Id,RHD,RDist,RDown,MinCDown,MaxCDown,OK",436"s#dmmmm-",437"F-------",438"QBfffffB",439AP_HAL::micros64(),440state.instance,441reported_heading_deg,442reported_distance,443reported_D,444min_D,445max_D,446interim_state.have_gps_yaw);447#endif448449return interim_state.have_gps_yaw;450}451#endif // GPS_MOVING_BASELINE452453/*454set altitude in location structure, honouring the driver option for455MSL vs ellipsoid height456*/457void AP_GPS_Backend::set_alt_amsl_cm(AP_GPS::GPS_State &_state, int32_t alt_amsl_cm)458{459if (option_set(AP_GPS::HeightEllipsoid) && _state.have_undulation) {460// user has asked ArduPilot to use ellipsoid height in the461// canonical height for mission and navigation462_state.location.alt = alt_amsl_cm - _state.undulation*100;463} else {464_state.location.alt = alt_amsl_cm;465}466}467468#if AP_GPS_DEBUG_LOGGING_ENABLED469470/*471log some data for debugging472473the logging format matches that used by SITL with SIM_GPS_TYPE=7,474allowing for development of GPS drivers based on logged data475*/476void AP_GPS_Backend::log_data(const uint8_t *data, uint16_t length)477{478if (state.instance < 2) {479logging[state.instance].buf.write(data, length);480}481if (!log_thread_created) {482log_thread_created = true;483hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_GPS_Backend::logging_start, void), "gps_log", 4096, AP_HAL::Scheduler::PRIORITY_IO, 0);484}485}486487AP_GPS_Backend::loginfo AP_GPS_Backend::logging[2];488bool AP_GPS_Backend::log_thread_created;489490// logging loop, needs to be static to allow for re-alloc of GPS backends491void AP_GPS_Backend::logging_loop(void)492{493while (true) {494hal.scheduler->delay(10);495static uint16_t lognum;496for (uint8_t instance=0; instance<2; instance++) {497if (logging[instance].fd == -1 && logging[instance].buf.available()) {498char fname[] = "gpsN_XXX.log";499fname[3] = '1' + instance;500if (lognum == 0) {501for (lognum=1; lognum<1000; lognum++) {502struct stat st;503hal.util->snprintf(&fname[5], 8, "%03u.log", lognum);504if (AP::FS().stat(fname, &st) != 0) {505break;506}507}508}509hal.util->snprintf(&fname[5], 8, "%03u.log", lognum);510logging[instance].fd = AP::FS().open(fname, O_WRONLY|O_CREAT|O_APPEND);511}512if (logging[instance].fd != -1) {513uint32_t n = 0;514const uint8_t *p;515while ((p = logging[instance].buf.readptr(n)) != nullptr && n != 0) {516struct {517uint32_t magic = 0x7fe53b04U;518uint32_t time_ms;519uint32_t n;520} header;521header.n = n;522header.time_ms = AP_HAL::millis();523// short writes are unlikely and are ignored (only FS full errors)524AP::FS().write(logging[instance].fd, (const uint8_t *)&header, sizeof(header));525AP::FS().write(logging[instance].fd, p, n);526logging[instance].buf.advance(n);527AP::FS().fsync(logging[instance].fd);528}529}530}531}532}533534// logging thread start, needs to be non-static for thread_create535void AP_GPS_Backend::logging_start(void)536{537logging_loop();538}539#endif // AP_GPS_DEBUG_LOGGING_ENABLED540541#endif // AP_GPS_ENABLED542543544