ardupilot/libraries/AP_GPS/AP_GPS_HIL.cpp
DrZiplok@gmail.com 8da4a29d58 Add support for the DIYD MTK v1.6 firmware
Nuke AP_GPS_IMU, as nothing is using it anymore.
Simplify the handling of no GPS/no fix detection.
Fix prototypes for ::init and ::read.
Update AP_GPS_Auto and corresponding example, nearly ready for primetime.
Use uint8_t rather than byte.
Strip some _error() calls to save space.  More could still go.



git-svn-id: https://arducopter.googlecode.com/svn/trunk@1246 f9c3cf11-9bcb-44bc-f272-b75c42450872
2010-12-24 06:35:09 +00:00

51 lines
1.4 KiB
C++

// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
//
// Hardware in the loop gps class.
// Code by James Goppert
//
// This library is free software; you can redistribute it and / or
// modify it under the terms of the GNU Lesser General Public
// License as published by the Free Software Foundation; either
// version 2.1 of the License, or (at your option) any later version.
//
// GPS configuration : Custom protocol per "DIYDrones Custom Binary Sentence Specification V1.1"
//
#include "AP_GPS_HIL.h"
#include "WProgram.h"
// Constructors ////////////////////////////////////////////////////////////////
AP_GPS_HIL::AP_GPS_HIL(Stream *s) : GPS(s)
{
}
// Public Methods //////////////////////////////////////////////////////////////
void AP_GPS_HIL::init(void)
{
}
bool AP_GPS_HIL::read(void)
{
bool result = _updated;
// return true once for each update pushed in
_updated = false;
return result;
}
void AP_GPS_HIL::setHIL(long _time, float _latitude, float _longitude, float _altitude,
float _ground_speed, float _ground_course, float _speed_3d, uint8_t _num_sats)
{
time = _time;
latitude = _latitude*1.0e7;
longitude = _longitude*1.0e7;
altitude = _altitude*1.0e2;
ground_speed = _ground_speed*1.0e2;
ground_course = _ground_course*1.0e2;
speed_3d = _speed_3d*1.0e2;
num_sats = _num_sats;
fix = true;
_updated = true;
}