Path: blob/master/libraries/AP_GPS/AP_GPS_ExternalAHRS.cpp
9568 views
/*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//16// ExternalAHRS GPS driver17//18#include <AP_ExternalAHRS/AP_ExternalAHRS.h>19#include "AP_GPS_ExternalAHRS.h"2021#if AP_EXTERNAL_AHRS_ENABLED2223// Reading does nothing in this class; we simply return whether or not24// the latest reading has been consumed. By calling this function we assume25// the caller is consuming the new data;26bool AP_GPS_ExternalAHRS::read(void)27{28if (new_data) {29new_data = false;30return true;31}32return false;33}3435// handles an incoming ExternalAHRS message and sets36// corresponding gps data appropriately;37void AP_GPS_ExternalAHRS::handle_external(const AP_ExternalAHRS::gps_data_message_t &pkt)38{39check_new_itow(pkt.ms_tow, sizeof(pkt));4041state.time_week = pkt.gps_week;42state.time_week_ms = pkt.ms_tow;43if (pkt.fix_type == AP_GPS_FixType::NO_GPS) {44state.status = AP_GPS::NO_FIX;45} else {46state.status = (AP_GPS::GPS_Status)pkt.fix_type;47}48state.num_sats = pkt.satellites_in_view;4950const Location loc {51pkt.latitude,52pkt.longitude,53pkt.msl_altitude,54Location::AltFrame::ABSOLUTE55};56#if CONFIG_HAL_BOARD == HAL_BOARD_SITL57if (!loc.initialised() && state.status >= AP_GPS::GPS_Status::GPS_OK_FIX_2D) {58AP_HAL::panic("Invalid location passed to AP_GPS_ExternalAHRS");59}60#endif6162state.location = loc;63state.hdop = pkt.hdop;64state.vdop = pkt.vdop;6566state.have_vertical_velocity = true;67state.velocity.x = pkt.ned_vel_north;68state.velocity.y = pkt.ned_vel_east;69state.velocity.z = pkt.ned_vel_down;7071velocity_to_speed_course(state);7273state.have_speed_accuracy = true;74state.have_horizontal_accuracy = true;75state.have_vertical_accuracy = true;76state.have_vertical_velocity = true;7778state.horizontal_accuracy = pkt.horizontal_pos_accuracy;79state.vertical_accuracy = pkt.vertical_pos_accuracy;80state.speed_accuracy = pkt.horizontal_vel_accuracy;8182state.last_gps_time_ms = AP_HAL::millis();8384new_data = true;85}8687/*88return velocity lag in seconds89*/90bool AP_GPS_ExternalAHRS::get_lag(float &lag_sec) const91{92// fixed assumed lag93lag_sec = 0.11;94return true;95}9697#endif // AP_EXTERNAL_AHRS_ENABLED9899100101