mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
refactor(uuv_pos_control): 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
ca52ab75a0
commit
3a47e283cc
@ -37,4 +37,6 @@ px4_add_module(
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
uuv_pos_control.cpp
|
||||
MODULE_CONFIG
|
||||
uuv_pos_control_params.yaml
|
||||
)
|
||||
|
||||
@ -1,188 +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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file uuv_pos_control_params.c
|
||||
*
|
||||
* Parameters defined by the position control task for unmanned underwater vehicles (UUVs)
|
||||
*
|
||||
* This is a modification of the fixed wing/ground rover params and it is designed for ground rovers.
|
||||
* It has been developed starting from the fw module, simplified and improved with dedicated items.
|
||||
*
|
||||
* All the ackowledgments and credits for the fw wing/rover app are reported in those files.
|
||||
*
|
||||
* @author Tim Hansen <timhansen93@googlemail.com>
|
||||
* @author Daniel Duecker <daniel.duecker@tuhh.de>
|
||||
*/
|
||||
|
||||
/*
|
||||
* Controller parameters, accessible via MAVLink
|
||||
*
|
||||
*/
|
||||
/**
|
||||
* Gain of P controller X
|
||||
*
|
||||
* @group UUV Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(UUV_GAIN_X_P, 1.0f);
|
||||
/**
|
||||
* Gain of P controller Y
|
||||
*
|
||||
* @group UUV Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(UUV_GAIN_Y_P, 1.0f);
|
||||
/**
|
||||
* Gain of P controller Z
|
||||
*
|
||||
* @group UUV Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(UUV_GAIN_Z_P, 1.0f);
|
||||
|
||||
/**
|
||||
* Gain of D controller X
|
||||
*
|
||||
* @group UUV Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(UUV_GAIN_X_D, 0.2f);
|
||||
/**
|
||||
* Gain of D controller Y
|
||||
*
|
||||
* @group UUV Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(UUV_GAIN_Y_D, 0.2f);
|
||||
/**
|
||||
* Gain of D controller Z
|
||||
*
|
||||
* @group UUV Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(UUV_GAIN_Z_D, 0.2f);
|
||||
|
||||
/**
|
||||
* Stabilization mode(1) or Position Control(0)
|
||||
*
|
||||
* @value 0 Tracks previous attitude setpoint
|
||||
* @value 1 Tracks horizontal attitude (allows yaw change)
|
||||
* @group UUV Position Control
|
||||
*/
|
||||
PARAM_DEFINE_INT32(UUV_STAB_MODE, 1);
|
||||
|
||||
/**
|
||||
* Deadband for changing position setpoint
|
||||
*
|
||||
* @group UUV Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(UUV_POS_STICK_DB, 0.1f);
|
||||
|
||||
/**
|
||||
* Gain for position control velocity setpoint update
|
||||
*
|
||||
* @group UUV Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(UUV_PGM_VEL, 0.5f);
|
||||
|
||||
/**
|
||||
* Stabilization mode(1) or Position Control(0)
|
||||
*
|
||||
* @value 0 Moves position setpoint in world frame
|
||||
* @value 1 Moves position setpoint in body frame
|
||||
* @group UUV Position Control
|
||||
*/
|
||||
PARAM_DEFINE_INT32(UUV_POS_MODE, 1);
|
||||
|
||||
|
||||
/**
|
||||
* Height proportional gain
|
||||
*
|
||||
* @group UUV Attitude Control
|
||||
* @decimal 2
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(UUV_HGT_P, 1.0f);
|
||||
|
||||
/**
|
||||
* Height differential gain
|
||||
*
|
||||
* @group UUV Attitude Control
|
||||
* @decimal 2
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(UUV_HGT_D, 1.0f);
|
||||
|
||||
/**
|
||||
* Height integrational gain
|
||||
*
|
||||
* @group UUV Attitude Control
|
||||
* @decimal 2
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(UUV_HGT_I, 0.2f);
|
||||
|
||||
/**
|
||||
* sum speed of error for integrational gain
|
||||
*
|
||||
* @group UUV Attitude Control
|
||||
* @decimal 2
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(UUV_HGT_I_SPD, 1.0f);
|
||||
|
||||
/**
|
||||
* Height change strength from manual input
|
||||
*
|
||||
* @group UUV Attitude Control
|
||||
* @decimal 2
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(UUV_HGT_STR, 1.0f);
|
||||
|
||||
/**
|
||||
* maximum Height distance controlled by manual input. Diff between actual and desired Height cant be higher than that
|
||||
*
|
||||
*
|
||||
* @group UUV Attitude Control
|
||||
* @decimal 2
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(UUV_HGT_MAX_DIFF, 0.3f);
|
||||
|
||||
/**
|
||||
* Height rc-button up
|
||||
*
|
||||
* @group UUV Attitude Control
|
||||
* @min 0
|
||||
* @max 16
|
||||
*/
|
||||
PARAM_DEFINE_INT32(UUV_HGT_B_UP, 11);
|
||||
|
||||
/**
|
||||
* Height rc-button down
|
||||
*
|
||||
* @group UUV Attitude Control
|
||||
* @min 0
|
||||
* @max 16
|
||||
*/
|
||||
PARAM_DEFINE_INT32(UUV_HGT_B_DOWN, 12);
|
||||
114
src/modules/uuv_pos_control/uuv_pos_control_params.yaml
Normal file
114
src/modules/uuv_pos_control/uuv_pos_control_params.yaml
Normal file
@ -0,0 +1,114 @@
|
||||
module_name: uuv_pos_control
|
||||
parameters:
|
||||
- group: UUV Attitude Control
|
||||
definitions:
|
||||
UUV_HGT_P:
|
||||
description:
|
||||
short: Height proportional gain
|
||||
type: float
|
||||
default: 1.0
|
||||
decimal: 2
|
||||
UUV_HGT_D:
|
||||
description:
|
||||
short: Height differential gain
|
||||
type: float
|
||||
default: 1.0
|
||||
decimal: 2
|
||||
UUV_HGT_I:
|
||||
description:
|
||||
short: Height integrational gain
|
||||
type: float
|
||||
default: 0.2
|
||||
decimal: 2
|
||||
UUV_HGT_I_SPD:
|
||||
description:
|
||||
short: sum speed of error for integrational gain
|
||||
type: float
|
||||
default: 1.0
|
||||
decimal: 2
|
||||
UUV_HGT_STR:
|
||||
description:
|
||||
short: Height change strength from manual input
|
||||
type: float
|
||||
default: 1.0
|
||||
decimal: 2
|
||||
UUV_HGT_MAX_DIFF:
|
||||
description:
|
||||
short: Max height error from manual input
|
||||
long: maximum Height distance controlled by manual input. Diff between actual
|
||||
and desired Height cant be higher than that
|
||||
type: float
|
||||
default: 0.3
|
||||
decimal: 2
|
||||
UUV_HGT_B_UP:
|
||||
description:
|
||||
short: Height rc-button up
|
||||
type: int32
|
||||
default: 11
|
||||
min: 0
|
||||
max: 16
|
||||
UUV_HGT_B_DOWN:
|
||||
description:
|
||||
short: Height rc-button down
|
||||
type: int32
|
||||
default: 12
|
||||
min: 0
|
||||
max: 16
|
||||
- group: UUV Position Control
|
||||
definitions:
|
||||
UUV_GAIN_X_P:
|
||||
description:
|
||||
short: Gain of P controller X
|
||||
type: float
|
||||
default: 1.0
|
||||
UUV_GAIN_Y_P:
|
||||
description:
|
||||
short: Gain of P controller Y
|
||||
type: float
|
||||
default: 1.0
|
||||
UUV_GAIN_Z_P:
|
||||
description:
|
||||
short: Gain of P controller Z
|
||||
type: float
|
||||
default: 1.0
|
||||
UUV_GAIN_X_D:
|
||||
description:
|
||||
short: Gain of D controller X
|
||||
type: float
|
||||
default: 0.2
|
||||
UUV_GAIN_Y_D:
|
||||
description:
|
||||
short: Gain of D controller Y
|
||||
type: float
|
||||
default: 0.2
|
||||
UUV_GAIN_Z_D:
|
||||
description:
|
||||
short: Gain of D controller Z
|
||||
type: float
|
||||
default: 0.2
|
||||
UUV_STAB_MODE:
|
||||
description:
|
||||
short: Stabilization mode(1) or Position Control(0)
|
||||
type: enum
|
||||
values:
|
||||
0: Tracks previous attitude setpoint
|
||||
1: Tracks horizontal attitude (allows yaw change)
|
||||
default: 1
|
||||
UUV_POS_STICK_DB:
|
||||
description:
|
||||
short: Deadband for changing position setpoint
|
||||
type: float
|
||||
default: 0.1
|
||||
UUV_PGM_VEL:
|
||||
description:
|
||||
short: Gain for position control velocity setpoint update
|
||||
type: float
|
||||
default: 0.5
|
||||
UUV_POS_MODE:
|
||||
description:
|
||||
short: Stabilization mode(1) or Position Control(0)
|
||||
type: enum
|
||||
values:
|
||||
0: Moves position setpoint in world frame
|
||||
1: Moves position setpoint in body frame
|
||||
default: 1
|
||||
Loading…
x
Reference in New Issue
Block a user