mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_LeadFitler: ported to AP_HAL
This commit is contained in:
parent
4acf2c8591
commit
3503c7627a
@ -8,13 +8,6 @@
|
||||
* version 2.1 of the License, or (at your option) any later version.
|
||||
*
|
||||
*/
|
||||
|
||||
#if defined(ARDUINO) && ARDUINO >= 100
|
||||
#include "Arduino.h"
|
||||
#else
|
||||
#include "WProgram.h"
|
||||
#endif
|
||||
|
||||
#include "AP_LeadFilter.h"
|
||||
|
||||
// setup the control preferences
|
||||
|
@ -1,11 +1,9 @@
|
||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
||||
|
||||
/// @file RC_Channel.h
|
||||
/// @brief RC_Channel manager, with EEPROM-backed storage of constants.
|
||||
|
||||
#ifndef AP_LeadFilter_h
|
||||
#define AP_LeadFilter_h
|
||||
#ifndef __AP_LEADFILTER_H__
|
||||
#define __AP_LEADFILTER_H__
|
||||
|
||||
#include <stdint.h>
|
||||
#include <AP_LeadFilter.h>
|
||||
|
||||
/// @class AP_LeadFilter
|
||||
@ -28,4 +26,4 @@ private:
|
||||
|
||||
};
|
||||
|
||||
#endif
|
||||
#endif // __AP_LEADFILTER_H__
|
||||
|
@ -5,36 +5,22 @@
|
||||
*
|
||||
*/
|
||||
|
||||
#include <FastSerial.h>
|
||||
#include <AP_Common.h> // ArduPilot Mega Common Library
|
||||
#include <AP_Common.h>
|
||||
#include <AP_Param.h>
|
||||
#include <Arduino_Mega_ISR_Registry.h>
|
||||
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
||||
#include <AP_LeadFilter.h> // GPS Lead filter
|
||||
#include <AP_Math.h>
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL_AVR.h>
|
||||
|
||||
// set your hardware type here
|
||||
#define CONFIG_APM_HARDWARE APM_HARDWARE_APM2
|
||||
#include <AP_LeadFilter.h>
|
||||
|
||||
Arduino_Mega_ISR_Registry isr_registry;
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// Serial ports
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
//
|
||||
// Note that FastSerial port buffers are allocated at ::begin time,
|
||||
// so there is not much of a penalty to defining ports that we don't
|
||||
// use.
|
||||
//
|
||||
FastSerialPort0(Serial); // FTDI/console
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
||||
|
||||
AP_LeadFilter xLeadFilter; // GPS lag filter
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(115200);
|
||||
Serial.println("AP_LeadFilter test ver 1.0");
|
||||
|
||||
delay(500);
|
||||
hal.console->println("AP_LeadFilter test ver 1.0");
|
||||
hal.scheduler->delay(500);
|
||||
}
|
||||
|
||||
void loop()
|
||||
@ -48,12 +34,12 @@ void loop()
|
||||
velocity = 0;
|
||||
xLeadFilter.clear();
|
||||
|
||||
Serial.printf("------------------\n");
|
||||
Serial.printf("start position = 0, lag of 1sec.\n");
|
||||
hal.console->printf("------------------\n");
|
||||
hal.console->printf("start position = 0, lag of 1sec.\n");
|
||||
for( i = 0; i < 10; i++ ) {
|
||||
// get updated position
|
||||
new_position = xLeadFilter.get_position(position, velocity); // new position with velocity of 1 m/s
|
||||
Serial.printf("start pos: %ld, start vel: %d, end pos: %ld\n", (long int)position, (int)velocity, (long int)new_position);
|
||||
hal.console->printf("start pos: %ld, start vel: %d, end pos: %ld\n", (long int)position, (int)velocity, (long int)new_position);
|
||||
position = new_position;
|
||||
velocity += 100;
|
||||
}
|
||||
@ -62,19 +48,17 @@ void loop()
|
||||
velocity = 0;
|
||||
xLeadFilter.clear();
|
||||
|
||||
Serial.printf("------------------\n");
|
||||
Serial.printf("start position = 0, lag of 200ms\n");
|
||||
hal.console->printf("------------------\n");
|
||||
hal.console->printf("start position = 0, lag of 200ms\n");
|
||||
for( i = 0; i < 10; i++ ) {
|
||||
// get updated position
|
||||
new_position = xLeadFilter.get_position(position, velocity, 0.200); // new position with velocity of 1 m/s
|
||||
Serial.printf("start pos: %ld, start vel: %d, end pos: %ld\n", (long int)position, (int)velocity, (long int)new_position);
|
||||
hal.console->printf("start pos: %ld, start vel: %d, end pos: %ld\n", (long int)position, (int)velocity, (long int)new_position);
|
||||
position = new_position;
|
||||
velocity += 100;
|
||||
}
|
||||
|
||||
delay(10000);
|
||||
hal.scheduler->delay(10000);
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
AP_HAL_MAIN();
|
||||
|
Loading…
Reference in New Issue
Block a user