mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
MaxsonarRFinder: convert_raw returns int16_t
This commit is contained in:
parent
32820b4260
commit
ab22d11110
@ -25,7 +25,6 @@
|
||||
* 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)
|
||||
@ -48,7 +47,7 @@ AP_RangeFinder_MaxsonarXL::AP_RangeFinder_MaxsonarXL(AP_HAL::AnalogSource *sourc
|
||||
}
|
||||
|
||||
// Public Methods //////////////////////////////////////////////////////////////
|
||||
float AP_RangeFinder_MaxsonarXL::calculate_scaler(int sonar_type, float adc_refence_voltage)
|
||||
float AP_RangeFinder_MaxsonarXL::calculate_scaler(int16_t sonar_type, float adc_refence_voltage)
|
||||
{
|
||||
float type_scaler = 1.0f;
|
||||
switch(sonar_type) {
|
||||
|
@ -31,10 +31,10 @@ class AP_RangeFinder_MaxsonarXL : public RangeFinder
|
||||
{
|
||||
public:
|
||||
AP_RangeFinder_MaxsonarXL(AP_HAL::AnalogSource *source, FilterInt16 *filter);
|
||||
int convert_raw_to_distance(int _raw_value) {
|
||||
return _raw_value * _scaler;
|
||||
int16_t convert_raw_to_distance(int16_t 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);
|
||||
float calculate_scaler(int16_t sonar_type, float adc_refence_voltage);
|
||||
|
||||
private:
|
||||
float _scaler; // used to account for different sonar types
|
||||
|
Loading…
Reference in New Issue
Block a user