mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
refactor(gimbal): convert params.c to module.yaml
Convert 1 parameter file(s) from legacy C format to YAML module configuration.
This commit is contained in:
parent
664cd01d2e
commit
14effea50d
@ -43,6 +43,8 @@ px4_add_module(
|
||||
output_mavlink.cpp
|
||||
output_rc.cpp
|
||||
gimbal.cpp
|
||||
MODULE_CONFIG
|
||||
gimbal_params.yaml
|
||||
DEPENDS
|
||||
geo
|
||||
)
|
||||
|
||||
@ -1,271 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2013-2020 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
|
||||
/**
|
||||
* Mount input mode
|
||||
*
|
||||
* This is the protocol used between the ground station and the autopilot.
|
||||
*
|
||||
* Recommended is Auto, RC only or MAVLink gimbal protocol v2.
|
||||
* The rest will be deprecated.
|
||||
*
|
||||
* @value -1 DISABLED
|
||||
* @value 0 Auto (RC and MAVLink gimbal protocol v2)
|
||||
* @value 1 RC
|
||||
* @value 2 MAVLINK_ROI (protocol v1, to be deprecated)
|
||||
* @value 3 MAVLINK_DO_MOUNT (protocol v1, to be deprecated)
|
||||
* @value 4 MAVlink gimbal protocol v2
|
||||
* @min -1
|
||||
* @max 4
|
||||
* @group Mount
|
||||
* @reboot_required true
|
||||
*/
|
||||
PARAM_DEFINE_INT32(MNT_MODE_IN, -1);
|
||||
|
||||
/**
|
||||
* Mount output mode
|
||||
*
|
||||
* This is the protocol used between the autopilot and a connected gimbal.
|
||||
*
|
||||
* Recommended is the MAVLink gimbal protocol v2 if the gimbal supports it.
|
||||
*
|
||||
* @value 0 AUX
|
||||
* @value 1 MAVLink gimbal protocol v1
|
||||
* @value 2 MAVLink gimbal protocol v2
|
||||
* @min 0
|
||||
* @max 2
|
||||
* @group Mount
|
||||
* @reboot_required true
|
||||
*/
|
||||
PARAM_DEFINE_INT32(MNT_MODE_OUT, 0);
|
||||
|
||||
/**
|
||||
* Mavlink System ID of the mount
|
||||
*
|
||||
* If MNT_MODE_OUT is MAVLink gimbal protocol v1, mount configure/control commands will be sent with this target ID.
|
||||
*
|
||||
* @group Mount
|
||||
*/
|
||||
PARAM_DEFINE_INT32(MNT_MAV_SYSID, 1);
|
||||
|
||||
/**
|
||||
* Mavlink Component ID of the mount
|
||||
*
|
||||
* If MNT_MODE_OUT is MAVLink protocol v2, mount configure/control commands will be sent with this component ID.
|
||||
*
|
||||
* @group Mount
|
||||
*/
|
||||
PARAM_DEFINE_INT32(MNT_MAV_COMPID, 154);
|
||||
|
||||
/**
|
||||
* Auxiliary channel to control roll (in AUX input or manual mode).
|
||||
*
|
||||
* @value 0 Disable
|
||||
* @value 1 AUX1
|
||||
* @value 2 AUX2
|
||||
* @value 3 AUX3
|
||||
* @value 4 AUX4
|
||||
* @value 5 AUX5
|
||||
* @value 6 AUX6
|
||||
* @min 0
|
||||
* @max 6
|
||||
* @group Mount
|
||||
*/
|
||||
PARAM_DEFINE_INT32(MNT_MAN_ROLL, 0);
|
||||
|
||||
/**
|
||||
* Auxiliary channel to control pitch (in AUX input or manual mode).
|
||||
*
|
||||
* @value 0 Disable
|
||||
* @value 1 AUX1
|
||||
* @value 2 AUX2
|
||||
* @value 3 AUX3
|
||||
* @value 4 AUX4
|
||||
* @value 5 AUX5
|
||||
* @value 6 AUX6
|
||||
* @min 0
|
||||
* @max 6
|
||||
* @group Mount
|
||||
*/
|
||||
PARAM_DEFINE_INT32(MNT_MAN_PITCH, 0);
|
||||
|
||||
/**
|
||||
* Auxiliary channel to control yaw (in AUX input or manual mode).
|
||||
*
|
||||
* @value 0 Disable
|
||||
* @value 1 AUX1
|
||||
* @value 2 AUX2
|
||||
* @value 3 AUX3
|
||||
* @value 4 AUX4
|
||||
* @value 5 AUX5
|
||||
* @value 6 AUX6
|
||||
* @min 0
|
||||
* @max 6
|
||||
* @group Mount
|
||||
*/
|
||||
PARAM_DEFINE_INT32(MNT_MAN_YAW, 0);
|
||||
|
||||
/**
|
||||
* Stabilize the mount
|
||||
*
|
||||
* Set to true for servo gimbal, false for passthrough.
|
||||
* This is required for a gimbal which is not capable of stabilizing itself
|
||||
* and relies on the IMU's attitude estimation.
|
||||
*
|
||||
* @value 0 Disable
|
||||
* @value 1 Stabilize all axis
|
||||
* @value 2 Stabilize yaw for absolute/lock mode.
|
||||
* @value 3 Stabilize pitch for absolute/lock mode.
|
||||
* @group Mount
|
||||
*/
|
||||
PARAM_DEFINE_INT32(MNT_DO_STAB, 0);
|
||||
|
||||
/**
|
||||
* Max positive angle of pitch setpoint (only in MNT_MODE_OUT=AUX).
|
||||
*
|
||||
* Use output driver settings to calibrate (e.g. PWM_CENT/_MIN/_MAX).
|
||||
*
|
||||
* @unit deg
|
||||
* @decimal 1
|
||||
* @group Mount
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MNT_MAX_PITCH, 45.0f);
|
||||
|
||||
/**
|
||||
* Min negative angle of pitch setpoint (only in MNT_MODE_OUT=AUX).
|
||||
*
|
||||
* Use output driver settings to calibrate (e.g. PWM_CENT/_MIN/_MAX).
|
||||
*
|
||||
* @unit deg
|
||||
* @decimal 1
|
||||
* @group Mount
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MNT_MIN_PITCH, -45.0f);
|
||||
|
||||
/**
|
||||
* Range of roll channel output (only in MNT_MODE_OUT=AUX).
|
||||
*
|
||||
* Use output driver settings to calibrate (e.g. PWM_CENT/_MIN/_MAX). Note that only symmetric angular ranges are supported.
|
||||
*
|
||||
* @min 1.0
|
||||
* @max 720.0
|
||||
* @unit deg
|
||||
* @decimal 1
|
||||
* @group Mount
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MNT_RANGE_ROLL, 90.0f);
|
||||
|
||||
/**
|
||||
* Range of yaw channel output (only in MNT_MODE_OUT=AUX).
|
||||
*
|
||||
* Use output driver settings to calibrate (e.g. PWM_CENT/_MIN/_MAX). Note that only symmetric angular ranges are supported.
|
||||
*
|
||||
* @min 1.0
|
||||
* @max 720.0
|
||||
* @unit deg
|
||||
* @decimal 1
|
||||
* @group Mount
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MNT_RANGE_YAW, 360.0f);
|
||||
|
||||
|
||||
/**
|
||||
* Angular pitch rate for manual input in degrees/second.
|
||||
*
|
||||
* Full stick input [-1..1] translats to [-pitch rate..pitch rate].
|
||||
*
|
||||
* @min 1.0
|
||||
* @max 90.0
|
||||
* @unit deg/s
|
||||
* @group Mount
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MNT_RATE_PITCH, 30.0f);
|
||||
|
||||
/**
|
||||
* Angular yaw rate for manual input in degrees/second.
|
||||
*
|
||||
* Full stick input [-1..1] translats to [-yaw rate..yaw rate].
|
||||
*
|
||||
* @min 1.0
|
||||
* @max 90.0
|
||||
* @unit deg/s
|
||||
* @group Mount
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MNT_RATE_YAW, 30.0f);
|
||||
|
||||
/**
|
||||
* Alpha filter time constant defining the convergence rate (in seconds) for open-loop AUX mount control.
|
||||
*
|
||||
* Use when no angular position feedback is available.
|
||||
* With MNT_MODE_OUT set to AUX, the mount operates in open-loop and directly commands the servo output.
|
||||
* Parameters must be tuned for the specific servo to approximate its speed and response.
|
||||
*
|
||||
* @min 0.0
|
||||
* @group Mount
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MNT_TAU, 0.3f);
|
||||
|
||||
|
||||
/**
|
||||
* Input mode for RC gimbal input
|
||||
*
|
||||
* @value 0 Angle
|
||||
* @value 1 Angular rate
|
||||
* @min 0
|
||||
* @max 1
|
||||
* @group Mount
|
||||
*/
|
||||
PARAM_DEFINE_INT32(MNT_RC_IN_MODE, 1);
|
||||
|
||||
/**
|
||||
* Pitch minimum when landed
|
||||
*
|
||||
* @min -90.0
|
||||
* @max 90.0
|
||||
* @unit deg
|
||||
* @decimal 1
|
||||
* @group Mount
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MNT_LND_P_MIN, -90.0f);
|
||||
|
||||
/**
|
||||
* Pitch maximum when landed
|
||||
*
|
||||
* @min -90.0
|
||||
* @max 90.0
|
||||
* @unit deg
|
||||
* @decimal 1
|
||||
* @group Mount
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MNT_LND_P_MAX, 90.0f);
|
||||
209
src/modules/gimbal/gimbal_params.yaml
Normal file
209
src/modules/gimbal/gimbal_params.yaml
Normal file
@ -0,0 +1,209 @@
|
||||
module_name: gimbal
|
||||
parameters:
|
||||
- group: Mount
|
||||
definitions:
|
||||
MNT_MODE_IN:
|
||||
description:
|
||||
short: Mount input mode
|
||||
long: |-
|
||||
This is the protocol used between the ground station and the autopilot.
|
||||
|
||||
Recommended is Auto, RC only or MAVLink gimbal protocol v2.
|
||||
The rest will be deprecated.
|
||||
type: enum
|
||||
values:
|
||||
-1: DISABLED
|
||||
0: Auto (RC and MAVLink gimbal protocol v2)
|
||||
1: RC
|
||||
2: MAVLINK_ROI (protocol v1, to be deprecated)
|
||||
3: MAVLINK_DO_MOUNT (protocol v1, to be deprecated)
|
||||
4: MAVlink gimbal protocol v2
|
||||
default: -1
|
||||
min: -1
|
||||
max: 4
|
||||
reboot_required: true
|
||||
MNT_MODE_OUT:
|
||||
description:
|
||||
short: Mount output mode
|
||||
long: |-
|
||||
This is the protocol used between the autopilot and a connected gimbal.
|
||||
|
||||
Recommended is the MAVLink gimbal protocol v2 if the gimbal supports it.
|
||||
type: enum
|
||||
values:
|
||||
0: AUX
|
||||
1: MAVLink gimbal protocol v1
|
||||
2: MAVLink gimbal protocol v2
|
||||
default: 0
|
||||
min: 0
|
||||
max: 2
|
||||
reboot_required: true
|
||||
MNT_MAV_SYSID:
|
||||
description:
|
||||
short: Mavlink System ID of the mount
|
||||
long: If MNT_MODE_OUT is MAVLink gimbal protocol v1, mount configure/control
|
||||
commands will be sent with this target ID.
|
||||
type: int32
|
||||
default: 1
|
||||
MNT_MAV_COMPID:
|
||||
description:
|
||||
short: Mavlink Component ID of the mount
|
||||
long: If MNT_MODE_OUT is MAVLink protocol v2, mount configure/control commands
|
||||
will be sent with this component ID.
|
||||
type: int32
|
||||
default: 154
|
||||
MNT_MAN_ROLL:
|
||||
description:
|
||||
short: Auxiliary channel to control roll (in AUX input or manual mode)
|
||||
type: enum
|
||||
values:
|
||||
0: Disable
|
||||
1: AUX1
|
||||
2: AUX2
|
||||
3: AUX3
|
||||
4: AUX4
|
||||
5: AUX5
|
||||
6: AUX6
|
||||
default: 0
|
||||
min: 0
|
||||
max: 6
|
||||
MNT_MAN_PITCH:
|
||||
description:
|
||||
short: Auxiliary channel to control pitch (in AUX input or manual mode)
|
||||
type: enum
|
||||
values:
|
||||
0: Disable
|
||||
1: AUX1
|
||||
2: AUX2
|
||||
3: AUX3
|
||||
4: AUX4
|
||||
5: AUX5
|
||||
6: AUX6
|
||||
default: 0
|
||||
min: 0
|
||||
max: 6
|
||||
MNT_MAN_YAW:
|
||||
description:
|
||||
short: Auxiliary channel to control yaw (in AUX input or manual mode)
|
||||
type: enum
|
||||
values:
|
||||
0: Disable
|
||||
1: AUX1
|
||||
2: AUX2
|
||||
3: AUX3
|
||||
4: AUX4
|
||||
5: AUX5
|
||||
6: AUX6
|
||||
default: 0
|
||||
min: 0
|
||||
max: 6
|
||||
MNT_DO_STAB:
|
||||
description:
|
||||
short: Stabilize the mount
|
||||
long: |-
|
||||
Set to true for servo gimbal, false for passthrough.
|
||||
This is required for a gimbal which is not capable of stabilizing itself
|
||||
and relies on the IMU's attitude estimation.
|
||||
type: enum
|
||||
values:
|
||||
0: Disable
|
||||
1: Stabilize all axis
|
||||
2: Stabilize yaw for absolute/lock mode.
|
||||
3: Stabilize pitch for absolute/lock mode.
|
||||
default: 0
|
||||
MNT_MAX_PITCH:
|
||||
description:
|
||||
short: Max positive angle of pitch setpoint (only in MNT_MODE_OUT=AUX)
|
||||
long: Use output driver settings to calibrate (e.g. PWM_CENT/_MIN/_MAX).
|
||||
type: float
|
||||
default: 45.0
|
||||
unit: deg
|
||||
decimal: 1
|
||||
MNT_MIN_PITCH:
|
||||
description:
|
||||
short: Min negative angle of pitch setpoint (only in MNT_MODE_OUT=AUX)
|
||||
long: Use output driver settings to calibrate (e.g. PWM_CENT/_MIN/_MAX).
|
||||
type: float
|
||||
default: -45.0
|
||||
unit: deg
|
||||
decimal: 1
|
||||
MNT_RANGE_ROLL:
|
||||
description:
|
||||
short: Range of roll channel output (only in MNT_MODE_OUT=AUX)
|
||||
long: Use output driver settings to calibrate (e.g. PWM_CENT/_MIN/_MAX). Note
|
||||
that only symmetric angular ranges are supported.
|
||||
type: float
|
||||
default: 90.0
|
||||
min: 1.0
|
||||
max: 720.0
|
||||
unit: deg
|
||||
decimal: 1
|
||||
MNT_RANGE_YAW:
|
||||
description:
|
||||
short: Range of yaw channel output (only in MNT_MODE_OUT=AUX)
|
||||
long: Use output driver settings to calibrate (e.g. PWM_CENT/_MIN/_MAX). Note
|
||||
that only symmetric angular ranges are supported.
|
||||
type: float
|
||||
default: 360.0
|
||||
min: 1.0
|
||||
max: 720.0
|
||||
unit: deg
|
||||
decimal: 1
|
||||
MNT_RATE_PITCH:
|
||||
description:
|
||||
short: Angular pitch rate for manual input in degrees/second
|
||||
long: Full stick input [-1..1] translats to [-pitch rate..pitch rate].
|
||||
type: float
|
||||
default: 30.0
|
||||
min: 1.0
|
||||
max: 90.0
|
||||
unit: deg/s
|
||||
MNT_RATE_YAW:
|
||||
description:
|
||||
short: Angular yaw rate for manual input in degrees/second
|
||||
long: Full stick input [-1..1] translats to [-yaw rate..yaw rate].
|
||||
type: float
|
||||
default: 30.0
|
||||
min: 1.0
|
||||
max: 90.0
|
||||
unit: deg/s
|
||||
MNT_TAU:
|
||||
description:
|
||||
short: Time constant for open-loop AUX gimbal control
|
||||
long: |-
|
||||
Alpha filter time constant defining the convergence rate (in seconds) for open-loop AUX mount control
|
||||
|
||||
Use when no angular position feedback is available.
|
||||
With MNT_MODE_OUT set to AUX, the mount operates in open-loop and directly commands the servo output.
|
||||
Parameters must be tuned for the specific servo to approximate its speed and response.
|
||||
type: float
|
||||
default: 0.3
|
||||
min: 0.0
|
||||
MNT_RC_IN_MODE:
|
||||
description:
|
||||
short: Input mode for RC gimbal input
|
||||
type: enum
|
||||
values:
|
||||
0: Angle
|
||||
1: Angular rate
|
||||
default: 1
|
||||
min: 0
|
||||
max: 1
|
||||
MNT_LND_P_MIN:
|
||||
description:
|
||||
short: Pitch minimum when landed
|
||||
type: float
|
||||
default: -90.0
|
||||
min: -90.0
|
||||
max: 90.0
|
||||
unit: deg
|
||||
decimal: 1
|
||||
MNT_LND_P_MAX:
|
||||
description:
|
||||
short: Pitch maximum when landed
|
||||
type: float
|
||||
default: 90.0
|
||||
min: -90.0
|
||||
max: 90.0
|
||||
unit: deg
|
||||
decimal: 1
|
||||
Loading…
x
Reference in New Issue
Block a user