uncrustify libraries/AP_LeadFilter/AP_LeadFilter.cpp

This commit is contained in:
uncrustify 2012-08-16 23:20:01 -07:00 committed by Pat Hickey
parent f8235e50da
commit aa5742cd3e

View File

@ -1,40 +1,40 @@
/*
AP_LeadFilter.cpp - GPS lag remover library for Arduino
Code by Jason Short. DIYDrones.com
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.
*/
* AP_LeadFilter.cpp - GPS lag remover library for Arduino
* Code by Jason Short. DIYDrones.com
*
* 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.
*
*/
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"
#include "Arduino.h"
#else
#include "WProgram.h"
#include "WProgram.h"
#endif
#include "AP_LeadFilter.h"
/*
int32_t
AP_LeadFilter::get_position(int32_t pos, int16_t vel)
{
vel = (_last_velocity + vel) / 2;
pos += vel;
pos += (vel - _last_velocity);
_last_velocity = vel;
return pos;
}
*/
* int32_t
* AP_LeadFilter::get_position(int32_t pos, int16_t vel)
* {
* vel = (_last_velocity + vel) / 2;
* pos += vel;
* pos += (vel - _last_velocity);
* _last_velocity = vel;
* return pos;
* }
*/
// setup the control preferences
int32_t
AP_LeadFilter::get_position(int32_t pos, int16_t vel)
{
// assumes a 1 second delay in the GPS
int16_t acc = vel - _last_velocity;
_last_velocity = vel;
return pos + vel + acc;
// assumes a 1 second delay in the GPS
int16_t acc = vel - _last_velocity;
_last_velocity = vel;
return pos + vel + acc;
}