-
Notifications
You must be signed in to change notification settings - Fork 17.4k
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
AP_InertialSensor: keep a queue of gyro samples for use by the rate t…
…hread decimate the gyro window locally configure rate loop buffer based on AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED allow backends to be updated from rate thread output debug error if rate loop buffer overruns add support for updating filter parameters independently of propagating samples add rate loop config abstraction that allows code to be elided on non-copter builds must be using harmonic notch to use rate thread mediate fast rate loop buffer using mutex and binary semaphore ensure gyro samples are used when the rate loop buffer isn't Co-Authored-By: Andrew Tridgell <andrew@tridgell.net>
- Loading branch information
Showing
6 changed files
with
237 additions
and
2 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,9 @@ | ||
#pragma once | ||
|
||
#include <AP_Vehicle/AP_Vehicle_Type.h> | ||
#include <AP_HAL/AP_HAL_Boards.h> | ||
#include <AP_InertialSensor/AP_InertialSensor_config.h> | ||
|
||
#ifndef AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED | ||
#define AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED (AP_INERTIALSENSOR_ENABLED && HAL_INS_RATE_LOOP && AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED && APM_BUILD_TYPE(APM_BUILD_ArduCopter)) | ||
#endif |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,124 @@ | ||
/* | ||
This program is free software: you can redistribute it and/or modify | ||
it under the terms of the GNU General Public License as published by | ||
the Free Software Foundation, either version 3 of the License, or | ||
(at your option) any later version. | ||
This program is distributed in the hope that it will be useful, | ||
but WITHOUT ANY WARRANTY; without even the implied warranty of | ||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the | ||
GNU General Public License for more details. | ||
You should have received a copy of the GNU General Public License | ||
along with this program. If not, see <http://www.gnu.org/licenses/>. | ||
*/ | ||
|
||
#include <AP_AHRS/AP_AHRS.h> | ||
#include "AP_InertialSensor_rate_config.h" | ||
#include "AP_InertialSensor.h" | ||
#include "AP_InertialSensor_Backend.h" | ||
|
||
#if AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED | ||
#include "FastRateBuffer.h" | ||
#include <stdio.h> | ||
|
||
extern const AP_HAL::HAL& hal; | ||
|
||
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS | ||
// hal.console can be accessed from bus threads on ChibiOS | ||
#define debug(fmt, args ...) do {hal.console->printf("IMU: " fmt "\n", ## args); } while(0) | ||
#else | ||
#define debug(fmt, args ...) do {printf("IMU: " fmt "\n", ## args); } while(0) | ||
#endif | ||
|
||
void AP_InertialSensor::enable_fast_rate_buffer() | ||
{ | ||
fast_rate_buffer = NEW_NOTHROW FastRateBuffer(); | ||
} | ||
|
||
void AP_InertialSensor::disable_fast_rate_buffer() | ||
{ | ||
delete fast_rate_buffer; | ||
fast_rate_buffer = nullptr; | ||
} | ||
|
||
uint32_t AP_InertialSensor::get_num_gyro_samples() | ||
{ | ||
return fast_rate_buffer->get_num_gyro_samples(); | ||
} | ||
|
||
void AP_InertialSensor::set_rate_decimation(uint8_t rdec) | ||
{ | ||
fast_rate_buffer->set_rate_decimation(rdec); | ||
} | ||
|
||
// are gyro samples being sourced from the rate loop buffer | ||
bool AP_InertialSensor::use_rate_loop_gyro_samples() const | ||
{ | ||
return fast_rate_buffer != nullptr; | ||
} | ||
|
||
// whether or not to push the current gyro sample | ||
bool AP_InertialSensor::is_rate_loop_gyro_enabled(uint8_t instance) const | ||
{ | ||
return use_rate_loop_gyro_samples() && fast_rate_buffer->use_rate_loop_gyro_samples() && instance == AP::ahrs().get_primary_gyro_index(); | ||
} | ||
|
||
bool AP_InertialSensor::get_next_gyro_sample(Vector3f& gyro) | ||
{ | ||
if (!use_rate_loop_gyro_samples()) { | ||
return false; | ||
} | ||
|
||
return fast_rate_buffer->get_next_gyro_sample(gyro); | ||
} | ||
|
||
bool FastRateBuffer::get_next_gyro_sample(Vector3f& gyro) | ||
{ | ||
if (!use_rate_loop_gyro_samples()) { | ||
return false; | ||
} | ||
|
||
if (_rate_loop_gyro_window.available() == 0) { | ||
_notifier.wait_blocking(); | ||
} | ||
|
||
WITH_SEMAPHORE(_mutex); | ||
|
||
return _rate_loop_gyro_window.pop(gyro); | ||
} | ||
|
||
bool AP_InertialSensor::push_next_gyro_sample(const Vector3f& gyro) | ||
{ | ||
if (++fast_rate_buffer->rate_decimation_count < fast_rate_buffer->rate_decimation) { | ||
return false; | ||
} | ||
/* | ||
tell the rate thread we have a new sample | ||
*/ | ||
WITH_SEMAPHORE(fast_rate_buffer->_mutex); | ||
|
||
if (!fast_rate_buffer->_rate_loop_gyro_window.push(gyro)) { | ||
debug("dropped rate loop sample"); | ||
} | ||
fast_rate_buffer->rate_decimation_count = 0; | ||
fast_rate_buffer->_notifier.signal(); | ||
return true; | ||
} | ||
|
||
void AP_InertialSensor::update_backend_filters() | ||
{ | ||
for (uint8_t i=0; i<_backend_count; i++) { | ||
_backends[i]->update_filters(); | ||
} | ||
} | ||
|
||
void AP_InertialSensor_Backend::update_filters() | ||
{ | ||
WITH_SEMAPHORE(_sem); | ||
|
||
update_accel_filters(accel_instance); | ||
update_gyro_filters(gyro_instance); | ||
} | ||
|
||
#endif // AP_INERTIALSENSOR_RATE_LOOP_WINDOW_ENABLED |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,50 @@ | ||
/* | ||
This program is free software: you can redistribute it and/or modify | ||
it under the terms of the GNU General Public License as published by | ||
the Free Software Foundation, either version 3 of the License, or | ||
(at your option) any later version. | ||
This program is distributed in the hope that it will be useful, | ||
but WITHOUT ANY WARRANTY; without even the implied warranty of | ||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the | ||
GNU General Public License for more details. | ||
You should have received a copy of the GNU General Public License | ||
along with this program. If not, see <http://www.gnu.org/licenses/>. | ||
*/ | ||
#pragma once | ||
|
||
#include "AP_InertialSensor.h" | ||
|
||
#if AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED | ||
|
||
#define AP_INERTIAL_SENSOR_RATE_LOOP_BUFFER_SIZE 8 // gyro buffer size for rate loop | ||
|
||
#include <AP_HAL/AP_HAL_Boards.h> | ||
#include <AP_HAL/utility/RingBuffer.h> | ||
#include <AP_Math/AP_Math.h> | ||
#include <AP_HAL/Semaphores.h> | ||
|
||
class FastRateBuffer | ||
{ | ||
friend class AP_InertialSensor; | ||
public: | ||
bool get_next_gyro_sample(Vector3f& gyro); | ||
uint32_t get_num_gyro_samples() { return _rate_loop_gyro_window.available(); } | ||
void set_rate_decimation(uint8_t rdec) { rate_decimation = rdec; } | ||
// whether or not to push the current gyro sample | ||
bool use_rate_loop_gyro_samples() const { return rate_decimation > 0; } | ||
bool gyro_samples_available() { return _rate_loop_gyro_window.available() > 0; } | ||
|
||
private: | ||
/* | ||
binary semaphore for rate loop to use to start a rate loop when | ||
we hav finished filtering the primary IMU | ||
*/ | ||
ObjectBuffer<Vector3f> _rate_loop_gyro_window{AP_INERTIAL_SENSOR_RATE_LOOP_BUFFER_SIZE}; | ||
uint8_t rate_decimation; // 0 means off | ||
uint8_t rate_decimation_count; | ||
HAL_BinarySemaphore _notifier; | ||
HAL_Semaphore _mutex; | ||
}; | ||
#endif |