aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2012-11-13 18:57:35 +0100
committerLorenz Meier <lm@inf.ethz.ch>2012-11-13 18:57:35 +0100
commita6294be6f076913d7b2c04e42aae1c0c93193a6f (patch)
treeaab14c218bbd54cab50a4706c661d612a964476e
parentd15e6ae73a57da9e16e61b58576c7a5bfddf6517 (diff)
parent403874d313464c72da309483e6e8271e9c70f965 (diff)
downloadpx4-firmware-a6294be6f076913d7b2c04e42aae1c0c93193a6f.tar.gz
px4-firmware-a6294be6f076913d7b2c04e42aae1c0c93193a6f.tar.bz2
px4-firmware-a6294be6f076913d7b2c04e42aae1c0c93193a6f.zip
Merge branch 'fw_control' of https://github.com/thomasgubler/Firmware
-rw-r--r--Documentation/code_structure_diagrams.odgbin21581 -> 17975 bytes
-rw-r--r--Documentation/commander_app.odgbin12944 -> 11628 bytes
-rw-r--r--Documentation/commander_app.pdfbin18357 -> 0 bytes
-rw-r--r--Documentation/commander_app.pngbin57865 -> 25356 bytes
-rw-r--r--Documentation/inter_app_communication.odgbin10337 -> 0 bytes
-rw-r--r--Documentation/inter_app_communication.pdfbin12744 -> 0 bytes
-rw-r--r--Documentation/inter_app_communication.pngbin20516 -> 0 bytes
-rw-r--r--Documentation/position_control.odgbin0 -> 12559 bytes
-rw-r--r--Documentation/position_control.pngbin0 -> 36561 bytes
-rw-r--r--Documentation/state_machine.odgbin0 -> 18576 bytes
-rw-r--r--Documentation/state_machine.pngbin210919 -> 208880 bytes
-rw-r--r--ROMFS/mixers/FMU_AERT.mix4
-rw-r--r--ROMFS/mixers/FMU_AET.mix4
-rw-r--r--ROMFS/mixers/FMU_RET.mix4
-rw-r--r--apps/fixedwing_att_control/Makefile45
-rw-r--r--apps/fixedwing_att_control/fixedwing_att_control_att.c161
-rw-r--r--apps/fixedwing_att_control/fixedwing_att_control_att.h49
-rw-r--r--apps/fixedwing_att_control/fixedwing_att_control_main.c277
-rw-r--r--apps/fixedwing_att_control/fixedwing_att_control_rate.c183
-rw-r--r--apps/fixedwing_att_control/fixedwing_att_control_rate.h48
-rw-r--r--apps/fixedwing_pos_control/Makefile45
-rw-r--r--apps/fixedwing_pos_control/fixedwing_pos_control.h73
-rw-r--r--apps/fixedwing_pos_control/fixedwing_pos_control_main.c441
-rw-r--r--apps/systemlib/geo/geo.c76
-rw-r--r--apps/systemlib/geo/geo.h9
-rw-r--r--apps/uORB/topics/vehicle_attitude_setpoint.h6
-rw-r--r--nuttx/configs/px4fmu/nsh/appconfig4
27 files changed, 1378 insertions, 51 deletions
diff --git a/Documentation/code_structure_diagrams.odg b/Documentation/code_structure_diagrams.odg
index 7bab5f4c8..2b9037103 100644
--- a/Documentation/code_structure_diagrams.odg
+++ b/Documentation/code_structure_diagrams.odg
Binary files differ
diff --git a/Documentation/commander_app.odg b/Documentation/commander_app.odg
index c05fba3c5..17459f7cf 100644
--- a/Documentation/commander_app.odg
+++ b/Documentation/commander_app.odg
Binary files differ
diff --git a/Documentation/commander_app.pdf b/Documentation/commander_app.pdf
deleted file mode 100644
index 6d55e2809..000000000
--- a/Documentation/commander_app.pdf
+++ /dev/null
Binary files differ
diff --git a/Documentation/commander_app.png b/Documentation/commander_app.png
index b71f1b8a7..6503817da 100644
--- a/Documentation/commander_app.png
+++ b/Documentation/commander_app.png
Binary files differ
diff --git a/Documentation/inter_app_communication.odg b/Documentation/inter_app_communication.odg
deleted file mode 100644
index 9f7b68440..000000000
--- a/Documentation/inter_app_communication.odg
+++ /dev/null
Binary files differ
diff --git a/Documentation/inter_app_communication.pdf b/Documentation/inter_app_communication.pdf
deleted file mode 100644
index 384894832..000000000
--- a/Documentation/inter_app_communication.pdf
+++ /dev/null
Binary files differ
diff --git a/Documentation/inter_app_communication.png b/Documentation/inter_app_communication.png
deleted file mode 100644
index 6681fe47d..000000000
--- a/Documentation/inter_app_communication.png
+++ /dev/null
Binary files differ
diff --git a/Documentation/position_control.odg b/Documentation/position_control.odg
new file mode 100644
index 000000000..5fb002c5e
--- /dev/null
+++ b/Documentation/position_control.odg
Binary files differ
diff --git a/Documentation/position_control.png b/Documentation/position_control.png
new file mode 100644
index 000000000..d8d1a8b0c
--- /dev/null
+++ b/Documentation/position_control.png
Binary files differ
diff --git a/Documentation/state_machine.odg b/Documentation/state_machine.odg
new file mode 100644
index 000000000..2f55a13dd
--- /dev/null
+++ b/Documentation/state_machine.odg
Binary files differ
diff --git a/Documentation/state_machine.png b/Documentation/state_machine.png
index 9fef9057a..4daeddfc9 100644
--- a/Documentation/state_machine.png
+++ b/Documentation/state_machine.png
Binary files differ
diff --git a/ROMFS/mixers/FMU_AERT.mix b/ROMFS/mixers/FMU_AERT.mix
index d7e317e13..75e82bb00 100644
--- a/ROMFS/mixers/FMU_AERT.mix
+++ b/ROMFS/mixers/FMU_AERT.mix
@@ -36,8 +36,8 @@ factors (to reverse the servo movement) and adjust the offset, scaling and
endpoints to suit.
M: 1
-O: 10000 10000 0 -10000 10000
-S: 0 1 10000 10000 0 -10000 10000
+O: 10000 10000 0 -10000 10000
+S: 0 1 -10000 -10000 0 -10000 10000
Rudder mixer
------------
diff --git a/ROMFS/mixers/FMU_AET.mix b/ROMFS/mixers/FMU_AET.mix
index bd7056f7c..20cb88b91 100644
--- a/ROMFS/mixers/FMU_AET.mix
+++ b/ROMFS/mixers/FMU_AET.mix
@@ -39,8 +39,8 @@ factors (to reverse the servo movement) and adjust the offset, scaling and
endpoints to suit.
M: 1
-O: 10000 10000 0 -10000 10000
-S: 0 1 10000 10000 0 -10000 10000
+O: 10000 10000 0 -10000 10000
+S: 0 1 -10000 -10000 0 -10000 10000
Output 2
--------
diff --git a/ROMFS/mixers/FMU_RET.mix b/ROMFS/mixers/FMU_RET.mix
index 156fcb129..95beb8927 100644
--- a/ROMFS/mixers/FMU_RET.mix
+++ b/ROMFS/mixers/FMU_RET.mix
@@ -32,8 +32,8 @@ factors (to reverse the servo movement) and adjust the offset, scaling and
endpoints to suit.
M: 1
-O: 10000 10000 0 -10000 10000
-S: 0 1 10000 10000 0 -10000 10000
+O: 10000 10000 0 -10000 10000
+S: 0 1 -10000 -10000 0 -10000 10000
Output 2
--------
diff --git a/apps/fixedwing_att_control/Makefile b/apps/fixedwing_att_control/Makefile
new file mode 100644
index 000000000..01465fa9e
--- /dev/null
+++ b/apps/fixedwing_att_control/Makefile
@@ -0,0 +1,45 @@
+############################################################################
+#
+# Copyright (C) 2012 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 Control application
+#
+
+APPNAME = fixedwing_att_control
+PRIORITY = SCHED_PRIORITY_MAX - 30
+STACKSIZE = 2048
+
+INCLUDES = $(TOPDIR)/../mavlink/include/mavlink
+
+include $(APPDIR)/mk/app.mk
+
diff --git a/apps/fixedwing_att_control/fixedwing_att_control_att.c b/apps/fixedwing_att_control/fixedwing_att_control_att.c
new file mode 100644
index 000000000..18b290f99
--- /dev/null
+++ b/apps/fixedwing_att_control/fixedwing_att_control_att.c
@@ -0,0 +1,161 @@
+/****************************************************************************
+ *
+ * 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 <fixedwing_att_control_att.h>
+
+#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>
+
+
+
+
+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,
+ 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_tait_bryan, att->roll, 0, 0);
+
+ /* Pitch (P) */
+ float pitch_sp_rollcompensation = att_sp->pitch_tait_bryan + p.pitch_roll_compensation_p * att_sp->roll_tait_bryan;
+ rates_sp->pitch = pid_calculate(&pitch_controller, pitch_sp_rollcompensation, att->pitch, 0, 0);
+
+ /* Yaw (from coordinated turn constraint or lateral force) */
+ //TODO
+
+ counter++;
+
+ return 0;
+}
+
+
+
diff --git a/apps/fixedwing_att_control/fixedwing_att_control_att.h b/apps/fixedwing_att_control/fixedwing_att_control_att.h
new file mode 100644
index 000000000..ca7c14b43
--- /dev/null
+++ b/apps/fixedwing_att_control/fixedwing_att_control_att.h
@@ -0,0 +1,49 @@
+/****************************************************************************
+ *
+ * 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>
+
+int fixedwing_att_control_attitude(const struct vehicle_attitude_setpoint_s *att_sp,
+ const struct vehicle_attitude_s *att,
+ struct vehicle_rates_setpoint_s *rates_sp);
+
+#endif /* FIXEDWING_ATT_CONTROL_ATT_H_ */
diff --git a/apps/fixedwing_att_control/fixedwing_att_control_main.c b/apps/fixedwing_att_control/fixedwing_att_control_main.c
new file mode 100644
index 000000000..ad0f201e1
--- /dev/null
+++ b/apps/fixedwing_att_control/fixedwing_att_control_main.c
@@ -0,0 +1,277 @@
+/****************************************************************************
+ *
+ * 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/debug_key_value.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>
+#include <fixedwing_att_control_att.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
+
+/* 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));
+// static struct debug_key_value_s debug_output;
+// memset(&debug_output, 0, sizeof(debug_output));
+
+ /* 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 debug_pub = orb_advertise(ORB_ID(debug_key_value), &debug_output);
+// debug_output.key[0] = '1';
+
+
+ /* subscribe */
+ int att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
+ int att_sp_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint));
+
+ /* Setup of loop */
+ float gyro[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);
+
+ /*Get Local Copies */
+ /* get a local copy of attitude */
+ orb_copy(ORB_ID(vehicle_attitude), att_sub, &att);
+ orb_copy(ORB_ID(vehicle_attitude_setpoint), att_sp_sub, &att_sp);
+
+ gyro[0] = att.rollspeed;
+ gyro[1] = att.pitchspeed;
+ gyro[2] = att.yawspeed;
+
+ /* Control */
+
+ /* Attitude Control */
+ fixedwing_att_control_attitude(&att_sp,
+ &att,
+ &rates_sp);
+
+ /* Attitude Rate Control */
+ fixedwing_att_control_rates(&rates_sp, gyro, &actuators);
+
+ //REMOVEME XXX
+ actuators.control[3] = 0.7f;
+
+ orb_publish(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_pub, &actuators);
+// debug_output.value = rates_sp.pitch;
+// orb_publish(ORB_ID(debug_key_value), debug_pub, &debug_output);
+ }
+
+ 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);
+
+ 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,
+ 4096,
+ 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/apps/fixedwing_att_control/fixedwing_att_control_rate.c b/apps/fixedwing_att_control/fixedwing_att_control_rate.c
new file mode 100644
index 000000000..b81d50168
--- /dev/null
+++ b/apps/fixedwing_att_control/fixedwing_att_control_rate.c
@@ -0,0 +1,183 @@
+/****************************************************************************
+ *
+ * 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 <fixedwing_att_control_rate.h>
+
+#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>
+
+
+
+
+
+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;
+
+};
+
+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;
+
+};
+
+
+
+/* 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");
+
+ 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));
+
+
+ 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, deltaT);
+
+
+ actuators->control[1] = pid_calculate(&pitch_rate_controller, rate_sp->pitch, rates[1], 0, deltaT); //TODO: (-) sign comes from the elevator (positive --> deflection downwards), this has to be moved to the mixer...
+ actuators->control[2] = 0;//pid_calculate(&yaw_rate_controller, rate_sp->yaw, rates[2], 0, deltaT); //XXX TODO disabled for now
+
+ counter++;
+
+ return 0;
+}
+
+
+
diff --git a/apps/fixedwing_att_control/fixedwing_att_control_rate.h b/apps/fixedwing_att_control/fixedwing_att_control_rate.h
new file mode 100644
index 000000000..d394c3dac
--- /dev/null
+++ b/apps/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/apps/fixedwing_pos_control/Makefile b/apps/fixedwing_pos_control/Makefile
new file mode 100644
index 000000000..bce391f49
--- /dev/null
+++ b/apps/fixedwing_pos_control/Makefile
@@ -0,0 +1,45 @@
+############################################################################
+#
+# Copyright (C) 2012 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 Control application
+#
+
+APPNAME = fixedwing_pos_control
+PRIORITY = SCHED_PRIORITY_MAX - 30
+STACKSIZE = 2048
+
+INCLUDES = $(TOPDIR)/../mavlink/include/mavlink
+
+include $(APPDIR)/mk/app.mk
+
diff --git a/apps/fixedwing_pos_control/fixedwing_pos_control.h b/apps/fixedwing_pos_control/fixedwing_pos_control.h
new file mode 100644
index 000000000..f631c90a1
--- /dev/null
+++ b/apps/fixedwing_pos_control/fixedwing_pos_control.h
@@ -0,0 +1,73 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Author: @author Doug Weibel <douglas.weibel@colorado.edu>
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ @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_pos_control.h
+ * Position control for fixed wing airframes.
+ */
+
+#ifndef FIXEDWING_POS_CONTROL_H_
+#define FIXEDWING_POS_CONTROL_H_
+
+#include <uORB/uORB.h>
+#include <uORB/topics/vehicle_attitude.h>
+#include <uORB/topics/vehicle_attitude_setpoint.h>
+#include <uORB/topics/vehicle_rates_setpoint.h>
+#include <uORB/topics/actuator_controls.h>
+
+#endif
+
+
+struct planned_path_segments_s {
+ bool segment_type;
+ double start_lat; // Start of line or center of arc
+ double start_lon;
+ double end_lat;
+ double end_lon;
+ float radius; // Radius of arc
+ float arc_start_bearing; // Bearing from center to start of arc
+ float arc_sweep; // Angle (radians) swept out by arc around center.
+ // Positive for clockwise, negative for counter-clockwise
+};
+
+
+float _wrap180(float bearing);
+float _wrap360(float bearing);
+float _wrapPI(float bearing);
+float _wrap2PI(float bearing);
+
+/* FIXEDWING_CONTROL_H_ */
+
diff --git a/apps/fixedwing_pos_control/fixedwing_pos_control_main.c b/apps/fixedwing_pos_control/fixedwing_pos_control_main.c
new file mode 100644
index 000000000..443048913
--- /dev/null
+++ b/apps/fixedwing_pos_control/fixedwing_pos_control_main.c
@@ -0,0 +1,441 @@
+/****************************************************************************
+ *
+ * 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_pos_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_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_attitude.h>
+#include <systemlib/param/param.h>
+#include <systemlib/pid/pid.h>
+#include <systemlib/geo/geo.h>
+#include <systemlib/systemlib.h>
+
+/*
+ * Controller parameters, accessible via MAVLink
+ *
+ */
+PARAM_DEFINE_FLOAT(FW_HEADING_P, 0.1f);
+PARAM_DEFINE_FLOAT(FW_XTRACK_P, 0.01745f); // Radians per meter off track
+PARAM_DEFINE_FLOAT(FW_ALT_P, 0.1f);
+PARAM_DEFINE_FLOAT(FW_ROLL_LIM, 0.7f); // Roll angle limit in radians
+PARAM_DEFINE_FLOAT(FW_PITCH_LIM, 0.35f); // Pitch angle limit in radians
+
+
+struct fw_pos_control_params {
+ float heading_p;
+ float xtrack_p;
+ float altitude_p;
+ float roll_lim;
+ float pitch_lim;
+};
+
+struct fw_pos_control_param_handles {
+ param_t heading_p;
+ param_t xtrack_p;
+ param_t altitude_p;
+ param_t roll_lim;
+ param_t pitch_lim;
+
+};
+
+
+/* Prototypes */
+/* 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_pos_control_params *p);
+
+/**
+ * Deamon management function.
+ */
+__EXPORT int fixedwing_pos_control_main(int argc, char *argv[]);
+
+/**
+ * Mainloop of deamon.
+ */
+int fixedwing_pos_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 */
+
+
+/**
+ * Parameter management
+ */
+static int parameters_init(struct fw_pos_control_param_handles *h)
+{
+ /* PID parameters */
+ h->heading_p = param_find("FW_HEADING_P");
+ h->xtrack_p = param_find("FW_XTRACK_P");
+ h->altitude_p = param_find("FW_ALT_P");
+ h->roll_lim = param_find("FW_ROLL_LIM");
+ h->pitch_lim = param_find("FW_PITCH_LIM");
+
+
+ return OK;
+}
+
+static int parameters_update(const struct fw_pos_control_param_handles *h, struct fw_pos_control_params *p)
+{
+ param_get(h->heading_p, &(p->heading_p));
+ param_get(h->xtrack_p, &(p->xtrack_p));
+ param_get(h->altitude_p, &(p->altitude_p));
+ param_get(h->roll_lim, &(p->roll_lim));
+ param_get(h->pitch_lim, &(p->pitch_lim));
+
+ return OK;
+}
+
+
+/* Main Thread */
+int fixedwing_pos_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_global_position_s global_pos;
+ memset(&global_pos, 0, sizeof(global_pos));
+ struct vehicle_global_position_s start_pos; // Temporary variable, replace with
+ memset(&start_pos, 0, sizeof(start_pos)); // previous waypoint when available
+ struct vehicle_global_position_setpoint_s global_setpoint;
+ memset(&global_setpoint, 0, sizeof(global_setpoint));
+ struct vehicle_attitude_s att;
+ memset(&att, 0, sizeof(att));
+ struct crosstrack_error_s xtrack_err;
+ memset(&xtrack_err, 0, sizeof(xtrack_err));
+
+ /* output structs */
+ struct vehicle_attitude_setpoint_s attitude_setpoint;
+ memset(&attitude_setpoint, 0, sizeof(attitude_setpoint));
+
+ /* publish attitude setpoint */
+ attitude_setpoint.roll_tait_bryan = 0.0f;
+ attitude_setpoint.pitch_tait_bryan = 0.0f;
+ attitude_setpoint.yaw_tait_bryan = 0.0f;
+ orb_advert_t attitude_setpoint_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &attitude_setpoint);
+
+ /* subscribe */
+ int global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position));
+ int global_setpoint_sub = orb_subscribe(ORB_ID(vehicle_global_position_setpoint));
+ int att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
+
+ /* Setup of loop */
+ struct pollfd fds = { .fd = att_sub, .events = POLLIN };
+ bool global_sp_updated_set_once = false;
+
+ float psi_track = 0.0f;
+
+ while(!thread_should_exit)
+ {
+ /* wait for a sensor update, check for exit condition every 500 ms */
+ poll(&fds, 1, 500);
+
+ static int counter = 0;
+ static bool initialized = false;
+
+ static struct fw_pos_control_params p;
+ static struct fw_pos_control_param_handles h;
+
+ PID_t heading_controller;
+ PID_t altitude_controller;
+
+ if(!initialized)
+ {
+ parameters_init(&h);
+ parameters_update(&h, &p);
+ pid_init(&heading_controller, p.heading_p, 0.0f, 0.0f, 0.0f,p.roll_lim,PID_MODE_DERIVATIV_NONE);
+ pid_init(&altitude_controller, p.altitude_p, 0.0f, 0.0f, 0.0f,p.pitch_lim,PID_MODE_DERIVATIV_NONE);
+ initialized = true;
+ }
+
+ /* load new parameters with lower rate */
+ if (counter % 100 == 0) {
+ /* update parameters from storage */
+ parameters_update(&h, &p);
+ pid_set_parameters(&heading_controller, p.heading_p, 0, 0, 0, p.roll_lim);
+ pid_set_parameters(&altitude_controller, p.altitude_p, 0, 0, 0, p.pitch_lim);
+
+ }
+
+ /* Check if there is a new position or setpoint */
+ bool pos_updated;
+ orb_check(global_pos_sub, &pos_updated);
+ bool global_sp_updated;
+ orb_check(global_setpoint_sub, &global_sp_updated);
+
+ /* Load local copies */
+ orb_copy(ORB_ID(vehicle_attitude), att_sub, &att);
+ if(pos_updated)
+ orb_copy(ORB_ID(vehicle_global_position), global_pos_sub, &global_pos);
+ if (global_sp_updated)
+ orb_copy(ORB_ID(vehicle_global_position_setpoint), global_setpoint_sub, &global_setpoint);
+
+ if(global_sp_updated) {
+ start_pos = global_pos; //for now using the current position as the startpoint (= approx. last waypoint because the setpoint switch occurs at the waypoint)
+ global_sp_updated_set_once = true;
+ psi_track = get_bearing_to_next_waypoint((double)global_pos.lat / (double)1e7d, (double)global_pos.lon / (double)1e7d,
+ (double)global_setpoint.lat / (double)1e7d, (double)global_setpoint.lon / (double)1e7d);
+ printf("psi_track: %0.4f\n", psi_track);
+ }
+
+ /* Control */
+
+
+ /* Simple Horizontal Control */
+ if(global_sp_updated_set_once)
+ {
+// if (counter % 100 == 0)
+// printf("lat_sp %d, ln_sp %d, lat: %d, lon: %d\n", global_setpoint.lat, global_setpoint.lon, global_pos.lat, global_pos.lon);
+
+ /* calculate crosstrack error */
+ // Only the case of a straight line track following handled so far
+ int distance_res = get_distance_to_line(&xtrack_err, (double)global_pos.lat / (double)1e7d, (double)global_pos.lon / (double)1e7d,
+ (double)start_pos.lat / (double)1e7d, (double)start_pos.lon / (double)1e7d,
+ (double)global_setpoint.lat / (double)1e7d, (double)global_setpoint.lon / (double)1e7d);
+
+ if(!(distance_res != OK || xtrack_err.past_end)) {
+
+ float delta_psi_c = -p.xtrack_p * xtrack_err.distance; //(-) because z axis points downwards
+
+ if(delta_psi_c > 60.0f*M_DEG_TO_RAD)
+ delta_psi_c = 60.0f*M_DEG_TO_RAD;
+
+ if(delta_psi_c < -60.0f*M_DEG_TO_RAD)
+ delta_psi_c = -60.0f*M_DEG_TO_RAD;
+
+ float psi_c = psi_track + delta_psi_c;
+
+ float psi_e = psi_c - att.yaw;
+
+ /* shift error to prevent wrapping issues */
+ psi_e = _wrapPI(psi_e);
+
+ /* calculate roll setpoint, do this artificially around zero */
+ attitude_setpoint.roll_tait_bryan = pid_calculate(&heading_controller, psi_e, 0.0f, 0.0f, 0.0f);
+
+// if (counter % 100 == 0)
+// printf("xtrack_err.distance: %0.4f, delta_psi_c: %0.4f\n",xtrack_err.distance, delta_psi_c);
+ }
+ else {
+ if (counter % 100 == 0)
+ printf("distance_res: %d, past_end %d\n", distance_res, xtrack_err.past_end);
+ }
+
+ }
+
+ /* Very simple Altitude Control */
+ if(global_sp_updated_set_once && pos_updated)
+ {
+
+ //TODO: take care of relative vs. ab. altitude
+ attitude_setpoint.pitch_tait_bryan = pid_calculate(&altitude_controller, global_setpoint.altitude, global_pos.alt, 0.0f, 0.0f);
+
+ }
+ /*Publish the attitude setpoint */
+ orb_publish(ORB_ID(vehicle_attitude_setpoint), attitude_setpoint_pub, &attitude_setpoint);
+
+ counter++;
+ }
+
+ printf("[fixedwing_pos_control] exiting.\n");
+ thread_running = false;
+
+
+ close(attitude_setpoint_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_pos_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_pos_control_main(int argc, char *argv[])
+{
+ if (argc < 1)
+ usage("missing command");
+
+ if (!strcmp(argv[1], "start")) {
+
+ if (thread_running) {
+ printf("fixedwing_pos_control already running\n");
+ /* this is not an error */
+ exit(0);
+ }
+
+ thread_should_exit = false;
+ deamon_task = task_spawn("fixedwing_pos_control",
+ SCHED_DEFAULT,
+ SCHED_PRIORITY_MAX - 20,
+ 4096,
+ fixedwing_pos_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_pos_control is running\n");
+ } else {
+ printf("\tfixedwing_pos_control not started\n");
+ }
+ exit(0);
+ }
+
+ usage("unrecognized command");
+ exit(1);
+}
+
+
+float _wrapPI(float bearing)
+{
+
+ while (bearing > M_PI_F) {
+ bearing = bearing - M_TWOPI_F;
+ }
+
+ while (bearing <= -M_PI_F) {
+ bearing = bearing + M_TWOPI_F;
+ }
+
+ return bearing;
+}
+
+float _wrap2PI(float bearing)
+{
+
+ while (bearing >= M_TWOPI_F) {
+ bearing = bearing - M_TWOPI_F;
+ }
+
+ while (bearing < 0.0f) {
+ bearing = bearing + M_TWOPI_F;
+ }
+
+ return bearing;
+}
+
+float _wrap180(float bearing)
+{
+
+ while (bearing > 180.0f) {
+ bearing = bearing - 360.0f;
+ }
+
+ while (bearing <= -180.0f) {
+ bearing = bearing + 360.0f;
+ }
+
+ return bearing;
+}
+
+float _wrap360(float bearing)
+{
+
+ while (bearing >= 360.0f) {
+ bearing = bearing - 360.0f;
+ }
+
+ while (bearing < 0.0f) {
+ bearing = bearing + 360.0f;
+ }
+
+ return bearing;
+}
+
+
+
+
diff --git a/apps/systemlib/geo/geo.c b/apps/systemlib/geo/geo.c
index abe44c69e..2f4b37e79 100644
--- a/apps/systemlib/geo/geo.c
+++ b/apps/systemlib/geo/geo.c
@@ -45,7 +45,12 @@
*/
#include <systemlib/geo/geo.h>
+#include <nuttx/config.h>
+#include <unistd.h>
+#include <pthread.h>
+#include <stdio.h>
#include <math.h>
+#include <stdbool.h>
/* values for map projection */
@@ -230,25 +235,24 @@ __EXPORT float get_bearing_to_next_waypoint(double lat_now, double lon_now, doub
// Additional functions - @author Doug Weibel <douglas.weibel@colorado.edu>
-__EXPORT crosstrack_error_s get_distance_to_line(double lat_now, double lon_now, double lat_start, double lon_start, double lat_end, double lon_end)
+__EXPORT int get_distance_to_line(struct crosstrack_error_s * crosstrack_error, double lat_now, double lon_now, double lat_start, double lon_start, double lat_end, double lon_end)
{
// This function returns the distance to the nearest point on the track line. Distance is positive if current
// position is right of the track and negative if left of the track as seen from a point on the track line
// headed towards the end point.
- crosstrack_error_s return_var;
float dist_to_end;
float bearing_end;
float bearing_track;
float bearing_diff;
- return_var.error = true; // Set error flag, cleared when valid result calculated.
- return_var.past_end = false;
- return_var.distance = 0.0f;
- return_var.bearing = 0.0f;
+ int return_value = ERROR; // Set error flag, cleared when valid result calculated.
+ crosstrack_error->past_end = false;
+ crosstrack_error->distance = 0.0f;
+ crosstrack_error->bearing = 0.0f;
// Return error if arguments are bad
- if (lat_now == 0.0d || lon_now == 0.0d || lat_start == 0.0d || lon_start == 0.0d || lat_end == 0.0d || lon_end == 0.0d) return return_var;
+ if (lat_now == 0.0d || lon_now == 0.0d || lat_start == 0.0d || lon_start == 0.0d || lat_end == 0.0d || lon_end == 0.0d) return return_value;
bearing_end = get_bearing_to_next_waypoint(lat_now, lon_now, lat_end, lon_end);
bearing_track = get_bearing_to_next_waypoint(lat_start, lon_start, lat_end, lon_end);
@@ -257,35 +261,34 @@ __EXPORT crosstrack_error_s get_distance_to_line(double lat_now, double lon_now,
// Return past_end = true if past end point of line
if (bearing_diff > M_PI_2_F || bearing_diff < -M_PI_2_F) {
- return_var.past_end = true;
- return_var.error = false;
- return return_var;
+ crosstrack_error->past_end = true;
+ return_value = OK;
+ return return_value;
}
dist_to_end = get_distance_to_next_waypoint(lat_now, lon_now, lat_end, lon_end);
- return_var.distance = (dist_to_end) * sin(bearing_diff);
+ crosstrack_error->distance = (dist_to_end) * sin(bearing_diff);
if (sin(bearing_diff) >= 0) {
- return_var.bearing = _wrapPI(bearing_track - M_PI_2_F);
+ crosstrack_error->bearing = _wrapPI(bearing_track - M_PI_2_F);
} else {
- return_var.bearing = _wrapPI(bearing_track + M_PI_2_F);
+ crosstrack_error->bearing = _wrapPI(bearing_track + M_PI_2_F);
}
- return_var.error = false;
+ return_value = OK;
- return return_var;
+ return return_value;
}
-__EXPORT crosstrack_error_s get_distance_to_arc(double lat_now, double lon_now, double lat_center, double lon_center,
+__EXPORT int get_distance_to_arc(struct crosstrack_error_s * crosstrack_error, double lat_now, double lon_now, double lat_center, double lon_center,
float radius, float arc_start_bearing, float arc_sweep)
{
// This function returns the distance to the nearest point on the track arc. Distance is positive if current
// position is right of the arc and negative if left of the arc as seen from the closest point on the arc and
// headed towards the end point.
- crosstrack_error_s return_var;
// Determine if the current position is inside or outside the sector between the line from the center
// to the arc start and the line from the center to the arc end
@@ -294,13 +297,13 @@ __EXPORT crosstrack_error_s get_distance_to_arc(double lat_now, double lon_now,
float bearing_now = get_bearing_to_next_waypoint(lat_now, lon_now, lat_center, lon_center);
bool in_sector;
- return_var.error = true; // Set error flag, cleared when valid result calculated.
- return_var.past_end = false;
- return_var.distance = 0.0f;
- return_var.bearing = 0.0f;
+ int return_value = ERROR; // Set error flag, cleared when valid result calculated.
+ crosstrack_error->past_end = false;
+ crosstrack_error->distance = 0.0f;
+ crosstrack_error->bearing = 0.0f;
// Return error if arguments are bad
- if (lat_now == 0.0d || lon_now == 0.0d || lat_center == 0.0d || lon_center == 0.0d || radius == 0.0d) return return_var;
+ if (lat_now == 0.0d || lon_now == 0.0d || lat_center == 0.0d || lon_center == 0.0d || radius == 0.0d) return return_value;
if (arc_sweep >= 0) {
@@ -313,7 +316,7 @@ __EXPORT crosstrack_error_s get_distance_to_arc(double lat_now, double lon_now,
bearing_sector_end = arc_start_bearing;
bearing_sector_start = arc_start_bearing - arc_sweep;
- if (bearing_sector_start < 0.0) bearing_sector_start += M_TWOPI_F;
+ if (bearing_sector_start < 0.0f) bearing_sector_start += M_TWOPI_F;
}
in_sector = false;
@@ -326,16 +329,16 @@ __EXPORT crosstrack_error_s get_distance_to_arc(double lat_now, double lon_now,
// If in the sector then calculate distance and bearing to closest point
if (in_sector) {
- return_var.past_end = false;
+ crosstrack_error->past_end = false;
float dist_to_center = get_distance_to_next_waypoint(lat_now, lon_now, lat_center, lon_center);
if (dist_to_center <= radius) {
- return_var.distance = radius - dist_to_center;
- return_var.bearing = bearing_now + M_PI_F;
+ crosstrack_error->distance = radius - dist_to_center;
+ crosstrack_error->bearing = bearing_now + M_PI_F;
} else {
- return_var.distance = dist_to_center - radius;
- return_var.bearing = bearing_now;
+ crosstrack_error->distance = dist_to_center - radius;
+ crosstrack_error->bearing = bearing_now;
}
// If out of the sector then calculate dist and bearing to start or end point
@@ -359,21 +362,22 @@ __EXPORT crosstrack_error_s get_distance_to_arc(double lat_now, double lon_now,
float dist_to_start = get_distance_to_next_waypoint(lat_now, lon_now, lat_start, lon_start);
float dist_to_end = get_distance_to_next_waypoint(lat_now, lon_now, lat_end, lon_end);
+
if (dist_to_start < dist_to_end) {
- return_var.distance = dist_to_start;
- return_var.bearing = get_bearing_to_next_waypoint(lat_now, lon_now, lat_start, lon_start);
+ crosstrack_error->distance = dist_to_start;
+ crosstrack_error->bearing = get_bearing_to_next_waypoint(lat_now, lon_now, lat_start, lon_start);
} else {
- return_var.past_end = true;
- return_var.distance = dist_to_end;
- return_var.bearing = get_bearing_to_next_waypoint(lat_now, lon_now, lat_end, lon_end);
+ crosstrack_error->past_end = true;
+ crosstrack_error->distance = dist_to_end;
+ crosstrack_error->bearing = get_bearing_to_next_waypoint(lat_now, lon_now, lat_end, lon_end);
}
}
- return_var.bearing = _wrapPI(return_var.bearing);
- return_var.error = false;
- return return_var;
+ crosstrack_error->bearing = _wrapPI(crosstrack_error->bearing);
+ return_value = OK;
+ return return_value;
}
float _wrapPI(float bearing)
diff --git a/apps/systemlib/geo/geo.h b/apps/systemlib/geo/geo.h
index 807e508a2..7aad79a8c 100644
--- a/apps/systemlib/geo/geo.h
+++ b/apps/systemlib/geo/geo.h
@@ -48,12 +48,11 @@
#include <stdbool.h>
-typedef struct {
- bool error; // Flag that the calculation failed
+struct crosstrack_error_s {
bool past_end; // Flag indicating we are past the end of the line/arc segment
float distance; // Distance in meters to closest point on line/arc
float bearing; // Bearing in radians to closest point on line/arc
-} crosstrack_error_s;
+} ;
__EXPORT static void map_projection_init(double lat_0, double lon_0);
@@ -67,9 +66,9 @@ __EXPORT float get_bearing_to_next_waypoint(double lat_now, double lon_now, doub
//
-__EXPORT crosstrack_error_s get_distance_to_line(double lat_now, double lon_now, double lat_start, double lon_start, double lat_end, double lon_end);
+__EXPORT int get_distance_to_line(struct crosstrack_error_s * crosstrack_error, double lat_now, double lon_now, double lat_start, double lon_start, double lat_end, double lon_end);
-__EXPORT crosstrack_error_s get_distance_to_arc(double lat_now, double lon_now, double lat_center, double lon_center,
+__EXPORT int get_distance_to_arc(struct crosstrack_error_s * crosstrack_error, double lat_now, double lon_now, double lat_center, double lon_center,
float radius, float arc_start_bearing, float arc_sweep);
float _wrap180(float bearing);
diff --git a/apps/uORB/topics/vehicle_attitude_setpoint.h b/apps/uORB/topics/vehicle_attitude_setpoint.h
index 62367cf77..8663846fc 100644
--- a/apps/uORB/topics/vehicle_attitude_setpoint.h
+++ b/apps/uORB/topics/vehicle_attitude_setpoint.h
@@ -56,9 +56,9 @@ struct vehicle_attitude_setpoint_s
{
uint64_t timestamp; /**< in microseconds since system start, is set whenever the writing thread stores new data */
- //float roll_tait_bryan; /**< Tait-Bryan angle in NED frame */
- //float pitch_tait_bryan; /**< Tait-Bryan angle in NED frame */
- //float yaw_tait_bryan; /**< Tait-Bryan angle in NED frame */
+ float roll_tait_bryan; /**< Tait-Bryan angle in NED frame */
+ float pitch_tait_bryan; /**< Tait-Bryan angle in NED frame */
+ float yaw_tait_bryan; /**< Tait-Bryan angle in NED frame */
//float tait_bryan_valid; /**< Set to true if Tait-Bryan angles are valid */
float roll_body; /**< body angle in NED frame */
diff --git a/nuttx/configs/px4fmu/nsh/appconfig b/nuttx/configs/px4fmu/nsh/appconfig
index 2e9a989ad..798f57e93 100644
--- a/nuttx/configs/px4fmu/nsh/appconfig
+++ b/nuttx/configs/px4fmu/nsh/appconfig
@@ -75,7 +75,9 @@ CONFIGURED_APPS += sensors
CONFIGURED_APPS += ardrone_interface
CONFIGURED_APPS += multirotor_att_control
CONFIGURED_APPS += multirotor_pos_control
-CONFIGURED_APPS += fixedwing_control
+#CONFIGURED_APPS += fixedwing_control
+CONFIGURED_APPS += fixedwing_att_control
+CONFIGURED_APPS += fixedwing_pos_control
CONFIGURED_APPS += position_estimator
CONFIGURED_APPS += attitude_estimator_ekf