mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
RangeFinder - small bug fix to initialise prescale variable.
Fixed up example sketch so it compiles and works again!
This commit is contained in:
parent
55af9dbe61
commit
1f53c25577
@ -9,7 +9,7 @@ class AP_AnalogSource_ADC : public AP_AnalogSource
|
||||
{
|
||||
public:
|
||||
AP_AnalogSource_ADC( AP_ADC * adc, int ch, float prescale = 1.0 ) :
|
||||
_adc(adc), _ch(ch) {}
|
||||
_adc(adc), _ch(ch), _prescale(prescale) {}
|
||||
int read(void);
|
||||
|
||||
private:
|
||||
|
@ -8,8 +8,6 @@
|
||||
|
||||
class AP_RangeFinder_MaxsonarXL : public RangeFinder
|
||||
{
|
||||
// public:
|
||||
//AP_GPS_MTK(Stream *s);
|
||||
public:
|
||||
AP_RangeFinder_MaxsonarXL(AP_AnalogSource *source, ModeFilter *filter);
|
||||
|
||||
|
@ -18,9 +18,9 @@
|
||||
#define AP_RANGEFINDER_ORIENTATION_BACK_LEFT 5, -5, 0
|
||||
#define AP_RANGEFINDER_ORIENTATION_FRONT_LEFT 5, 5, 0
|
||||
*/
|
||||
//#define AP_RANGEFINDER_PITOT_TUBE 1007
|
||||
|
||||
//#define AP_RANGEFINDER_NUM_AVERAGES 4
|
||||
// define Pitot tube's ADC Channel
|
||||
#define AP_RANGEFINDER_PITOT_TYPE_ADC_CHANNEL 7
|
||||
|
||||
class RangeFinder
|
||||
{
|
||||
|
Loading…
Reference in New Issue
Block a user