AP_RangeFinder: create and use new AP_HAL::PWMSource object

This commit is contained in:
Peter Barker 2020-09-01 15:25:44 +10:00 committed by Peter Barker
parent 55f72c1534
commit 72b49efc78
4 changed files with 26 additions and 145 deletions

View File

@ -40,10 +40,10 @@ AP_RangeFinder_HC_SR04::AP_RangeFinder_HC_SR04(RangeFinder::RangeFinder_State &_
set_status(RangeFinder::Status::NoData);
}
void AP_RangeFinder_HC_SR04::check_pins()
bool AP_RangeFinder_HC_SR04::check_pins()
{
check_echo_pin();
check_trigger_pin();
return check_echo_pin() && trigger_pin > 0;
}
void AP_RangeFinder_HC_SR04::check_trigger_pin()
@ -55,46 +55,9 @@ void AP_RangeFinder_HC_SR04::check_trigger_pin()
trigger_pin = params.stop_pin;
}
void AP_RangeFinder_HC_SR04::check_echo_pin()
bool AP_RangeFinder_HC_SR04::check_echo_pin()
{
if (params.pin == echo_pin) {
// no change
return;
}
// detach last one
if (echo_pin) {
if (!hal.gpio->detach_interrupt(echo_pin)) {
GCS_SEND_TEXT(MAV_SEVERITY_WARNING,
"HC_SR04: Failed to detach from pin %u",
echo_pin);
// ignore this failure or the user may be stuck
}
}
echo_pin = params.pin;
if (!params.pin) {
// don't need to install handler
return;
}
// install interrupt handler on rising and falling edge
hal.gpio->pinMode(params.pin, HAL_GPIO_INPUT);
if (!hal.gpio->attach_interrupt(
params.pin,
FUNCTOR_BIND_MEMBER(&AP_RangeFinder_HC_SR04::irq_handler,
void,
uint8_t,
bool,
uint32_t),
AP_HAL::GPIO::INTERRUPT_BOTH)) {
// failed to attach interrupt
GCS_SEND_TEXT(MAV_SEVERITY_WARNING,
"HC_SR04: Failed to attach to pin %u",
(unsigned int)params.pin);
return;
}
return pwm_source.set_pin(params.pin, "HC_SR04");
}
@ -116,35 +79,19 @@ bool AP_RangeFinder_HC_SR04::detect(AP_RangeFinder_Params &_params)
}
// interrupt handler for reading distance-proportional time interval
void AP_RangeFinder_HC_SR04::irq_handler(uint8_t pin, bool pin_high, uint32_t timestamp_us)
{
if (pin_high) {
pulse_start_us = timestamp_us;
} else {
irq_value_us = timestamp_us - pulse_start_us;
}
}
/*
update distance_cm
*/
void AP_RangeFinder_HC_SR04::update(void)
{
// check if pin has changed and configure interrupt handlers if required:
check_pins();
if (!echo_pin || ! trigger_pin || echo_pin == -1 || trigger_pin == -1) {
if (!check_pins()) {
// disabled (either by configuration or failure to attach interrupt)
state.distance_cm = 0.0f;
return;
}
// disable interrupts and grab state
void *irqstate = hal.scheduler->disable_interrupts_save();
const uint32_t value_us = irq_value_us;
irq_value_us = 0;
hal.scheduler->restore_interrupts(irqstate);
const uint32_t value_us = pwm_source.get_pwm_us();
const uint32_t now = AP_HAL::millis();
if (value_us == 0) {

View File

@ -24,20 +24,17 @@ protected:
private:
void check_pins();
void check_echo_pin();
bool check_pins();
bool check_echo_pin();
void check_trigger_pin();
void irq_handler(uint8_t pin, bool pin_high, uint32_t timestamp_us);
int8_t echo_pin;
int8_t trigger_pin;
uint32_t last_reading_ms; // system time of last read (used for health reporting)
uint32_t last_distance_cm; // last distance reported (used to prevent glitches in measurement)
uint8_t glitch_count; // glitch counter
// follow are modified by the IRQ handler:
uint32_t pulse_start_us; // system time of start of timing pulse
uint32_t irq_value_us; // last calculated pwm value (irq copy)
int8_t last_warn_echo_pin;
AP_HAL::PWMSource pwm_source;
uint32_t last_ping_ms;
};

View File

@ -39,79 +39,24 @@ bool AP_RangeFinder_PWM::detect()
return true;
}
// interrupt handler for reading pwm value
void AP_RangeFinder_PWM::irq_handler(uint8_t pin, bool pin_high, uint32_t timestamp_us)
{
if (pin_high) {
irq_pulse_start_us = timestamp_us;
} else {
if (irq_pulse_start_us != 0) {
irq_value_us += timestamp_us - irq_pulse_start_us;
irq_pulse_start_us = 0;
irq_sample_count++;
}
}
}
// read - return last value measured by sensor
bool AP_RangeFinder_PWM::get_reading(uint16_t &reading_cm)
{
// disable interrupts and grab state
void *irqstate = hal.scheduler->disable_interrupts_save();
const uint32_t value_us = irq_value_us;
const uint16_t sample_count = irq_sample_count;
irq_value_us = 0;
irq_sample_count = 0;
hal.scheduler->restore_interrupts(irqstate);
if (value_us == 0 || sample_count == 0) {
const uint32_t value_us = pwm_source.get_pwm_avg_us();
if (value_us == 0) {
return false;
}
reading_cm = value_us/(sample_count * 10); // correct for LidarLite. Parameter needed? Converts from decimetres -> cm here
reading_cm = value_us/10; // correct for LidarLite. Parameter needed? Converts from decimetres -> cm here
return true;
}
void AP_RangeFinder_PWM::check_pin()
bool AP_RangeFinder_PWM::check_pin()
{
if (params.pin == last_pin) {
return;
}
// detach last one
if (last_pin > 0) {
if (!hal.gpio->detach_interrupt(last_pin)) {
GCS_SEND_TEXT(MAV_SEVERITY_WARNING,
"RangeFinder_PWM: Failed to detach from pin %u",
last_pin);
// ignore this failure or the user may be stuck
}
}
// set last pin to params.pin so we don't continually try to attach
// to it if the attach is failing
last_pin = params.pin;
if (params.pin <= 0) {
// don't need to install handler
return;
}
// install interrupt handler on rising and falling edge
hal.gpio->pinMode(params.pin, HAL_GPIO_INPUT);
if (!hal.gpio->attach_interrupt(
params.pin,
FUNCTOR_BIND_MEMBER(&AP_RangeFinder_PWM::irq_handler,
void,
uint8_t,
bool,
uint32_t),
AP_HAL::GPIO::INTERRUPT_BOTH)) {
// failed to attach interrupt
GCS_SEND_TEXT(MAV_SEVERITY_WARNING,
"RangeFinder_PWM: Failed to attach to pin %u",
(unsigned int)params.pin);
return;
if (!pwm_source.set_pin(params.pin, "RangeFinder_PWM")) {
return false;
}
return true;
}
void AP_RangeFinder_PWM::check_stop_pin()
@ -125,10 +70,10 @@ void AP_RangeFinder_PWM::check_stop_pin()
last_stop_pin = params.stop_pin;
}
void AP_RangeFinder_PWM::check_pins()
bool AP_RangeFinder_PWM::check_pins()
{
check_pin();
check_stop_pin();
return check_pin();
}
@ -138,10 +83,7 @@ void AP_RangeFinder_PWM::check_pins()
void AP_RangeFinder_PWM::update(void)
{
// check if pin has changed and configure interrupt handlers if required:
check_pins();
if (last_pin <= 0) {
// disabled (by configuration)
if (!check_pins()) {
return;
}

View File

@ -44,20 +44,15 @@ protected:
private:
int8_t last_pin; // last pin used for reading pwm (used to recognise change in pin assignment)
int8_t last_warn_pin; // last pin used for reading pwm (used to recognise change in pin assignment)
// the following three members are updated by the interrupt handler
uint32_t irq_value_us; // some of calculated pwm values (irq copy)
uint16_t irq_sample_count; // number of pwm values in irq_value_us (irq copy)
uint32_t irq_pulse_start_us; // system time of start of pulse
void irq_handler(uint8_t pin, bool pin_high, uint32_t timestamp_us);
void check_pin();
bool check_pin();
void check_stop_pin();
void check_pins();
bool check_pins();
uint8_t last_stop_pin = -1;
AP_HAL::PWMSource pwm_source;
float &estimated_terrain_height;
// return true if we are beyond the power saving range