From e59aaa771c790c87d765e3fab329e8bd4be241a9 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 19 Feb 2015 21:51:53 +0100 Subject: Rover: Add simple steering controller. --- src/examples/rover_steering_control/main.c | 412 ++++++++++++++++++++++++++ src/examples/rover_steering_control/module.mk | 45 +++ src/examples/rover_steering_control/params.c | 64 ++++ src/examples/rover_steering_control/params.h | 61 ++++ 4 files changed, 582 insertions(+) create mode 100644 src/examples/rover_steering_control/main.c create mode 100644 src/examples/rover_steering_control/module.mk create mode 100644 src/examples/rover_steering_control/params.c create mode 100644 src/examples/rover_steering_control/params.h (limited to 'src/examples') diff --git a/src/examples/rover_steering_control/main.c b/src/examples/rover_steering_control/main.c new file mode 100644 index 000000000..d3a646ee9 --- /dev/null +++ b/src/examples/rover_steering_control/main.c @@ -0,0 +1,412 @@ +/**************************************************************************** + * + * Copyright (c) 2013-2015 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 main.c + * + * 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 + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +/* process-specific header files */ +#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 rover_steering_control_main(int argc, char *argv[]); + +/** + * Mainloop of daemon. + */ +int rover_steering_control_thread_main(int argc, char *argv[]); + +/** + * Print the correct usage. + */ +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 + */ +void control_attitude(const struct vehicle_attitude_setpoint_s *att_sp, const struct vehicle_attitude_s *att, + struct actuator_controls_s *actuators); + +/* Variables */ +static bool thread_should_exit = false; /**< Daemon exit flag */ +static bool thread_running = false; /**< Daemon status flag */ +static int deamon_task; /**< Handle of deamon task / thread */ +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, + struct actuator_controls_s *actuators) +{ + + /* + * The PX4 architecture provides a mixer outside of the controller. + * The mixer is fed with a default vector of actuator controls, representing + * moments applied to the vehicle frame. This vector + * is structured as: + * + * Control Group 0 (attitude): + * + * 0 - roll (-1..+1) + * 1 - pitch (-1..+1) + * 2 - yaw (-1..+1) + * 3 - thrust ( 0..+1) + * 4 - flaps (-1..+1) + * ... + * + * Control Group 1 (payloads / special): + * + * ... + */ + + /* set r/p zero */ + actuators->control[0] = 0.0f; + actuators->control[1] = 0.0f; + + /* + * Calculate roll error and apply P gain + */ + float yaw_err = att->yaw - att_sp->yaw_body; + actuators->control[2] = yaw_err * p.yaw_p; + + /* copy throttle */ + actuators->control[3] = att_sp->thrust; +} + +/* Main Thread */ +int rover_steering_control_thread_main(int argc, char *argv[]) +{ + /* read arguments */ + bool verbose = false; + + for (int i = 1; i < argc; i++) { + if (strcmp(argv[i], "-v") == 0 || strcmp(argv[i], "--verbose") == 0) { + verbose = true; + } + } + + /* initialize parameters, first the handles, then the values */ + parameters_init(&ph); + parameters_update(&ph, &p); + + + /* + * 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; + memset(&att_sp, 0, sizeof(att_sp)); + struct vehicle_global_position_s global_pos; + memset(&global_pos, 0, sizeof(global_pos)); + struct manual_control_setpoint_s manual_sp; + memset(&manual_sp, 0, sizeof(manual_sp)); + struct vehicle_status_s vstatus; + memset(&vstatus, 0, sizeof(vstatus)); + struct position_setpoint_s global_sp; + memset(&global_sp, 0, sizeof(global_sp)); + + /* output structs - this is what is sent to the mixer */ + struct actuator_controls_s actuators; + memset(&actuators, 0, sizeof(actuators)); + + + /* 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); + + /* subscribe to topics. */ + int att_sub = orb_subscribe(ORB_ID(vehicle_attitude)); + int global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position)); + int manual_sp_sub = orb_subscribe(ORB_ID(manual_control_setpoint)); + int vstatus_sub = orb_subscribe(ORB_ID(vehicle_status)); + int att_sp_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint)); + int param_sub = orb_subscribe(ORB_ID(parameter_update)); + + /* Setup of loop */ + + struct pollfd fds[2] = {{ .fd = param_sub, .events = POLLIN }, + { .fd = att_sub, .events = POLLIN } + }; + + while (!thread_should_exit) { + + /* + * Wait for a sensor or param update, check for exit condition every 500 ms. + * This means that the execution will block here without consuming any resources, + * but will continue to execute the very moment a new attitude measurement or + * a param update is published. So no latency in contrast to the polling + * design pattern (do not confuse the poll() system call with polling). + * + * This design pattern makes the controller also agnostic of the attitude + * update speed - it runs as fast as the attitude updates with minimal latency. + */ + int ret = poll(fds, 2, 500); + + if (ret < 0) { + /* + * 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) { + /* no return value = nothing changed for 500 ms, ignore */ + } else { + + /* only update parameters if they changed */ + if (fds[0].revents & POLLIN) { + /* read from param to clear updated flag (uORB API requirement) */ + struct parameter_update_s update; + orb_copy(ORB_ID(parameter_update), param_sub, &update); + + /* if a param update occured, re-read our parameters */ + parameters_update(&ph, &p); + } + + /* only run controller if attitude changed */ + if (fds[1].revents & POLLIN) { + + + /* Check if there is a new position measurement or position setpoint */ + bool pos_updated; + orb_check(global_pos_sub, &pos_updated); + bool att_sp_updated; + orb_check(att_sp_sub, &att_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); + + if (att_sp_updated) { + struct vehicle_attitude_setpoint_s _att_sp; + orb_copy(ORB_ID(vehicle_attitude_setpoint), att_sp_sub, &_att_sp); + + /* control attitude / heading */ + control_attitude(&_att_sp, &att, &actuators); + } + + if (manual_sp_updated) + /* get the RC (or otherwise user based) input */ + { + orb_copy(ORB_ID(manual_control_setpoint), manual_sp_sub, &manual_sp); + } + + // XXX copy from manual depending on flight / usage mode to override + + /* get the system status and the flight mode we're in */ + orb_copy(ORB_ID(vehicle_status), vstatus_sub, &vstatus); + + /* sanity check and publish actuator outputs */ + if (isfinite(actuators.control[0]) && + isfinite(actuators.control[1]) && + isfinite(actuators.control[2]) && + isfinite(actuators.control[3])) { + orb_publish(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_pub, &actuators); + + if (verbose) { + warnx("published"); + } + } + } + } + } + + warnx("exiting, stopping all motors."); + thread_running = false; + + /* kill all outputs */ + for (unsigned i = 0; i < NUM_ACTUATOR_CONTROLS; i++) { + actuators.control[i] = 0.0f; + } + + orb_publish(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_pub, &actuators); + + fflush(stdout); + + return 0; +} + +/* Startup Functions */ + +static void +usage(const char *reason) +{ + if (reason) { + fprintf(stderr, "%s\n", reason); + } + + fprintf(stderr, "usage: rover_steering_control {start|stop|status}\n\n"); + exit(1); +} + +/** + * 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_spawn_cmd(). + */ +int rover_steering_control_main(int argc, char *argv[]) +{ + if (argc < 1) { + usage("missing command"); + } + + if (!strcmp(argv[1], "start")) { + + if (thread_running) { + warnx("running"); + /* this is not an error */ + exit(0); + } + + thread_should_exit = false; + deamon_task = task_spawn_cmd("rover_steering_control", + SCHED_DEFAULT, + SCHED_PRIORITY_MAX - 20, + 2048, + rover_steering_control_thread_main, + (argv) ? (char *const *)&argv[2] : (char *const *)NULL); + thread_running = true; + exit(0); + } + + if (!strcmp(argv[1], "stop")) { + thread_should_exit = true; + exit(0); + } + + if (!strcmp(argv[1], "status")) { + if (thread_running) { + warnx("running"); + + } else { + warnx("not started"); + } + + exit(0); + } + + usage("unrecognized command"); + exit(1); +} + + + diff --git a/src/examples/rover_steering_control/module.mk b/src/examples/rover_steering_control/module.mk new file mode 100644 index 000000000..34f462bd4 --- /dev/null +++ b/src/examples/rover_steering_control/module.mk @@ -0,0 +1,45 @@ +############################################################################ +# +# Copyright (c) 2012-2015 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. +# +############################################################################ + +# +# Rover Steering Demo / Example Application +# + +MODULE_COMMAND = rover_steering_control + +SRCS = main.c \ + params.c + +MODULE_STACKSIZE = 1200 + +EXTRACFLAGS = -Wframe-larger-than=1300 diff --git a/src/examples/rover_steering_control/params.c b/src/examples/rover_steering_control/params.c new file mode 100644 index 000000000..c941c1a02 --- /dev/null +++ b/src/examples/rover_steering_control/params.c @@ -0,0 +1,64 @@ +/**************************************************************************** + * + * Copyright (c) 2013-2015 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 params.c + * + * Parameters for rover demo + * + * @author Lorenz Meier + */ + +#include "params.h" + +/* controller parameters, use max. 15 characters for param name! */ + +/** + * + */ +PARAM_DEFINE_FLOAT(RV_YAW_P, 0.1f); + +int parameters_init(struct param_handles *h) +{ + /* PID parameters */ + h->yaw_p = param_find("RV_YAW_P"); + + return OK; +} + +int parameters_update(const struct param_handles *h, struct params *p) +{ + param_get(h->yaw_p, &(p->yaw_p)); + + return OK; +} diff --git a/src/examples/rover_steering_control/params.h b/src/examples/rover_steering_control/params.h new file mode 100644 index 000000000..b0f76bca0 --- /dev/null +++ b/src/examples/rover_steering_control/params.h @@ -0,0 +1,61 @@ +/**************************************************************************** + * + * Copyright (c) 2013 PX4 Development Team. All rights reserved. + * Author: Lorenz Meier + * + * 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 params.h + * + * Definition of parameters for fixedwing example + */ + +#include + +struct params { + float yaw_p; +}; + +struct param_handles { + param_t yaw_p; +}; + +/** + * Initialize all parameter handles and values + * + */ +int parameters_init(struct param_handles *h); + +/** + * Update all parameters + * + */ +int parameters_update(const struct param_handles *h, struct params *p); -- cgit v1.2.3