mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
AP_IOMCU: fix ADC scaling on IOMCU
This commit is contained in:
parent
11f98f7421
commit
db6383eee7
@ -74,14 +74,14 @@ public:
|
|||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
get servo rail voltage
|
get servo rail voltage adc counts
|
||||||
*/
|
*/
|
||||||
float get_vservo(void) const { return reg_status.vservo * 0.001; }
|
uint16_t get_vservo_adc_count(void) const { return reg_status.vservo; }
|
||||||
|
|
||||||
/*
|
/*
|
||||||
get rssi voltage
|
get rssi voltage adc counts
|
||||||
*/
|
*/
|
||||||
float get_vrssi(void) const { return reg_status.vrssi * 0.001; }
|
uint16_t get_vrssi_adc_count(void) const { return reg_status.vrssi; }
|
||||||
|
|
||||||
// set target for IMU heater
|
// set target for IMU heater
|
||||||
void set_heater_duty_cycle(uint8_t duty_cycle);
|
void set_heater_duty_cycle(uint8_t duty_cycle);
|
||||||
|
@ -75,7 +75,7 @@ static uint16_t adc_sample_channel(uint32_t channel)
|
|||||||
uint16_t adc_sample_vservo(void)
|
uint16_t adc_sample_vservo(void)
|
||||||
{
|
{
|
||||||
const uint32_t channel = ADC_SQR3_SQ1_N(ADC_CHANNEL_IN4);
|
const uint32_t channel = ADC_SQR3_SQ1_N(ADC_CHANNEL_IN4);
|
||||||
return adc_sample_channel(channel) * 9900 / 4096;
|
return adc_sample_channel(channel);
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
@ -84,5 +84,5 @@ uint16_t adc_sample_vservo(void)
|
|||||||
uint16_t adc_sample_vrssi(void)
|
uint16_t adc_sample_vrssi(void)
|
||||||
{
|
{
|
||||||
const uint32_t channel = ADC_SQR3_SQ1_N(ADC_CHANNEL_IN5);
|
const uint32_t channel = ADC_SQR3_SQ1_N(ADC_CHANNEL_IN5);
|
||||||
return adc_sample_channel(channel) * 9900 / 4096;
|
return adc_sample_channel(channel);
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user