mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
AP_ADC: added num_samples_available to allow main loop to be synced with arrival of new sensor data for Oilpan.
This commit is contained in:
parent
38feee9c61
commit
5a3645d36a
@ -44,6 +44,8 @@ public:
|
|||||||
// check if Ch6() can return new data
|
// check if Ch6() can return new data
|
||||||
virtual bool new_data_available(const uint8_t *channel_numbers) = 0;
|
virtual bool new_data_available(const uint8_t *channel_numbers) = 0;
|
||||||
|
|
||||||
|
virtual uint16_t num_samples_available(const uint8_t *channel_numbers) = 0;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -246,3 +246,18 @@ uint32_t AP_ADC_ADS7844::Ch6(const uint8_t *channel_numbers, float *result)
|
|||||||
// return number of microseconds since last call
|
// return number of microseconds since last call
|
||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/// Get minimum number of samples read from the sensors
|
||||||
|
uint16_t AP_ADC_ADS7844::num_samples_available(const uint8_t *channel_numbers)
|
||||||
|
{
|
||||||
|
// get count of first channel as a base
|
||||||
|
uint16_t min_count = _count[channel_numbers[0]];
|
||||||
|
|
||||||
|
// reduce to minimum count of all other channels
|
||||||
|
for (uint8_t i=1; i<6; i++) {
|
||||||
|
if (_count[channel_numbers[i]] < min_count) {
|
||||||
|
min_count = _count[channel_numbers[i]];
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return min_count;
|
||||||
|
}
|
||||||
|
@ -33,6 +33,9 @@ public:
|
|||||||
// check if Ch6 would block
|
// check if Ch6 would block
|
||||||
bool new_data_available(const uint8_t *channel_numbers);
|
bool new_data_available(const uint8_t *channel_numbers);
|
||||||
|
|
||||||
|
// Get minimum number of samples read from the sensors
|
||||||
|
uint16_t num_samples_available(const uint8_t *channel_numbers);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
static void read(uint32_t);
|
static void read(uint32_t);
|
||||||
|
|
||||||
|
@ -88,3 +88,9 @@ bool AP_ADC_HIL::new_data_available(const uint8_t *channel_numbers)
|
|||||||
{
|
{
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Get minimum number of samples read from the sensors
|
||||||
|
uint16_t AP_ADC_HIL::num_samples_available(const uint8_t *channel_numbers)
|
||||||
|
{
|
||||||
|
return 1;
|
||||||
|
}
|
@ -41,6 +41,9 @@ public:
|
|||||||
// see if Ch6 would block
|
// see if Ch6 would block
|
||||||
bool new_data_available(const uint8_t *channel_numbers);
|
bool new_data_available(const uint8_t *channel_numbers);
|
||||||
|
|
||||||
|
// Get minimum number of samples read from the sensors
|
||||||
|
uint16_t num_samples_available(const uint8_t *channel_numbers);
|
||||||
|
|
||||||
///
|
///
|
||||||
// Set the adc raw values given the current rotations rates,
|
// Set the adc raw values given the current rotations rates,
|
||||||
// temps, accels, and pressures
|
// temps, accels, and pressures
|
||||||
|
Loading…
Reference in New Issue
Block a user