mirror of https://github.com/ArduPilot/ardupilot
AP Rangefinder had some bad characters in it. Converted and cleaned the text files.
This commit is contained in:
parent
9cbfcac802
commit
d7d04f67e4
|
@ -31,9 +31,9 @@
|
|||
|
||||
// Constructor //////////////////////////////////////////////////////////////
|
||||
|
||||
AP_RangeFinder_MaxsonarXL::AP_RangeFinder_MaxsonarXL(AP_AnalogSource *source,
|
||||
ModeFilter *filter) :
|
||||
RangeFinder(source, filter), _scaler(AP_RANGEFINDER_MAXSONARXL_SCALER)
|
||||
AP_RangeFinder_MaxsonarXL::AP_RangeFinder_MaxsonarXL(AP_AnalogSource *source, ModeFilter *filter):
|
||||
RangeFinder(source, filter),
|
||||
_scaler(AP_RANGEFINDER_MAXSONARXL_SCALER)
|
||||
{
|
||||
max_distance = AP_RANGEFINDER_MAXSONARXL_MAX_DISTANCE;
|
||||
min_distance = AP_RANGEFINDER_MAXSONARXL_MIN_DISTANCE;
|
||||
|
|
|
@ -27,6 +27,7 @@ class AP_RangeFinder_MaxsonarXL : public RangeFinder
|
|||
AP_RangeFinder_MaxsonarXL(AP_AnalogSource *source, ModeFilter *filter);
|
||||
int convert_raw_to_distance(int _raw_value) { return _raw_value * _scaler; } // read value from analog port and return distance in cm
|
||||
float calculate_scaler(int sonar_type, float adc_refence_voltage);
|
||||
|
||||
private:
|
||||
float _scaler; // used to account for different sonar types
|
||||
};
|
||||
|
|
|
@ -31,8 +31,7 @@
|
|||
|
||||
// Constructor //////////////////////////////////////////////////////////////
|
||||
|
||||
AP_RangeFinder_SharpGP2Y::AP_RangeFinder_SharpGP2Y(AP_AnalogSource *source,
|
||||
ModeFilter *filter) :
|
||||
AP_RangeFinder_SharpGP2Y::AP_RangeFinder_SharpGP2Y(AP_AnalogSource *source, ModeFilter *filter) :
|
||||
RangeFinder(source, filter)
|
||||
{
|
||||
max_distance = AP_RANGEFINDER_SHARPEGP2Y_MAX_DISTANCE;
|
||||
|
|
|
@ -10,7 +10,12 @@ class AP_RangeFinder_SharpGP2Y : public RangeFinder
|
|||
{
|
||||
public:
|
||||
AP_RangeFinder_SharpGP2Y(AP_AnalogSource *source, ModeFilter *filter);
|
||||
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
|
||||
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
|
||||
|
|
|
@ -33,7 +33,6 @@ int RangeFinder::read()
|
|||
int temp_dist;
|
||||
|
||||
raw_value = _analog_source->read();
|
||||
|
||||
// convert analog value to distance in cm (using child implementation most likely)
|
||||
temp_dist = convert_raw_to_distance(raw_value);
|
||||
|
||||
|
|
|
@ -24,8 +24,7 @@ class RangeFinder
|
|||
protected:
|
||||
RangeFinder(AP_AnalogSource * source, ModeFilter *filter) :
|
||||
_analog_source(source),
|
||||
_mode_filter(filter)
|
||||
{}
|
||||
_mode_filter(filter) {}
|
||||
public:
|
||||
|
||||
int raw_value; // raw value from the sensor
|
||||
|
|
Loading…
Reference in New Issue