From 23a62342359ba99eb1c6bb1832ba266b442a7e3e Mon Sep 17 00:00:00 2001 From: px4dev Date: Sat, 1 Jun 2013 23:31:53 +0200 Subject: Rename our 'task_spawn' to 'task_spawn_cmd' since NuttX now has its own version of task_spawn that's different. --- src/examples/fixedwing_control/main.c | 2 +- src/examples/px4_daemon_app/px4_daemon_app.c | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) (limited to 'src/examples') diff --git a/src/examples/fixedwing_control/main.c b/src/examples/fixedwing_control/main.c index 89fbef020..27888523b 100644 --- a/src/examples/fixedwing_control/main.c +++ b/src/examples/fixedwing_control/main.c @@ -528,7 +528,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/px4_daemon_app/px4_daemon_app.c b/src/examples/px4_daemon_app/px4_daemon_app.c index a5d847777..fbb38e4b9 100644 --- a/src/examples/px4_daemon_app/px4_daemon_app.c +++ b/src/examples/px4_daemon_app/px4_daemon_app.c @@ -91,7 +91,7 @@ int px4_deamon_app_main(int argc, char *argv[]) } thread_should_exit = false; - deamon_task = task_spawn("deamon", + deamon_task = task_spawn_cmd("deamon", SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT, 4096, -- cgit v1.2.3 From 422c675c551c4a160e8bcdb18ffe3c6160b63980 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 5 Jul 2013 11:44:25 +0200 Subject: Commented flow example slightly better --- .../flow_position_control/flow_position_control_params.c | 11 +++++++++++ 1 file changed, 11 insertions(+) (limited to 'src/examples') 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); -- cgit v1.2.3