refactor(mc_pos_control): convert params.c to module.yaml

Convert 10 parameter file(s) from legacy C format to YAML
module configuration.
This commit is contained in:
Jacob Dahl 2026-03-17 21:55:35 -08:00 committed by Jacob Dahl
parent 397cd8375c
commit 22e700b6d7
21 changed files with 811 additions and 1204 deletions

View File

@ -42,6 +42,17 @@ px4_add_module(
SRCS
MulticopterPositionControl.cpp
MulticopterPositionControl.hpp
MODULE_CONFIG
multicopter_altitude_mode_params.yaml
multicopter_autonomous_params.yaml
multicopter_nudging_params.yaml
multicopter_position_control_gain_params.yaml
multicopter_position_control_limits_params.yaml
multicopter_position_control_params.yaml
multicopter_position_mode_params.yaml
multicopter_responsiveness_params.yaml
multicopter_stabilized_mode_params.yaml
multicopter_takeoff_land_params.yaml
DEPENDS
GotoControl
PositionControl

View File

@ -1,117 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2023 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.
*
****************************************************************************/
/**
* Maximum upwards acceleration in climb rate controlled modes
*
* @unit m/s^2
* @min 2
* @max 15
* @decimal 1
* @increment 1
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_ACC_UP_MAX, 4.f);
/**
* Maximum downwards acceleration in climb rate controlled modes
*
* @unit m/s^2
* @min 2
* @max 15
* @decimal 1
* @increment 1
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_ACC_DOWN_MAX, 3.f);
/**
* Manual yaw rate input filter time constant
*
* Not used in Stabilized mode
* Setting this parameter to 0 disables the filter
*
* @unit s
* @min 0
* @max 5
* @decimal 2
* @increment 0.01
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_MAN_Y_TAU, 0.08f);
/**
* Altitude reference mode
*
* Control height
* 0: relative earth frame origin which may drift due to sensors
* 1: relative to ground (requires distance sensor) which changes with terrain variation.
* It will revert to relative earth frame if the distance to ground estimate becomes invalid.
* 2: relative to ground (requires distance sensor) when stationary
* and relative to earth frame when moving horizontally.
* The speed threshold is MPC_HOLD_MAX_XY
*
* @min 0
* @max 2
* @value 0 Altitude following
* @value 1 Terrain following
* @value 2 Terrain hold
* @group Multicopter Position Control
*/
PARAM_DEFINE_INT32(MPC_ALT_MODE, 2);
/**
* Maximum horizontal velocity for which position hold is enabled (use 0 to disable check)
*
* Only used with MPC_POS_MODE Direct velocity or MPC_ALT_MODE 2
*
* @unit m/s
* @min 0
* @max 3
* @decimal 2
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_HOLD_MAX_XY, 0.8f);
/**
* Maximum vertical velocity for which position hold is enabled (use 0 to disable check)
*
* Only used with MPC_ALT_MODE 1
*
* @unit m/s
* @min 0
* @max 3
* @decimal 2
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_HOLD_MAX_Z, 0.6f);

View File

@ -0,0 +1,82 @@
module_name: mc_pos_control
parameters:
- group: Multicopter Position Control
definitions:
MPC_ACC_UP_MAX:
description:
short: Maximum upwards acceleration in climb rate controlled modes
type: float
default: 4.0
unit: m/s^2
min: 2
max: 15
decimal: 1
increment: 1
MPC_ACC_DOWN_MAX:
description:
short: Maximum downwards acceleration in climb rate controlled modes
type: float
default: 3.0
unit: m/s^2
min: 2
max: 15
decimal: 1
increment: 1
MPC_MAN_Y_TAU:
description:
short: Manual yaw rate input filter time constant
long: |-
Not used in Stabilized mode
Setting this parameter to 0 disables the filter
type: float
default: 0.08
unit: s
min: 0
max: 5
decimal: 2
increment: 0.01
MPC_ALT_MODE:
description:
short: Altitude reference mode
long: |-
Control height
0: relative earth frame origin which may drift due to sensors
1: relative to ground (requires distance sensor) which changes with terrain variation.
It will revert to relative earth frame if the distance to ground estimate becomes invalid.
2: relative to ground (requires distance sensor) when stationary
and relative to earth frame when moving horizontally.
The speed threshold is MPC_HOLD_MAX_XY
type: enum
values:
0: Altitude following
1: Terrain following
2: Terrain hold
default: 2
min: 0
max: 2
MPC_HOLD_MAX_XY:
description:
short: Max horizontal velocity for position hold
long: |-
Maximum horizontal velocity for which position hold is enabled (use 0 to disable check)
Only used with MPC_POS_MODE Direct velocity or MPC_ALT_MODE 2
type: float
default: 0.8
unit: m/s
min: 0
max: 3
decimal: 2
MPC_HOLD_MAX_Z:
description:
short: Max vertical velocity for position hold
long: |-
Maximum vertical velocity for which position hold is enabled (use 0 to disable check)
Only used with MPC_ALT_MODE 1
type: float
default: 0.6
unit: m/s
min: 0
max: 3
decimal: 2

View File

@ -1,178 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2023 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.
*
****************************************************************************/
/**
* Default horizontal velocity in autonomous modes
*
* e.g. in Missions, RTL, Goto if the waypoint does not specify differently
*
* @unit m/s
* @min 3
* @max 20
* @decimal 0
* @increment 1
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_XY_CRUISE, 5.f);
/**
* Ascent velocity in autonomous modes
*
* For manually controlled modes and offboard see MPC_Z_VEL_MAX_UP
*
* @unit m/s
* @min 0.5
* @max 8
* @decimal 1
* @increment 0.5
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_Z_V_AUTO_UP, 3.f);
/**
* Descent velocity in autonomous modes
*
* For manual modes and offboard, see MPC_Z_VEL_MAX_DN
*
* @unit m/s
* @min 0.5
* @max 4
* @decimal 1
* @increment 0.5
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_Z_V_AUTO_DN, 1.5f);
/**
* Acceleration for autonomous and for manual modes
*
* When piloting manually, this parameter is only used in MPC_POS_MODE Acceleration based.
*
* @unit m/s^2
* @min 2
* @max 15
* @decimal 1
* @increment 1
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_ACC_HOR, 3.f);
/**
* Jerk limit in autonomous modes
*
* Limit the maximum jerk of the vehicle (how fast the acceleration can change).
* A lower value leads to smoother vehicle motions but also limited agility.
*
* @unit m/s^3
* @min 1
* @max 80
* @decimal 1
* @increment 1
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_JERK_AUTO, 4.f);
/**
* Proportional gain for horizontal trajectory position error
*
* @min 0.1
* @max 1
* @decimal 1
* @increment 0.1
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_XY_TRAJ_P, 0.5f);
/**
* Maximum horizontal error allowed by the trajectory generator
*
* The integration speed of the trajectory setpoint is linearly
* reduced with the horizontal position tracking error. When the
* error is above this parameter, the integration of the
* trajectory is stopped to wait for the drone.
*
* This value can be adjusted depending on the tracking
* capabilities of the vehicle.
*
* @min 0.1
* @max 10
* @decimal 1
* @increment 1
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_XY_ERR_MAX, 2.f);
/**
* Maximum yaw rate in autonomous modes
*
* Limits the rate of change of the yaw setpoint to avoid large
* control output and mixer saturation.
*
* @unit deg/s
* @min 5
* @max 360
* @decimal 0
* @increment 5
* @group Multicopter Attitude Control
*/
PARAM_DEFINE_FLOAT(MPC_YAWRAUTO_MAX, 60.f);
/**
* Maximum yaw acceleration in autonomous modes
*
* Limits the acceleration of the yaw setpoint to avoid large
* control output and mixer saturation.
*
* @unit deg/s^2
* @min 5
* @max 360
* @decimal 0
* @increment 5
* @group Multicopter Attitude Control
*/
PARAM_DEFINE_FLOAT(MPC_YAWRAUTO_ACC, 20.f);
/**
* Heading behavior in autonomous modes
*
* @min 0
* @max 4
* @value 0 towards waypoint
* @value 1 towards home
* @value 2 away from home
* @value 3 along trajectory
* @value 4 towards waypoint (yaw first)
* @value 5 yaw fixed
* @group Mission
*/
PARAM_DEFINE_INT32(MPC_YAW_MODE, 0);

View File

@ -0,0 +1,132 @@
module_name: mc_pos_control
parameters:
- group: Mission
definitions:
MPC_YAW_MODE:
description:
short: Heading behavior in autonomous modes
type: enum
values:
0: towards waypoint
1: towards home
2: away from home
3: along trajectory
4: towards waypoint (yaw first)
5: yaw fixed
default: 0
min: 0
max: 4
- group: Multicopter Attitude Control
definitions:
MPC_YAWRAUTO_MAX:
description:
short: Maximum yaw rate in autonomous modes
long: |-
Limits the rate of change of the yaw setpoint to avoid large
control output and mixer saturation.
type: float
default: 60.0
unit: deg/s
min: 5
max: 360
decimal: 0
increment: 5
MPC_YAWRAUTO_ACC:
description:
short: Maximum yaw acceleration in autonomous modes
long: |-
Limits the acceleration of the yaw setpoint to avoid large
control output and mixer saturation.
type: float
default: 20.0
unit: deg/s^2
min: 5
max: 360
decimal: 0
increment: 5
- group: Multicopter Position Control
definitions:
MPC_XY_CRUISE:
description:
short: Default horizontal velocity in autonomous modes
long: e.g. in Missions, RTL, Goto if the waypoint does not specify differently
type: float
default: 5.0
unit: m/s
min: 3
max: 20
decimal: 0
increment: 1
MPC_Z_V_AUTO_UP:
description:
short: Ascent velocity in autonomous modes
long: For manually controlled modes and offboard see MPC_Z_VEL_MAX_UP
type: float
default: 3.0
unit: m/s
min: 0.5
max: 8
decimal: 1
increment: 0.5
MPC_Z_V_AUTO_DN:
description:
short: Descent velocity in autonomous modes
long: For manual modes and offboard, see MPC_Z_VEL_MAX_DN
type: float
default: 1.5
unit: m/s
min: 0.5
max: 4
decimal: 1
increment: 0.5
MPC_ACC_HOR:
description:
short: Acceleration for autonomous and for manual modes
long: When piloting manually, this parameter is only used in MPC_POS_MODE
Acceleration based.
type: float
default: 3.0
unit: m/s^2
min: 2
max: 15
decimal: 1
increment: 1
MPC_JERK_AUTO:
description:
short: Jerk limit in autonomous modes
long: |-
Limit the maximum jerk of the vehicle (how fast the acceleration can change).
A lower value leads to smoother vehicle motions but also limited agility.
type: float
default: 4.0
unit: m/s^3
min: 1
max: 80
decimal: 1
increment: 1
MPC_XY_TRAJ_P:
description:
short: Proportional gain for horizontal trajectory position error
type: float
default: 0.5
min: 0.1
max: 1
decimal: 1
increment: 0.1
MPC_XY_ERR_MAX:
description:
short: Maximum horizontal error allowed by the trajectory generator
long: |-
The integration speed of the trajectory setpoint is linearly
reduced with the horizontal position tracking error. When the
error is above this parameter, the integration of the
trajectory is stopped to wait for the drone.
This value can be adjusted depending on the tracking
capabilities of the vehicle.
type: float
default: 2.0
min: 0.1
max: 10
decimal: 1
increment: 1

View File

@ -1,69 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2023 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.
*
****************************************************************************/
/**
* Enable nudging based on user input during autonomous land routine
*
* Using stick input the vehicle can be moved horizontally and yawed.
* The descend speed is amended:
* stick full up - 0
* stick centered - MPC_LAND_SPEED
* stick full down - 2 * MPC_LAND_SPEED
*
* Manual override during auto modes has to be disabled to use this feature (see COM_RC_OVERRIDE).
*
* @min 0
* @max 1
* @value 0 Nudging disabled
* @value 1 Nudging enabled
* @group Multicopter Position Control
*/
PARAM_DEFINE_INT32(MPC_LAND_RC_HELP, 0);
/**
* User assisted landing radius
*
* When nudging is enabled (see MPC_LAND_RC_HELP), this defines the maximum
* allowed horizontal displacement from the original landing point.
* - If inside of the radius, only allow nudging inputs that do not move the vehicle outside of it.
* - If outside of the radius, only allow nudging inputs that move the vehicle back towards it.
*
* Set it to -1 for infinite radius.
*
* @unit m
* @min -1
* @decimal 0
* @increment 1
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_LAND_RADIUS, -1.0f);

View File

@ -0,0 +1,38 @@
module_name: mc_pos_control
parameters:
- group: Multicopter Position Control
definitions:
MPC_LAND_RC_HELP:
description:
short: Enable nudging based on user input during autonomous land routine
long: |-
Using stick input the vehicle can be moved horizontally and yawed.
The descend speed is amended:
stick full up - 0
stick centered - MPC_LAND_SPEED
stick full down - 2 * MPC_LAND_SPEED
Manual override during auto modes has to be disabled to use this feature (see COM_RC_OVERRIDE).
type: enum
values:
0: Nudging disabled
1: Nudging enabled
default: 0
min: 0
max: 1
MPC_LAND_RADIUS:
description:
short: User assisted landing radius
long: |-
When nudging is enabled (see MPC_LAND_RC_HELP), this defines the maximum
allowed horizontal displacement from the original landing point.
- If inside of the radius, only allow nudging inputs that do not move the vehicle outside of it.
- If outside of the radius, only allow nudging inputs that move the vehicle back towards it.
Set it to -1 for infinite radius.
type: float
default: -1.0
unit: m
min: -1
decimal: 0
increment: 1

View File

@ -1,137 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2023 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.
*
****************************************************************************/
/**
* Proportional gain for vertical position error
*
* Defined as corrective velocity in m/s per m position error
*
* @min 0.1
* @max 1.5
* @decimal 2
* @increment 0.1
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_Z_P, 1.f);
/**
* Proportional gain for horizontal position error
*
* Defined as corrective velocity in m/s per m position error
*
* @min 0
* @max 2
* @decimal 2
* @increment 0.1
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_XY_P, 0.95f);
/**
* Proportional gain for vertical velocity error
*
* Defined as corrective acceleration in m/s^2 per m/s velocity error
*
* @min 2
* @max 15
* @decimal 2
* @increment 0.1
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_Z_VEL_P_ACC, 4.f);
/**
* Proportional gain for horizontal velocity error
*
* Defined as corrective acceleration in m/s^2 per m/s velocity error
*
* @min 1.2
* @max 5
* @decimal 2
* @increment 0.1
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_XY_VEL_P_ACC, 1.8f);
/**
* Integral gain for vertical velocity error
*
* Defined as corrective acceleration in m/s^2 per m velocity integral
*
* @min 0.2
* @max 3
* @decimal 2
* @increment 0.1
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_Z_VEL_I_ACC, 2.f);
/**
* Integral gain for horizontal velocity error
*
* Defined as correction acceleration in m/s^2 per m velocity integral
* Allows to eliminate steady state errors in disturbances like wind.
*
* @min 0
* @max 60
* @decimal 2
* @increment 0.02
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_XY_VEL_I_ACC, 0.4f);
/**
* Differential gain for vertical velocity error
*
* Defined as corrective acceleration in m/s^2 per m/s^2 velocity derivative
*
* @min 0
* @max 2
* @decimal 2
* @increment 0.02
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_Z_VEL_D_ACC, 0.f);
/**
* Differential gain for horizontal velocity error
*
* Defined as corrective acceleration in m/s^2 per m/s^2 velocity derivative
*
* @min 0.1
* @max 2
* @decimal 2
* @increment 0.02
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_XY_VEL_D_ACC, 0.2f);

View File

@ -0,0 +1,86 @@
module_name: mc_pos_control
parameters:
- group: Multicopter Position Control
definitions:
MPC_Z_P:
description:
short: Proportional gain for vertical position error
long: Defined as corrective velocity in m/s per m position error
type: float
default: 1.0
min: 0.1
max: 1.5
decimal: 2
increment: 0.1
MPC_XY_P:
description:
short: Proportional gain for horizontal position error
long: Defined as corrective velocity in m/s per m position error
type: float
default: 0.95
min: 0
max: 2
decimal: 2
increment: 0.1
MPC_Z_VEL_P_ACC:
description:
short: Proportional gain for vertical velocity error
long: Defined as corrective acceleration in m/s^2 per m/s velocity error
type: float
default: 4.0
min: 2
max: 15
decimal: 2
increment: 0.1
MPC_XY_VEL_P_ACC:
description:
short: Proportional gain for horizontal velocity error
long: Defined as corrective acceleration in m/s^2 per m/s velocity error
type: float
default: 1.8
min: 1.2
max: 5
decimal: 2
increment: 0.1
MPC_Z_VEL_I_ACC:
description:
short: Integral gain for vertical velocity error
long: Defined as corrective acceleration in m/s^2 per m velocity integral
type: float
default: 2.0
min: 0.2
max: 3
decimal: 2
increment: 0.1
MPC_XY_VEL_I_ACC:
description:
short: Integral gain for horizontal velocity error
long: |-
Defined as correction acceleration in m/s^2 per m velocity integral
Allows to eliminate steady state errors in disturbances like wind.
type: float
default: 0.4
min: 0
max: 60
decimal: 2
increment: 0.02
MPC_Z_VEL_D_ACC:
description:
short: Differential gain for vertical velocity error
long: Defined as corrective acceleration in m/s^2 per m/s^2 velocity derivative
type: float
default: 0.0
min: 0
max: 2
decimal: 2
increment: 0.02
MPC_XY_VEL_D_ACC:
description:
short: Differential gain for horizontal velocity error
long: Defined as corrective acceleration in m/s^2 per m/s^2 velocity derivative
type: float
default: 0.2
min: 0.1
max: 2
decimal: 2
increment: 0.02

View File

@ -1,152 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2023 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.
*
****************************************************************************/
/**
* Maximum horizontal velocity
*
* Absolute maximum for all velocity controlled modes.
* Any higher value is truncated.
*
* @unit m/s
* @min 0
* @max 20
* @decimal 1
* @increment 1
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_XY_VEL_MAX, 12.f);
/**
* Maximum ascent velocity
*
* Absolute maximum for all climb rate controlled modes.
* In manually piloted modes full stick deflection commands this velocity.
*
* For default autonomous velocity see MPC_Z_V_AUTO_UP
*
* @unit m/s
* @min 0.5
* @max 8
* @increment 0.1
* @decimal 1
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_Z_VEL_MAX_UP, 3.f);
/**
* Maximum descent velocity
*
* Absolute maximum for all climb rate controlled modes.
* In manually piloted modes full stick deflection commands this velocity.
*
* For default autonomous velocity see MPC_Z_V_AUTO_UP
*
* @unit m/s
* @min 0.5
* @max 4
* @increment 0.1
* @decimal 1
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_Z_VEL_MAX_DN, 1.5f);
/**
* Maximum tilt angle in air
*
* Absolute maximum for all velocity or acceleration controlled modes.
* Any higher value is truncated.
*
* @unit deg
* @min 20
* @max 89
* @decimal 0
* @increment 1
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_TILTMAX_AIR, 45.f);
/**
* Maximum tilt during inital takeoff ramp
*
* Tighter tilt limit during takeoff to avoid tip over.
*
* @unit deg
* @min 5
* @max 89
* @decimal 0
* @increment 1
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_TILTMAX_LND, 12.f);
/**
* Minimum collective thrust in climb rate controlled modes
*
* Too low thrust leads to loss of roll/pitch/yaw torque control authority.
* With airmode enabled this parameters can be set to 0
* while still keeping torque authority (see MC_AIRMODE).
*
* @unit norm
* @min 0.05
* @max 0.5
* @decimal 2
* @increment 0.01
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_THR_MIN, 0.12f);
/**
* Maximum collective thrust in climb rate controlled modes
*
* Limit allowed thrust e.g. for indoor test of overpowered vehicle.
*
* @unit norm
* @min 0
* @max 1
* @decimal 2
* @increment 0.05
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_THR_MAX, 1.f);
/**
* Acceleration to tilt coupling
*
* Set to decouple tilt from vertical acceleration.
* This provides smoother flight but slightly worse tracking in position and auto modes.
* Unset if accurate position tracking during dynamic maneuvers is more important than a smooth flight.
*
* @boolean
* @group Multicopter Position Control
*/
PARAM_DEFINE_INT32(MPC_ACC_DECOUPLE, 1);

View File

@ -0,0 +1,105 @@
module_name: mc_pos_control
parameters:
- group: Multicopter Position Control
definitions:
MPC_XY_VEL_MAX:
description:
short: Maximum horizontal velocity
long: |-
Absolute maximum for all velocity controlled modes.
Any higher value is truncated.
type: float
default: 12.0
unit: m/s
min: 0
max: 20
decimal: 1
increment: 1
MPC_Z_VEL_MAX_UP:
description:
short: Maximum ascent velocity
long: |-
Absolute maximum for all climb rate controlled modes.
In manually piloted modes full stick deflection commands this velocity.
For default autonomous velocity see MPC_Z_V_AUTO_UP
type: float
default: 3.0
unit: m/s
min: 0.5
max: 8
increment: 0.1
decimal: 1
MPC_Z_VEL_MAX_DN:
description:
short: Maximum descent velocity
long: |-
Absolute maximum for all climb rate controlled modes.
In manually piloted modes full stick deflection commands this velocity.
For default autonomous velocity see MPC_Z_V_AUTO_UP
type: float
default: 1.5
unit: m/s
min: 0.5
max: 4
increment: 0.1
decimal: 1
MPC_TILTMAX_AIR:
description:
short: Maximum tilt angle in air
long: |-
Absolute maximum for all velocity or acceleration controlled modes.
Any higher value is truncated.
type: float
default: 45.0
unit: deg
min: 20
max: 89
decimal: 0
increment: 1
MPC_TILTMAX_LND:
description:
short: Maximum tilt during inital takeoff ramp
long: Tighter tilt limit during takeoff to avoid tip over.
type: float
default: 12.0
unit: deg
min: 5
max: 89
decimal: 0
increment: 1
MPC_THR_MIN:
description:
short: Minimum collective thrust in climb rate controlled modes
long: |-
Too low thrust leads to loss of roll/pitch/yaw torque control authority.
With airmode enabled this parameters can be set to 0
while still keeping torque authority (see MC_AIRMODE).
type: float
default: 0.12
unit: norm
min: 0.05
max: 0.5
decimal: 2
increment: 0.01
MPC_THR_MAX:
description:
short: Maximum collective thrust in climb rate controlled modes
long: Limit allowed thrust e.g. for indoor test of overpowered vehicle.
type: float
default: 1.0
unit: norm
min: 0
max: 1
decimal: 2
increment: 0.05
MPC_ACC_DECOUPLE:
description:
short: Acceleration to tilt coupling
long: |-
Set to decouple tilt from vertical acceleration.
This provides smoother flight but slightly worse tracking in position and auto modes.
Unset if accurate position tracking during dynamic maneuvers is more important than a smooth flight.
type: boolean
default: 1

View File

@ -1,121 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2023 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.
*
****************************************************************************/
/**
* Vertical thrust required to hover
*
* Mapped to center throttle stick in Stabilized mode (see MPC_THR_CURVE).
* Used for initialization of the hover thrust estimator.
* The estimated hover thrust is used as base for zero vertical acceleration in altitude control.
* The hover thrust is important for land detection to work correctly.
*
* @unit norm
* @min 0.1
* @max 0.8
* @decimal 2
* @increment 0.01
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_THR_HOVER, 0.5f);
/**
* Horizontal thrust margin
*
* Margin that is kept for horizontal control when higher priority vertical thrust is saturated.
* To avoid completely starving horizontal control with high vertical error.
*
* @unit norm
* @min 0
* @max 0.5
* @decimal 2
* @increment 0.01
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_THR_XY_MARG, 0.3f);
/**
* Velocity low pass cutoff frequency
*
* A value of 0 disables the filter.
*
* @unit Hz
* @min 0
* @max 50
* @decimal 1
* @increment 0.5
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_VEL_LP, 0.0f);
/**
* Velocity notch filter frequency
*
* The center frequency for the 2nd order notch filter on the velocity.
* A value of 0 disables the filter.
*
* @unit Hz
* @min 0
* @max 50
* @decimal 1
* @increment 0.5
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_VEL_NF_FRQ, 0.0f);
/**
* Velocity notch filter bandwidth
*
* A value of 0 disables the filter.
*
* @unit Hz
* @min 0
* @max 50
* @decimal 1
* @increment 0.5
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_VEL_NF_BW, 5.0f);
/**
* Velocity derivative low pass cutoff frequency
*
* A value of 0 disables the filter.
*
* @unit Hz
* @min 0
* @max 50
* @decimal 1
* @increment 0.5
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_VELD_LP, 5.0f);

View File

@ -0,0 +1,78 @@
module_name: mc_pos_control
parameters:
- group: Multicopter Position Control
definitions:
MPC_THR_HOVER:
description:
short: Vertical thrust required to hover
long: |-
Mapped to center throttle stick in Stabilized mode (see MPC_THR_CURVE).
Used for initialization of the hover thrust estimator.
The estimated hover thrust is used as base for zero vertical acceleration in altitude control.
The hover thrust is important for land detection to work correctly.
type: float
default: 0.5
unit: norm
min: 0.1
max: 0.8
decimal: 2
increment: 0.01
MPC_THR_XY_MARG:
description:
short: Horizontal thrust margin
long: |-
Margin that is kept for horizontal control when higher priority vertical thrust is saturated.
To avoid completely starving horizontal control with high vertical error.
type: float
default: 0.3
unit: norm
min: 0
max: 0.5
decimal: 2
increment: 0.01
MPC_VEL_LP:
description:
short: Velocity low pass cutoff frequency
long: A value of 0 disables the filter.
type: float
default: 0.0
unit: Hz
min: 0
max: 50
decimal: 1
increment: 0.5
MPC_VEL_NF_FRQ:
description:
short: Velocity notch filter frequency
long: |-
The center frequency for the 2nd order notch filter on the velocity.
A value of 0 disables the filter.
type: float
default: 0.0
unit: Hz
min: 0
max: 50
decimal: 1
increment: 0.5
MPC_VEL_NF_BW:
description:
short: Velocity notch filter bandwidth
long: A value of 0 disables the filter.
type: float
default: 5.0
unit: Hz
min: 0
max: 50
decimal: 1
increment: 0.5
MPC_VELD_LP:
description:
short: Velocity derivative low pass cutoff frequency
long: A value of 0 disables the filter.
type: float
default: 5.0
unit: Hz
min: 0
max: 50
decimal: 1
increment: 0.5

View File

@ -1,131 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2023 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.
*
****************************************************************************/
/**
* Position/Altitude mode variant
*
* The supported sub-modes are:
* Direct velocity:
* Sticks directly map to velocity setpoints without smoothing.
* Also applies to vertical direction and Altitude mode.
* Useful for velocity control tuning.
* Acceleration based:
* Sticks map to acceleration and there's a virtual brake drag
*
* @value 0 Direct velocity
* @value 4 Acceleration based
* @group Multicopter Position Control
*/
PARAM_DEFINE_INT32(MPC_POS_MODE, 4);
/**
* Maximum horizontal velocity setpoint in Position mode
*
* Must be smaller than MPC_XY_VEL_MAX.
*
* The maximum sideways and backward speed can be set differently
* using MPC_VEL_MAN_SIDE and MPC_VEL_MAN_BACK, respectively.
*
* @unit m/s
* @min 3
* @max 20
* @increment 1
* @decimal 1
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_VEL_MANUAL, 10.f);
/**
* Maximum sideways velocity in Position mode
*
* If set to a negative value or larger than
* MPC_VEL_MANUAL then MPC_VEL_MANUAL is used.
*
* @unit m/s
* @min -1
* @max 20
* @increment 1
* @decimal 1
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_VEL_MAN_SIDE, -1.f);
/**
* Maximum backward velocity in Position mode
*
* If set to a negative value or larger than
* MPC_VEL_MANUAL then MPC_VEL_MANUAL is used.
*
* @unit m/s
* @min -1
* @max 20
* @increment 1
* @decimal 1
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_VEL_MAN_BACK, -1.f);
/**
* Maximum horizontal acceleration
*
* MPC_POS_MODE
* 1 just deceleration
* 4 not used, use MPC_ACC_HOR instead
*
* @unit m/s^2
* @min 2
* @max 15
* @increment 1
* @decimal 2
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_ACC_HOR_MAX, 5.f);
/**
* Maximum horizontal and vertical jerk in Position/Altitude mode
*
* Limit the maximum jerk (acceleration change) of the vehicle.
* A lower value leads to smoother motions but limits agility.
*
* Setting this to the maximum value essentially disables the limit.
*
* Only used with MPC_POS_MODE Acceleration based.
*
* @unit m/s^3
* @min 0.5
* @max 500
* @decimal 0
* @increment 1
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_JERK_MAX, 8.f);

View File

@ -0,0 +1,92 @@
module_name: mc_pos_control
parameters:
- group: Multicopter Position Control
definitions:
MPC_POS_MODE:
description:
short: Position/Altitude mode variant
long: |-
The supported sub-modes are:
Direct velocity:
Sticks directly map to velocity setpoints without smoothing.
Also applies to vertical direction and Altitude mode.
Useful for velocity control tuning.
Acceleration based:
Sticks map to acceleration and there's a virtual brake drag
type: enum
values:
0: Direct velocity
4: Acceleration based
default: 4
MPC_VEL_MANUAL:
description:
short: Maximum horizontal velocity setpoint in Position mode
long: |-
Must be smaller than MPC_XY_VEL_MAX.
The maximum sideways and backward speed can be set differently
using MPC_VEL_MAN_SIDE and MPC_VEL_MAN_BACK, respectively.
type: float
default: 10.0
unit: m/s
min: 3
max: 20
increment: 1
decimal: 1
MPC_VEL_MAN_SIDE:
description:
short: Maximum sideways velocity in Position mode
long: |-
If set to a negative value or larger than
MPC_VEL_MANUAL then MPC_VEL_MANUAL is used.
type: float
default: -1.0
unit: m/s
min: -1
max: 20
increment: 1
decimal: 1
MPC_VEL_MAN_BACK:
description:
short: Maximum backward velocity in Position mode
long: |-
If set to a negative value or larger than
MPC_VEL_MANUAL then MPC_VEL_MANUAL is used.
type: float
default: -1.0
unit: m/s
min: -1
max: 20
increment: 1
decimal: 1
MPC_ACC_HOR_MAX:
description:
short: Maximum horizontal acceleration
long: |-
MPC_POS_MODE
1 just deceleration
4 not used, use MPC_ACC_HOR instead
type: float
default: 5.0
unit: m/s^2
min: 2
max: 15
increment: 1
decimal: 2
MPC_JERK_MAX:
description:
short: Maximum horizontal and vertical jerk in Position/Altitude mode
long: |-
Limit the maximum jerk (acceleration change) of the vehicle.
A lower value leads to smoother motions but limits agility.
Setting this to the maximum value essentially disables the limit.
Only used with MPC_POS_MODE Acceleration based.
type: float
default: 8.0
unit: m/s^3
min: 0.5
max: 500
decimal: 0
increment: 1

View File

@ -1,80 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2023 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.
*
****************************************************************************/
/**
* Responsiveness
*
* Changes the overall responsiveness of the vehicle.
* The higher the value, the faster the vehicle will react.
*
* If set to a value greater than zero, other parameters are automatically set (such as
* the acceleration or jerk limits).
* If set to a negative value, the existing individual parameters are used.
*
* @min -1
* @max 1
* @decimal 2
* @increment 0.05
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(SYS_VEHICLE_RESP, -0.4f);
/**
* Overall Horizontal Velocity Limit
*
* If set to a value greater than zero, other parameters are automatically set (such as
* MPC_XY_VEL_MAX or MPC_VEL_MANUAL).
* If set to a negative value, the existing individual parameters are used.
*
* @min -20
* @max 20
* @decimal 1
* @increment 1
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_XY_VEL_ALL, -10.f);
/**
* Overall Vertical Velocity Limit
*
* If set to a value greater than zero, other parameters are automatically set (such as
* MPC_Z_VEL_MAX_UP or MPC_LAND_SPEED).
* If set to a negative value, the existing individual parameters are used.
*
* @min -3
* @max 8
* @decimal 1
* @increment 0.5
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_Z_VEL_ALL, -3.f);

View File

@ -0,0 +1,46 @@
module_name: mc_pos_control
parameters:
- group: Multicopter Position Control
definitions:
SYS_VEHICLE_RESP:
description:
short: Responsiveness
long: |-
Changes the overall responsiveness of the vehicle.
The higher the value, the faster the vehicle will react.
If set to a value greater than zero, other parameters are automatically set (such as
the acceleration or jerk limits).
If set to a negative value, the existing individual parameters are used.
type: float
default: -0.4
min: -1
max: 1
decimal: 2
increment: 0.05
MPC_XY_VEL_ALL:
description:
short: Overall Horizontal Velocity Limit
long: |-
If set to a value greater than zero, other parameters are automatically set (such as
MPC_XY_VEL_MAX or MPC_VEL_MANUAL).
If set to a negative value, the existing individual parameters are used.
type: float
default: -10.0
min: -20
max: 20
decimal: 1
increment: 1
MPC_Z_VEL_ALL:
description:
short: Overall Vertical Velocity Limit
long: |-
If set to a value greater than zero, other parameters are automatically set (such as
MPC_Z_VEL_MAX_UP or MPC_LAND_SPEED).
If set to a negative value, the existing individual parameters are used.
type: float
default: -3.0
min: -3
max: 8
decimal: 1
increment: 0.5

View File

@ -1,96 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2023 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.
*
****************************************************************************/
/**
* Maximal tilt angle in Stabilized, Altitude and Altitude Cruise mode
*
* @unit deg
* @min 1
* @max 70
* @decimal 0
* @increment 1
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_MAN_TILT_MAX, 35.f);
/**
* Max manual yaw rate for Stabilized, Altitude, Position mode
*
* @unit deg/s
* @min 0
* @max 400
* @decimal 0
* @increment 10
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_MAN_Y_MAX, 150.f);
/**
* Minimum collective thrust in Stabilized mode
*
* The value is mapped to the lowest throttle stick position in Stabilized mode.
*
* Too low collective thrust leads to loss of roll/pitch/yaw torque control authority.
* Airmode is used to keep torque authority with zero thrust (see MC_AIRMODE).
*
* @unit norm
* @min 0
* @max 1
* @decimal 2
* @increment 0.01
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_MANTHR_MIN, 0.08f);
/**
* Thrust curve mapping in Stabilized Mode
*
* Defines how the throttle stick is mapped to collective thrust in Stabilized mode.
*
* Rescale to hover thrust estimate:
* Stick input is linearly rescaled, such that a centered throttle stick corresponds to the hover thrust estimator's output.
*
* No rescale:
* Directly map the stick 1:1 to the output.
* Can be useful with very low hover thrust which leads to much distortion and the upper half getting sensitive.
*
* Rescale to hover thrust parameter:
* Similar to rescaling to the hover thrust estimate, but it uses the hover thrust parameter value (see MPC_THR_HOVER) instead of estimated value.
* With MPC_THR_HOVER 0.5 it's equivalent to No rescale.
*
* @value 0 Rescale to estimate
* @value 1 No rescale
* @value 2 Rescale to parameter
* @group Multicopter Position Control
*/
PARAM_DEFINE_INT32(MPC_THR_CURVE, 0);

View File

@ -0,0 +1,61 @@
module_name: mc_pos_control
parameters:
- group: Multicopter Position Control
definitions:
MPC_MAN_TILT_MAX:
description:
short: Maximal tilt angle in Stabilized, Altitude and Altitude Cruise mode
type: float
default: 35.0
unit: deg
min: 1
max: 70
decimal: 0
increment: 1
MPC_MAN_Y_MAX:
description:
short: Max manual yaw rate for Stabilized, Altitude, Position mode
type: float
default: 150.0
unit: deg/s
min: 0
max: 400
decimal: 0
increment: 10
MPC_MANTHR_MIN:
description:
short: Minimum collective thrust in Stabilized mode
long: |-
The value is mapped to the lowest throttle stick position in Stabilized mode.
Too low collective thrust leads to loss of roll/pitch/yaw torque control authority.
Airmode is used to keep torque authority with zero thrust (see MC_AIRMODE).
type: float
default: 0.08
unit: norm
min: 0
max: 1
decimal: 2
increment: 0.01
MPC_THR_CURVE:
description:
short: Thrust curve mapping in Stabilized Mode
long: |-
Defines how the throttle stick is mapped to collective thrust in Stabilized mode.
Rescale to hover thrust estimate:
Stick input is linearly rescaled, such that a centered throttle stick corresponds to the hover thrust estimator's output.
No rescale:
Directly map the stick 1:1 to the output.
Can be useful with very low hover thrust which leads to much distortion and the upper half getting sensitive.
Rescale to hover thrust parameter:
Similar to rescaling to the hover thrust estimate, but it uses the hover thrust parameter value (see MPC_THR_HOVER) instead of estimated value.
With MPC_THR_HOVER 0.5 it's equivalent to No rescale.
type: enum
values:
0: Rescale to estimate
1: No rescale
2: Rescale to parameter
default: 0

View File

@ -1,123 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2023 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.
*
****************************************************************************/
/**
* Smooth takeoff ramp time constant
*
* Increasing this value will make climb rate controlled takeoff slower.
* If it's too slow the drone might scratch the ground and tip over.
* A time constant of 0 disables the ramp
*
* @unit s
* @min 0
* @max 5
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_TKO_RAMP_T, 3.f);
/**
* Takeoff climb rate
*
* @unit m/s
* @min 1
* @max 5
* @decimal 2
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_TKO_SPEED, 1.5f);
/**
* Altitude for 1. step of slow landing (descend)
*
* Below this altitude descending velocity gets limited to a value
* between "MPC_Z_VEL_MAX_DN" (or "MPC_Z_V_AUTO_DN") and "MPC_LAND_SPEED"
* Value needs to be higher than "MPC_LAND_ALT2"
*
* @unit m
* @min 0
* @max 122
* @decimal 1
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_LAND_ALT1, 10.f);
/**
* Altitude for 2. step of slow landing (landing)
*
* Below this altitude descending velocity gets
* limited to "MPC_LAND_SPEED"
* Value needs to be lower than "MPC_LAND_ALT1"
*
* @unit m
* @min 0
* @max 122
* @decimal 1
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_LAND_ALT2, 5.f);
/**
* Altitude for 3. step of slow landing
*
* If a valid distance sensor measurement to the ground is available,
* limit descending velocity to "MPC_LAND_CRWL" below this altitude.
*
* @unit m
* @min 0
* @max 122
* @decimal 1
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_LAND_ALT3, 1.f);
/**
* Landing descend rate
*
* @unit m/s
* @min 0.6
* @decimal 1
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_LAND_SPEED, 0.7f);
/**
* Land crawl descend rate
*
* Used below MPC_LAND_ALT3 if distance sensor data is availabe.
*
* @unit m/s
* @min 0.1
* @decimal 1
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_LAND_CRWL, 0.3f);

View File

@ -0,0 +1,80 @@
module_name: mc_pos_control
parameters:
- group: Multicopter Position Control
definitions:
MPC_TKO_RAMP_T:
description:
short: Smooth takeoff ramp time constant
long: |-
Increasing this value will make climb rate controlled takeoff slower.
If it's too slow the drone might scratch the ground and tip over.
A time constant of 0 disables the ramp
type: float
default: 3.0
unit: s
min: 0
max: 5
MPC_TKO_SPEED:
description:
short: Takeoff climb rate
type: float
default: 1.5
unit: m/s
min: 1
max: 5
decimal: 2
MPC_LAND_ALT1:
description:
short: Altitude for 1. step of slow landing (descend)
long: |-
Below this altitude descending velocity gets limited to a value
between "MPC_Z_VEL_MAX_DN" (or "MPC_Z_V_AUTO_DN") and "MPC_LAND_SPEED"
Value needs to be higher than "MPC_LAND_ALT2"
type: float
default: 10.0
unit: m
min: 0
max: 122
decimal: 1
MPC_LAND_ALT2:
description:
short: Altitude for 2. step of slow landing (landing)
long: |-
Below this altitude descending velocity gets
limited to "MPC_LAND_SPEED"
Value needs to be lower than "MPC_LAND_ALT1"
type: float
default: 5.0
unit: m
min: 0
max: 122
decimal: 1
MPC_LAND_ALT3:
description:
short: Altitude for 3. step of slow landing
long: |-
If a valid distance sensor measurement to the ground is available,
limit descending velocity to "MPC_LAND_CRWL" below this altitude.
type: float
default: 1.0
unit: m
min: 0
max: 122
decimal: 1
MPC_LAND_SPEED:
description:
short: Landing descend rate
type: float
default: 0.7
unit: m/s
min: 0.6
decimal: 1
MPC_LAND_CRWL:
description:
short: Land crawl descend rate
long: Used below MPC_LAND_ALT3 if distance sensor data is availabe.
type: float
default: 0.3
unit: m/s
min: 0.1
decimal: 1