AP_HAL_SITL: ADC resolution configurable by define, default to 16 bit

This commit is contained in:
Jonathan Challinger 2023-05-04 12:50:02 -07:00 committed by Andrew Tridgell
parent 0b34df3328
commit 4ef070956d
6 changed files with 35 additions and 26 deletions

View File

@ -5,6 +5,8 @@
#include "AnalogIn.h" #include "AnalogIn.h"
#include <stdint.h> #include <stdint.h>
#define VOLTAGE_TO_PIN_VALUE(_v) (constrain_float(_v * (SITL_ADC_MAX_PIN_VALUE/SITL_ADC_FULL_SCALE_VOLTAGE), 0, SITL_ADC_MAX_PIN_VALUE))
using namespace HALSITL; using namespace HALSITL;
extern const AP_HAL::HAL& hal; extern const AP_HAL::HAL& hal;
@ -19,38 +21,34 @@ float ADCSource::read_average() {
} }
float ADCSource::voltage_average() { float ADCSource::voltage_average() {
return (5.0f/1023.0f) * read_average(); return voltage_latest();
} }
float ADCSource::voltage_latest() { float ADCSource::voltage_latest() {
return (5.0f/1023.0f) * read_latest();
}
float ADCSource::read_latest() {
switch (_pin) { switch (_pin) {
case ANALOG_INPUT_BOARD_VCC: case ANALOG_INPUT_BOARD_VCC:
return 1023; return SITL_ADC_MAX_PIN_VALUE;
case 0: case 0:
return _sitlState->sonar_pin_value; return _sitlState->sonar_pin_voltage;
case 1: case 1:
return _sitlState->airspeed_pin_value[0]; return _sitlState->airspeed_pin_voltage[0];
case 2: case 2:
return _sitlState->airspeed_pin_value[1]; return _sitlState->airspeed_pin_voltage[1];
case 12: case 12:
return _sitlState->current_pin_value; return _sitlState->current_pin_voltage;
case 13: case 13:
return _sitlState->voltage_pin_value; return _sitlState->voltage_pin_voltage;
case 14: case 14:
return _sitlState->current2_pin_value; return _sitlState->current2_pin_voltage;
case 15: case 15:
return _sitlState->voltage2_pin_value; return _sitlState->voltage2_pin_voltage;
case ANALOG_INPUT_NONE: case ANALOG_INPUT_NONE:
default: default:
@ -58,6 +56,10 @@ float ADCSource::read_latest() {
} }
} }
float ADCSource::read_latest() {
return VOLTAGE_TO_PIN_VALUE(voltage_latest());
}
bool ADCSource::set_pin(uint8_t pin) { bool ADCSource::set_pin(uint8_t pin) {
_pin = pin; _pin = pin;
return true; return true;

View File

@ -3,6 +3,9 @@
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include "AP_HAL_SITL_Namespace.h" #include "AP_HAL_SITL_Namespace.h"
#define SITL_ADC_RESOLUTION 16 // bits of resolution
#define SITL_ADC_MAX_PIN_VALUE ((1<<SITL_ADC_RESOLUTION)-1)
#define SITL_ADC_FULL_SCALE_VOLTAGE 5.0f
#define SITL_INPUT_MAX_CHANNELS 12 #define SITL_INPUT_MAX_CHANNELS 12
class HALSITL::ADCSource : public AP_HAL::AnalogSource { class HALSITL::ADCSource : public AP_HAL::AnalogSource {

View File

@ -912,11 +912,11 @@ void SITL_State::_simulator_servos(struct sitl_input &input)
} }
// assume 3DR power brick // assume 3DR power brick
voltage_pin_value = float_to_uint16(((voltage / 10.1f) / 5.0f) * 1024); voltage_pin_voltage = (voltage / 10.1f);
current_pin_value = float_to_uint16(((_current / 17.0f) / 5.0f) * 1024); current_pin_voltage = _current/17.0f;
// fake battery2 as just a 25% gain on the first one // fake battery2 as just a 25% gain on the first one
voltage2_pin_value = float_to_uint16(((voltage * 0.25f / 10.1f) / 5.0f) * 1024); voltage2_pin_voltage = voltage_pin_voltage * .25f;
current2_pin_value = float_to_uint16(((_current * 0.25f / 17.0f) / 5.0f) * 1024); current2_pin_voltage = current_pin_voltage * .25f;
} }
void SITL_State::init(int argc, char * const argv[]) void SITL_State::init(int argc, char * const argv[])

View File

@ -96,12 +96,12 @@ public:
} }
// simulated airspeed, sonar and battery monitor // simulated airspeed, sonar and battery monitor
uint16_t sonar_pin_value; // pin 0 float sonar_pin_voltage; // pin 0
uint16_t airspeed_pin_value[AIRSPEED_MAX_SENSORS]; // pin 1 float airspeed_pin_voltage[AIRSPEED_MAX_SENSORS]; // pin 1
uint16_t voltage_pin_value; // pin 13 float voltage_pin_voltage; // pin 13
uint16_t current_pin_value; // pin 12 float current_pin_voltage; // pin 12
uint16_t voltage2_pin_value; // pin 15 float voltage2_pin_voltage; // pin 15
uint16_t current2_pin_value; // pin 14 float current2_pin_voltage; // pin 14
// paths for UART devices // paths for UART devices
const char *_uart_path[9] { const char *_uart_path[9] {

View File

@ -20,6 +20,10 @@ extern const AP_HAL::HAL& hal;
using namespace HALSITL; using namespace HALSITL;
// scaling value taken from AP_Airspeed_analog.cpp
#define VOLTS_TO_PASCAL 819
#define PASCAL_TO_VOLTS(_p) (_p/VOLTS_TO_PASCAL)
// return current scale factor that converts from equivalent to true airspeed // return current scale factor that converts from equivalent to true airspeed
// valid for altitudes up to 10km AMSL // valid for altitudes up to 10km AMSL
// assumes standard atmosphere lapse rate // assumes standard atmosphere lapse rate
@ -78,8 +82,8 @@ void SITL_State::_update_airspeed(float true_airspeed)
airspeed_raw = airspeed_pressure + arspd.offset; airspeed_raw = airspeed_pressure + arspd.offset;
_sitl->state.airspeed_raw_pressure[i] = airspeed_pressure; _sitl->state.airspeed_raw_pressure[i] = airspeed_pressure;
airspeed_pin_value[i] = MIN(0xFFFF, airspeed_raw / 4); airspeed_pin_voltage[i] = PASCAL_TO_VOLTS(airspeed_raw);
} }
} }

View File

@ -51,7 +51,7 @@ float SITL_State::_sonar_pin_voltage() const
*/ */
void SITL_State::_update_rangefinder() void SITL_State::_update_rangefinder()
{ {
sonar_pin_value = 1023 * (_sonar_pin_voltage() / 5.0f); sonar_pin_voltage = _sonar_pin_voltage();
} }
#endif #endif