Browse Source

HAL_ChibiOS: fixed RSSI voltage from IOMCU

mission-4.1.18
Andrew Tridgell 6 years ago
parent
commit
340f1b43e6
  1. 32
      libraries/AP_HAL_ChibiOS/AnalogIn.cpp
  2. 2
      libraries/AP_HAL_ChibiOS/AnalogIn.h

32
libraries/AP_HAL_ChibiOS/AnalogIn.cpp

@ -51,6 +51,9 @@ extern const AP_HAL::HAL& hal;
using namespace ChibiOS; using namespace ChibiOS;
// special pins
#define ANALOG_SERVO_VRSSI_PIN 103
/* /*
scaling table between ADC count and actual input voltage, to account scaling table between ADC count and actual input voltage, to account
for voltage dividers on the board. for voltage dividers on the board.
@ -183,13 +186,6 @@ void AnalogSource::_add_value(float v, float vcc5V)
} }
AnalogIn::AnalogIn() :
_board_voltage(0),
_servorail_voltage(0),
_power_flags(0)
{
}
/* /*
callback from ADC driver when sample buffer is filled callback from ADC driver when sample buffer is filled
*/ */
@ -290,24 +286,30 @@ void AnalogIn::_timer_tick(void)
} }
#endif #endif
} }
#if HAL_WITH_IO_MCU
// now handle special inputs from IOMCU
_servorail_voltage = iomcu.get_vservo();
_rssi_voltage = iomcu.get_vrssi();
#endif
for (uint8_t i=0; i<ADC_GRP1_NUM_CHANNELS; i++) { for (uint8_t i=0; i<ADC_GRP1_NUM_CHANNELS; i++) {
Debug("chan %u value=%u\n", Debug("chan %u value=%u\n",
(unsigned)pin_config[i].channel, (unsigned)pin_config[i].channel,
(unsigned)buf_adc[i]); (unsigned)buf_adc[i]);
for (uint8_t j=0; j < ANALOG_MAX_CHANNELS; j++) { for (uint8_t j=0; j < ANALOG_MAX_CHANNELS; j++) {
ChibiOS::AnalogSource *c = _channels[j]; ChibiOS::AnalogSource *c = _channels[j];
if (c != nullptr && pin_config[i].channel == c->_pin) { if (c != nullptr) {
// add a value if (pin_config[i].channel == c->_pin) {
c->_add_value(buf_adc[i], _board_voltage); // add a value
c->_add_value(buf_adc[i], _board_voltage);
} else if (c->_pin == ANALOG_SERVO_VRSSI_PIN) {
c->_add_value(_rssi_voltage / VOLTAGE_SCALING, 0);
}
} }
} }
} }
#if HAL_WITH_IO_MCU
// now handle special inputs from IOMCU
_servorail_voltage = iomcu.get_vservo();
#endif
#if CHIBIOS_ADC_MAVLINK_DEBUG #if CHIBIOS_ADC_MAVLINK_DEBUG
static uint8_t count; static uint8_t count;
if (AP_HAL::millis() > 5000 && count++ == 10) { if (AP_HAL::millis() > 5000 && count++ == 10) {

2
libraries/AP_HAL_ChibiOS/AnalogIn.h

@ -57,7 +57,6 @@ class ChibiOS::AnalogIn : public AP_HAL::AnalogIn {
public: public:
friend class AnalogSource; friend class AnalogSource;
AnalogIn();
void init() override; void init() override;
AP_HAL::AnalogSource* channel(int16_t pin) override; AP_HAL::AnalogSource* channel(int16_t pin) override;
void _timer_tick(void); void _timer_tick(void);
@ -80,6 +79,7 @@ private:
uint32_t _last_run; uint32_t _last_run;
float _board_voltage; float _board_voltage;
float _servorail_voltage; float _servorail_voltage;
float _rssi_voltage;
uint16_t _power_flags; uint16_t _power_flags;
ADCConversionGroup adcgrpcfg; ADCConversionGroup adcgrpcfg;

Loading…
Cancel
Save