AP_RangeFinder - cut over to use new ModeFilter from Filter library
This commit is contained in:
parent
ae8fd43335
commit
00a1b5cd53
@ -35,7 +35,7 @@
|
|||||||
|
|
||||||
// Constructor //////////////////////////////////////////////////////////////
|
// 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),
|
RangeFinder(source, filter),
|
||||||
_scaler(AP_RANGEFINDER_MAXSONARXL_SCALER)
|
_scaler(AP_RANGEFINDER_MAXSONARXL_SCALER)
|
||||||
{
|
{
|
||||||
|
@ -24,7 +24,7 @@
|
|||||||
class AP_RangeFinder_MaxsonarXL : public RangeFinder
|
class AP_RangeFinder_MaxsonarXL : public RangeFinder
|
||||||
{
|
{
|
||||||
public:
|
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
|
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);
|
float calculate_scaler(int sonar_type, float adc_refence_voltage);
|
||||||
|
|
||||||
|
@ -35,7 +35,7 @@
|
|||||||
|
|
||||||
// Constructor //////////////////////////////////////////////////////////////
|
// 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)
|
RangeFinder(source, filter)
|
||||||
{
|
{
|
||||||
max_distance = AP_RANGEFINDER_SHARPEGP2Y_MAX_DISTANCE;
|
max_distance = AP_RANGEFINDER_SHARPEGP2Y_MAX_DISTANCE;
|
||||||
|
@ -9,7 +9,7 @@
|
|||||||
class AP_RangeFinder_SharpGP2Y : public RangeFinder
|
class AP_RangeFinder_SharpGP2Y : public RangeFinder
|
||||||
{
|
{
|
||||||
public:
|
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) {
|
int convert_raw_to_distance(int _raw_value) {
|
||||||
if( _raw_value == 0 )
|
if( _raw_value == 0 )
|
||||||
return max_distance;
|
return max_distance;
|
||||||
|
@ -43,7 +43,7 @@ int RangeFinder::read()
|
|||||||
// ensure distance is within min and max
|
// ensure distance is within min and max
|
||||||
temp_dist = constrain(temp_dist, min_distance, max_distance);
|
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;
|
return distance;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -4,7 +4,7 @@
|
|||||||
#include <stdlib.h>
|
#include <stdlib.h>
|
||||||
#include <inttypes.h>
|
#include <inttypes.h>
|
||||||
#include "../AP_AnalogSource/AP_AnalogSource.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
|
#define AP_RANGEFINDER_ORIENTATION_FRONT 0, 10, 0
|
||||||
@ -22,7 +22,7 @@
|
|||||||
class RangeFinder
|
class RangeFinder
|
||||||
{
|
{
|
||||||
protected:
|
protected:
|
||||||
RangeFinder(AP_AnalogSource * source, ModeFilter *filter) :
|
RangeFinder(AP_AnalogSource * source, FilterInt16 *filter) :
|
||||||
_analog_source(source),
|
_analog_source(source),
|
||||||
_mode_filter(filter) {}
|
_mode_filter(filter) {}
|
||||||
public:
|
public:
|
||||||
@ -38,6 +38,6 @@ class RangeFinder
|
|||||||
virtual int read(); // read value from sensor and return distance in cm
|
virtual int read(); // read value from sensor and return distance in cm
|
||||||
|
|
||||||
AP_AnalogSource *_analog_source;
|
AP_AnalogSource *_analog_source;
|
||||||
ModeFilter *_mode_filter;
|
FilterInt16 *_mode_filter;
|
||||||
};
|
};
|
||||||
#endif
|
#endif
|
||||||
|
@ -4,6 +4,9 @@
|
|||||||
*/
|
*/
|
||||||
|
|
||||||
// includes
|
// includes
|
||||||
|
#include <FastSerial.h>
|
||||||
|
#include <AP_Common.h>
|
||||||
|
#include <AP_Math.h>
|
||||||
#include <AP_RangeFinder.h> // Range finder library
|
#include <AP_RangeFinder.h> // Range finder library
|
||||||
#include <Arduino_Mega_ISR_Registry.h>
|
#include <Arduino_Mega_ISR_Registry.h>
|
||||||
#include <AP_PeriodicProcess.h>
|
#include <AP_PeriodicProcess.h>
|
||||||
@ -11,6 +14,11 @@
|
|||||||
#include <AP_AnalogSource.h>
|
#include <AP_AnalogSource.h>
|
||||||
#include <ModeFilter.h> // mode filter
|
#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
|
// 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
|
#define USE_ADC_ADS7844 // use APM1's built in ADC and connect sonar to pitot tube
|
||||||
|
|
||||||
@ -24,7 +32,7 @@
|
|||||||
|
|
||||||
// declare global instances
|
// declare global instances
|
||||||
Arduino_Mega_ISR_Registry isr_registry;
|
Arduino_Mega_ISR_Registry isr_registry;
|
||||||
ModeFilter mode_filter;
|
ModeFilterInt16 mode_filter(5,2);
|
||||||
#ifdef USE_ADC_ADS7844
|
#ifdef USE_ADC_ADS7844
|
||||||
AP_TimerProcess adc_scheduler;
|
AP_TimerProcess adc_scheduler;
|
||||||
AP_ADC_ADS7844 adc;
|
AP_ADC_ADS7844 adc;
|
||||||
|
Loading…
Reference in New Issue
Block a user