From be247b6e908cd84ae047586a87a361d11fd993ca Mon Sep 17 00:00:00 2001 From: Jukka Laitinen Date: Wed, 7 Aug 2024 15:24:44 +0300 Subject: [PATCH] [WIP] Start adding boilerplates for redundancy logic Signed-off-by: Jukka Laitinen --- src/modules/redundancy/CMakeLists.txt | 40 +++++++ src/modules/redundancy/Kconfig | 12 ++ src/modules/redundancy/redundancy.cpp | 161 ++++++++++++++++++++++++++ src/modules/redundancy/redundancy.h | 84 ++++++++++++++ 4 files changed, 297 insertions(+) create mode 100644 src/modules/redundancy/CMakeLists.txt create mode 100644 src/modules/redundancy/Kconfig create mode 100644 src/modules/redundancy/redundancy.cpp create mode 100644 src/modules/redundancy/redundancy.h diff --git a/src/modules/redundancy/CMakeLists.txt b/src/modules/redundancy/CMakeLists.txt new file mode 100644 index 000000000000..c40e3ee6a084 --- /dev/null +++ b/src/modules/redundancy/CMakeLists.txt @@ -0,0 +1,40 @@ +############################################################################ +# +# Copyright (c) 2024 Technology Innovation Institute. 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. +# +############################################################################ + +px4_add_module( + MODULE modules__redundancy + MAIN redundancy + COMPILE_FLAGS + SRCS + redundancy.cpp + ) diff --git a/src/modules/redundancy/Kconfig b/src/modules/redundancy/Kconfig new file mode 100644 index 000000000000..281270ca09c7 --- /dev/null +++ b/src/modules/redundancy/Kconfig @@ -0,0 +1,12 @@ +menuconfig MODULES_REDUNDANCY + bool "Redundant FCs present" + default n + ---help--- + Enable support for FC redundancy, i.e. multiple FCs on the drone + +menuconfig USER_REDUNDANCY + bool "Redundancy running as userspace module" + default y + depends on BOARD_PROTECTED && MODULES_REDUNDANCY + ---help--- + Put redundancy in userspace memory diff --git a/src/modules/redundancy/redundancy.cpp b/src/modules/redundancy/redundancy.cpp new file mode 100644 index 000000000000..e31d406ae52b --- /dev/null +++ b/src/modules/redundancy/redundancy.cpp @@ -0,0 +1,161 @@ +/**************************************************************************** + * + * Copyright (c) 2024 Technology Innovation Institute. 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. + * + ****************************************************************************/ + +#include "redundancy.h" +#include +#include +#include +#include + +using namespace time_literals; + +const unsigned REDUNDANCY_INTERVAL_MS = 10_ms; + +Redundancy::Redundancy() : + ModuleParams(nullptr), + ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::nav_and_controllers) +{ +} + +Redundancy::~Redundancy() +{ +} + +bool Redundancy::send_vehicle_command(uint16_t cmd, float param1 = NAN, float param2 = NAN) +{ + vehicle_command_s vcmd = {}; + vcmd.timestamp = hrt_absolute_time(); + vcmd.param1 = param1; + vcmd.param2 = param2; + vcmd.param3 = NAN; + vcmd.param4 = NAN; + vcmd.param5 = (double)NAN; + vcmd.param6 = (double)NAN; + vcmd.param7 = NAN; + vcmd.command = cmd; + vcmd.target_system = _status.system_id; + vcmd.target_component = _status.component_id; + + // publish the vehicle command + return _pub_vehicle_command.publish(vcmd); +} + +void Redundancy::manage_arming() +{ +} + +void Redundancy::manage_disarming() +{ +} + +void Redundancy::Run() +{ + _status_sub.copy(&_status); + _landed_sub.copy(&_landed); + + for (int i = 0; i < vehicle_status_s::MAX_REDUNDANT_CONTROLLERS; i++) { + _redundant_status_sub[i].copy(&_redundant_status[i]); + } + + if (_status.arming_state != vehicle_status_s::ARMING_STATE_ARMED) { + manage_arming(); + + } else { + manage_disarming(); + } + + if (should_exit()) { + exit_and_cleanup(); + return; + } + + ScheduleDelayed(REDUNDANCY_INTERVAL_MS); +} + +int Redundancy::task_spawn(int argc, char *argv[]) +{ + Redundancy *instance = new Redundancy(); + + if (instance) { + _object.store(instance); + _task_id = task_id_is_work_queue; + + instance->ScheduleNow(); + + return PX4_OK; + + } else { + PX4_ERR("alloc failed"); + } + + delete instance; + _object.store(nullptr); + _task_id = -1; + + return PX4_ERROR; +} + + +int Redundancy::custom_command(int argc, char *argv[]) +{ + print_usage("unrecognized command"); + + return 0; +} + +int Redundancy::print_usage(const char *reason) +{ + if (reason) { + printf("%s\n\n", reason); + } + + PRINT_MODULE_DESCRIPTION( + R"DESCR_STR( +### Description +Background process running periodically to perform redundancy related tasks, +such as arming / disarming redundant FCs and doing fault detection and handling + +The tasks can be started via CLI +)DESCR_STR"); + + PRINT_MODULE_USAGE_NAME("redundancy", "system"); + PRINT_MODULE_USAGE_COMMAND("start"); + PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); + + return 0; +} + +extern "C" __EXPORT int redundancy_main(int argc, char *argv[]) +{ + return Redundancy::main(argc, argv); +} diff --git a/src/modules/redundancy/redundancy.h b/src/modules/redundancy/redundancy.h new file mode 100644 index 000000000000..c5cbd27f51ff --- /dev/null +++ b/src/modules/redundancy/redundancy.h @@ -0,0 +1,84 @@ +/**************************************************************************** + * + * Copyright (c) 2024 Technology Innovation Institute. 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 +#include +#include + +#include +#include +#include +#include +#include + +class Redundancy final : public ModuleBase, public ModuleParams, public px4::ScheduledWorkItem +{ +public: + Redundancy(); + ~Redundancy() override; + + /** @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); + + /** @see ModuleBase::run() */ + void Run() override; + +private: + uORB::Subscription _status_sub{ORB_ID(vehicle_status)}; + vehicle_status_s _status; + + uORB::Subscription _redundant_status_sub[vehicle_status_s::MAX_REDUNDANT_CONTROLLERS] {ORB_ID(vehicle_status), ORB_ID(vehicle_status)}; + vehicle_status_s _redundant_status[vehicle_status_s::MAX_REDUNDANT_CONTROLLERS]; + + uORB::Subscription _landed_sub{ORB_ID(vehicle_land_detected)};; + vehicle_land_detected_s _landed; + + uORB::Publication _pub_vehicle_command{ORB_ID(vehicle_command)}; + + uint16_t _redundant_fc_arming{0}; + uint16_t _redundant_fc_disarming{0}; + + bool send_vehicle_command(uint16_t cmd, float param1, float param2); + + void manage_arming(); + void manage_disarming(); + +};