Browse Source

AP Rangefinder had some bad characters in it. Converted and cleaned the text files.

mission-4.1.18
Jason Short 13 years ago
parent
commit
b6fc8e519c
  1. 10
      libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.cpp
  2. 1
      libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.h
  3. 3
      libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.cpp
  4. 7
      libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.h
  5. 1
      libraries/AP_RangeFinder/RangeFinder.cpp
  6. 3
      libraries/AP_RangeFinder/RangeFinder.h

10
libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.cpp

@ -31,13 +31,13 @@ @@ -31,13 +31,13 @@
// 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;
}
}
// Public Methods //////////////////////////////////////////////////////////////
float AP_RangeFinder_MaxsonarXL::calculate_scaler(int sonar_type, float adc_refence_voltage)

1
libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.h

@ -27,6 +27,7 @@ class AP_RangeFinder_MaxsonarXL : public RangeFinder @@ -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
};

3
libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.cpp

@ -31,8 +31,7 @@ @@ -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;

7
libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.h

@ -10,7 +10,12 @@ class AP_RangeFinder_SharpGP2Y : public RangeFinder @@ -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

1
libraries/AP_RangeFinder/RangeFinder.cpp

@ -33,7 +33,6 @@ int RangeFinder::read() @@ -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);

3
libraries/AP_RangeFinder/RangeFinder.h

@ -24,8 +24,7 @@ class RangeFinder @@ -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…
Cancel
Save