mirror of https://github.com/ArduPilot/ardupilot
GPS: expose last_fix_time
This commit is contained in:
parent
17daa2f31c
commit
e9f35bfa7f
|
@ -36,9 +36,9 @@ GPS::update(void)
|
||||||
|
|
||||||
if (_status == GPS_OK) {
|
if (_status == GPS_OK) {
|
||||||
// update our acceleration
|
// update our acceleration
|
||||||
float deltat = 1.0e-3 * (_idleTimer - _last_fix_time);
|
float deltat = 1.0e-3 * (_idleTimer - last_fix_time);
|
||||||
float deltav = 1.0e-2 * ((float)ground_speed - (float)_last_ground_speed);
|
float deltav = 1.0e-2 * ((float)ground_speed - (float)_last_ground_speed);
|
||||||
_last_fix_time = _idleTimer;
|
last_fix_time = _idleTimer;
|
||||||
_last_ground_speed = ground_speed;
|
_last_ground_speed = ground_speed;
|
||||||
|
|
||||||
if (deltat > 2.0 || deltat == 0) {
|
if (deltat > 2.0 || deltat == 0) {
|
||||||
|
|
|
@ -113,6 +113,9 @@ public:
|
||||||
// our approximate linear acceleration in m/s/s
|
// our approximate linear acceleration in m/s/s
|
||||||
float acceleration(void) { return _acceleration; }
|
float acceleration(void) { return _acceleration; }
|
||||||
|
|
||||||
|
// the time we got our last fix in system milliseconds
|
||||||
|
uint32_t last_fix_time;
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
Stream *_port; ///< port the GPS is attached to
|
Stream *_port; ///< port the GPS is attached to
|
||||||
|
|
||||||
|
@ -173,9 +176,6 @@ private:
|
||||||
/// Our current status
|
/// Our current status
|
||||||
GPS_Status _status;
|
GPS_Status _status;
|
||||||
|
|
||||||
// the time we got our last fix in system milliseconds
|
|
||||||
uint32_t _last_fix_time;
|
|
||||||
|
|
||||||
// previous ground speed in cm/s
|
// previous ground speed in cm/s
|
||||||
uint32_t _last_ground_speed;
|
uint32_t _last_ground_speed;
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue