refactor(drivers/uavcan): convert params.c to module.yaml

Convert 1 parameter file(s) from legacy C format to YAML
module configuration.
This commit is contained in:
Jacob Dahl 2026-03-17 21:55:33 -08:00 committed by Jacob Dahl
parent 15b6dc442c
commit 5586a666c6
3 changed files with 290 additions and 388 deletions

View File

@ -184,6 +184,7 @@ px4_add_module(
sensors/safety_button.cpp
MODULE_CONFIG
module.yaml
uavcan_params.yaml
DEPENDS
px4_uavcan_dsdlc

View File

@ -1,388 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2014-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.
*
****************************************************************************/
/**
* @author Pavel Kirienko <pavel.kirienko@gmail.com>
*/
/**
* UAVCAN mode
*
* 0 - UAVCAN disabled.
* 1 - Enables support for UAVCAN sensors without dynamic node ID allocation and firmware update.
* 2 - Enables support for UAVCAN sensors with dynamic node ID allocation and firmware update.
* 3 - Enables support for UAVCAN sensors and actuators with dynamic node ID allocation and firmware update. Also sets the motor control outputs to UAVCAN.
*
* @min 0
* @max 3
* @value 0 Disabled
* @value 1 Sensors Manual Config
* @value 2 Sensors Automatic Config
* @value 3 Sensors and Actuators (ESCs) Automatic Config
* @reboot_required true
* @group UAVCAN
*/
PARAM_DEFINE_INT32(UAVCAN_ENABLE, 0);
/**
* UAVCAN Node ID.
*
* Read the specs at https://dronecan.github.io/ to learn more about Node ID.
*
* @min 1
* @max 125
* @reboot_required true
* @group UAVCAN
*/
PARAM_DEFINE_INT32(UAVCAN_NODE_ID, 1);
/**
* UAVCAN CAN bus bitrate.
*
* @unit bit/s
* @min 20000
* @max 1000000
* @reboot_required true
* @group UAVCAN
*/
PARAM_DEFINE_INT32(UAVCAN_BITRATE, 1000000);
/**
* UAVCAN rangefinder minimum range
*
* This parameter defines the minimum valid range for a rangefinder connected via UAVCAN.
*
* @unit m
* @group UAVCAN
*/
PARAM_DEFINE_FLOAT(UAVCAN_RNG_MIN, 0.0f);
/**
* UAVCAN rangefinder maximum range
*
* This parameter defines the maximum valid range for a rangefinder connected via UAVCAN.
*
* @unit m
* @group UAVCAN
*/
PARAM_DEFINE_FLOAT(UAVCAN_RNG_MAX, 999.0f);
/**
* UAVCAN fuel tank maximum capacity
*
* This parameter defines the maximum fuel capacity of the vehicle's fuel tank.
*
* @min 0.0
* @max 100000.0
* @unit liters
* @decimal 1
* @increment 0.1
* @reboot_required true
* @group UAVCAN
*/
PARAM_DEFINE_FLOAT(UAVCAN_ECU_MAXF, 15.0f);
/**
* UAVCAN fuel tank fuel type
*
* This parameter defines the type of fuel used in the vehicle's fuel tank.
*
* 0: Unknown
* 1: Liquid (e.g., gasoline, diesel)
* 2: Gas (e.g., hydrogen, methane, propane)
*
* @min 0
* @max 2
* @value 0 Unknown
* @value 1 Liquid
* @value 2 Gas
* @reboot_required true
* @group UAVCAN
*/
PARAM_DEFINE_INT32(UAVCAN_ECU_FUELT, 1);
/**
* UAVCAN Navigation light operating mode
*
* This parameter defines the minimum condition under which the system will command
* Navigation lights to turn on. Affects lights with functions: Anti-collision, Colored Navigation Lights or Hybrid lights.
*
* For hybrid functions (StatusOrAntiCollision, etc.), the light
* displays status colors when this mode is inactive, and switches to the
* navigation light function when this mode becomes active.
*
* 0 - Always off
* 1 - When autopilot is armed
* 2 - When autopilot is prearmed
* 3 - Always on
*
* @min 0
* @max 3
* @value 0 Always off
* @value 1 When autopilot is armed
* @value 2 When autopilot is prearmed
* @value 3 Always on
* @reboot_required true
* @group UAVCAN
*/
PARAM_DEFINE_INT32(UAVCAN_LGT_MODE, 1);
/**
* publish Arming Status stream
*
* Enable UAVCAN Arming Status stream publication
* uavcan::equipment::safety::ArmingStatus
*
* @boolean
* @reboot_required true
* @group UAVCAN
*/
PARAM_DEFINE_INT32(UAVCAN_PUB_ARM, 0);
/**
* publish RTCM stream
*
* Enable UAVCAN RTCM stream publication
* uavcan::equipment::gnss::RTCMStream
*
* @boolean
* @reboot_required true
* @group UAVCAN
*/
PARAM_DEFINE_INT32(UAVCAN_PUB_RTCM, 0);
/**
* publish moving baseline data RTCM stream
*
* Enable UAVCAN RTCM stream publication
* ardupilot::gnss::MovingBaselineData
*
* @boolean
* @reboot_required true
* @group UAVCAN
*/
PARAM_DEFINE_INT32(UAVCAN_PUB_MBD, 0);
/**
* subscription airspeed
*
* Enable UAVCAN airspeed subscriptions.
* uavcan::equipment::air_data::IndicatedAirspeed
* uavcan::equipment::air_data::TrueAirspeed
* uavcan::equipment::air_data::StaticTemperature
*
* @boolean
* @reboot_required true
* @group UAVCAN
*/
PARAM_DEFINE_INT32(UAVCAN_SUB_ASPD, 0);
/**
* subscription barometer
*
* Enable UAVCAN barometer subscription.
* uavcan::equipment::air_data::StaticPressure
* uavcan::equipment::air_data::StaticTemperature
*
* @boolean
* @reboot_required true
* @group UAVCAN
*/
PARAM_DEFINE_INT32(UAVCAN_SUB_BARO, 0);
/**
* subscription battery
*
* Enable UAVCAN battery subscription.
* uavcan::equipment::power::BatteryInfo
* ardupilot::equipment::power::BatteryInfoAux
* cuav::equipment::power::CBAT
*
* 0 - Disable
* 1 - Use raw data. Recommended for Smart battery
* 2 - Filter the data with internal battery library (unsupported with CBAT)
*
* @min 0
* @max 2
* @value 0 Disable
* @value 1 Raw data
* @value 2 Filter data
* @reboot_required true
* @group UAVCAN
*/
PARAM_DEFINE_INT32(UAVCAN_SUB_BAT, 0);
/**
* subscription differential pressure
*
* Enable UAVCAN differential pressure subscription.
* uavcan::equipment::air_data::RawAirData
*
* @boolean
* @reboot_required true
* @group UAVCAN
*/
PARAM_DEFINE_INT32(UAVCAN_SUB_DPRES, 0);
/**
* subscription flow
*
* Enable UAVCAN optical flow subscription.
*
* @boolean
* @reboot_required true
* @group UAVCAN
*/
PARAM_DEFINE_INT32(UAVCAN_SUB_FLOW, 0);
/**
* subscription fuel tank
*
* Enable UAVCAN fuel tank status subscription.
*
* @boolean
* @reboot_required true
* @group UAVCAN
*/
PARAM_DEFINE_INT32(UAVCAN_SUB_FUEL, 0);
/**
* subscription GPS
*
* Enable UAVCAN GPS subscriptions.
* uavcan::equipment::gnss::Fix
* uavcan::equipment::gnss::Fix2
* uavcan::equipment::gnss::Auxiliary
*
* @boolean
* @reboot_required true
* @group UAVCAN
*/
PARAM_DEFINE_INT32(UAVCAN_SUB_GPS, 1);
/**
* subscription GPS Relative
*
* Enable UAVCAN GPS Relative subscription.
* ardupilot::gnss::RelPosHeading
*
* @boolean
* @reboot_required true
* @group UAVCAN
*/
PARAM_DEFINE_INT32(UAVCAN_SUB_GPS_R, 1);
/**
* subscription hygrometer
*
* Enable UAVCAN hygrometer subscriptions.
* dronecan::sensors::hygrometer::Hygrometer
*
* @boolean
* @reboot_required true
* @group UAVCAN
*/
PARAM_DEFINE_INT32(UAVCAN_SUB_HYGRO, 0);
/**
* subscription ICE
*
* Enable UAVCAN internal combustion engine (ICE) subscription.
* uavcan::equipment::ice::reciprocating::Status
*
* @boolean
* @reboot_required true
* @group UAVCAN
*/
PARAM_DEFINE_INT32(UAVCAN_SUB_ICE, 0);
/**
* subscription IMU
*
* Enable UAVCAN IMU subscription.
* uavcan::equipment::ahrs::RawIMU
*
* @boolean
* @reboot_required true
* @group UAVCAN
*/
PARAM_DEFINE_INT32(UAVCAN_SUB_IMU, 0);
/**
* subscription magnetometer
*
* Enable UAVCAN mag subscription.
* uavcan::equipment::ahrs::MagneticFieldStrength
* uavcan::equipment::ahrs::MagneticFieldStrength2
*
* @boolean
* @reboot_required true
* @group UAVCAN
*/
PARAM_DEFINE_INT32(UAVCAN_SUB_MAG, 1);
/**
* subscription range finder
*
* Enable UAVCAN range finder subscription.
* uavcan::equipment::range_sensor::Measurement
*
* @boolean
* @reboot_required true
* @group UAVCAN
*/
PARAM_DEFINE_INT32(UAVCAN_SUB_RNG, 0);
/**
* subscription button
*
* Enable UAVCAN button subscription.
* ardupilot::indication::Button
*
* @boolean
* @reboot_required true
* @group UAVCAN
*/
PARAM_DEFINE_INT32(UAVCAN_SUB_BTN, 0);
/**
* subscription MovingBaselineData
*
* Enable UAVCAN MovingBaselineData subscription.
* ardupilot::gnss::MovingBaselineData
*
* @boolean
* @reboot_required true
* @group UAVCAN
*/
PARAM_DEFINE_INT32(UAVCAN_SUB_MBD, 0);

View File

@ -0,0 +1,289 @@
module_name: uavcan
parameters:
- group: UAVCAN
definitions:
UAVCAN_ENABLE:
description:
short: UAVCAN mode
long: |-
0 - UAVCAN disabled.
1 - Enables support for UAVCAN sensors without dynamic node ID allocation and firmware update.
2 - Enables support for UAVCAN sensors with dynamic node ID allocation and firmware update.
3 - Enables support for UAVCAN sensors and actuators with dynamic node ID allocation and firmware update. Also sets the motor control outputs to UAVCAN.
type: enum
values:
0: Disabled
1: Sensors Manual Config
2: Sensors Automatic Config
3: Sensors and Actuators (ESCs) Automatic Config
default: 0
min: 0
max: 3
reboot_required: true
UAVCAN_NODE_ID:
description:
short: UAVCAN Node ID
long: Read the specs at https://dronecan.github.io/ to learn more about Node
ID.
type: int32
default: 1
min: 1
max: 125
reboot_required: true
UAVCAN_BITRATE:
description:
short: UAVCAN CAN bus bitrate
type: int32
default: 1000000
unit: bit/s
min: 20000
max: 1000000
reboot_required: true
UAVCAN_RNG_MIN:
description:
short: UAVCAN rangefinder minimum range
long: This parameter defines the minimum valid range for a rangefinder connected
via UAVCAN.
type: float
default: 0.0
unit: m
UAVCAN_RNG_MAX:
description:
short: UAVCAN rangefinder maximum range
long: This parameter defines the maximum valid range for a rangefinder connected
via UAVCAN.
type: float
default: 999.0
unit: m
UAVCAN_ECU_MAXF:
description:
short: UAVCAN fuel tank maximum capacity
long: This parameter defines the maximum fuel capacity of the vehicle's fuel
tank.
type: float
default: 15.0
min: 0.0
max: 100000.0
unit: liters
decimal: 1
increment: 0.1
reboot_required: true
UAVCAN_ECU_FUELT:
description:
short: UAVCAN fuel tank fuel type
long: |-
This parameter defines the type of fuel used in the vehicle's fuel tank.
0: Unknown
1: Liquid (e.g., gasoline, diesel)
2: Gas (e.g., hydrogen, methane, propane)
type: enum
values:
0: Unknown
1: Liquid
2: Gas
default: 1
min: 0
max: 2
reboot_required: true
UAVCAN_LGT_MODE:
description:
short: UAVCAN Navigation light operating mode
long: |-
This parameter defines the minimum condition under which the system will command
Navigation lights to turn on. Affects lights with functions: Anti-collision, Colored Navigation Lights or Hybrid lights.
For hybrid functions (StatusOrAntiCollision, etc.), the light
displays status colors when this mode is inactive, and switches to the
navigation light function when this mode becomes active.
0 - Always off
1 - When autopilot is armed
2 - When autopilot is prearmed
3 - Always on
type: enum
values:
0: Always off
1: When autopilot is armed
2: When autopilot is prearmed
3: Always on
default: 1
min: 0
max: 3
reboot_required: true
UAVCAN_PUB_ARM:
description:
short: publish Arming Status stream
long: |-
Enable UAVCAN Arming Status stream publication
uavcan::equipment::safety::ArmingStatus
type: boolean
default: 0
reboot_required: true
UAVCAN_PUB_RTCM:
description:
short: publish RTCM stream
long: |-
Enable UAVCAN RTCM stream publication
uavcan::equipment::gnss::RTCMStream
type: boolean
default: 0
reboot_required: true
UAVCAN_PUB_MBD:
description:
short: publish moving baseline data RTCM stream
long: |-
Enable UAVCAN RTCM stream publication
ardupilot::gnss::MovingBaselineData
type: boolean
default: 0
reboot_required: true
UAVCAN_SUB_ASPD:
description:
short: subscription airspeed
long: |-
Enable UAVCAN airspeed subscriptions.
uavcan::equipment::air_data::IndicatedAirspeed
uavcan::equipment::air_data::TrueAirspeed
uavcan::equipment::air_data::StaticTemperature
type: boolean
default: 0
reboot_required: true
UAVCAN_SUB_BARO:
description:
short: subscription barometer
long: |-
Enable UAVCAN barometer subscription.
uavcan::equipment::air_data::StaticPressure
uavcan::equipment::air_data::StaticTemperature
type: boolean
default: 0
reboot_required: true
UAVCAN_SUB_BAT:
description:
short: subscription battery
long: |-
Enable UAVCAN battery subscription.
uavcan::equipment::power::BatteryInfo
ardupilot::equipment::power::BatteryInfoAux
cuav::equipment::power::CBAT
0 - Disable
1 - Use raw data. Recommended for Smart battery
2 - Filter the data with internal battery library (unsupported with CBAT)
type: enum
values:
0: Disable
1: Raw data
2: Filter data
default: 0
min: 0
max: 2
reboot_required: true
UAVCAN_SUB_DPRES:
description:
short: subscription differential pressure
long: |-
Enable UAVCAN differential pressure subscription.
uavcan::equipment::air_data::RawAirData
type: boolean
default: 0
reboot_required: true
UAVCAN_SUB_FLOW:
description:
short: subscription flow
long: Enable UAVCAN optical flow subscription.
type: boolean
default: 0
reboot_required: true
UAVCAN_SUB_FUEL:
description:
short: subscription fuel tank
long: Enable UAVCAN fuel tank status subscription.
type: boolean
default: 0
reboot_required: true
UAVCAN_SUB_GPS:
description:
short: subscription GPS
long: |-
Enable UAVCAN GPS subscriptions.
uavcan::equipment::gnss::Fix
uavcan::equipment::gnss::Fix2
uavcan::equipment::gnss::Auxiliary
type: boolean
default: 1
reboot_required: true
UAVCAN_SUB_GPS_R:
description:
short: subscription GPS Relative
long: |-
Enable UAVCAN GPS Relative subscription.
ardupilot::gnss::RelPosHeading
type: boolean
default: 1
reboot_required: true
UAVCAN_SUB_HYGRO:
description:
short: subscription hygrometer
long: |-
Enable UAVCAN hygrometer subscriptions.
dronecan::sensors::hygrometer::Hygrometer
type: boolean
default: 0
reboot_required: true
UAVCAN_SUB_ICE:
description:
short: subscription ICE
long: |-
Enable UAVCAN internal combustion engine (ICE) subscription.
uavcan::equipment::ice::reciprocating::Status
type: boolean
default: 0
reboot_required: true
UAVCAN_SUB_IMU:
description:
short: subscription IMU
long: |-
Enable UAVCAN IMU subscription.
uavcan::equipment::ahrs::RawIMU
type: boolean
default: 0
reboot_required: true
UAVCAN_SUB_MAG:
description:
short: subscription magnetometer
long: |-
Enable UAVCAN mag subscription.
uavcan::equipment::ahrs::MagneticFieldStrength
uavcan::equipment::ahrs::MagneticFieldStrength2
type: boolean
default: 1
reboot_required: true
UAVCAN_SUB_RNG:
description:
short: subscription range finder
long: |-
Enable UAVCAN range finder subscription.
uavcan::equipment::range_sensor::Measurement
type: boolean
default: 0
reboot_required: true
UAVCAN_SUB_BTN:
description:
short: subscription button
long: |-
Enable UAVCAN button subscription.
ardupilot::indication::Button
type: boolean
default: 0
reboot_required: true
UAVCAN_SUB_MBD:
description:
short: subscription MovingBaselineData
long: |-
Enable UAVCAN MovingBaselineData subscription.
ardupilot::gnss::MovingBaselineData
type: boolean
default: 0
reboot_required: true