aboutsummaryrefslogtreecommitdiff
path: root/src/examples
diff options
context:
space:
mode:
authorJulian Oes <julian@oes.ch>2013-07-08 10:31:32 +0200
committerJulian Oes <julian@oes.ch>2013-07-08 10:31:32 +0200
commit88389ea2554c6f56a4fdd86cdd86a1e7b6affc21 (patch)
tree3ef98ded43e5f3a2cdc30a836a3a7329fe5757bb /src/examples
parent76346bfe19c816491a6982abfa10f48cd9d258f6 (diff)
parentcf2dbdf9a1ae06c7d0e0a7963916a3709a1bc075 (diff)
downloadpx4-firmware-88389ea2554c6f56a4fdd86cdd86a1e7b6affc21.tar.gz
px4-firmware-88389ea2554c6f56a4fdd86cdd86a1e7b6affc21.tar.bz2
px4-firmware-88389ea2554c6f56a4fdd86cdd86a1e7b6affc21.zip
Merge branch 'master' into new_state_machine
compiling again Conflicts: src/modules/fixedwing_att_control/fixedwing_att_control_att.c src/modules/fixedwing_att_control/fixedwing_att_control_rate.c src/modules/fixedwing_pos_control/fixedwing_pos_control_main.c src/modules/mavlink/orb_listener.c src/modules/multirotor_att_control/multirotor_attitude_control.c src/modules/multirotor_att_control/multirotor_rate_control.c src/modules/systemlib/pid/pid.c src/modules/systemlib/pid/pid.h src/modules/uORB/objects_common.cpp
Diffstat (limited to 'src/examples')
-rw-r--r--src/examples/fixedwing_control/main.c2
-rw-r--r--src/examples/flow_position_control/flow_position_control_params.c11
-rw-r--r--src/examples/px4_daemon_app/px4_daemon_app.c2
3 files changed, 13 insertions, 2 deletions
diff --git a/src/examples/fixedwing_control/main.c b/src/examples/fixedwing_control/main.c
index 6f52c60bb..ae33a3702 100644
--- a/src/examples/fixedwing_control/main.c
+++ b/src/examples/fixedwing_control/main.c
@@ -531,7 +531,7 @@ int ex_fixedwing_control_main(int argc, char *argv[])
}
thread_should_exit = false;
- deamon_task = task_spawn("ex_fixedwing_control",
+ deamon_task = task_spawn_cmd("ex_fixedwing_control",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 20,
2048,
diff --git a/src/examples/flow_position_control/flow_position_control_params.c b/src/examples/flow_position_control/flow_position_control_params.c
index 4f3598a57..eb1473647 100644
--- a/src/examples/flow_position_control/flow_position_control_params.c
+++ b/src/examples/flow_position_control/flow_position_control_params.c
@@ -40,14 +40,25 @@
#include "flow_position_control_params.h"
/* controller parameters */
+
+// Position control P gain
PARAM_DEFINE_FLOAT(FPC_POS_P, 3.0f);
+// Position control D / damping gain
PARAM_DEFINE_FLOAT(FPC_POS_D, 0.0f);
+// Altitude control P gain
PARAM_DEFINE_FLOAT(FPC_H_P, 0.15f);
+// Altitude control I (integrator) gain
PARAM_DEFINE_FLOAT(FPC_H_I, 0.00001f);
+// Altitude control D gain
PARAM_DEFINE_FLOAT(FPC_H_D, 0.8f);
+// Altitude control rate limiter
PARAM_DEFINE_FLOAT(FPC_H_RATE, 0.1f);
+// Altitude control minimum altitude
PARAM_DEFINE_FLOAT(FPC_H_MIN, 0.5f);
+// Altitude control maximum altitude (higher than 1.5m is untested)
PARAM_DEFINE_FLOAT(FPC_H_MAX, 1.5f);
+// Altitude control feed forward throttle - adjust to the
+// throttle position (0..1) where the copter hovers in manual flight
PARAM_DEFINE_FLOAT(FPC_T_FFWD, 0.7f); // adjust this before flight
PARAM_DEFINE_FLOAT(FPC_L_S_X, 1.2f);
PARAM_DEFINE_FLOAT(FPC_L_S_Y, 1.2f);
diff --git a/src/examples/px4_daemon_app/px4_daemon_app.c b/src/examples/px4_daemon_app/px4_daemon_app.c
index c568aaadc..53f1b4a9a 100644
--- a/src/examples/px4_daemon_app/px4_daemon_app.c
+++ b/src/examples/px4_daemon_app/px4_daemon_app.c
@@ -95,7 +95,7 @@ int px4_daemon_app_main(int argc, char *argv[])
}
thread_should_exit = false;
- daemon_task = task_spawn("daemon",
+ daemon_task = task_spawn_cmd("daemon",
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
4096,