aboutsummaryrefslogtreecommitdiff
path: root/src/modules/fixedwing_att_control
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2013-04-27 14:28:47 +0200
committerLorenz Meier <lm@inf.ethz.ch>2013-04-27 14:28:47 +0200
commit988bf1eb0a3d36532883734a416f9c9e1e6ba125 (patch)
treecc576d159661afe667a79527110c81b0588a1710 /src/modules/fixedwing_att_control
parent5085023796b0ca68f28b08d3d98ffbb7f789fd3b (diff)
downloadpx4-firmware-988bf1eb0a3d36532883734a416f9c9e1e6ba125.tar.gz
px4-firmware-988bf1eb0a3d36532883734a416f9c9e1e6ba125.tar.bz2
px4-firmware-988bf1eb0a3d36532883734a416f9c9e1e6ba125.zip
Moved all fixed wing controllers to new world
Diffstat (limited to 'src/modules/fixedwing_att_control')
-rw-r--r--src/modules/fixedwing_att_control/fixedwing_att_control_att.c169
-rw-r--r--src/modules/fixedwing_att_control/fixedwing_att_control_att.h51
-rw-r--r--src/modules/fixedwing_att_control/fixedwing_att_control_main.c370
-rw-r--r--src/modules/fixedwing_att_control/fixedwing_att_control_rate.c211
-rw-r--r--src/modules/fixedwing_att_control/fixedwing_att_control_rate.h48
-rw-r--r--src/modules/fixedwing_att_control/module.mk42
6 files changed, 891 insertions, 0 deletions
diff --git a/src/modules/fixedwing_att_control/fixedwing_att_control_att.c b/src/modules/fixedwing_att_control/fixedwing_att_control_att.c
new file mode 100644
index 000000000..769b8b0a8
--- /dev/null
+++ b/src/modules/fixedwing_att_control/fixedwing_att_control_att.c
@@ -0,0 +1,169 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Author: @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ *
+ * 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 fixedwing_att_control_rate.c
+ * Implementation of a fixed wing attitude controller.
+ */
+
+#include <nuttx/config.h>
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include <unistd.h>
+#include <fcntl.h>
+#include <errno.h>
+#include <math.h>
+#include <poll.h>
+#include <time.h>
+#include <drivers/drv_hrt.h>
+#include <arch/board/board.h>
+#include <uORB/uORB.h>
+
+#include <uORB/topics/vehicle_attitude.h>
+#include <uORB/topics/vehicle_attitude_setpoint.h>
+#include <uORB/topics/manual_control_setpoint.h>
+#include <systemlib/param/param.h>
+#include <systemlib/pid/pid.h>
+#include <systemlib/geo/geo.h>
+#include <systemlib/systemlib.h>
+
+#include "fixedwing_att_control_att.h"
+
+
+struct fw_att_control_params {
+ float roll_p;
+ float rollrate_lim;
+ float pitch_p;
+ float pitchrate_lim;
+ float yawrate_lim;
+ float pitch_roll_compensation_p;
+};
+
+struct fw_pos_control_param_handles {
+ param_t roll_p;
+ param_t rollrate_lim;
+ param_t pitch_p;
+ param_t pitchrate_lim;
+ param_t yawrate_lim;
+ param_t pitch_roll_compensation_p;
+};
+
+
+
+/* Internal Prototypes */
+static int parameters_init(struct fw_pos_control_param_handles *h);
+static int parameters_update(const struct fw_pos_control_param_handles *h, struct fw_att_control_params *p);
+
+static int parameters_init(struct fw_pos_control_param_handles *h)
+{
+ /* PID parameters */
+ h->roll_p = param_find("FW_ROLL_P");
+ h->rollrate_lim = param_find("FW_ROLLR_LIM");
+ h->pitch_p = param_find("FW_PITCH_P");
+ h->pitchrate_lim = param_find("FW_PITCHR_LIM");
+ h->yawrate_lim = param_find("FW_YAWR_LIM");
+ h->pitch_roll_compensation_p = param_find("FW_PITCH_RCOMP");
+
+ return OK;
+}
+
+static int parameters_update(const struct fw_pos_control_param_handles *h, struct fw_att_control_params *p)
+{
+ param_get(h->roll_p, &(p->roll_p));
+ param_get(h->rollrate_lim, &(p->rollrate_lim));
+ param_get(h->pitch_p, &(p->pitch_p));
+ param_get(h->pitchrate_lim, &(p->pitchrate_lim));
+ param_get(h->yawrate_lim, &(p->yawrate_lim));
+ param_get(h->pitch_roll_compensation_p, &(p->pitch_roll_compensation_p));
+
+ return OK;
+}
+
+int fixedwing_att_control_attitude(const struct vehicle_attitude_setpoint_s *att_sp,
+ const struct vehicle_attitude_s *att,
+ const float speed_body[],
+ struct vehicle_rates_setpoint_s *rates_sp)
+{
+ static int counter = 0;
+ static bool initialized = false;
+
+ static struct fw_att_control_params p;
+ static struct fw_pos_control_param_handles h;
+
+ static PID_t roll_controller;
+ static PID_t pitch_controller;
+
+
+ if (!initialized) {
+ parameters_init(&h);
+ parameters_update(&h, &p);
+ pid_init(&roll_controller, p.roll_p, 0, 0, 0, p.rollrate_lim, PID_MODE_DERIVATIV_NONE); //P Controller
+ pid_init(&pitch_controller, p.pitch_p, 0, 0, 0, p.pitchrate_lim, PID_MODE_DERIVATIV_NONE); //P Controller
+ initialized = true;
+ }
+
+ /* load new parameters with lower rate */
+ if (counter % 100 == 0) {
+ /* update parameters from storage */
+ parameters_update(&h, &p);
+ pid_set_parameters(&roll_controller, p.roll_p, 0, 0, 0, p.rollrate_lim);
+ pid_set_parameters(&pitch_controller, p.pitch_p, 0, 0, 0, p.pitchrate_lim);
+ }
+
+ /* Roll (P) */
+ rates_sp->roll = pid_calculate(&roll_controller, att_sp->roll_body, att->roll, 0, 0);
+
+
+ /* Pitch (P) */
+
+ /* compensate feedforward for loss of lift due to non-horizontal angle of wing */
+ float pitch_sp_rollcompensation = p.pitch_roll_compensation_p * fabsf(sinf(att_sp->roll_body));
+ /* set pitch plus feedforward roll compensation */
+ rates_sp->pitch = pid_calculate(&pitch_controller,
+ att_sp->pitch_body + pitch_sp_rollcompensation,
+ att->pitch, 0, 0);
+
+ /* Yaw (from coordinated turn constraint or lateral force) */
+ rates_sp->yaw = (att->rollspeed * rates_sp->roll + 9.81f * sinf(att->roll) * cosf(att->pitch) + speed_body[0] * rates_sp->pitch * sinf(att->roll))
+ / (speed_body[0] * cosf(att->roll) * cosf(att->pitch) + speed_body[2] * sinf(att->pitch));
+
+// printf("rates_sp->yaw %.4f \n", (double)rates_sp->yaw);
+
+ counter++;
+
+ return 0;
+}
+
+
+
diff --git a/src/modules/fixedwing_att_control/fixedwing_att_control_att.h b/src/modules/fixedwing_att_control/fixedwing_att_control_att.h
new file mode 100644
index 000000000..600e35b89
--- /dev/null
+++ b/src/modules/fixedwing_att_control/fixedwing_att_control_att.h
@@ -0,0 +1,51 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Author: @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ *
+ *
+ * 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 Fixed Wing Attitude Control */
+
+#ifndef FIXEDWING_ATT_CONTROL_ATT_H_
+#define FIXEDWING_ATT_CONTROL_ATT_H_
+
+#include <uORB/topics/vehicle_rates_setpoint.h>
+#include <uORB/topics/vehicle_attitude_setpoint.h>
+#include <uORB/topics/vehicle_attitude.h>
+#include <uORB/topics/vehicle_global_position.h>
+
+int fixedwing_att_control_attitude(const struct vehicle_attitude_setpoint_s *att_sp,
+ const struct vehicle_attitude_s *att,
+ const float speed_body[],
+ struct vehicle_rates_setpoint_s *rates_sp);
+
+#endif /* FIXEDWING_ATT_CONTROL_ATT_H_ */
diff --git a/src/modules/fixedwing_att_control/fixedwing_att_control_main.c b/src/modules/fixedwing_att_control/fixedwing_att_control_main.c
new file mode 100644
index 000000000..58477632b
--- /dev/null
+++ b/src/modules/fixedwing_att_control/fixedwing_att_control_main.c
@@ -0,0 +1,370 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Author: @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * @author Doug Weibel <douglas.weibel@colorado.edu>
+ *
+ * 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 fixedwing_att_control.c
+ * Implementation of a fixed wing attitude controller.
+ */
+
+#include <nuttx/config.h>
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include <unistd.h>
+#include <fcntl.h>
+#include <errno.h>
+#include <math.h>
+#include <poll.h>
+#include <time.h>
+#include <drivers/drv_hrt.h>
+#include <arch/board/board.h>
+#include <uORB/uORB.h>
+#include <uORB/topics/vehicle_global_position.h>
+#include <uORB/topics/vehicle_global_position_setpoint.h>
+#include <uORB/topics/vehicle_attitude.h>
+#include <uORB/topics/vehicle_status.h>
+#include <uORB/topics/vehicle_attitude_setpoint.h>
+#include <uORB/topics/manual_control_setpoint.h>
+#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 <systemlib/param/param.h>
+#include <systemlib/pid/pid.h>
+#include <systemlib/geo/geo.h>
+#include <systemlib/perf_counter.h>
+#include <systemlib/systemlib.h>
+
+#include "fixedwing_att_control_rate.h"
+#include "fixedwing_att_control_att.h"
+
+/* Prototypes */
+/**
+ * Deamon management function.
+ */
+__EXPORT int fixedwing_att_control_main(int argc, char *argv[]);
+
+/**
+ * Mainloop of deamon.
+ */
+int fixedwing_att_control_thread_main(int argc, char *argv[]);
+
+/**
+ * Print the correct usage.
+ */
+static void usage(const char *reason);
+
+/* Variables */
+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 */
+
+/* Main Thread */
+int fixedwing_att_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;
+ }
+ }
+
+ /* welcome user */
+ printf("[fixedwing att control] started\n");
+
+ /* declare and safely initialize all structs */
+ 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_rates_setpoint_s rates_sp;
+ memset(&rates_sp, 0, sizeof(rates_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));
+
+ /* output structs */
+ struct actuator_controls_s actuators;
+ memset(&actuators, 0, sizeof(actuators));
+
+
+ /* publish actuator controls */
+ for (unsigned i = 0; i < NUM_ACTUATOR_CONTROLS; i++) {
+ actuators.control[i] = 0.0f;
+ }
+
+ 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 */
+ 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));
+ int manual_sp_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
+ int vstatus_sub = orb_subscribe(ORB_ID(vehicle_status));
+
+ /* Setup of loop */
+ float gyro[3] = {0.0f, 0.0f, 0.0f};
+ float speed_body[3] = {0.0f, 0.0f, 0.0f};
+ struct pollfd fds = { .fd = att_sub, .events = POLLIN };
+
+ while (!thread_should_exit) {
+ /* wait for a sensor update, check for exit condition every 500 ms */
+ poll(&fds, 1, 500);
+
+ /* Check if there is a new position measurement or attitude setpoint */
+ bool pos_updated;
+ orb_check(global_pos_sub, &pos_updated);
+ bool att_sp_updated;
+ orb_check(att_sp_sub, &att_sp_updated);
+
+ /* get a local copy of attitude */
+ orb_copy(ORB_ID(vehicle_attitude), att_sub, &att);
+
+ if (att_sp_updated)
+ orb_copy(ORB_ID(vehicle_attitude_setpoint), att_sp_sub, &att_sp);
+
+ if (pos_updated) {
+ orb_copy(ORB_ID(vehicle_global_position), global_pos_sub, &global_pos);
+
+ if (att.R_valid) {
+ speed_body[0] = att.R[0][0] * global_pos.vx + att.R[0][1] * global_pos.vy + att.R[0][2] * global_pos.vz;
+ speed_body[1] = att.R[1][0] * global_pos.vx + att.R[1][1] * global_pos.vy + att.R[1][2] * global_pos.vz;
+ speed_body[2] = att.R[2][0] * global_pos.vx + att.R[2][1] * global_pos.vy + att.R[2][2] * global_pos.vz;
+
+ } else {
+ speed_body[0] = 0;
+ speed_body[1] = 0;
+ speed_body[2] = 0;
+
+ printf("FW ATT CONTROL: Did not get a valid R\n");
+ }
+ }
+
+ orb_copy(ORB_ID(manual_control_setpoint), manual_sp_sub, &manual_sp);
+ orb_copy(ORB_ID(vehicle_status), vstatus_sub, &vstatus);
+
+ gyro[0] = att.rollspeed;
+ gyro[1] = att.pitchspeed;
+ gyro[2] = att.yawspeed;
+
+ /* control */
+
+ if (vstatus.state_machine == SYSTEM_STATE_AUTO ||
+ vstatus.state_machine == SYSTEM_STATE_STABILIZED) {
+ /* attitude control */
+ fixedwing_att_control_attitude(&att_sp, &att, speed_body, &rates_sp);
+
+ /* angular rate control */
+ fixedwing_att_control_rates(&rates_sp, gyro, &actuators);
+
+ /* pass through throttle */
+ actuators.control[3] = att_sp.thrust;
+
+ /* set flaps to zero */
+ actuators.control[4] = 0.0f;
+
+ } 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) {
+
+ /* put plane into loiter */
+ att_sp.roll_body = 0.3f;
+ att_sp.pitch_body = 0.0f;
+
+ /* limit throttle to 60 % of last value if sane */
+ if (isfinite(manual_sp.throttle) &&
+ (manual_sp.throttle >= 0.0f) &&
+ (manual_sp.throttle <= 1.0f)) {
+ att_sp.thrust = 0.6f * manual_sp.throttle;
+
+ } else {
+ att_sp.thrust = 0.0f;
+ }
+
+ att_sp.yaw_body = 0;
+
+ // XXX disable yaw control, loiter
+
+ } else {
+
+ att_sp.roll_body = manual_sp.roll;
+ att_sp.pitch_body = manual_sp.pitch;
+ att_sp.yaw_body = 0;
+ att_sp.thrust = manual_sp.throttle;
+ }
+
+ att_sp.timestamp = hrt_absolute_time();
+
+ /* attitude control */
+ fixedwing_att_control_attitude(&att_sp, &att, speed_body, &rates_sp);
+
+ /* angular rate control */
+ fixedwing_att_control_rates(&rates_sp, gyro, &actuators);
+
+ /* pass through throttle */
+ actuators.control[3] = att_sp.thrust;
+
+ /* pass through flaps */
+ if (isfinite(manual_sp.flaps)) {
+ actuators.control[4] = manual_sp.flaps;
+
+ } else {
+ actuators.control[4] = 0.0f;
+ }
+
+ } else if (vstatus.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_DIRECT) {
+ /* directly pass through values */
+ actuators.control[0] = manual_sp.roll;
+ /* positive pitch means negative actuator -> pull up */
+ actuators.control[1] = manual_sp.pitch;
+ actuators.control[2] = manual_sp.yaw;
+ actuators.control[3] = manual_sp.throttle;
+
+ if (isfinite(manual_sp.flaps)) {
+ actuators.control[4] = manual_sp.flaps;
+
+ } else {
+ actuators.control[4] = 0.0f;
+ }
+ }
+ }
+
+ /* publish rates */
+ orb_publish(ORB_ID(vehicle_rates_setpoint), rates_pub, &rates_sp);
+
+ /* 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);
+ }
+ }
+
+ printf("[fixedwing_att_control] exiting, stopping all motors.\n");
+ 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);
+
+
+
+ close(att_sub);
+ close(actuator_pub);
+ close(rates_pub);
+
+ fflush(stdout);
+ exit(0);
+
+ return 0;
+
+}
+
+/* Startup Functions */
+
+static void
+usage(const char *reason)
+{
+ if (reason)
+ fprintf(stderr, "%s\n", reason);
+
+ fprintf(stderr, "usage: fixedwing_att_control {start|stop|status}\n\n");
+ exit(1);
+}
+
+/**
+ * The deamon 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 fixedwing_att_control_main(int argc, char *argv[])
+{
+ if (argc < 1)
+ usage("missing command");
+
+ if (!strcmp(argv[1], "start")) {
+
+ if (thread_running) {
+ printf("fixedwing_att_control already running\n");
+ /* this is not an error */
+ exit(0);
+ }
+
+ thread_should_exit = false;
+ deamon_task = task_spawn("fixedwing_att_control",
+ SCHED_DEFAULT,
+ SCHED_PRIORITY_MAX - 20,
+ 2048,
+ fixedwing_att_control_thread_main,
+ (argv) ? (const char **)&argv[2] : (const char **)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) {
+ printf("\tfixedwing_att_control is running\n");
+
+ } else {
+ printf("\tfixedwing_att_control not started\n");
+ }
+
+ exit(0);
+ }
+
+ usage("unrecognized command");
+ exit(1);
+}
+
+
+
diff --git a/src/modules/fixedwing_att_control/fixedwing_att_control_rate.c b/src/modules/fixedwing_att_control/fixedwing_att_control_rate.c
new file mode 100644
index 000000000..4eccc118c
--- /dev/null
+++ b/src/modules/fixedwing_att_control/fixedwing_att_control_rate.c
@@ -0,0 +1,211 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Author: Thomas Gubler <thomasgubler@student.ethz.ch>
+ *
+ * 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 fixedwing_att_control_rate.c
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ *
+ * Implementation of a fixed wing attitude controller.
+ *
+ */
+
+#include <nuttx/config.h>
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include <unistd.h>
+#include <fcntl.h>
+#include <errno.h>
+#include <math.h>
+#include <poll.h>
+#include <time.h>
+#include <drivers/drv_hrt.h>
+#include <arch/board/board.h>
+#include <uORB/uORB.h>
+
+#include <uORB/topics/vehicle_attitude.h>
+#include <uORB/topics/vehicle_attitude_setpoint.h>
+#include <uORB/topics/manual_control_setpoint.h>
+#include <systemlib/param/param.h>
+#include <systemlib/pid/pid.h>
+#include <systemlib/geo/geo.h>
+#include <systemlib/systemlib.h>
+
+#include "fixedwing_att_control_rate.h"
+
+/*
+ * Controller parameters, accessible via MAVLink
+ *
+ */
+// Roll control parameters
+PARAM_DEFINE_FLOAT(FW_ROLLR_P, 0.9f);
+PARAM_DEFINE_FLOAT(FW_ROLLR_I, 0.2f);
+PARAM_DEFINE_FLOAT(FW_ROLLR_AWU, 0.9f);
+PARAM_DEFINE_FLOAT(FW_ROLLR_LIM, 0.7f); // Roll rate limit in radians/sec, applies to the roll controller
+PARAM_DEFINE_FLOAT(FW_ROLL_P, 4.0f);
+PARAM_DEFINE_FLOAT(FW_PITCH_RCOMP, 0.1f);
+
+//Pitch control parameters
+PARAM_DEFINE_FLOAT(FW_PITCHR_P, 0.8f);
+PARAM_DEFINE_FLOAT(FW_PITCHR_I, 0.2f);
+PARAM_DEFINE_FLOAT(FW_PITCHR_AWU, 0.8f);
+PARAM_DEFINE_FLOAT(FW_PITCHR_LIM, 0.35f); // Pitch rate limit in radians/sec, applies to the pitch controller
+PARAM_DEFINE_FLOAT(FW_PITCH_P, 8.0f);
+
+//Yaw control parameters //XXX TODO this is copy paste, asign correct values
+PARAM_DEFINE_FLOAT(FW_YAWR_P, 0.3f);
+PARAM_DEFINE_FLOAT(FW_YAWR_I, 0.0f);
+PARAM_DEFINE_FLOAT(FW_YAWR_AWU, 0.0f);
+PARAM_DEFINE_FLOAT(FW_YAWR_LIM, 0.35f); // Yaw rate limit in radians/sec
+
+/* feedforward compensation */
+PARAM_DEFINE_FLOAT(FW_PITCH_THR_P, 0.1f); /**< throttle to pitch coupling feedforward */
+
+struct fw_rate_control_params {
+ float rollrate_p;
+ float rollrate_i;
+ float rollrate_awu;
+ float pitchrate_p;
+ float pitchrate_i;
+ float pitchrate_awu;
+ float yawrate_p;
+ float yawrate_i;
+ float yawrate_awu;
+ float pitch_thr_ff;
+};
+
+struct fw_rate_control_param_handles {
+ param_t rollrate_p;
+ param_t rollrate_i;
+ param_t rollrate_awu;
+ param_t pitchrate_p;
+ param_t pitchrate_i;
+ param_t pitchrate_awu;
+ param_t yawrate_p;
+ param_t yawrate_i;
+ param_t yawrate_awu;
+ param_t pitch_thr_ff;
+};
+
+
+
+/* Internal Prototypes */
+static int parameters_init(struct fw_rate_control_param_handles *h);
+static int parameters_update(const struct fw_rate_control_param_handles *h, struct fw_rate_control_params *p);
+
+static int parameters_init(struct fw_rate_control_param_handles *h)
+{
+ /* PID parameters */
+ h->rollrate_p = param_find("FW_ROLLR_P"); //TODO define rate params for fixed wing
+ h->rollrate_i = param_find("FW_ROLLR_I");
+ h->rollrate_awu = param_find("FW_ROLLR_AWU");
+
+ h->pitchrate_p = param_find("FW_PITCHR_P");
+ h->pitchrate_i = param_find("FW_PITCHR_I");
+ h->pitchrate_awu = param_find("FW_PITCHR_AWU");
+
+ h->yawrate_p = param_find("FW_YAWR_P");
+ h->yawrate_i = param_find("FW_YAWR_I");
+ h->yawrate_awu = param_find("FW_YAWR_AWU");
+ h->pitch_thr_ff = param_find("FW_PITCH_THR_P");
+
+ return OK;
+}
+
+static int parameters_update(const struct fw_rate_control_param_handles *h, struct fw_rate_control_params *p)
+{
+ param_get(h->rollrate_p, &(p->rollrate_p));
+ param_get(h->rollrate_i, &(p->rollrate_i));
+ param_get(h->rollrate_awu, &(p->rollrate_awu));
+ param_get(h->pitchrate_p, &(p->pitchrate_p));
+ param_get(h->pitchrate_i, &(p->pitchrate_i));
+ param_get(h->pitchrate_awu, &(p->pitchrate_awu));
+ param_get(h->yawrate_p, &(p->yawrate_p));
+ param_get(h->yawrate_i, &(p->yawrate_i));
+ param_get(h->yawrate_awu, &(p->yawrate_awu));
+ param_get(h->pitch_thr_ff, &(p->pitch_thr_ff));
+
+ return OK;
+}
+
+int fixedwing_att_control_rates(const struct vehicle_rates_setpoint_s *rate_sp,
+ const float rates[],
+ struct actuator_controls_s *actuators)
+{
+ static int counter = 0;
+ static bool initialized = false;
+
+ static struct fw_rate_control_params p;
+ static struct fw_rate_control_param_handles h;
+
+ static PID_t roll_rate_controller;
+ static PID_t pitch_rate_controller;
+ static PID_t yaw_rate_controller;
+
+ static uint64_t last_run = 0;
+ const float deltaT = (hrt_absolute_time() - last_run) / 1000000.0f;
+ last_run = hrt_absolute_time();
+
+ if (!initialized) {
+ parameters_init(&h);
+ parameters_update(&h, &p);
+ pid_init(&roll_rate_controller, p.rollrate_p, p.rollrate_i, 0, p.rollrate_awu, 1, PID_MODE_DERIVATIV_NONE); // set D part to 0 because the controller layout is with a PI rate controller
+ pid_init(&pitch_rate_controller, p.pitchrate_p, p.pitchrate_i, 0, p.pitchrate_awu, 1, PID_MODE_DERIVATIV_NONE); // set D part to 0 because the contpitcher layout is with a PI rate contpitcher
+ pid_init(&yaw_rate_controller, p.yawrate_p, p.yawrate_i, 0, p.yawrate_awu, 1, PID_MODE_DERIVATIV_NONE); // set D part to 0 because the contpitcher layout is with a PI rate contpitcher
+ initialized = true;
+ }
+
+ /* load new parameters with lower rate */
+ if (counter % 100 == 0) {
+ /* update parameters from storage */
+ parameters_update(&h, &p);
+ pid_set_parameters(&roll_rate_controller, p.rollrate_p, p.rollrate_i, 0, p.rollrate_awu, 1);
+ pid_set_parameters(&pitch_rate_controller, p.pitchrate_p, p.pitchrate_i, 0, p.pitchrate_awu, 1);
+ pid_set_parameters(&yaw_rate_controller, p.yawrate_p, p.yawrate_i, 0, p.yawrate_awu, 1);
+ }
+
+
+ /* roll rate (PI) */
+ actuators->control[0] = pid_calculate(&roll_rate_controller, rate_sp->roll, rates[0], 0.0f, deltaT);
+ /* pitch rate (PI) */
+ actuators->control[1] = -pid_calculate(&pitch_rate_controller, rate_sp->pitch, rates[1], 0.0f, deltaT);
+ /* yaw rate (PI) */
+ actuators->control[2] = pid_calculate(&yaw_rate_controller, rate_sp->yaw, rates[2], 0.0f, deltaT);
+
+ counter++;
+
+ return 0;
+}
+
+
+
diff --git a/src/modules/fixedwing_att_control/fixedwing_att_control_rate.h b/src/modules/fixedwing_att_control/fixedwing_att_control_rate.h
new file mode 100644
index 000000000..500e3e197
--- /dev/null
+++ b/src/modules/fixedwing_att_control/fixedwing_att_control_rate.h
@@ -0,0 +1,48 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Author: @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ *
+ *
+ * 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 Fixed Wing Attitude Rate Control */
+
+#ifndef FIXEDWING_ATT_CONTROL_RATE_H_
+#define FIXEDWING_ATT_CONTROL_RATE_H_
+
+#include <uORB/topics/vehicle_rates_setpoint.h>
+#include <uORB/topics/actuator_controls.h>
+
+int fixedwing_att_control_rates(const struct vehicle_rates_setpoint_s *rate_sp,
+ const float rates[],
+ struct actuator_controls_s *actuators);
+
+#endif /* FIXEDWING_ATT_CONTROL_RATE_H_ */
diff --git a/src/modules/fixedwing_att_control/module.mk b/src/modules/fixedwing_att_control/module.mk
new file mode 100644
index 000000000..fd1a8724a
--- /dev/null
+++ b/src/modules/fixedwing_att_control/module.mk
@@ -0,0 +1,42 @@
+############################################################################
+#
+# 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
+# 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.
+#
+############################################################################
+
+#
+# Fixedwing Attitude Control application
+#
+
+MODULE_COMMAND = fixedwing_att_control
+
+SRCS = fixedwing_att_control_main.c \
+ fixedwing_att_control_att.c \
+ fixedwing_att_control_rate.c