ardupilot/libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.h

18 lines
563 B
C++

#ifndef AP_RangeFinder_SharpGP2Y_H
#define AP_RangeFinder_SharpGP2Y_H
#include "RangeFinder.h"
#define AP_RANGEFINDER_SHARPEGP2Y_MIN_DISTANCE 20
#define AP_RANGEFINDER_SHARPEGP2Y_MAX_DISTANCE 150
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
};
#endif