AP_RangeFinder - removed LV version because we use XL which covers both types of sonars

git-svn-id: https://arducopter.googlecode.com/svn/trunk@3237 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
rmackay9@yahoo.com 2011-09-04 06:55:58 +00:00
parent 88c2f56617
commit ada9c36e0c
9 changed files with 9 additions and 94 deletions

View File

@ -5,4 +5,3 @@
#include "AP_RangeFinder_SharpGP2Y.h"
#include "AP_RangeFinder_MaxsonarXL.h"
#include "AP_RangeFinder_MaxsonarLV.h"

View File

@ -1,49 +0,0 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 3; indent-tabs-mode: t -*-
/*
AP_RangeFinder_MaxsonarLV.cpp - Arduino Library for Maxbotix's LV-MaxSonar
Sonic proximity sensor
Code by Jose Julio and Randy Mackay. 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.
Sparkfun URL: http://www.sparkfun.com/products/8502
datasheet: http://www.maxbotix.com/uploads/LV-MaxSonar-EZ0-Datasheet.pdf
Sensor should be connected to one of the analog ports
Variables:
int raw_value : raw value from the sensor
int distance : distance in cm
int max_distance : maximum measurable distance (in cm)
int min_distance : minimum measurable distance (in cm)
Methods:
init(int analogPort) : Initialization of sensor
read() : read value from analog port and returns the distance (in cm)
*/
// AVR LibC Includes
#include "WConstants.h"
#include "AP_RangeFinder_MaxsonarLV.h"
// Constructor //////////////////////////////////////////////////////////////
/*AP_RangeFinder_MaxsonarLV::AP_RangeFinder_MaxsonarLV()
{
max_distance = AP_RANGEFINDER_MAXSONARLV_MAX_DISTANCE;
min_distance = AP_RANGEFINDER_MAXSONARLV_MIN_DISTANCE;
}
*/
AP_RangeFinder_MaxsonarLV::AP_RangeFinder_MaxsonarLV(AP_ADC *adc, ModeFilter *filter) :
RangeFinder(adc, filter)
{
max_distance = AP_RANGEFINDER_MAXSONARLV_MAX_DISTANCE;
min_distance = AP_RANGEFINDER_MAXSONARLV_MIN_DISTANCE;
}
// Public Methods //////////////////////////////////////////////////////////////

View File

@ -1,17 +0,0 @@
#ifndef AP_RangeFinder_MaxsonarLV_H
#define AP_RangeFinder_MaxsonarLV_H
#include "RangeFinder.h"
#define AP_RANGEFINDER_MAXSONARLV_MIN_DISTANCE 15
#define AP_RANGEFINDER_MAXSONARLV_MAX_DISTANCE 645
class AP_RangeFinder_MaxsonarLV : public RangeFinder
{
public:
//AP_RangeFinder_MaxsonarLV();
AP_RangeFinder_MaxsonarLV(AP_ADC *adc, ModeFilter *filter);
int convert_raw_to_distance(int _raw_value) { return _raw_value * 2.54; } // read value from analog port and return distance in cm
};
#endif

View File

@ -21,7 +21,6 @@
int min_distance : minimum measurable distance (in cm)
Methods:
init(int analogPort) : Initialization of sensor
read() : read value from analog port and returns the distance (in cm)
*/
@ -31,9 +30,6 @@
#include "AP_RangeFinder_MaxsonarXL.h"
// Constructor //////////////////////////////////////////////////////////////
//AP_GPS_MTK16::AP_GPS_MTK16(Stream *s) : GPS(s)
//{
//}
AP_RangeFinder_MaxsonarXL::AP_RangeFinder_MaxsonarXL(AP_ADC *adc, ModeFilter *filter) :
RangeFinder(adc, filter)

View File

@ -21,7 +21,6 @@
int min_distance : minimum measurable distance (in cm)
Methods:
init(int analogPort) : Initialization of sensor
read() : read value from analog port
*/
@ -31,13 +30,7 @@
#include "AP_RangeFinder_SharpGP2Y.h"
// Constructor //////////////////////////////////////////////////////////////
/*
AP_RangeFinder_SharpGP2Y::AP_RangeFinder_SharpGP2Y()
{
max_distance = AP_RANGEFINDER_SHARPEGP2Y_MAX_DISTANCE;
min_distance = AP_RANGEFINDER_SHARPEGP2Y_MIN_DISTANCE;
}
*/
AP_RangeFinder_SharpGP2Y::AP_RangeFinder_SharpGP2Y(AP_ADC *adc, ModeFilter *filter) :
RangeFinder(adc, filter)
{

View File

@ -10,7 +10,6 @@ class AP_RangeFinder_SharpGP2Y : public RangeFinder
{
public:
AP_RangeFinder_SharpGP2Y(AP_ADC *adc, ModeFilter *filter);
//AP_RangeFinder_SharpGP2Y();
int convert_raw_to_distance(int _raw_value) { if( _raw_value == 0 ) return max_distance; else return 14500/_raw_value; } // read value from analog port and return distance in cm
};

View File

@ -34,10 +34,6 @@ class RangeFinder
{}
public:
//int _history[AP_RANGEFINDER_NUM_AVERAGES]; // history of recent distances used for filtering
//int _num_averages; // filter will return average of this many historic values (must be < AP_RANGEFINDER_NUM_AVERAGES)
//int _history_ptr; // pointer to the most recent entry in the history table
int raw_value; // raw value from the sensor
int distance; // distance in cm
int max_distance; // maximum measurable distance (in cm) - should be set in child's constructor
@ -46,7 +42,6 @@ class RangeFinder
virtual void set_analog_port(int analogPort);
virtual void set_orientation(int x, int y, int z);
//virtual void set_filter(int num_averages) { _num_averages = num_averages; } // allows control of amount of filtering done
virtual int convert_raw_to_distance(int _raw_value) { return _raw_value; } // function that each child class should override to convert voltage to distance
virtual int read(); // read value from sensor and return distance in cm

View File

@ -5,24 +5,24 @@
#include <AP_RangeFinder.h> // Range finder library
#include <AP_ADC.h> // ArduPilot Mega Analog to Digital Converter Library
#include <ModeFilter.h> // mode filter
#define RF_PIN AP_RANGEFINDER_PITOT_TUBE // the pitot tube on the front of the oilpan
//#define RF_PIN A5 // A5 is the far back-right pin on the oilpan (near the CLI switch)
// declare global instances for reading pitot tube
AP_ADC_ADS7844 adc;
ModeFilter mode_filter;
// create the range finder object
//AP_RangeFinder_SharpGP2Y aRF;
AP_RangeFinder_MaxsonarXL aRF;
//AP_RangeFinder_MaxsonarLV aRF;
//AP_RangeFinder_SharpGP2Y aRF(&adc, &mode_filter);
AP_RangeFinder_MaxsonarXL aRF(&adc, &mode_filter);
void setup()
{
Serial.begin(38400);
Serial.begin(115200);
Serial.println("Range Finder Test v1.0");
adc.Init(); // APM ADC library initialization
aRF.init(RF_PIN, &adc);
}
void loop()

View File

@ -2,11 +2,10 @@ RangeFinder KEYWORD1
AP_RangeFinder KEYWORD1
AP_RangeFinder_SharpGP2Y KEYWORD1
AP_RangeFinder_MaxsonarXL KEYWORD1
AP_RangeFinder_MaxsonarLV KEYWORD1
init KEYWORD2
read KEYWORD2
filter KEYWORD2
set_analog_port KEYWORD2
set_orientation KEYWORD2
convert_raw_to_distance KEYWORD2
raw_value KEYWORD2
distance KEYWORD2
max_distance KEYWORD2