aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2014-12-18 22:18:08 +0100
committerThomas Gubler <thomasgubler@gmail.com>2014-12-18 22:18:08 +0100
commit5becd2227a26b686c7bbee38e61d19024b5aea5f (patch)
tree958b02caaffa4672abf77d4374b86388b318304e
parentc4b53503354bb78080f3c6835095b848ad22b27b (diff)
parentf3b5b67eec258476480a225b6b835e46335003b4 (diff)
downloadpx4-firmware-5becd2227a26b686c7bbee38e61d19024b5aea5f.tar.gz
px4-firmware-5becd2227a26b686c7bbee38e61d19024b5aea5f.tar.bz2
px4-firmware-5becd2227a26b686c7bbee38e61d19024b5aea5f.zip
Merge pull request #1509 from PX4/VTOL_startup_and_parameter_fix
Vtol startup and parameter fix
-rw-r--r--ROMFS/px4fmu_common/init.d/13001_caipirinha_vtol6
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.vtol_defaults2
-rw-r--r--ROMFS/px4fmu_common/init.d/rcS2
-rw-r--r--src/modules/vtol_att_control/vtol_att_control_main.cpp10
-rw-r--r--src/modules/vtol_att_control/vtol_att_control_params.c95
5 files changed, 95 insertions, 20 deletions
diff --git a/ROMFS/px4fmu_common/init.d/13001_caipirinha_vtol b/ROMFS/px4fmu_common/init.d/13001_caipirinha_vtol
index bff971c0f..7e9a6d3dc 100644
--- a/ROMFS/px4fmu_common/init.d/13001_caipirinha_vtol
+++ b/ROMFS/px4fmu_common/init.d/13001_caipirinha_vtol
@@ -9,8 +9,8 @@ sh /etc/init.d/rc.vtol_defaults
set MIXER FMU_caipirinha_vtol
-set PWM_OUTPUTS 12
+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 VT_MOT_COUNT 2
+param set VT_IDLE_PWM_MC 1080
diff --git a/ROMFS/px4fmu_common/init.d/rc.vtol_defaults b/ROMFS/px4fmu_common/init.d/rc.vtol_defaults
index 10ee5db9b..6dc5a65db 100644
--- a/ROMFS/px4fmu_common/init.d/rc.vtol_defaults
+++ b/ROMFS/px4fmu_common/init.d/rc.vtol_defaults
@@ -2,7 +2,7 @@
set VEHICLE_TYPE vtol
-if [ $DO_AUTOCONFIG == yes ]
+if [ $AUTOCNF == yes ]
then
#
#Default controller parameters for MC
diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS
index 5748fe2b5..14fc8d2b4 100644
--- a/ROMFS/px4fmu_common/init.d/rcS
+++ b/ROMFS/px4fmu_common/init.d/rcS
@@ -584,7 +584,7 @@ then
sh /etc/init.d/rc.interface
# Start standard vtol apps
- if [ $LOAD_DEFAULT_APPS == yes ]
+ if [ $LOAD_DAPPS == yes ]
then
sh /etc/init.d/rc.vtol_apps
fi
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..958907d1b 100644
--- a/src/modules/vtol_att_control/vtol_att_control_main.cpp
+++ b/src/modules/vtol_att_control/vtol_att_control_main.cpp
@@ -238,11 +238,11 @@ 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.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");
- _params_handles.mc_airspeed_trim = param_find("VTOL_MC_AIRSPEED_TRIM");
+ _params_handles.idle_pwm_mc = param_find("VT_IDLE_PWM_MC");
+ _params_handles.vtol_motor_count = param_find("VT_MOT_COUNT");
+ _params_handles.mc_airspeed_min = param_find("VT_MC_ARSPD_MIN");
+ _params_handles.mc_airspeed_max = param_find("VT_MC_ARSPD_MAX");
+ _params_handles.mc_airspeed_trim = param_find("VT_MC_ARSPD_TRIM");
/* fetch initial parameter values */
parameters_update();
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..e21bccb0c 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
-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);
+/**
+ * VTOL number of engines
+ *
+ * @min 1.0
+ * @group VTOL Attitude Control
+ */
+PARAM_DEFINE_INT32(VT_MOT_COUNT,0);
+
+/**
+ * Idle speed of VTOL when in multicopter mode
+ *
+ * @min 900
+ * @group VTOL Attitude Control
+ */
+PARAM_DEFINE_INT32(VT_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(VT_MC_ARSPD_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(VT_MC_ARSPD_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(VT_MC_ARSPD_TRIM,10.0f);