ardupilot/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarLV.h
james.goppert 7809b0ca2a Massive warning fixes.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@2089 f9c3cf11-9bcb-44bc-f272-b75c42450872
2011-05-04 19:12:27 +00:00

16 lines
459 B
C++

#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();
int convert_raw_to_distance(int _raw_value) { return _raw_value * 2.54; } // read value from analog port and return distance in cm
};
#endif