mirror of https://github.com/ArduPilot/ardupilot
Merge branch 'master' of https://code.google.com/p/ardupilot-mega
This commit is contained in:
commit
a9eb37d9f3
|
@ -78,7 +78,8 @@ http://code.google.com/p/ardupilot-mega/downloads/list
|
|||
#include <RC_Channel.h> // RC Channel Library
|
||||
#include <AP_RangeFinder.h> // Range finder library
|
||||
#include <AP_OpticalFlow.h> // Optical Flow library
|
||||
#include <ModeFilter.h>
|
||||
#include <Filter.h> // Filter library
|
||||
#include <ModeFilter.h> // Mode Filter from Filter library
|
||||
#include <AP_Relay.h> // APM relay
|
||||
#include <GCS_MAVLink.h> // MAVLink GCS definitions
|
||||
#include <memcheck.h>
|
||||
|
@ -268,7 +269,7 @@ GCS_MAVLINK gcs3;
|
|||
// SONAR selection
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
//
|
||||
ModeFilter sonar_mode_filter;
|
||||
ModeFilterInt16 sonar_mode_filter(5,2);
|
||||
#if CONFIG_SONAR == ENABLED
|
||||
#if CONFIG_SONAR_SOURCE == SONAR_SOURCE_ADC
|
||||
AP_AnalogSource_ADC sonar_analog_source( &adc, CONFIG_SONAR_SOURCE_ADC_CHANNEL, 0.25);
|
||||
|
|
|
@ -44,7 +44,8 @@ version 2.1 of the License, or (at your option) any later version.
|
|||
#include <PID.h> // PID library
|
||||
#include <RC_Channel.h> // RC Channel Library
|
||||
#include <AP_RangeFinder.h> // Range finder library
|
||||
#include <ModeFilter.h>
|
||||
#include <Filter.h> // Filter library
|
||||
#include <ModeFilter.h> // Mode Filter from Filter library
|
||||
#include <AP_Relay.h> // APM relay
|
||||
#include <AP_Mount.h> // Camera/Antenna mount
|
||||
#include <GCS_MAVLink.h> // MAVLink GCS definitions
|
||||
|
@ -224,7 +225,7 @@ GCS_MAVLINK gcs3;
|
|||
// PITOT selection
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
//
|
||||
ModeFilter sonar_mode_filter;
|
||||
ModeFilterInt16 sonar_mode_filter(5,2);
|
||||
|
||||
#if CONFIG_PITOT_SOURCE == PITOT_SOURCE_ADC
|
||||
AP_AnalogSource_ADC pitot_analog_source( &adc,
|
||||
|
|
|
@ -20,8 +20,9 @@
|
|||
#ifndef AP_Mount_H
|
||||
#define AP_Mount_H
|
||||
|
||||
//#include <AP_Common.h>
|
||||
#include <FastSerial.h>
|
||||
#include <AP_Math.h>
|
||||
#include <AP_Common.h>
|
||||
#include <AP_GPS.h>
|
||||
#include <AP_DCM.h>
|
||||
#include <GCS_MAVLink.h>
|
||||
|
|
|
@ -35,7 +35,7 @@
|
|||
|
||||
// Constructor //////////////////////////////////////////////////////////////
|
||||
|
||||
AP_RangeFinder_MaxsonarXL::AP_RangeFinder_MaxsonarXL(AP_AnalogSource *source, ModeFilter *filter):
|
||||
AP_RangeFinder_MaxsonarXL::AP_RangeFinder_MaxsonarXL(AP_AnalogSource *source, FilterInt16 *filter):
|
||||
RangeFinder(source, filter),
|
||||
_scaler(AP_RANGEFINDER_MAXSONARXL_SCALER)
|
||||
{
|
||||
|
|
|
@ -24,7 +24,7 @@
|
|||
class AP_RangeFinder_MaxsonarXL : public RangeFinder
|
||||
{
|
||||
public:
|
||||
AP_RangeFinder_MaxsonarXL(AP_AnalogSource *source, ModeFilter *filter);
|
||||
AP_RangeFinder_MaxsonarXL(AP_AnalogSource *source, FilterInt16 *filter);
|
||||
int convert_raw_to_distance(int _raw_value) { return _raw_value * _scaler; } // read value from analog port and return distance in cm
|
||||
float calculate_scaler(int sonar_type, float adc_refence_voltage);
|
||||
|
||||
|
|
|
@ -35,7 +35,7 @@
|
|||
|
||||
// Constructor //////////////////////////////////////////////////////////////
|
||||
|
||||
AP_RangeFinder_SharpGP2Y::AP_RangeFinder_SharpGP2Y(AP_AnalogSource *source, ModeFilter *filter) :
|
||||
AP_RangeFinder_SharpGP2Y::AP_RangeFinder_SharpGP2Y(AP_AnalogSource *source, FilterInt16 *filter) :
|
||||
RangeFinder(source, filter)
|
||||
{
|
||||
max_distance = AP_RANGEFINDER_SHARPEGP2Y_MAX_DISTANCE;
|
||||
|
|
|
@ -9,7 +9,7 @@
|
|||
class AP_RangeFinder_SharpGP2Y : public RangeFinder
|
||||
{
|
||||
public:
|
||||
AP_RangeFinder_SharpGP2Y(AP_AnalogSource *source, ModeFilter *filter);
|
||||
AP_RangeFinder_SharpGP2Y(AP_AnalogSource *source, FilterInt16 *filter);
|
||||
int convert_raw_to_distance(int _raw_value) {
|
||||
if( _raw_value == 0 )
|
||||
return max_distance;
|
||||
|
|
|
@ -43,7 +43,7 @@ int RangeFinder::read()
|
|||
// ensure distance is within min and max
|
||||
temp_dist = constrain(temp_dist, min_distance, max_distance);
|
||||
|
||||
distance = _mode_filter->get_filtered_with_sample(temp_dist);
|
||||
distance = _mode_filter->apply(temp_dist);
|
||||
return distance;
|
||||
}
|
||||
|
||||
|
|
|
@ -4,7 +4,7 @@
|
|||
#include <stdlib.h>
|
||||
#include <inttypes.h>
|
||||
#include "../AP_AnalogSource/AP_AnalogSource.h"
|
||||
#include "../ModeFilter/ModeFilter.h" // ArduPilot Mega RC Library
|
||||
#include "../Filter/Filter.h" // Filter library
|
||||
|
||||
/*
|
||||
#define AP_RANGEFINDER_ORIENTATION_FRONT 0, 10, 0
|
||||
|
@ -22,7 +22,7 @@
|
|||
class RangeFinder
|
||||
{
|
||||
protected:
|
||||
RangeFinder(AP_AnalogSource * source, ModeFilter *filter) :
|
||||
RangeFinder(AP_AnalogSource * source, FilterInt16 *filter) :
|
||||
_analog_source(source),
|
||||
_mode_filter(filter) {}
|
||||
public:
|
||||
|
@ -38,6 +38,6 @@ class RangeFinder
|
|||
virtual int read(); // read value from sensor and return distance in cm
|
||||
|
||||
AP_AnalogSource *_analog_source;
|
||||
ModeFilter *_mode_filter;
|
||||
FilterInt16 *_mode_filter;
|
||||
};
|
||||
#endif
|
||||
|
|
|
@ -4,6 +4,9 @@
|
|||
*/
|
||||
|
||||
// includes
|
||||
#include <FastSerial.h>
|
||||
#include <AP_Common.h>
|
||||
#include <AP_Math.h>
|
||||
#include <AP_RangeFinder.h> // Range finder library
|
||||
#include <Arduino_Mega_ISR_Registry.h>
|
||||
#include <AP_PeriodicProcess.h>
|
||||
|
@ -11,6 +14,11 @@
|
|||
#include <AP_AnalogSource.h>
|
||||
#include <ModeFilter.h> // mode filter
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// Serial ports
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
FastSerialPort0(Serial); // FTDI/console
|
||||
|
||||
// comment out line below if using APM2 or analog pin instead of APM1's built in ADC
|
||||
#define USE_ADC_ADS7844 // use APM1's built in ADC and connect sonar to pitot tube
|
||||
|
||||
|
@ -24,7 +32,7 @@
|
|||
|
||||
// declare global instances
|
||||
Arduino_Mega_ISR_Registry isr_registry;
|
||||
ModeFilter mode_filter;
|
||||
ModeFilterInt16 mode_filter(5,2);
|
||||
#ifdef USE_ADC_ADS7844
|
||||
AP_TimerProcess adc_scheduler;
|
||||
AP_ADC_ADS7844 adc;
|
||||
|
|
|
@ -0,0 +1,82 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
//
|
||||
// This 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.
|
||||
//
|
||||
|
||||
/// @file AverageFilter.h
|
||||
/// @brief A class to provide the average of a number of samples
|
||||
///
|
||||
/// DO NOT CREATE AND DESTROY INSTANCES OF THIS CLASS BECAUSE THE ALLOC/MALLOC WILL LEAD TO MEMORY FRAGMENTATION
|
||||
|
||||
#ifndef AverageFilter_h
|
||||
#define AverageFilter_h
|
||||
|
||||
#include <inttypes.h>
|
||||
#include <Filter.h>
|
||||
|
||||
// 1st parameter <T> is the type of data being filtered.
|
||||
// 2nd parameter <U> is a larger data type used during summation to prevent overflows
|
||||
template <class T, class U>
|
||||
class AverageFilter : public Filter<T>
|
||||
{
|
||||
public:
|
||||
AverageFilter(uint8_t requested_size) : Filter<T>(requested_size) {};
|
||||
|
||||
// apply - Add a new raw value to the filter, retrieve the filtered result
|
||||
virtual T apply(T sample);
|
||||
|
||||
// reset - clear the filter
|
||||
virtual void reset();
|
||||
|
||||
private:
|
||||
uint8_t _num_samples;
|
||||
};
|
||||
|
||||
// Typedef for convenience (1st argument is the data size, 2nd argument is a datasize that's bigger to handle overflows)
|
||||
typedef AverageFilter<int8_t, int16_t> AverageFilterInt8;
|
||||
typedef AverageFilter<uint8_t, uint16_t> AverageFilterUInt8;
|
||||
typedef AverageFilter<int16_t, int32_t> AverageFilterInt16;
|
||||
typedef AverageFilter<uint16_t, uint32_t> AverageFilterUInt16;
|
||||
typedef AverageFilter<int32_t, float> AverageFilterInt32;
|
||||
typedef AverageFilter<uint32_t, float> AverageFilterUInt32;
|
||||
|
||||
// Public Methods //////////////////////////////////////////////////////////////
|
||||
|
||||
template <class T, class U>
|
||||
T AverageFilter<T,U>::apply(T sample)
|
||||
{
|
||||
U result = 0;
|
||||
|
||||
// call parent's apply function to get the sample into the array
|
||||
Filter<T>::apply(sample);
|
||||
|
||||
// increment the number of samples so far
|
||||
_num_samples++;
|
||||
if( _num_samples > Filter<T>::filter_size || _num_samples == 0 )
|
||||
_num_samples = Filter<T>::filter_size;
|
||||
|
||||
// get sum of all values - there is a risk of overflow here that we ignore
|
||||
for(int8_t i=0; i<Filter<T>::filter_size; i++)
|
||||
result += Filter<T>::samples[i];
|
||||
|
||||
return (T)(result / _num_samples);
|
||||
}
|
||||
|
||||
// reset - clear all samples
|
||||
template <class T, class U>
|
||||
void AverageFilter<T,U>::reset()
|
||||
{
|
||||
// call parent's apply function to get the sample into the array
|
||||
Filter<T>::reset();
|
||||
|
||||
// clear our variable
|
||||
_num_samples = 0;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
|
||||
|
|
@ -0,0 +1,97 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
//
|
||||
// This 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.
|
||||
//
|
||||
|
||||
/// @file Filter.h
|
||||
/// @brief A base class for apply various filters to values
|
||||
///
|
||||
/// DO NOT CREATE AND DESTROY INSTANCES OF THIS CLASS BECAUSE THE ALLOC/MALLOC WILL LEAD TO MEMORY FRAGMENTATION
|
||||
|
||||
#ifndef Filter_h
|
||||
#define Filter_h
|
||||
|
||||
#include <inttypes.h>
|
||||
#include <AP_Common.h>
|
||||
|
||||
#define FILTER_MAX_SAMPLES 10 // maximum size of the sample buffer (normally older values will be overwritten as new appear)
|
||||
|
||||
template <class T>
|
||||
class Filter
|
||||
{
|
||||
public:
|
||||
Filter(uint8_t requested_size);
|
||||
~Filter();
|
||||
|
||||
// apply - Add a new raw value to the filter, retrieve the filtered result
|
||||
virtual T apply(T sample);
|
||||
|
||||
// reset - clear the filter
|
||||
virtual void reset();
|
||||
|
||||
uint8_t filter_size; // max number of items in filter
|
||||
T* samples; // buffer of samples
|
||||
uint8_t sample_index; // pointer to the next empty slot in the buffer
|
||||
|
||||
private:
|
||||
};
|
||||
|
||||
// Typedef for convenience
|
||||
typedef Filter<int16_t> FilterInt16;
|
||||
|
||||
// Constructor
|
||||
template <class T>
|
||||
Filter<T>::Filter(uint8_t requested_size) :
|
||||
filter_size(requested_size), sample_index(0)
|
||||
{
|
||||
// check filter size
|
||||
if( Filter<T>::filter_size > FILTER_MAX_SAMPLES )
|
||||
Filter<T>::filter_size = FILTER_MAX_SAMPLES;
|
||||
|
||||
// create array
|
||||
samples = (T *)malloc(Filter<T>::filter_size * sizeof(T));
|
||||
|
||||
// clear array
|
||||
reset();
|
||||
}
|
||||
|
||||
// Destructor - THIS SHOULD NEVER BE CALLED OR IT COULD LEAD TO MEMORY FRAGMENTATION
|
||||
template <class T>
|
||||
Filter<T>::~Filter()
|
||||
{
|
||||
// free up the samples array
|
||||
free(samples);
|
||||
}
|
||||
|
||||
// reset - clear all samples
|
||||
template <class T>
|
||||
void Filter<T>::reset()
|
||||
{
|
||||
for( int8_t i=0; i<filter_size; i++ ) {
|
||||
samples[i] = 0;
|
||||
}
|
||||
sample_index = 0;
|
||||
}
|
||||
|
||||
// apply - take in a new raw sample, and return the filtered results
|
||||
template <class T>
|
||||
T Filter<T>::apply(T sample){
|
||||
|
||||
// add sample to array
|
||||
samples[sample_index++] = sample;
|
||||
|
||||
// wrap index if necessary
|
||||
if( sample_index >= filter_size )
|
||||
sample_index = 0;
|
||||
|
||||
// base class doesn't know what filtering to do so we just return the raw sample
|
||||
return sample;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
|
||||
|
|
@ -0,0 +1,123 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
//
|
||||
// This 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.
|
||||
//
|
||||
|
||||
/// @file ModeFilter.h
|
||||
/// @brief A class to apply a mode filter which is basically picking the median value from the last x samples
|
||||
/// the filter size (i.e buffer size) should always be an odd number
|
||||
///
|
||||
/// DO NOT CREATE AND DESTROY INSTANCES OF THIS CLASS BECAUSE THE ALLOC/MALLOC WILL LEAD TO MEMORY FRAGMENTATION
|
||||
|
||||
#ifndef ModeFilter_h
|
||||
#define ModeFilter_h
|
||||
|
||||
#include <inttypes.h>
|
||||
#include <Filter.h>
|
||||
|
||||
template <class T>
|
||||
class ModeFilter : public Filter<T>
|
||||
{
|
||||
public:
|
||||
ModeFilter(uint8_t requested_size, uint8_t return_element);
|
||||
|
||||
// apply - Add a new raw value to the filter, retrieve the filtered result
|
||||
virtual T apply(T sample);
|
||||
|
||||
private:
|
||||
// private methods
|
||||
uint8_t _return_element;
|
||||
void isort(T sample, bool drop_high_sample);
|
||||
bool drop_high_sample; // switch to determine whether to drop the highest or lowest sample when new value arrives
|
||||
};
|
||||
|
||||
// Typedef for convenience
|
||||
typedef ModeFilter<int16_t> ModeFilterInt16;
|
||||
|
||||
// Constructor //////////////////////////////////////////////////////////////
|
||||
|
||||
template <class T>
|
||||
ModeFilter<T>::ModeFilter(uint8_t requested_size, uint8_t return_element) :
|
||||
Filter<T>(requested_size),
|
||||
_return_element(return_element),
|
||||
drop_high_sample(true)
|
||||
{
|
||||
// ensure we have a valid return_nth_element value. if not, revert to median
|
||||
if( _return_element >= Filter<T>::filter_size )
|
||||
_return_element = Filter<T>::filter_size / 2;
|
||||
};
|
||||
|
||||
// Public Methods //////////////////////////////////////////////////////////////
|
||||
|
||||
template <class T>
|
||||
T ModeFilter<T>::apply(T sample)
|
||||
{
|
||||
// insert the new items into the samples buffer
|
||||
isort(sample, drop_high_sample);
|
||||
|
||||
// next time drop from the other end of the sample buffer
|
||||
drop_high_sample = !drop_high_sample;
|
||||
|
||||
// return results
|
||||
if( Filter<T>::sample_index < Filter<T>::filter_size ) {
|
||||
// middle sample if buffer is not yet full
|
||||
return Filter<T>::samples[(Filter<T>::sample_index / 2)];
|
||||
}else{
|
||||
// return element specified by user in constructor
|
||||
return Filter<T>::samples[_return_element];
|
||||
}
|
||||
}
|
||||
|
||||
//
|
||||
// insertion sort - takes a new sample and pushes it into the sample array
|
||||
// drops either the highest or lowest sample depending on the 'drop_high_sample' parameter
|
||||
//
|
||||
template <class T>
|
||||
void ModeFilter<T>::isort(T new_sample, bool drop_high)
|
||||
{
|
||||
int8_t i;
|
||||
|
||||
// if the buffer isn't full simply increase the #items in the buffer (i.e. sample_index)
|
||||
// the rest is the same as dropping the high sample
|
||||
if( Filter<T>::sample_index < Filter<T>::filter_size ) {
|
||||
Filter<T>::sample_index++;
|
||||
drop_high = true;
|
||||
}
|
||||
|
||||
if( drop_high ) { // drop highest sample from the buffer to make room for our new sample
|
||||
|
||||
// start from top. Note: sample_index always points to the next open space so we start from sample_index-1
|
||||
i = Filter<T>::sample_index-1;
|
||||
|
||||
// if the next element is higher than our new sample, push it up one position
|
||||
while( Filter<T>::samples[i-1] > new_sample && i > 0 ) {
|
||||
Filter<T>::samples[i] = Filter<T>::samples[i-1];
|
||||
i--;
|
||||
}
|
||||
|
||||
// add our new sample to the buffer
|
||||
Filter<T>::samples[i] = new_sample;
|
||||
|
||||
}else{ // drop lowest sample from the buffer to make room for our new sample
|
||||
|
||||
// start from the bottom
|
||||
i = 0;
|
||||
|
||||
// if the element is lower than our new sample, push it down one position
|
||||
while( Filter<T>::samples[i+1] < new_sample && i < Filter<T>::sample_index-1 ) {
|
||||
Filter<T>::samples[i] = Filter<T>::samples[i+1];
|
||||
i++;
|
||||
}
|
||||
|
||||
// add our new sample to the buffer
|
||||
Filter<T>::samples[i] = new_sample;
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
|
||||
|
|
@ -0,0 +1,54 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
//
|
||||
// This 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.
|
||||
//
|
||||
|
||||
/// @file SumFilter.h
|
||||
/// @brief A class to apply an average filter (but we save some calc time by not averaging the values but instead save one division by just adding the values up
|
||||
///
|
||||
/// DO NOT CREATE AND DESTROY INSTANCES OF THIS CLASS BECAUSE THE ALLOC/MALLOC WILL LEAD TO MEMORY FRAGMENTATION
|
||||
|
||||
#ifndef SumFilter_h
|
||||
#define SumFilter_h
|
||||
|
||||
#include <inttypes.h>
|
||||
#include <Filter.h>
|
||||
|
||||
template <class T>
|
||||
class SumFilter : public Filter<T>
|
||||
{
|
||||
public:
|
||||
SumFilter(uint8_t requested_size) : Filter<T>(requested_size) {};
|
||||
|
||||
// apply - Add a new raw value to the filter, retrieve the filtered result
|
||||
virtual T apply(T sample);
|
||||
|
||||
private:
|
||||
};
|
||||
|
||||
// Typedef for convenience
|
||||
typedef SumFilter<int16_t> SumFilterInt16;
|
||||
|
||||
// Public Methods //////////////////////////////////////////////////////////////
|
||||
template <class T>
|
||||
T SumFilter<T>::apply(T sample){
|
||||
|
||||
T result = 0;
|
||||
|
||||
// call parent's apply function to get the sample into the array
|
||||
Filter<T>::apply(sample);
|
||||
|
||||
// get sum of all values - there is a risk of overflow here that we ignore
|
||||
for(int8_t i=0; i<Filter<T>::filter_size; i++)
|
||||
result += Filter<T>::samples[i];
|
||||
|
||||
return result;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
|
||||
|
|
@ -0,0 +1,77 @@
|
|||
/*
|
||||
Example of Filter library.
|
||||
Code by Randy Mackay and Jason Short. DIYDrones.com
|
||||
*/
|
||||
|
||||
#include <FastSerial.h>
|
||||
#include <AP_Common.h>
|
||||
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
||||
#include <Filter.h> // Filter library
|
||||
#include <ModeFilter.h> // ModeFilter library (inherits from Filter class)
|
||||
#include <SumFilter.h>
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// Serial ports
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
FastSerialPort0(Serial); // FTDI/console
|
||||
|
||||
//typedef ModeFilter<int16_t> IntModeFilter;
|
||||
//typedef SumFilter<int16_t> IntSumFilter;
|
||||
|
||||
int16_t rangevalue[] = {31000, 31000, 50, 55, 60, 55, 10, 0, 31000};
|
||||
|
||||
// create a global instance of the class instead of local to avoid memory fragmentation
|
||||
ModeFilterInt16 mfilter(5,2); // buffer of 5 values, result will be from buffer element 2 (ie. the 3rd element which is the middle)
|
||||
//SumFilterInt16 mfilter(5);
|
||||
|
||||
//Function to print contents of a filter
|
||||
void printFilter(Filter<int16_t>& filter)
|
||||
{
|
||||
for(int8_t i=0; i < filter.filter_size; i++)
|
||||
{
|
||||
Serial.printf("%d ",(int)filter.samples[i]);
|
||||
}
|
||||
Serial.println();
|
||||
}
|
||||
|
||||
void setup()
|
||||
{
|
||||
// Open up a serial connection
|
||||
Serial.begin(115200);
|
||||
|
||||
// introduction
|
||||
Serial.printf("ArduPilot ModeFilter library test ver 1.0\n\n");
|
||||
|
||||
// Wait for the serial connection
|
||||
delay(500);
|
||||
}
|
||||
|
||||
//Main loop where the action takes place
|
||||
void loop()
|
||||
{
|
||||
int8_t i = 0;
|
||||
int16_t filtered_value;
|
||||
|
||||
while( i < 9 ) {
|
||||
|
||||
// output to user
|
||||
Serial.printf("applying: %d\n",(int)rangevalue[i]);
|
||||
|
||||
// display original
|
||||
Serial.printf("before: ");
|
||||
printFilter(mfilter);
|
||||
|
||||
// apply new value and retrieved filtered result
|
||||
filtered_value = mfilter.apply(rangevalue[i]);
|
||||
|
||||
// display results
|
||||
Serial.printf("after: ");
|
||||
printFilter(mfilter);
|
||||
Serial.printf("The filtered value is: %d\n\n",(int)filtered_value);
|
||||
|
||||
i++;
|
||||
}
|
||||
delay(100000);
|
||||
}
|
||||
|
||||
|
|
@ -1,2 +1 @@
|
|||
BOARD = mega
|
||||
include ../../../AP_Common/Arduino.mk
|
|
@ -0,0 +1,8 @@
|
|||
Filter KEYWORD1
|
||||
ModeFilter KEYWORD1
|
||||
SumFilter KEYWORD1
|
||||
apply KEYWORD2
|
||||
reset KEYWORD2
|
||||
max_samples KEYWORD2
|
||||
samples KEYWORD2
|
||||
sample_index KEYWORD2
|
|
@ -1,87 +0,0 @@
|
|||
/*
|
||||
ModeFilter.cpp - Mode Filter Library for Ardupilot Mega. Arduino
|
||||
Code by Jason Short. DIYDrones.com
|
||||
Adapted from code by Jason Lessels(June 6, 2011), Bill Gentles (Nov. 12, 2010)
|
||||
|
||||
|
||||
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.
|
||||
|
||||
|
||||
*/
|
||||
#include "ModeFilter.h"
|
||||
|
||||
#include <avr/interrupt.h>
|
||||
#if defined(ARDUINO) && ARDUINO >= 100
|
||||
#include "Arduino.h"
|
||||
#else
|
||||
#include "WProgram.h"
|
||||
#endif
|
||||
|
||||
|
||||
// Constructors ////////////////////////////////////////////////////////////////
|
||||
|
||||
ModeFilter::ModeFilter() :
|
||||
_sample_index(0)
|
||||
{
|
||||
}
|
||||
|
||||
// Public Methods //////////////////////////////////////////////////////////////
|
||||
//Sorting function
|
||||
// sort function (Author: Bill Gentles, Nov. 12, 2010)
|
||||
// *a is an array pointer function
|
||||
|
||||
int ModeFilter::get_filtered_with_sample(int _sample){
|
||||
_samples[_sample_index] = _sample;
|
||||
|
||||
_sample_index++;
|
||||
|
||||
if (_sample_index >= MOD_FILTER_SIZE)
|
||||
_sample_index = 0;
|
||||
|
||||
isort();
|
||||
|
||||
return mode();
|
||||
}
|
||||
|
||||
|
||||
void ModeFilter::isort()
|
||||
{
|
||||
for (int i = 1; i < MOD_FILTER_SIZE; ++i) {
|
||||
int j = _samples[i];
|
||||
int k;
|
||||
for (k = i - 1; (k >= 0) && (j < _samples[k]); k--){
|
||||
_samples[k + 1] = _samples[k];
|
||||
}
|
||||
_samples[k + 1] = j;
|
||||
}
|
||||
}
|
||||
|
||||
//Mode function, returning the mode or median.
|
||||
int16_t ModeFilter::mode(){
|
||||
int fmode = 0;
|
||||
byte i = 0;
|
||||
byte count = 0;
|
||||
byte maxCount = 0;
|
||||
byte bimodal = 0;
|
||||
|
||||
while(count > maxCount){
|
||||
fmode = _samples[i];
|
||||
maxCount = count;
|
||||
bimodal = 0;
|
||||
}
|
||||
|
||||
if(count == 0) i++;
|
||||
|
||||
if(count == maxCount){ //If the dataset has 2 or more modes.
|
||||
bimodal = 1;
|
||||
}
|
||||
|
||||
if(fmode == 0 || bimodal == 1){ //Return the median if there is no mode.
|
||||
fmode = _samples[(MOD_FILTER_SIZE / 2)];
|
||||
}
|
||||
|
||||
return fmode;
|
||||
}
|
|
@ -1,26 +0,0 @@
|
|||
#ifndef ModeFilter_h
|
||||
#define ModeFilter_h
|
||||
|
||||
#define MOD_FILTER_SIZE 6
|
||||
|
||||
#include <inttypes.h>
|
||||
|
||||
class ModeFilter
|
||||
{
|
||||
private:
|
||||
public:
|
||||
ModeFilter();
|
||||
|
||||
int get_filtered_with_sample(int _sample);
|
||||
int16_t _samples[MOD_FILTER_SIZE];
|
||||
|
||||
private:
|
||||
void isort();
|
||||
int16_t mode();
|
||||
int8_t _sample_index;
|
||||
};
|
||||
|
||||
#endif
|
||||
|
||||
|
||||
|
|
@ -1,51 +0,0 @@
|
|||
/*
|
||||
Example of APM_RC library.
|
||||
Code by Jordi MuÒoz and Jose Julio. DIYDrones.com
|
||||
|
||||
Print Input values and send Output to the servos
|
||||
(Works with last PPM_encoder firmware)
|
||||
*/
|
||||
|
||||
#include <ModeFilter.h> // ArduPilot Mega RC Library
|
||||
|
||||
int rangevalue[] = {31000, 31000, 50, 55, 60, 55, 10, 0, 31000};
|
||||
|
||||
ModeFilter mfilter;
|
||||
byte i = 0;
|
||||
|
||||
void setup()
|
||||
{
|
||||
//Open up a serial connection
|
||||
Serial.begin(115200);
|
||||
//Wait for the serial connection
|
||||
delay(500);
|
||||
}
|
||||
|
||||
//Main loop where the action takes place
|
||||
void loop()
|
||||
{
|
||||
while(i < 9){
|
||||
printArray(mfilter._samples, 6);
|
||||
int modE = mfilter.get_filtered_with_sample(rangevalue[i]);
|
||||
i++;
|
||||
|
||||
Serial.print("The mode/median is: ");
|
||||
Serial.print(modE);
|
||||
Serial.println();
|
||||
}
|
||||
delay(100000);
|
||||
}
|
||||
|
||||
/*-----------Functions------------*/
|
||||
//Function to print the arrays.
|
||||
void printArray(int *a, int n)
|
||||
{
|
||||
for (int i = 0; i < n; i++)
|
||||
{
|
||||
Serial.print(a[i], DEC);
|
||||
Serial.print(' ');
|
||||
}
|
||||
|
||||
Serial.println();
|
||||
}
|
||||
|
|
@ -1,8 +0,0 @@
|
|||
APM_RC KEYWORD1
|
||||
begin KEYWORD2
|
||||
InputCh KEYWORD2
|
||||
OutputCh KEYWORD2
|
||||
GetState KEYWORD2
|
||||
Force_Out0_Out1 KEYWORD2
|
||||
Force_Out2_Out3 KEYWORD2
|
||||
Force_Out6_Out7 KEYWORD2
|
Loading…
Reference in New Issue