aboutsummaryrefslogtreecommitdiff
path: root/apps
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 /apps
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 'apps')
-rw-r--r--apps/examples/control_demo/Makefile42
-rw-r--r--apps/examples/control_demo/control_demo.cpp168
-rw-r--r--apps/examples/control_demo/params.c71
-rw-r--r--apps/fixedwing_att_control/Makefile45
-rw-r--r--apps/fixedwing_att_control/fixedwing_att_control_att.c170
-rw-r--r--apps/fixedwing_att_control/fixedwing_att_control_att.h51
-rw-r--r--apps/fixedwing_att_control/fixedwing_att_control_main.c369
-rw-r--r--apps/fixedwing_att_control/fixedwing_att_control_rate.c209
-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_main.c479
11 files changed, 0 insertions, 1697 deletions
diff --git a/apps/examples/control_demo/Makefile b/apps/examples/control_demo/Makefile
deleted file mode 100644
index 6e40e645f..000000000
--- a/apps/examples/control_demo/Makefile
+++ /dev/null
@@ -1,42 +0,0 @@
-############################################################################
-#
-# 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.
-#
-############################################################################
-
-#
-# Basic example application
-#
-
-APPNAME = control_demo
-PRIORITY = SCHED_PRIORITY_DEFAULT
-STACKSIZE = 2048
-
-include $(APPDIR)/mk/app.mk
diff --git a/apps/examples/control_demo/control_demo.cpp b/apps/examples/control_demo/control_demo.cpp
deleted file mode 100644
index e609f2f4b..000000000
--- a/apps/examples/control_demo/control_demo.cpp
+++ /dev/null
@@ -1,168 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: @author Example User <mail@example.com>
- *
- * 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 control_demo.cpp
- * Demonstration of control library
- */
-
-#include <nuttx/config.h>
-#include <unistd.h>
-#include <stdio.h>
-#include <stdlib.h>
-#include <string.h>
-#include <systemlib/systemlib.h>
-#include <controllib/fixedwing.hpp>
-#include <systemlib/param/param.h>
-#include <drivers/drv_hrt.h>
-#include <math.h>
-
-static bool thread_should_exit = false; /**< Deamon exit flag */
-static bool thread_running = false; /**< Deamon status flag */
-static int deamon_task; /**< Handle of deamon task / thread */
-
-/**
- * Deamon management function.
- */
-extern "C" __EXPORT int control_demo_main(int argc, char *argv[]);
-
-/**
- * Mainloop of deamon.
- */
-int control_demo_thread_main(int argc, char *argv[]);
-
-/**
- * Test function
- */
-void test();
-
-/**
- * Print the correct usage.
- */
-static void usage(const char *reason);
-
-static void
-usage(const char *reason)
-{
- if (reason)
- fprintf(stderr, "%s\n", reason);
-
- fprintf(stderr, "usage: control_demo {start|stop|status} [-p <additional params>]\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 control_demo_main(int argc, char *argv[])
-{
-
- if (argc < 1)
- usage("missing command");
-
- if (!strcmp(argv[1], "start")) {
-
- if (thread_running) {
- printf("control_demo already running\n");
- /* this is not an error */
- exit(0);
- }
-
- thread_should_exit = false;
- deamon_task = task_spawn("control_demo",
- SCHED_DEFAULT,
- SCHED_PRIORITY_MAX - 10,
- 5120,
- control_demo_thread_main,
- (argv) ? (const char **)&argv[2] : (const char **)NULL);
- exit(0);
- }
-
- if (!strcmp(argv[1], "test")) {
- test();
- exit(0);
- }
-
- if (!strcmp(argv[1], "stop")) {
- thread_should_exit = true;
- exit(0);
- }
-
- if (!strcmp(argv[1], "status")) {
- if (thread_running) {
- printf("\tcontrol_demo app is running\n");
-
- } else {
- printf("\tcontrol_demo app not started\n");
- }
-
- exit(0);
- }
-
- usage("unrecognized command");
- exit(1);
-}
-
-int control_demo_thread_main(int argc, char *argv[])
-{
-
- printf("[control_Demo] starting\n");
-
- using namespace control;
-
- fixedwing::BlockMultiModeBacksideAutopilot autopilot(NULL, "FWB");
-
- thread_running = true;
-
- while (!thread_should_exit) {
- autopilot.update();
- }
-
- printf("[control_demo] exiting.\n");
-
- thread_running = false;
-
- return 0;
-}
-
-void test()
-{
- printf("beginning control lib test\n");
- control::basicBlocksTest();
-}
diff --git a/apps/examples/control_demo/params.c b/apps/examples/control_demo/params.c
deleted file mode 100644
index 428b779b1..000000000
--- a/apps/examples/control_demo/params.c
+++ /dev/null
@@ -1,71 +0,0 @@
-#include <systemlib/param/param.h>
-
-// currently tuned for easystar from arkhangar in HIL
-//https://github.com/arktools/arkhangar
-
-// 16 is max name length
-
-// gyro low pass filter
-PARAM_DEFINE_FLOAT(FWB_P_LP, 300.0f); // roll rate low pass cut freq
-PARAM_DEFINE_FLOAT(FWB_Q_LP, 300.0f); // pitch rate low pass cut freq
-PARAM_DEFINE_FLOAT(FWB_R_LP, 300.0f); // yaw rate low pass cut freq
-
-// yaw washout
-PARAM_DEFINE_FLOAT(FWB_R_HP, 1.0f); // yaw rate high pass
-
-// stabilization mode
-PARAM_DEFINE_FLOAT(FWB_P2AIL, 0.3f); // roll rate 2 aileron
-PARAM_DEFINE_FLOAT(FWB_Q2ELV, 0.1f); // pitch rate 2 elevator
-PARAM_DEFINE_FLOAT(FWB_R2RDR, 0.1f); // yaw rate 2 rudder
-
-// psi -> phi -> p
-PARAM_DEFINE_FLOAT(FWB_PSI2PHI, 0.5f); // heading 2 roll
-PARAM_DEFINE_FLOAT(FWB_PHI2P, 1.0f); // roll to roll rate
-PARAM_DEFINE_FLOAT(FWB_PHI_LIM_MAX, 0.3f); // roll limit, 28 deg
-
-// velocity -> theta
-PARAM_DEFINE_FLOAT(FWB_V2THE_P, 1.0f); // velocity to pitch angle PID, prop gain
-PARAM_DEFINE_FLOAT(FWB_V2THE_I, 0.0f); // integral gain
-PARAM_DEFINE_FLOAT(FWB_V2THE_D, 0.0f); // derivative gain
-PARAM_DEFINE_FLOAT(FWB_V2THE_D_LP, 0.0f); // derivative low-pass
-PARAM_DEFINE_FLOAT(FWB_V2THE_I_MAX, 0.0f); // integrator wind up guard
-PARAM_DEFINE_FLOAT(FWB_THE_MIN, -0.5f); // the max commanded pitch angle
-PARAM_DEFINE_FLOAT(FWB_THE_MAX, 0.5f); // the min commanded pitch angle
-
-
-// theta -> q
-PARAM_DEFINE_FLOAT(FWB_THE2Q_P, 1.0f); // pitch angle to pitch-rate PID
-PARAM_DEFINE_FLOAT(FWB_THE2Q_I, 0.0f);
-PARAM_DEFINE_FLOAT(FWB_THE2Q_D, 0.0f);
-PARAM_DEFINE_FLOAT(FWB_THE2Q_D_LP, 0.0f);
-PARAM_DEFINE_FLOAT(FWB_THE2Q_I_MAX, 0.0f);
-
-// h -> thr
-PARAM_DEFINE_FLOAT(FWB_H2THR_P, 0.01f); // altitude to throttle PID
-PARAM_DEFINE_FLOAT(FWB_H2THR_I, 0.0f);
-PARAM_DEFINE_FLOAT(FWB_H2THR_D, 0.0f);
-PARAM_DEFINE_FLOAT(FWB_H2THR_D_LP, 0.0f);
-PARAM_DEFINE_FLOAT(FWB_H2THR_I_MAX, 0.0f);
-
-// crosstrack
-PARAM_DEFINE_FLOAT(FWB_XT2YAW_MAX, 1.57f); // cross-track to yaw angle limit 90 deg
-PARAM_DEFINE_FLOAT(FWB_XT2YAW, 0.005f); // cross-track to yaw angle gain
-
-// speed command
-PARAM_DEFINE_FLOAT(FWB_V_MIN, 10.0f); // minimum commanded velocity
-PARAM_DEFINE_FLOAT(FWB_V_CMD, 12.0f); // commanded velocity
-PARAM_DEFINE_FLOAT(FWB_V_MAX, 16.0f); // maximum commanded velocity
-
-// rate of climb
-// this is what rate of climb is commanded (in m/s)
-// when the pitch stick is fully defelcted in simple mode
-PARAM_DEFINE_FLOAT(FWB_ROC_MAX, 1.0f);
-
-// rate of climb -> thr
-PARAM_DEFINE_FLOAT(FWB_ROC2THR_P, 0.01f); // rate of climb to throttle PID
-PARAM_DEFINE_FLOAT(FWB_ROC2THR_I, 0.0f);
-PARAM_DEFINE_FLOAT(FWB_ROC2THR_D, 0.0f);
-PARAM_DEFINE_FLOAT(FWB_ROC2THR_D_LP, 0.0f);
-PARAM_DEFINE_FLOAT(FWB_ROC2THR_I_MAX, 0.0f);
-
-PARAM_DEFINE_FLOAT(FWB_TRIM_THR, 0.8f); // trim throttle (0,1)
diff --git a/apps/fixedwing_att_control/Makefile b/apps/fixedwing_att_control/Makefile
deleted file mode 100644
index 01465fa9e..000000000
--- a/apps/fixedwing_att_control/Makefile
+++ /dev/null
@@ -1,45 +0,0 @@
-############################################################################
-#
-# 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
deleted file mode 100644
index b012448a2..000000000
--- a/apps/fixedwing_att_control/fixedwing_att_control_att.c
+++ /dev/null
@@ -1,170 +0,0 @@
-/****************************************************************************
- *
- * 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,
- 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/apps/fixedwing_att_control/fixedwing_att_control_att.h b/apps/fixedwing_att_control/fixedwing_att_control_att.h
deleted file mode 100644
index 600e35b89..000000000
--- a/apps/fixedwing_att_control/fixedwing_att_control_att.h
+++ /dev/null
@@ -1,51 +0,0 @@
-/****************************************************************************
- *
- * 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/apps/fixedwing_att_control/fixedwing_att_control_main.c b/apps/fixedwing_att_control/fixedwing_att_control_main.c
deleted file mode 100644
index aa9db6d52..000000000
--- a/apps/fixedwing_att_control/fixedwing_att_control_main.c
+++ /dev/null
@@ -1,369 +0,0 @@
-/****************************************************************************
- *
- * 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/apps/fixedwing_att_control/fixedwing_att_control_rate.c b/apps/fixedwing_att_control/fixedwing_att_control_rate.c
deleted file mode 100644
index ba5b593e2..000000000
--- a/apps/fixedwing_att_control/fixedwing_att_control_rate.c
+++ /dev/null
@@ -1,209 +0,0 @@
-/****************************************************************************
- *
- * 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
- * Implementation of a fixed wing attitude controller.
- *
- * @author Thomas Gubler <thomasgubler@student.ethz.ch>
- */
-#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>
-
-/*
- * 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/apps/fixedwing_att_control/fixedwing_att_control_rate.h b/apps/fixedwing_att_control/fixedwing_att_control_rate.h
deleted file mode 100644
index 500e3e197..000000000
--- a/apps/fixedwing_att_control/fixedwing_att_control_rate.h
+++ /dev/null
@@ -1,48 +0,0 @@
-/****************************************************************************
- *
- * 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
deleted file mode 100644
index bce391f49..000000000
--- a/apps/fixedwing_pos_control/Makefile
+++ /dev/null
@@ -1,45 +0,0 @@
-############################################################################
-#
-# 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_main.c b/apps/fixedwing_pos_control/fixedwing_pos_control_main.c
deleted file mode 100644
index 71c78f5b8..000000000
--- a/apps/fixedwing_pos_control/fixedwing_pos_control_main.c
+++ /dev/null
@@ -1,479 +0,0 @@
-/****************************************************************************
- *
- * 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 <uORB/topics/parameter_update.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>
-
-/*
- * Controller parameters, accessible via MAVLink
- *
- */
-PARAM_DEFINE_FLOAT(FW_HEAD_P, 0.1f);
-PARAM_DEFINE_FLOAT(FW_HEADR_I, 0.1f);
-PARAM_DEFINE_FLOAT(FW_HEADR_LIM, 1.5f); //TODO: think about reasonable value
-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_HEADR_P, 0.1f);
-PARAM_DEFINE_FLOAT(FW_PITCH_LIM, 0.35f); /**< Pitch angle limit in radians per second */
-
-struct fw_pos_control_params {
- float heading_p;
- float headingr_p;
- float headingr_i;
- float headingr_lim;
- float xtrack_p;
- float altitude_p;
- float roll_lim;
- float pitch_lim;
-};
-
-struct fw_pos_control_param_handles {
- param_t heading_p;
- param_t headingr_p;
- param_t headingr_i;
- param_t headingr_lim;
- param_t xtrack_p;
- param_t altitude_p;
- param_t roll_lim;
- param_t pitch_lim;
-};
-
-
-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
-};
-
-
-/* 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_HEAD_P");
- h->headingr_p = param_find("FW_HEADR_P");
- h->headingr_i = param_find("FW_HEADR_I");
- h->headingr_lim = param_find("FW_HEADR_LIM");
- 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->headingr_p, &(p->headingr_p));
- param_get(h->headingr_i, &(p->headingr_i));
- param_get(h->headingr_lim, &(p->headingr_lim));
- 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 pos 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));
- struct parameter_update_s param_update;
- memset(&param_update, 0, sizeof(param_update));
-
- /* output structs */
- struct vehicle_attitude_setpoint_s attitude_setpoint;
- memset(&attitude_setpoint, 0, sizeof(attitude_setpoint));
-
- /* publish attitude setpoint */
- attitude_setpoint.roll_body = 0.0f;
- attitude_setpoint.pitch_body = 0.0f;
- attitude_setpoint.yaw_body = 0.0f;
- attitude_setpoint.thrust = 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));
- int param_sub = orb_subscribe(ORB_ID(parameter_update));
-
- /* Setup of loop */
- struct pollfd fds[2] = {
- { .fd = param_sub, .events = POLLIN },
- { .fd = att_sub, .events = POLLIN }
- };
- bool global_sp_updated_set_once = false;
-
- float psi_track = 0.0f;
-
- int counter = 0;
-
- struct fw_pos_control_params p;
- struct fw_pos_control_param_handles h;
-
- PID_t heading_controller;
- PID_t heading_rate_controller;
- PID_t offtrack_controller;
- PID_t altitude_controller;
-
- parameters_init(&h);
- parameters_update(&h, &p);
- pid_init(&heading_controller, p.heading_p, 0.0f, 0.0f, 0.0f, 10000.0f, PID_MODE_DERIVATIV_NONE); //arbitrary high limit
- pid_init(&heading_rate_controller, p.headingr_p, p.headingr_i, 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);
- pid_init(&offtrack_controller, p.xtrack_p, 0.0f, 0.0f, 0.0f , 60.0f * M_DEG_TO_RAD, PID_MODE_DERIVATIV_NONE); //TODO: remove hardcoded value
-
- /* error and performance monitoring */
- perf_counter_t fw_interval_perf = perf_alloc(PC_INTERVAL, "fixedwing_pos_control_interval");
- perf_counter_t fw_err_perf = perf_alloc(PC_COUNT, "fixedwing_pos_control_err");
-
- while (!thread_should_exit) {
- /* wait for a sensor update, check for exit condition every 500 ms */
- int ret = poll(fds, 2, 500);
-
- if (ret < 0) {
- /* poll error, count it in perf */
- perf_count(fw_err_perf);
-
- } else if (ret == 0) {
- /* no return value, ignore */
- } else {
-
- /* only update parameters if they changed */
- if (fds[0].revents & POLLIN) {
- /* read from param to clear updated flag */
- struct parameter_update_s update;
- orb_copy(ORB_ID(parameter_update), param_sub, &update);
-
- /* update parameters from storage */
- parameters_update(&h, &p);
- pid_set_parameters(&heading_controller, p.heading_p, 0, 0, 0, 10000.0f); //arbitrary high limit
- pid_set_parameters(&heading_rate_controller, p.headingr_p, p.headingr_i, 0, 0, p.roll_lim);
- pid_set_parameters(&altitude_controller, p.altitude_p, 0, 0, 0, p.pitch_lim);
- pid_set_parameters(&offtrack_controller, p.xtrack_p, 0, 0, 0, 60.0f * M_DEG_TO_RAD); //TODO: remove hardcoded value
- }
-
- /* only run controller if attitude changed */
- if (fds[1].revents & POLLIN) {
-
-
- static uint64_t last_run = 0;
- const float deltaT = (hrt_absolute_time() - last_run) / 1000000.0f;
- last_run = hrt_absolute_time();
-
- /* 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);
- 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("next wp direction: %0.4f\n", (double)psi_track);
- }
-
- /* 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);
-
- // XXX what is xtrack_err.past_end?
- if (distance_res == OK /*&& !xtrack_err.past_end*/) {
-
- float delta_psi_c = pid_calculate(&offtrack_controller, 0, xtrack_err.distance, 0.0f, 0.0f); //p.xtrack_p * xtrack_err.distance
-
- float psi_c = psi_track + delta_psi_c;
- float psi_e = psi_c - att.yaw;
-
- /* wrap difference back onto -pi..pi range */
- psi_e = _wrap_pi(psi_e);
-
- if (verbose) {
- printf("xtrack_err.distance %.4f ", (double)xtrack_err.distance);
- printf("delta_psi_c %.4f ", (double)delta_psi_c);
- printf("psi_c %.4f ", (double)psi_c);
- printf("att.yaw %.4f ", (double)att.yaw);
- printf("psi_e %.4f ", (double)psi_e);
- }
-
- /* calculate roll setpoint, do this artificially around zero */
- float delta_psi_rate_c = pid_calculate(&heading_controller, psi_e, 0.0f, 0.0f, 0.0f);
- float psi_rate_track = 0; //=V_gr/r_track , this will be needed for implementation of arc following
- float psi_rate_c = delta_psi_rate_c + psi_rate_track;
-
- /* limit turn rate */
- if (psi_rate_c > p.headingr_lim) {
- psi_rate_c = p.headingr_lim;
-
- } else if (psi_rate_c < -p.headingr_lim) {
- psi_rate_c = -p.headingr_lim;
- }
-
- float psi_rate_e = psi_rate_c - att.yawspeed;
-
- // XXX sanity check: Assume 10 m/s stall speed and no stall condition
- float ground_speed = sqrtf(global_pos.vx * global_pos.vx + global_pos.vy * global_pos.vy);
-
- if (ground_speed < 10.0f) {
- ground_speed = 10.0f;
- }
-
- float psi_rate_e_scaled = psi_rate_e * ground_speed / 9.81f; //* V_gr / g
-
- attitude_setpoint.roll_body = pid_calculate(&heading_rate_controller, psi_rate_e_scaled, 0.0f, 0.0f, deltaT);
-
- if (verbose) {
- printf("psi_rate_c %.4f ", (double)psi_rate_c);
- printf("psi_rate_e_scaled %.4f ", (double)psi_rate_e_scaled);
- printf("rollbody %.4f\n", (double)attitude_setpoint.roll_body);
- }
-
- if (verbose && counter % 100 == 0)
- printf("xtrack_err.distance: %0.4f, delta_psi_c: %0.4f\n", xtrack_err.distance, delta_psi_c);
-
- } else {
- if (verbose && counter % 100 == 0)
- printf("distance_res: %d, past_end %d\n", distance_res, xtrack_err.past_end);
- }
-
- /* Very simple Altitude Control */
- if (pos_updated) {
-
- //TODO: take care of relative vs. ab. altitude
- attitude_setpoint.pitch_body = pid_calculate(&altitude_controller, global_setpoint.altitude, global_pos.alt, 0.0f, 0.0f);
-
- }
-
- // XXX need speed control
- attitude_setpoint.thrust = 0.7f;
-
- /* publish the attitude setpoint */
- orb_publish(ORB_ID(vehicle_attitude_setpoint), attitude_setpoint_pub, &attitude_setpoint);
-
- /* measure in what intervals the controller runs */
- perf_count(fw_interval_perf);
-
- counter++;
-
- } else {
- // XXX no setpoint, decent default needed (loiter?)
- }
- }
- }
- }
-
- 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,
- 2048,
- 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);
-}