Browse Source

AP_HAL: added voltage_average_ratiometric() call to AnalogIn

this is for ratiometric sensors such as the 3DR airspeed sensor and
the Maxbotix analog sonar
master
Andrew Tridgell 12 years ago
parent
commit
589b8cdb58
  1. 4
      libraries/AP_HAL/AnalogIn.h
  2. 1
      libraries/AP_HAL_AVR/AnalogIn.h
  3. 11
      libraries/AP_HAL_AVR/AnalogIn_ADC.cpp
  4. 2
      libraries/AP_HAL_AVR_SITL/AnalogIn.cpp
  5. 1
      libraries/AP_HAL_AVR_SITL/AnalogIn.h
  6. 2
      libraries/AP_HAL_AVR_SITL/sitl_ins.cpp
  7. 1
      libraries/AP_HAL_Empty/AnalogIn.h
  8. 1
      libraries/AP_HAL_PX4/AnalogIn.h
  9. 1
      libraries/AP_HAL_SMACCM/AnalogIn.h

4
libraries/AP_HAL/AnalogIn.h

@ -27,6 +27,10 @@ public: @@ -27,6 +27,10 @@ public:
// return a voltage from 0.0 to 5.0V, scaled
// against a reference voltage
virtual float voltage_average() = 0;
// return a voltage from 0.0 to 5.0V, assuming a ratiometric
// sensor
virtual float voltage_average_ratiometric() = 0;
};
class AP_HAL::AnalogIn {

1
libraries/AP_HAL_AVR/AnalogIn.h

@ -19,6 +19,7 @@ public: @@ -19,6 +19,7 @@ public:
float read_latest();
void set_pin(uint8_t p);
float voltage_average();
float voltage_average_ratiometric();
void set_stop_pin(uint8_t p);
void set_settle_time(uint16_t settle_time_ms);

11
libraries/AP_HAL_AVR/AnalogIn_ADC.cpp

@ -59,6 +59,17 @@ float ADCSource::voltage_average(void) @@ -59,6 +59,17 @@ float ADCSource::voltage_average(void)
return v * vcc_mV * 9.765625e-7; // 9.765625e-7 = 1.0/(1024*1000)
}
/*
return voltage from 0.0 to 5.0V, assuming a ratiometric sensor. This
means the result is really a pseudo-voltage, that assumes the supply
voltage is exactly 5.0V.
*/
float ADCSource::voltage_average_ratiometric(void)
{
float v = read_average();
return v * (5.0f / 1023.0f);
}
void ADCSource::set_pin(uint8_t pin) {
_pin = pin;
}

2
libraries/AP_HAL_AVR_SITL/AnalogIn.cpp

@ -22,7 +22,7 @@ float ADCSource::read_average() { @@ -22,7 +22,7 @@ float ADCSource::read_average() {
}
float ADCSource::voltage_average() {
return (5.0/1024.0) * read_average();
return (5.0f/1023.0f) * read_average();
}
float ADCSource::read_latest() {

1
libraries/AP_HAL_AVR_SITL/AnalogIn.h

@ -19,6 +19,7 @@ public: @@ -19,6 +19,7 @@ public:
float read_latest();
void set_pin(uint8_t p);
float voltage_average();
float voltage_average_ratiometric() { return voltage_average(); }
void set_stop_pin(uint8_t pin) {}
void set_settle_time(uint16_t settle_time_ms) {}

2
libraries/AP_HAL_AVR_SITL/sitl_ins.cpp

@ -31,7 +31,7 @@ using namespace AVR_SITL; @@ -31,7 +31,7 @@ using namespace AVR_SITL;
uint16_t SITL_State::_airspeed_sensor(float airspeed)
{
const float airspeed_ratio = 1.9936;
const float airspeed_offset = 2820;
const float airspeed_offset = 503;
float airspeed_pressure, airspeed_raw;
airspeed_pressure = (airspeed*airspeed) / airspeed_ratio;

1
libraries/AP_HAL_Empty/AnalogIn.h

@ -13,6 +13,7 @@ public: @@ -13,6 +13,7 @@ public:
void set_stop_pin(uint8_t p);
void set_settle_time(uint16_t settle_time_ms);
float voltage_average();
float voltage_average_ratiometric() { return voltage_average(); }
private:
float _v;
};

1
libraries/AP_HAL_PX4/AnalogIn.h

@ -26,6 +26,7 @@ public: @@ -26,6 +26,7 @@ public:
float read_latest();
void set_pin(uint8_t p);
float voltage_average();
float voltage_average_ratiometric() { return voltage_average(); }
// stop pins not implemented on PX4 yet
void set_stop_pin(uint8_t p) {}

1
libraries/AP_HAL_SMACCM/AnalogIn.h

@ -11,6 +11,7 @@ public: @@ -11,6 +11,7 @@ public:
float read_latest();
void set_pin(uint8_t p);
float voltage_average();
float voltage_average_ratiometric() { return voltage_average(); }
void set_stop_pin(uint8_t p) {}
void set_settle_time(uint16_t settle_time_ms) {}

Loading…
Cancel
Save