mc_rate_control: move acro parameter to separate file

This commit is contained in:
Matthias Grob 2023-09-19 12:01:44 +02:00 committed by Daniel Agar
parent c1dbe177b8
commit df3a0de734
2 changed files with 143 additions and 107 deletions

View File

@ -0,0 +1,142 @@
/****************************************************************************
*
* 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.
*
****************************************************************************/
/**
* @file mc_acro_params.c
*
* Parameters for Acro mode behavior
*/
/**
* Max acro roll rate
*
* default: 2 turns per second
*
* @unit deg/s
* @min 0.0
* @max 1800.0
* @decimal 1
* @increment 5
* @group Multicopter Rate Control
*/
PARAM_DEFINE_FLOAT(MC_ACRO_R_MAX, 720.0f);
/**
* Max acro pitch rate
*
* default: 2 turns per second
*
* @unit deg/s
* @min 0.0
* @max 1800.0
* @decimal 1
* @increment 5
* @group Multicopter Rate Control
*/
PARAM_DEFINE_FLOAT(MC_ACRO_P_MAX, 720.0f);
/**
* Max acro yaw rate
*
* default 1.5 turns per second
*
* @unit deg/s
* @min 0.0
* @max 1800.0
* @decimal 1
* @increment 5
* @group Multicopter Rate Control
*/
PARAM_DEFINE_FLOAT(MC_ACRO_Y_MAX, 540.0f);
/**
* Acro mode Expo factor for Roll and Pitch.
*
* Exponential factor for tuning the input curve shape.
*
* 0 Purely linear input curve
* 1 Purely cubic input curve
*
* @min 0
* @max 1
* @decimal 2
* @group Multicopter Rate Control
*/
PARAM_DEFINE_FLOAT(MC_ACRO_EXPO, 0.69f);
/**
* Acro mode Expo factor for Yaw.
*
* Exponential factor for tuning the input curve shape.
*
* 0 Purely linear input curve
* 1 Purely cubic input curve
*
* @min 0
* @max 1
* @decimal 2
* @group Multicopter Rate Control
*/
PARAM_DEFINE_FLOAT(MC_ACRO_EXPO_Y, 0.69f);
/**
* Acro mode SuperExpo factor for Roll and Pitch.
*
* SuperExpo factor for refining the input curve shape tuned using MC_ACRO_EXPO.
*
* 0 Pure Expo function
* 0.7 reasonable shape enhancement for intuitive stick feel
* 0.95 very strong bent input curve only near maxima have effect
*
* @min 0
* @max 0.95
* @decimal 2
* @group Multicopter Rate Control
*/
PARAM_DEFINE_FLOAT(MC_ACRO_SUPEXPO, 0.7f);
/**
* Acro mode SuperExpo factor for Yaw.
*
* SuperExpo factor for refining the input curve shape tuned using MC_ACRO_EXPO_Y.
*
* 0 Pure Expo function
* 0.7 reasonable shape enhancement for intuitive stick feel
* 0.95 very strong bent input curve only near maxima have effect
*
* @min 0
* @max 0.95
* @decimal 2
* @group Multicopter Rate Control
*/
PARAM_DEFINE_FLOAT(MC_ACRO_SUPEXPOY, 0.7f);

View File

@ -33,10 +33,8 @@
/**
* @file mc_rate_control_params.c
* Parameters for multicopter attitude controller.
*
* @author Lorenz Meier <lorenz@px4.io>
* @author Anton Babushkin <anton@px4.io>
* Parameters for multicopter rate controller
*/
/**
@ -281,110 +279,6 @@ PARAM_DEFINE_FLOAT(MC_YAWRATE_FF, 0.0f);
*/
PARAM_DEFINE_FLOAT(MC_YAWRATE_K, 1.0f);
/**
* Max acro roll rate
*
* default: 2 turns per second
*
* @unit deg/s
* @min 0.0
* @max 1800.0
* @decimal 1
* @increment 5
* @group Multicopter Rate Control
*/
PARAM_DEFINE_FLOAT(MC_ACRO_R_MAX, 720.0f);
/**
* Max acro pitch rate
*
* default: 2 turns per second
*
* @unit deg/s
* @min 0.0
* @max 1800.0
* @decimal 1
* @increment 5
* @group Multicopter Rate Control
*/
PARAM_DEFINE_FLOAT(MC_ACRO_P_MAX, 720.0f);
/**
* Max acro yaw rate
*
* default 1.5 turns per second
*
* @unit deg/s
* @min 0.0
* @max 1800.0
* @decimal 1
* @increment 5
* @group Multicopter Rate Control
*/
PARAM_DEFINE_FLOAT(MC_ACRO_Y_MAX, 540.0f);
/**
* Acro mode Expo factor for Roll and Pitch.
*
* Exponential factor for tuning the input curve shape.
*
* 0 Purely linear input curve
* 1 Purely cubic input curve
*
* @min 0
* @max 1
* @decimal 2
* @group Multicopter Rate Control
*/
PARAM_DEFINE_FLOAT(MC_ACRO_EXPO, 0.69f);
/**
* Acro mode Expo factor for Yaw.
*
* Exponential factor for tuning the input curve shape.
*
* 0 Purely linear input curve
* 1 Purely cubic input curve
*
* @min 0
* @max 1
* @decimal 2
* @group Multicopter Rate Control
*/
PARAM_DEFINE_FLOAT(MC_ACRO_EXPO_Y, 0.69f);
/**
* Acro mode SuperExpo factor for Roll and Pitch.
*
* SuperExpo factor for refining the input curve shape tuned using MC_ACRO_EXPO.
*
* 0 Pure Expo function
* 0.7 reasonable shape enhancement for intuitive stick feel
* 0.95 very strong bent input curve only near maxima have effect
*
* @min 0
* @max 0.95
* @decimal 2
* @group Multicopter Rate Control
*/
PARAM_DEFINE_FLOAT(MC_ACRO_SUPEXPO, 0.7f);
/**
* Acro mode SuperExpo factor for Yaw.
*
* SuperExpo factor for refining the input curve shape tuned using MC_ACRO_EXPO_Y.
*
* 0 Pure Expo function
* 0.7 reasonable shape enhancement for intuitive stick feel
* 0.95 very strong bent input curve only near maxima have effect
*
* @min 0
* @max 0.95
* @decimal 2
* @group Multicopter Rate Control
*/
PARAM_DEFINE_FLOAT(MC_ACRO_SUPEXPOY, 0.7f);
/**
* Battery power level scaler
*