Browse Source

AP_HAL: added voltage_latest() interface

this will be used for reading the 5V rail
master
Andrew Tridgell 12 years ago
parent
commit
a587b1140a
  1. 4
      libraries/AP_HAL/AnalogIn.h
  2. 4
      libraries/AP_HAL_AVR_SITL/AnalogIn.cpp
  3. 1
      libraries/AP_HAL_AVR_SITL/AnalogIn.h
  4. 4
      libraries/AP_HAL_Empty/AnalogIn.cpp
  5. 1
      libraries/AP_HAL_Empty/AnalogIn.h
  6. 5
      libraries/AP_HAL_SMACCM/AnalogIn.cpp
  7. 1
      libraries/AP_HAL_SMACCM/AnalogIn.h

4
libraries/AP_HAL/AnalogIn.h

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

4
libraries/AP_HAL_AVR_SITL/AnalogIn.cpp

@ -24,6 +24,10 @@ float ADCSource::voltage_average() { @@ -24,6 +24,10 @@ float ADCSource::voltage_average() {
return (5.0f/1023.0f) * read_average();
}
float ADCSource::voltage_latest() {
return (5.0f/1023.0f) * read_latest();
}
float ADCSource::read_latest() {
switch (_pin) {
case ANALOG_INPUT_BOARD_VCC:

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_latest();
float voltage_average_ratiometric() { return voltage_average(); }
void set_stop_pin(uint8_t pin) {}
void set_settle_time(uint16_t settle_time_ms) {}

4
libraries/AP_HAL_Empty/AnalogIn.cpp

@ -14,6 +14,10 @@ float EmptyAnalogSource::voltage_average() { @@ -14,6 +14,10 @@ float EmptyAnalogSource::voltage_average() {
return 5.0 * _v / 1024.0;
}
float EmptyAnalogSource::voltage_latest() {
return 5.0 * _v / 1024.0;
}
float EmptyAnalogSource::read_latest() {
return _v;
}

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_latest();
float voltage_average_ratiometric() { return voltage_average(); }
private:
float _v;

5
libraries/AP_HAL_SMACCM/AnalogIn.cpp

@ -16,6 +16,11 @@ float SMACCMAnalogSource::voltage_average() { @@ -16,6 +16,11 @@ float SMACCMAnalogSource::voltage_average() {
return (5.0/1024.0) * read_average();
}
float SMACCMAnalogSource::voltage_latest() {
// this assumes 5.0V scaling and 1024 range
return (5.0/1024.0) * read_latest();
}
float SMACCMAnalogSource::read_latest() {
return _v;
}

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_latest();
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