aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorRoman Bapst <romanbapst@yahoo.de>2014-12-18 10:46:36 +0100
committerRoman Bapst <romanbapst@yahoo.de>2014-12-18 10:46:36 +0100
commit669e1f96d8fed848d2fbe71d3a10adb749a5fcc4 (patch)
tree4bd5e4609fc595a0d063c3e196ca0212974db6ee
parent0e79cbf234ba633669bbc1e939b1722f5396dc11 (diff)
downloadpx4-firmware-669e1f96d8fed848d2fbe71d3a10adb749a5fcc4.tar.gz
px4-firmware-669e1f96d8fed848d2fbe71d3a10adb749a5fcc4.tar.bz2
px4-firmware-669e1f96d8fed848d2fbe71d3a10adb749a5fcc4.zip
fixed parameter issue for VTOL so that parameter wiki tool can document them
-rw-r--r--ROMFS/px4fmu_common/init.d/13001_caipirinha_vtol2
-rw-r--r--src/modules/vtol_att_control/vtol_att_control_main.cpp2
-rw-r--r--src/modules/vtol_att_control/vtol_att_control_params.c93
3 files changed, 86 insertions, 11 deletions
diff --git a/ROMFS/px4fmu_common/init.d/13001_caipirinha_vtol b/ROMFS/px4fmu_common/init.d/13001_caipirinha_vtol
index 8f7a28b97..fb31142fa 100644
--- a/ROMFS/px4fmu_common/init.d/13001_caipirinha_vtol
+++ b/ROMFS/px4fmu_common/init.d/13001_caipirinha_vtol
@@ -13,4 +13,4 @@ set PWM_OUT 12
set PWM_MAX 2000
set PWM_RATE 400
param set VTOL_MOT_COUNT 2
-param set IDLE_PWM_MC 1080
+param set VTOL_IDLE_PWM_MC 1080
diff --git a/src/modules/vtol_att_control/vtol_att_control_main.cpp b/src/modules/vtol_att_control/vtol_att_control_main.cpp
index 24800cce8..de678a5b8 100644
--- a/src/modules/vtol_att_control/vtol_att_control_main.cpp
+++ b/src/modules/vtol_att_control/vtol_att_control_main.cpp
@@ -238,7 +238,7 @@ VtolAttitudeControl::VtolAttitudeControl() :
_params.idle_pwm_mc = PWM_LOWEST_MIN;
_params.vtol_motor_count = 0;
- _params_handles.idle_pwm_mc = param_find("IDLE_PWM_MC");
+ _params_handles.idle_pwm_mc = param_find("VTOL_IDLE_PWM_MC");
_params_handles.vtol_motor_count = param_find("VTOL_MOT_COUNT");
_params_handles.mc_airspeed_min = param_find("VTOL_MC_AIRSPEED_MIN");
_params_handles.mc_airspeed_max = param_find("VTOL_MC_AIRSPEED_MAX");
diff --git a/src/modules/vtol_att_control/vtol_att_control_params.c b/src/modules/vtol_att_control/vtol_att_control_params.c
index 44157acba..6a234a3ba 100644
--- a/src/modules/vtol_att_control/vtol_att_control_params.c
+++ b/src/modules/vtol_att_control/vtol_att_control_params.c
@@ -1,13 +1,88 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2014 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 vtol_att_control_params.c
+ * Parameters for vtol attitude controller.
+ *
+ * @author Roman Bapst <bapstr@ethz.ch>
+ */
+
#include <systemlib/param/param.h>
-// number of engines
+/**
+ * VTOL number of engines
+ *
+ * @min 1.0
+ * @group VTOL Attitude Control
+ */
PARAM_DEFINE_INT32(VTOL_MOT_COUNT,0);
-// idle pwm in multicopter mode
-PARAM_DEFINE_INT32(IDLE_PWM_MC,900);
-// min airspeed in multicopter mode
-PARAM_DEFINE_FLOAT(VTOL_MC_AIRSPEED_MIN,2);
-// max airspeed in multicopter mode
-PARAM_DEFINE_FLOAT(VTOL_MC_AIRSPEED_MAX,30);
-// trim airspeed in multicopter mode
-PARAM_DEFINE_FLOAT(VTOL_MC_AIRSPEED_TRIM,10);
+
+/**
+ * Idle speed of VTOL when in multicopter mode
+ *
+ * @min 900
+ * @group VTOL Attitude Control
+ */
+PARAM_DEFINE_INT32(VTOL_IDLE_PWM_MC,900);
+
+/**
+ * Minimum airspeed in multicopter mode
+ *
+ * This is the minimum speed of the air flowing over the control surfaces.
+ *
+ * @min 0.0
+ * @group VTOL Attitude Control
+ */
+PARAM_DEFINE_FLOAT(VTOL_MC_AIRSPEED_MIN,2.0f);
+
+/**
+ * Maximum airspeed in multicopter mode
+ *
+ * This is the maximum speed of the air flowing over the control surfaces.
+ *
+ * @min 0.0
+ * @group VTOL Attitude Control
+ */
+PARAM_DEFINE_FLOAT(VTOL_MC_AIRSPEED_MAX,30.0f);
+
+/**
+ * Trim airspeed when in multicopter mode
+ *
+ * This is the airflow over the control surfaces for which no airspeed scaling is applied in multicopter mode.
+ *
+ * @min 0.0
+ * @group VTOL Attitude Control
+ */
+PARAM_DEFINE_FLOAT(VTOL_MC_AIRSPEED_TRIM,10.0f);