Files
PX4-Autopilot/src/drivers/pps_capture/PPSCapture.hpp
T
Michael Schaeuble 5abee359d6 Remove PPS GPIO interrupt when the rate is higher than 20Hz
If the PPS GPIO is exposed to a signal with high frequency changes, a lot of
interrupts are scheduled and the handling of these calls can worst-case
starve flight critical processes leading to a loss of
control. Since PPS is not flight critical, we now give up the PPS
functionality and stop the interrupts to prevent the starvation of other processes.
2022-07-04 11:32:33 +02:00

85 lines
3.0 KiB
C++

/****************************************************************************
*
* Copyright (c) 2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
#include <drivers/drv_hrt.h>
#include <px4_arch/micro_hal.h>
#include <px4_platform_common/module.h>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <uORB/Publication.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/topics/pps_capture.h>
#include <uORB/topics/sensor_gps.h>
using namespace time_literals;
class PPSCapture : public ModuleBase<PPSCapture>, public px4::ScheduledWorkItem
{
public:
PPSCapture();
virtual ~PPSCapture();
/** @see ModuleBase */
static int task_spawn(int argc, char *argv[]);
/** @see ModuleBase */
static int custom_command(int argc, char *argv[]);
/** @see ModuleBase */
static int print_usage(const char *reason = nullptr);
bool init();
static int gpio_interrupt_callback(int irq, void *context, void *arg);
/** PPSCapture is an interrupt-driven task and needs to be manually stopped */
static void stop();
private:
void Run() override;
int _channel{-1};
uint32_t _pps_capture_gpio{0};
uORB::Publication<pps_capture_s> _pps_capture_pub{ORB_ID(pps_capture)};
uORB::Subscription _sensor_gps_sub{ORB_ID(sensor_gps)};
orb_advert_t _mavlink_log_pub{nullptr};
hrt_abstime _hrt_timestamp{0};
hrt_abstime _last_gps_timestamp{0};
uint64_t _last_gps_utc_timestamp{0};
uint8_t _pps_rate_exceeded_counter{0};
px4::atomic<bool> _pps_rate_failure{false};
};