Browse Source

Remove camera capture GPIO interrupt when the rate is higher than 5kHz

If the capture GPIO is exposed to a signal with high frequency changes, a lot of
interrupts are scheduled and the handling of these call can worst-case
starve flight critical processes leading to a loss of control. Since camera capture
is not flight critical, we now give up the capture
functionality and stop the interrupts to prevent the starvation of other processes.
main
Michael Schaeuble 3 years ago committed by Beat Küng
parent
commit
85a5dd87cd
  1. 26
      src/drivers/camera_capture/camera_capture.cpp
  2. 4
      src/drivers/camera_capture/camera_capture.hpp

26
src/drivers/camera_capture/camera_capture.cpp

@ -40,11 +40,15 @@ @@ -40,11 +40,15 @@
*/
#include "camera_capture.hpp"
#include <px4_platform_common/events.h>
#include <systemlib/mavlink_log.h>
#include <board_config.h>
#define commandParamToInt(n) static_cast<int>(n >= 0 ? n + 0.5f : n - 0.5f)
using namespace time_literals;
namespace camera_capture
{
CameraCapture *g_camera_capture{nullptr};
@ -104,6 +108,21 @@ CameraCapture::~CameraCapture() @@ -104,6 +108,21 @@ CameraCapture::~CameraCapture()
void
CameraCapture::capture_callback(uint32_t chan_index, hrt_abstime edge_time, uint32_t edge_state, uint32_t overflow)
{
// Maximum acceptable rate is 5kHz
if ((edge_time - _trigger.hrt_edge_time) < 200_us) {
++_trigger_rate_exceeded_counter;
if (_trigger_rate_exceeded_counter > 100) {
// Trigger rate too high, stop future interrupts
up_input_capture_set(_capture_channel, Disabled, 0, nullptr, nullptr);
_trigger_rate_failure.store(true);
}
} else if (_trigger_rate_exceeded_counter > 0) {
--_trigger_rate_exceeded_counter;
}
_trigger.chan_index = chan_index;
_trigger.hrt_edge_time = edge_time;
_trigger.edge_state = edge_state;
@ -140,6 +159,13 @@ CameraCapture::publish_trigger() @@ -140,6 +159,13 @@ CameraCapture::publish_trigger()
{
bool publish = false;
if (_trigger_rate_failure.load()) {
mavlink_log_warning(&_mavlink_log_pub, "Hardware fault: Camera capture disabled\t");
events::send(events::ID("camera_capture_trigger_rate_exceeded"),
events::Log::Error, "Hardware fault: Camera capture disabled");
_trigger_rate_failure.store(false);
}
camera_trigger_s trigger{};
// MODES 1 and 2 are not fully tested

4
src/drivers/camera_capture/camera_capture.hpp

@ -134,6 +134,10 @@ private: @@ -134,6 +134,10 @@ private:
hrt_abstime _pps_hrt_timestamp{0};
uint64_t _pps_rtc_timestamp{0};
uint8_t _trigger_rate_exceeded_counter{0};
px4::atomic<bool> _trigger_rate_failure{false};
orb_advert_t _mavlink_log_pub{nullptr};
// Signal capture callback
void capture_callback(uint32_t chan_index, hrt_abstime edge_time, uint32_t edge_state, uint32_t overflow);

Loading…
Cancel
Save