From a0fc4e49df159f1451424e5f01ae2a436f24c965 Mon Sep 17 00:00:00 2001 From: Jacob Dahl Date: Tue, 17 Mar 2026 21:55:31 -0800 Subject: [PATCH] refactor(drivers/camera_trigger): convert params.c to module.yaml Convert 1 parameter file(s) from legacy C format to YAML module configuration. --- src/drivers/camera_trigger/CMakeLists.txt | 2 + .../camera_trigger/camera_trigger_params.c | 165 ------------------ .../camera_trigger/camera_trigger_params.yaml | 107 ++++++++++++ 3 files changed, 109 insertions(+), 165 deletions(-) delete mode 100644 src/drivers/camera_trigger/camera_trigger_params.c create mode 100644 src/drivers/camera_trigger/camera_trigger_params.yaml diff --git a/src/drivers/camera_trigger/CMakeLists.txt b/src/drivers/camera_trigger/CMakeLists.txt index 77604edfc0..8d1d6ba228 100644 --- a/src/drivers/camera_trigger/CMakeLists.txt +++ b/src/drivers/camera_trigger/CMakeLists.txt @@ -48,6 +48,8 @@ px4_add_module( interfaces/src/pwm.cpp interfaces/src/seagull_map2.cpp interfaces/src/gpio.cpp + MODULE_CONFIG + camera_trigger_params.yaml DEPENDS px4_work_queue ) diff --git a/src/drivers/camera_trigger/camera_trigger_params.c b/src/drivers/camera_trigger/camera_trigger_params.c deleted file mode 100644 index 54e0fd3175..0000000000 --- a/src/drivers/camera_trigger/camera_trigger_params.c +++ /dev/null @@ -1,165 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2015-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. - * - ****************************************************************************/ - -/** - * @file camera_trigger_params.c - * Camera trigger parameters - * - * @author Mohammed Kabir - * @author Andreas Bircher - * @author Lorenz Meier - */ - -/** -* Camera trigger Interface -* -* Selects the trigger interface -* -* @value 1 GPIO -* @value 2 Seagull MAP2 (over PWM) -* @value 3 MAVLink (Camera Protocol v1) -* @value 4 Generic PWM (IR trigger, servo) -* -* @reboot_required true -* @group Camera trigger -*/ -PARAM_DEFINE_INT32(TRIG_INTERFACE, 4); - -/** - * Camera trigger interval - * - * This parameter sets the time between two consecutive trigger events - * - * @unit ms - * @min 4.0 - * @max 10000.0 - * @decimal 1 - * @reboot_required true - * @group Camera trigger - */ -PARAM_DEFINE_FLOAT(TRIG_INTERVAL, 40.0f); - -/** - * Minimum camera trigger interval - * - * This parameter sets the minimum time between two consecutive trigger events - * the specific camera setup is supporting. - * - * @unit ms - * @min 1.0 - * @max 10000.0 - * @decimal 1 - * @reboot_required true - * @group Camera trigger - */ -PARAM_DEFINE_FLOAT(TRIG_MIN_INTERVA, 1.0f); - -/** - * Camera trigger polarity - * - * This parameter sets the polarity of the trigger (0 = active low, 1 = active high ) - * - * @value 0 Active low - * @value 1 Active high - * @min 0 - * @max 1 - * @reboot_required true - * @group Camera trigger - */ -PARAM_DEFINE_INT32(TRIG_POLARITY, 0); - -/** - * Camera trigger activation time - * - * This parameter sets the time the trigger needs to pulled high or low. - * - * @unit ms - * @min 0.1 - * @max 3000 - * @decimal 1 - * @reboot_required true - * @group Camera trigger - */ -PARAM_DEFINE_FLOAT(TRIG_ACT_TIME, 40.0f); - -/** - * Camera trigger mode - * - * @value 0 Disable - * @value 1 Time based, on command - * @value 2 Time based, always on - * @value 3 Distance based, always on - * @value 4 Distance based, on command (Survey mode) - * @min 0 - * @max 4 - * @reboot_required true - * @group Camera trigger - */ -PARAM_DEFINE_INT32(TRIG_MODE, 0); - -/** - * Camera trigger distance - * - * Sets the distance at which to trigger the camera. - * - * @unit m - * @min 0 - * @increment 1 - * @decimal 1 - * @reboot_required true - * @group Camera trigger - */ -PARAM_DEFINE_FLOAT(TRIG_DISTANCE, 25.0f); - -/** - * PWM output to trigger shot. - * - * @min 1000 - * @max 2000 - * @unit us - * @group Camera trigger - * @reboot_required true - */ -PARAM_DEFINE_INT32(TRIG_PWM_SHOOT, 1900); - - -/** - * PWM neutral output on trigger pin. - * - * @min 1000 - * @max 2000 - * @unit us - * @group Camera trigger - * @reboot_required true - */ -PARAM_DEFINE_INT32(TRIG_PWM_NEUTRAL, 1500); diff --git a/src/drivers/camera_trigger/camera_trigger_params.yaml b/src/drivers/camera_trigger/camera_trigger_params.yaml new file mode 100644 index 0000000000..6d8330fcb1 --- /dev/null +++ b/src/drivers/camera_trigger/camera_trigger_params.yaml @@ -0,0 +1,107 @@ +module_name: camera_trigger +parameters: +- group: Camera trigger + definitions: + TRIG_INTERFACE: + description: + short: Camera trigger Interface + long: Selects the trigger interface + type: enum + values: + 1: GPIO + 2: Seagull MAP2 (over PWM) + 3: MAVLink (Camera Protocol v1) + 4: Generic PWM (IR trigger, servo) + default: 4 + reboot_required: true + TRIG_INTERVAL: + description: + short: Camera trigger interval + long: This parameter sets the time between two consecutive trigger events + type: float + default: 40.0 + unit: ms + min: 4.0 + max: 10000.0 + decimal: 1 + reboot_required: true + TRIG_MIN_INTERVA: + description: + short: Minimum camera trigger interval + long: |- + This parameter sets the minimum time between two consecutive trigger events + the specific camera setup is supporting. + type: float + default: 1.0 + unit: ms + min: 1.0 + max: 10000.0 + decimal: 1 + reboot_required: true + TRIG_POLARITY: + description: + short: Camera trigger polarity + long: This parameter sets the polarity of the trigger (0 = active low, 1 = + active high ) + type: enum + values: + 0: Active low + 1: Active high + default: 0 + min: 0 + max: 1 + reboot_required: true + TRIG_ACT_TIME: + description: + short: Camera trigger activation time + long: This parameter sets the time the trigger needs to pulled high or low. + type: float + default: 40.0 + unit: ms + min: 0.1 + max: 3000 + decimal: 1 + reboot_required: true + TRIG_MODE: + description: + short: Camera trigger mode + type: enum + values: + 0: Disable + 1: Time based, on command + 2: Time based, always on + 3: Distance based, always on + 4: Distance based, on command (Survey mode) + default: 0 + min: 0 + max: 4 + reboot_required: true + TRIG_DISTANCE: + description: + short: Camera trigger distance + long: Sets the distance at which to trigger the camera. + type: float + default: 25.0 + unit: m + min: 0 + increment: 1 + decimal: 1 + reboot_required: true + TRIG_PWM_SHOOT: + description: + short: PWM output to trigger shot + type: int32 + default: 1900 + min: 1000 + max: 2000 + unit: us + reboot_required: true + TRIG_PWM_NEUTRAL: + description: + short: PWM neutral output on trigger pin + type: int32 + default: 1500 + min: 1000 + max: 2000 + unit: us + reboot_required: true