mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
AP_RangeFinder - added support for MaxsonarLV and corrected some descriptions and links for the other rangefinders
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1234 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
dccfe83567
commit
9eb889d30d
@ -5,3 +5,4 @@
|
|||||||
|
|
||||||
#include "AP_RangeFinder_SharpGP2Y.h"
|
#include "AP_RangeFinder_SharpGP2Y.h"
|
||||||
#include "AP_RangeFinder_MaxsonarXL.h"
|
#include "AP_RangeFinder_MaxsonarXL.h"
|
||||||
|
#include "AP_RangeFinder_MaxsonarLV.h"
|
||||||
|
67
libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarLV.cpp
Normal file
67
libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarLV.cpp
Normal file
@ -0,0 +1,67 @@
|
|||||||
|
// -*- 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"
|
||||||
|
|
||||||
|
// Public Methods //////////////////////////////////////////////////////////////
|
||||||
|
void AP_RangeFinder_MaxsonarLV::init(int analogPort)
|
||||||
|
{
|
||||||
|
// local variables
|
||||||
|
int i;
|
||||||
|
|
||||||
|
// set the given analog port to an input
|
||||||
|
pinMode(analogPort, INPUT);
|
||||||
|
|
||||||
|
// initialise everything
|
||||||
|
_analogPort = analogPort;
|
||||||
|
max_distance = AP_RANGEFINDER_MAXSONARLV_MAX_DISTANCE;
|
||||||
|
min_distance = AP_RANGEFINDER_MAXSONARLV_MIN_DISTANCE;
|
||||||
|
|
||||||
|
// make first call to read to get initial distance
|
||||||
|
read();
|
||||||
|
|
||||||
|
// initialise history
|
||||||
|
for( i=0; i<AP_RANGEFINDER_NUM_AVERAGES; i++ )
|
||||||
|
_history[i] = distance;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Read Sensor data
|
||||||
|
int AP_RangeFinder_MaxsonarLV::read()
|
||||||
|
{
|
||||||
|
// read raw sensor value and convert to distance
|
||||||
|
raw_value = analogRead(_analogPort);
|
||||||
|
|
||||||
|
// for this sensor, the sensor value is in inches, need to convert to cm
|
||||||
|
distance = raw_value * 2.54;
|
||||||
|
distance = constrain(distance,min_distance,max_distance); // converts from inches to cm
|
||||||
|
|
||||||
|
// return distance
|
||||||
|
return filter(distance);
|
||||||
|
}
|
15
libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarLV.h
Normal file
15
libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarLV.h
Normal file
@ -0,0 +1,15 @@
|
|||||||
|
#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:
|
||||||
|
void init(int analogPort);
|
||||||
|
int read(); // read value from analog port and return distance in cm
|
||||||
|
};
|
||||||
|
#endif
|
@ -9,14 +9,14 @@
|
|||||||
License as published by the Free Software Foundation; either
|
License as published by the Free Software Foundation; either
|
||||||
version 2.1 of the License, or (at your option) any later version.
|
version 2.1 of the License, or (at your option) any later version.
|
||||||
|
|
||||||
Sparkfun URL: http://www.sparkfun.com/products/9495
|
Sparkfun URL: http://www.sparkfun.com/products/9491
|
||||||
datasheet: http://www.sparkfun.com/datasheets/Sensors/Proximity/XL-EZ4-Datasheet.pdf
|
datasheet: http://www.sparkfun.com/datasheets/Sensors/Proximity/XL-EZ0-Datasheet.pdf
|
||||||
|
|
||||||
Sensor should be connected to one of the analog ports
|
Sensor should be connected to one of the analog ports
|
||||||
|
|
||||||
Variables:
|
Variables:
|
||||||
int raw_value : raw value from the sensor
|
int raw_value : raw value from the sensor
|
||||||
int distance : distance in meters
|
int distance : distance in cm
|
||||||
int max_distance : maximum measurable distance (in cm)
|
int max_distance : maximum measurable distance (in cm)
|
||||||
int min_distance : minimum measurable distance (in cm)
|
int min_distance : minimum measurable distance (in cm)
|
||||||
|
|
||||||
|
@ -16,7 +16,7 @@
|
|||||||
|
|
||||||
Variables:
|
Variables:
|
||||||
int raw_value : raw value from the sensor
|
int raw_value : raw value from the sensor
|
||||||
int distance : distance in meters
|
int distance : distance in cm
|
||||||
int max_distance : maximum measurable distance (in cm)
|
int max_distance : maximum measurable distance (in cm)
|
||||||
int min_distance : minimum measurable distance (in cm)
|
int min_distance : minimum measurable distance (in cm)
|
||||||
|
|
||||||
|
@ -8,8 +8,9 @@
|
|||||||
#define RF_PIN A5 // the far back-right pin on the oilpan (near the CLI switch)
|
#define RF_PIN A5 // the far back-right pin on the oilpan (near the CLI switch)
|
||||||
|
|
||||||
// create the range finder object
|
// create the range finder object
|
||||||
AP_RangeFinder_SharpGP2Y aRF;
|
//AP_RangeFinder_SharpGP2Y aRF;
|
||||||
//AP_RangeFinder_MaxsonarXL aRF;
|
//AP_RangeFinder_MaxsonarXL aRF;
|
||||||
|
AP_RangeFinder_MaxsonarLV aRF;
|
||||||
|
|
||||||
void setup()
|
void setup()
|
||||||
{
|
{
|
||||||
|
@ -2,6 +2,7 @@ RangeFinder KEYWORD1
|
|||||||
AP_RangeFinder KEYWORD1
|
AP_RangeFinder KEYWORD1
|
||||||
AP_RangeFinder_SharpGP2Y KEYWORD1
|
AP_RangeFinder_SharpGP2Y KEYWORD1
|
||||||
AP_RangeFinder_MaxsonarXL KEYWORD1
|
AP_RangeFinder_MaxsonarXL KEYWORD1
|
||||||
|
AP_RangeFinder_MaxsonarLV KEYWORD1
|
||||||
init KEYWORD2
|
init KEYWORD2
|
||||||
read KEYWORD2
|
read KEYWORD2
|
||||||
filter KEYWORD2
|
filter KEYWORD2
|
||||||
|
Loading…
Reference in New Issue
Block a user