diff options
author | Julian Oes <julian@oes.ch> | 2013-06-12 12:24:52 +0200 |
---|---|---|
committer | Julian Oes <julian@oes.ch> | 2013-06-12 12:24:52 +0200 |
commit | 7f90ebf537f226bc974a9d6023b67a9b32dccfe3 (patch) | |
tree | 7664a08157148ab0429aae7cb1a02575c6ef5c5b /src/examples | |
parent | f5c157e74df12a0cb36b7d27cdad9828d96cc534 (diff) | |
parent | 42ce3112ad645e53788463180c350279b243b02e (diff) | |
download | px4-firmware-7f90ebf537f226bc974a9d6023b67a9b32dccfe3.tar.gz px4-firmware-7f90ebf537f226bc974a9d6023b67a9b32dccfe3.tar.bz2 px4-firmware-7f90ebf537f226bc974a9d6023b67a9b32dccfe3.zip |
Merge remote-tracking branch 'upstream/master' into new_state_machine
Conflicts:
src/examples/fixedwing_control/main.c
Diffstat (limited to 'src/examples')
-rw-r--r-- | src/examples/fixedwing_control/main.c | 130 | ||||
-rw-r--r-- | src/examples/fixedwing_control/params.c | 2 | ||||
-rw-r--r-- | src/examples/px4_daemon_app/px4_daemon_app.c | 54 |
3 files changed, 139 insertions, 47 deletions
diff --git a/src/examples/fixedwing_control/main.c b/src/examples/fixedwing_control/main.c index 7bf99785c..6f52c60bb 100644 --- a/src/examples/fixedwing_control/main.c +++ b/src/examples/fixedwing_control/main.c @@ -33,10 +33,13 @@ ****************************************************************************/ /** * @file main.c - * Implementation of a fixed wing attitude controller. This file is a complete - * fixed wing controller flying manual attitude control or auto waypoint control. + * + * Example implementation of a fixed wing attitude controller. This file is a complete + * fixed wing controller for manual attitude control or auto waypoint control. * There is no need to touch any other system components to extend / modify the * complete control architecture. + * + * @author Lorenz Meier <lm@inf.ethz.ch> */ #include <nuttx/config.h> @@ -60,7 +63,6 @@ #include <uORB/topics/actuator_controls.h> #include <uORB/topics/vehicle_rates_setpoint.h> #include <uORB/topics/vehicle_global_position.h> -#include <uORB/topics/debug_key_value.h> #include <uORB/topics/parameter_update.h> #include <systemlib/param/param.h> #include <systemlib/pid/pid.h> @@ -73,8 +75,15 @@ #include "params.h" /* Prototypes */ + /** * Daemon management function. + * + * This function allows to start / stop the background task (daemon). + * The purpose of it is to be able to start the controller on the + * command line, query its status and stop it, without giving up + * the command line to one particular process or the need for bg/fg + * ^Z support by the shell. */ __EXPORT int ex_fixedwing_control_main(int argc, char *argv[]); @@ -88,10 +97,34 @@ int fixedwing_control_thread_main(int argc, char *argv[]); */ static void usage(const char *reason); +/** + * Control roll and pitch angle. + * + * This very simple roll and pitch controller takes the current roll angle + * of the system and compares it to a reference. Pitch is controlled to zero and yaw remains + * uncontrolled (tutorial code, not intended for flight). + * + * @param att_sp The current attitude setpoint - the values the system would like to reach. + * @param att The current attitude. The controller should make the attitude match the setpoint + * @param speed_body The velocity of the system. Currently unused. + * @param rates_sp The angular rate setpoint. This is the output of the controller. + */ void control_attitude(const struct vehicle_attitude_setpoint_s *att_sp, const struct vehicle_attitude_s *att, - float speed_body[], float gyro[], struct vehicle_rates_setpoint_s *rates_sp, + float speed_body[], struct vehicle_rates_setpoint_s *rates_sp, struct actuator_controls_s *actuators); +/** + * Control heading. + * + * This very simple heading to roll angle controller outputs the desired roll angle based on + * the current position of the system, the desired position (the setpoint) and the current + * heading. + * + * @param pos The current position of the system + * @param sp The current position setpoint + * @param att The current attitude + * @param att_sp The attitude setpoint. This is the output of the controller + */ void control_heading(const struct vehicle_global_position_s *pos, const struct vehicle_global_position_setpoint_s *sp, const struct vehicle_attitude_s *att, struct vehicle_attitude_setpoint_s *att_sp); @@ -103,7 +136,7 @@ static struct params p; static struct param_handles ph; void control_attitude(const struct vehicle_attitude_setpoint_s *att_sp, const struct vehicle_attitude_s *att, - float speed_body[], float gyro[], struct vehicle_rates_setpoint_s *rates_sp, + float speed_body[], struct vehicle_rates_setpoint_s *rates_sp, struct actuator_controls_s *actuators) { @@ -148,13 +181,23 @@ void control_heading(const struct vehicle_global_position_s *pos, const struct v * Calculate heading error of current position to desired position */ - /* PX4 uses 1e7 scaled integers to represent global coordinates for max resolution */ + /* + * PX4 uses 1e7 scaled integers to represent global coordinates for max resolution, + * so they need to be scaled by 1e7 and converted to IEEE double precision floating point. + */ float bearing = get_bearing_to_next_waypoint(pos->lat/1e7d, pos->lon/1e7d, sp->lat/1e7d, sp->lon/1e7d); /* calculate heading error */ float yaw_err = att->yaw - bearing; /* apply control gain */ - att_sp->roll_body = yaw_err * p.hdng_p; + float roll_command = yaw_err * p.hdng_p; + + /* limit output, this commonly is a tuning parameter, too */ + if (att_sp->roll_body < -0.6f) { + att_sp->roll_body = -0.6f; + } else if (att_sp->roll_body > 0.6f) { + att_sp->roll_body = 0.6f; + } } /* Main Thread */ @@ -176,7 +219,32 @@ int fixedwing_control_thread_main(int argc, char *argv[]) parameters_init(&ph); parameters_update(&ph, &p); - /* declare and safely initialize all structs to zero */ + + /* + * PX4 uses a publish/subscribe design pattern to enable + * multi-threaded communication. + * + * The most elegant aspect of this is that controllers and + * other processes can either 'react' to new data, or run + * at their own pace. + * + * PX4 developer guide: + * https://pixhawk.ethz.ch/px4/dev/shared_object_communication + * + * Wikipedia description: + * http://en.wikipedia.org/wiki/Publish–subscribe_pattern + * + */ + + + + + /* + * Declare and safely initialize all structs to zero. + * + * These structs contain the system state and things + * like attitude, position, the current waypoint, etc. + */ struct vehicle_attitude_s att; memset(&att, 0, sizeof(att)); struct vehicle_attitude_setpoint_s att_sp; @@ -192,20 +260,24 @@ int fixedwing_control_thread_main(int argc, char *argv[]) struct vehicle_global_position_setpoint_s global_sp; memset(&global_sp, 0, sizeof(global_sp)); - /* output structs */ + /* output structs - this is what is sent to the mixer */ struct actuator_controls_s actuators; memset(&actuators, 0, sizeof(actuators)); - /* publish actuator controls */ + /* publish actuator controls with zero values */ for (unsigned i = 0; i < NUM_ACTUATOR_CONTROLS; i++) { actuators.control[i] = 0.0f; } + /* + * Advertise that this controller will publish actuator + * control values and the rate setpoint + */ orb_advert_t actuator_pub = orb_advertise(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, &actuators); orb_advert_t rates_pub = orb_advertise(ORB_ID(vehicle_rates_setpoint), &rates_sp); - /* subscribe */ + /* subscribe to topics. */ int att_sub = orb_subscribe(ORB_ID(vehicle_attitude)); int att_sp_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint)); int global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position)); @@ -215,8 +287,9 @@ int fixedwing_control_thread_main(int argc, char *argv[]) int param_sub = orb_subscribe(ORB_ID(parameter_update)); /* Setup of loop */ - float gyro[3] = {0.0f, 0.0f, 0.0f}; float speed_body[3] = {0.0f, 0.0f, 0.0f}; + /* RC failsafe check */ + bool throttle_half_once = false; struct pollfd fds[2] = {{ .fd = param_sub, .events = POLLIN }, { .fd = att_sub, .events = POLLIN }}; @@ -235,7 +308,10 @@ int fixedwing_control_thread_main(int argc, char *argv[]) int ret = poll(fds, 2, 500); if (ret < 0) { - /* poll error, this will not really happen in practice */ + /* + * Poll error, this will not really happen in practice, + * but its good design practice to make output an error message. + */ warnx("poll error"); } else if (ret == 0) { @@ -261,6 +337,8 @@ int fixedwing_control_thread_main(int argc, char *argv[]) orb_check(global_pos_sub, &pos_updated); bool global_sp_updated; orb_check(global_sp_sub, &global_sp_updated); + bool manual_sp_updated; + orb_check(manual_sp_sub, &manual_sp_updated); /* get a local copy of attitude */ orb_copy(ORB_ID(vehicle_attitude), att_sub, &att); @@ -268,6 +346,7 @@ int fixedwing_control_thread_main(int argc, char *argv[]) if (global_sp_updated) orb_copy(ORB_ID(vehicle_global_position_setpoint), global_sp_sub, &global_sp); + /* currently speed in body frame is not used, but here for reference */ if (pos_updated) { orb_copy(ORB_ID(vehicle_global_position), global_pos_sub, &global_pos); @@ -285,12 +364,19 @@ int fixedwing_control_thread_main(int argc, char *argv[]) } } - orb_copy(ORB_ID(manual_control_setpoint), manual_sp_sub, &manual_sp); - orb_copy(ORB_ID(vehicle_status), vstatus_sub, &vstatus); + if (manual_sp_updated) + /* get the RC (or otherwise user based) input */ + orb_copy(ORB_ID(manual_control_setpoint), manual_sp_sub, &manual_sp); - gyro[0] = att.rollspeed; - gyro[1] = att.pitchspeed; - gyro[2] = att.yawspeed; + /* check if the throttle was ever more than 50% - go later only to failsafe if yes */ + if (isfinite(manual_sp.throttle) && + (manual_sp.throttle >= 0.6f) && + (manual_sp.throttle <= 1.0f)) { + throttle_half_once = true; + } + + /* get the system status and the flight mode we're in */ + orb_copy(ORB_ID(vehicle_status), vstatus_sub, &vstatus); /* control */ @@ -307,7 +393,7 @@ int fixedwing_control_thread_main(int argc, char *argv[]) actuators.control[2] = 0.0f; /* simple attitude control */ - control_attitude(&att_sp, &att, speed_body, gyro, &rates_sp, &actuators); + control_attitude(&att_sp, &att, speed_body, &rates_sp, &actuators); /* pass through throttle */ actuators.control[3] = att_sp.thrust; @@ -316,10 +402,12 @@ int fixedwing_control_thread_main(int argc, char *argv[]) actuators.control[4] = 0.0f; } else if (vstatus.navigation_state == NAVIGATION_STATE_MANUAL) { + /* if in manual mode, decide between attitude stabilization (SAS) and full manual pass-through */ + } else if (vstatus.state_machine == SYSTEM_STATE_MANUAL) { if (vstatus.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_SAS) { /* if the RC signal is lost, try to stay level and go slowly back down to ground */ - if (vstatus.rc_signal_lost) { + if (vstatus.rc_signal_lost && throttle_half_once) { /* put plane into loiter */ att_sp.roll_body = 0.3f; @@ -350,7 +438,7 @@ int fixedwing_control_thread_main(int argc, char *argv[]) att_sp.timestamp = hrt_absolute_time(); /* attitude control */ - control_attitude(&att_sp, &att, speed_body, gyro, &rates_sp, &actuators); + control_attitude(&att_sp, &att, speed_body, &rates_sp, &actuators); /* pass through throttle */ actuators.control[3] = att_sp.thrust; diff --git a/src/examples/fixedwing_control/params.c b/src/examples/fixedwing_control/params.c index 8042c74f5..c2e94ff3d 100644 --- a/src/examples/fixedwing_control/params.c +++ b/src/examples/fixedwing_control/params.c @@ -45,7 +45,7 @@ /** * */ -PARAM_DEFINE_FLOAT(EXFW_HDNG_P, 0.2f); +PARAM_DEFINE_FLOAT(EXFW_HDNG_P, 0.1f); /** * diff --git a/src/examples/px4_daemon_app/px4_daemon_app.c b/src/examples/px4_daemon_app/px4_daemon_app.c index a5d847777..c568aaadc 100644 --- a/src/examples/px4_daemon_app/px4_daemon_app.c +++ b/src/examples/px4_daemon_app/px4_daemon_app.c @@ -1,7 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2012 PX4 Development Team. All rights reserved. - * Author: @author Example User <mail@example.com> + * Copyright (c) 2012, 2013 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 @@ -33,27 +32,33 @@ ****************************************************************************/ /** - * @file px4_deamon_app.c - * Deamon application example for PX4 autopilot + * @file px4_daemon_app.c + * daemon application example for PX4 autopilot + * + * @author Example User <mail@example.com> */ #include <nuttx/config.h> +#include <nuttx/sched.h> #include <unistd.h> #include <stdio.h> -static bool thread_should_exit = false; /**< Deamon exit flag */ -static bool thread_running = false; /**< Deamon status flag */ -static int deamon_task; /**< Handle of deamon task / thread */ +#include <systemlib/systemlib.h> +#include <systemlib/err.h> + +static bool thread_should_exit = false; /**< daemon exit flag */ +static bool thread_running = false; /**< daemon status flag */ +static int daemon_task; /**< Handle of daemon task / thread */ /** - * Deamon management function. + * daemon management function. */ -__EXPORT int px4_deamon_app_main(int argc, char *argv[]); +__EXPORT int px4_daemon_app_main(int argc, char *argv[]); /** - * Mainloop of deamon. + * Mainloop of daemon. */ -int px4_deamon_thread_main(int argc, char *argv[]); +int px4_daemon_thread_main(int argc, char *argv[]); /** * Print the correct usage. @@ -64,20 +69,19 @@ static void usage(const char *reason) { if (reason) - fprintf(stderr, "%s\n", reason); - fprintf(stderr, "usage: deamon {start|stop|status} [-p <additional params>]\n\n"); - exit(1); + warnx("%s\n", reason); + errx(1, "usage: daemon {start|stop|status} [-p <additional params>]\n\n"); } /** - * The deamon app only briefly exists to start + * The daemon app only briefly exists to start * the background job. The stack size assigned in the * Makefile does only apply to this management task. * * The actual stack size should be set in the call * to task_create(). */ -int px4_deamon_app_main(int argc, char *argv[]) +int px4_daemon_app_main(int argc, char *argv[]) { if (argc < 1) usage("missing command"); @@ -85,17 +89,17 @@ int px4_deamon_app_main(int argc, char *argv[]) if (!strcmp(argv[1], "start")) { if (thread_running) { - printf("deamon already running\n"); + warnx("daemon already running\n"); /* this is not an error */ exit(0); } thread_should_exit = false; - deamon_task = task_spawn("deamon", + daemon_task = task_spawn("daemon", SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT, 4096, - px4_deamon_thread_main, + px4_daemon_thread_main, (argv) ? (const char **)&argv[2] : (const char **)NULL); exit(0); } @@ -107,9 +111,9 @@ int px4_deamon_app_main(int argc, char *argv[]) if (!strcmp(argv[1], "status")) { if (thread_running) { - printf("\tdeamon app is running\n"); + warnx("\trunning\n"); } else { - printf("\tdeamon app not started\n"); + warnx("\tnot started\n"); } exit(0); } @@ -118,18 +122,18 @@ int px4_deamon_app_main(int argc, char *argv[]) exit(1); } -int px4_deamon_thread_main(int argc, char *argv[]) { +int px4_daemon_thread_main(int argc, char *argv[]) { - printf("[deamon] starting\n"); + warnx("[daemon] starting\n"); thread_running = true; while (!thread_should_exit) { - printf("Hello Deamon!\n"); + warnx("Hello daemon!\n"); sleep(10); } - printf("[deamon] exiting.\n"); + warnx("[daemon] exiting.\n"); thread_running = false; |