aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--ROMFS/px4fmu_common/init.d/3035_viper10
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.autostart11
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.fw_apps4
-rw-r--r--ROMFS/px4fmu_common/init.d/rcS2
-rw-r--r--makefiles/config_px4fmu-v2_default.mk5
-rw-r--r--src/drivers/hil/hil.cpp3
-rw-r--r--src/modules/bottle_drop/bottle_drop.c519
-rw-r--r--src/modules/bottle_drop/bottle_drop.cpp393
-rw-r--r--src/modules/bottle_drop/module.mk40
-rw-r--r--src/modules/fw_att_control/fw_att_control_main.cpp24
-rw-r--r--src/modules/uORB/topics/vehicle_command.h12
11 files changed, 1004 insertions, 19 deletions
diff --git a/ROMFS/px4fmu_common/init.d/3035_viper b/ROMFS/px4fmu_common/init.d/3035_viper
new file mode 100644
index 000000000..9c8f8a585
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/3035_viper
@@ -0,0 +1,10 @@
+#!nsh
+#
+# Viper
+#
+# Simon Wilks <sjwilks@gmail.com>
+#
+
+sh /etc/init.d/rc.fw_defaults
+
+set MIXER FMU_FX79 \ No newline at end of file
diff --git a/ROMFS/px4fmu_common/init.d/rc.autostart b/ROMFS/px4fmu_common/init.d/rc.autostart
index 17541e680..78778d806 100644
--- a/ROMFS/px4fmu_common/init.d/rc.autostart
+++ b/ROMFS/px4fmu_common/init.d/rc.autostart
@@ -21,6 +21,12 @@
# Simulation setups
#
+if param compare SYS_AUTOSTART 901
+then
+ sh /etc/init.d/901_bottle_drop_test.hil
+ set MODE custom
+fi
+
if param compare SYS_AUTOSTART 1000
then
sh /etc/init.d/1000_rc_fw_easystar.hil
@@ -103,6 +109,11 @@ then
sh /etc/init.d/3034_fx79
fi
+if param compare SYS_AUTOSTART 3035 35
+then
+ sh /etc/init.d/3035_viper
+fi
+
if param compare SYS_AUTOSTART 3100
then
sh /etc/init.d/3100_tbs_caipirinha
diff --git a/ROMFS/px4fmu_common/init.d/rc.fw_apps b/ROMFS/px4fmu_common/init.d/rc.fw_apps
index 9aca3fc5f..767c54629 100644
--- a/ROMFS/px4fmu_common/init.d/rc.fw_apps
+++ b/ROMFS/px4fmu_common/init.d/rc.fw_apps
@@ -13,3 +13,7 @@ ekf_att_pos_estimator start
#
fw_att_control start
fw_pos_control_l1 start
+
+bottle_drop start
+fmu mode_pwm
+mixer load /dev/px4fmu /etc/mixers/FMU_pass.mix
diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS
index 24b2a299a..19d42dfa5 100644
--- a/ROMFS/px4fmu_common/init.d/rcS
+++ b/ROMFS/px4fmu_common/init.d/rcS
@@ -235,7 +235,7 @@ then
tone_alarm $TUNE_OUT_ERROR
fi
fi
-
+
#
# Set default output if not set
#
diff --git a/makefiles/config_px4fmu-v2_default.mk b/makefiles/config_px4fmu-v2_default.mk
index d0a40445d..7e22c9a94 100644
--- a/makefiles/config_px4fmu-v2_default.mk
+++ b/makefiles/config_px4fmu-v2_default.mk
@@ -128,6 +128,11 @@ MODULES += lib/conversion
MODULES += lib/launchdetection
#
+# OBC challenge
+#
+MODULES += modules/bottle_drop
+
+#
# Demo apps
#
#MODULES += examples/math_demo
diff --git a/src/drivers/hil/hil.cpp b/src/drivers/hil/hil.cpp
index f17e99e9d..f0dc0c651 100644
--- a/src/drivers/hil/hil.cpp
+++ b/src/drivers/hil/hil.cpp
@@ -392,7 +392,8 @@ HIL::task_main()
if (fds[0].revents & POLLIN) {
/* get controls - must always do this to avoid spinning */
- orb_copy(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, _t_actuators, &_controls);
+ orb_copy(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS :
+ ORB_ID(actuator_controls_1), _t_actuators, &_controls);
/* can we mix? */
if (_mixers != nullptr) {
diff --git a/src/modules/bottle_drop/bottle_drop.c b/src/modules/bottle_drop/bottle_drop.c
new file mode 100644
index 000000000..1911329d0
--- /dev/null
+++ b/src/modules/bottle_drop/bottle_drop.c
@@ -0,0 +1,519 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file bottle_drop.c
+ * bottle_drop application
+ *
+ * @author Dominik Juchli <juchlid@ethz.ch>
+ */
+
+#include <nuttx/config.h>
+#include <nuttx/sched.h>
+#include <unistd.h>
+#include <stdio.h>
+#include <stdlib.h>
+#include <poll.h>
+#include <stdbool.h>
+#include <fcntl.h>
+#include <string.h>
+#include <math.h>
+
+
+#include <systemlib/systemlib.h>
+#include <systemlib/err.h>
+#include <systemlib/param/param.h>
+
+#include <geo/geo.h>
+#include <dataman/dataman.h>
+
+#include <uORB/uORB.h>
+#include <uORB/topics/actuator_controls.h>
+#include <uORB/topics/vehicle_attitude.h>
+#include <uORB/topics/vehicle_global_position.h>
+#include <uORB/topics/parameter_update.h>
+#include <uORB/topics/mission.h>
+
+#include <drivers/drv_hrt.h>
+
+PARAM_DEFINE_FLOAT(BD_HEIGHT, 60.0f);
+PARAM_DEFINE_FLOAT(BD_GPROPERTIES, 0.03f);
+PARAM_DEFINE_FLOAT(BD_TURNRADIUS, 70.0f);
+PARAM_DEFINE_FLOAT(BD_PRECISION, 1.0f);
+PARAM_DEFINE_INT32(BD_APPROVAL, 0);
+
+
+
+
+static bool thread_should_exit = false; /**< daemon exit flag */
+static bool thread_running = false; /**< daemon status flag */
+static int daemon_task; /**< Handle of daemon task / thread */
+
+static bool drop = false;
+
+/**
+ * daemon management function.
+ */
+__EXPORT int bottle_drop_main(int argc, char *argv[]);
+
+/**
+ * Mainloop of daemon.
+ */
+int bottle_drop_thread_main(int argc, char *argv[]);
+
+/**
+ * Print the correct usage.
+ */
+static void usage(const char *reason);
+
+static void
+usage(const char *reason)
+{
+ if (reason)
+ warnx("%s\n", reason);
+ errx(1, "usage: daemon {start|stop|status} [-p <additional params>]\n\n");
+}
+
+/**
+ * The daemon app only briefly exists to start
+ * the background job. The stack size assigned in the
+ * Makefile does only apply to this management task.
+ *
+ * The actual stack size should be set in the call
+ * to task_create().
+ */
+int bottle_drop_main(int argc, char *argv[])
+{
+ if (argc < 1)
+ usage("missing command");
+
+ if (!strcmp(argv[1], "start")) {
+
+ if (thread_running) {
+ warnx("daemon already running\n");
+ /* this is not an error */
+ exit(0);
+ }
+
+ thread_should_exit = false;
+ daemon_task = task_spawn_cmd("bottle_drop",
+ SCHED_DEFAULT,
+ SCHED_PRIORITY_DEFAULT,
+ 4096,
+ bottle_drop_thread_main,
+ (argv) ? (const char **)&argv[2] : (const char **)NULL);
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "drop")) {
+ drop = true;
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "stop")) {
+ thread_should_exit = true;
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "status")) {
+ if (thread_running) {
+ warnx("\trunning\n");
+ } else {
+ warnx("\tnot started\n");
+ }
+ exit(0);
+ }
+
+ usage("unrecognized command");
+ exit(1);
+}
+
+int bottle_drop_thread_main(int argc, char *argv[]) {
+
+ warnx("starting\n");
+
+ bool updated = false;
+
+ float height; // height at which the normal should be dropped NED
+ float z_0; // ground properties
+ float turn_radius; // turn radius of the UAV
+ float precision; // Expected precision of the UAV
+ bool drop_approval; // if approval is given = true, otherwise = false
+
+ thread_running = true;
+
+ /* XXX TODO: create, publish and read in wind speed topic */
+ struct wind_speed_s {
+ float vx; // m/s
+ float vy; // m/s
+ float altitude; // m
+ } wind_speed;
+
+ wind_speed.vx = 4.2f;
+ wind_speed.vy = 0.0f;
+ wind_speed.altitude = 62.0f;
+
+
+ /* XXX TODO: create, publish and read in target position in NED*/
+ struct position_s {
+ double lat; //degrees 1E7
+ double lon; //degrees 1E7
+ float alt; //m
+ } target_position, drop_position;
+
+ target_position.lat = 47.385806;
+ target_position.lon = 8.589093;
+ target_position.alt = 0.0f;
+
+
+ // constant
+ float g = 9.81f; // constant of gravity [m/s^2]
+ float m = 0.5f; // mass of bottle [kg]
+ float rho = 1.2f; // air density [kg/m^3]
+ float A = (powf(0.063f, 2.0f)/4.0f*M_PI_F); // Bottle cross section [m^2]
+ float dt = 0.01f; // step size [s]
+ float dt2 = 0.05f; // step size 2 [s]
+
+ // Has to be estimated by experiment
+ float cd = 0.86f; // Drag coefficient for a cylinder with a d/l ratio of 1/3 []
+ float t_signal = 0.084f; // Time span between sending the signal and the bottle top reaching level height with the bottom of the plane [s]
+ float t_door = 0.7f; // The time the system needs to open the door + safety, is also the time the palyload needs to safely escape the shaft [s]
+
+
+ // Definition
+ float h_0; // height over target
+ float az; // acceleration in z direction[m/s^2]
+ float vz; // velocity in z direction [m/s]
+ float z; // fallen distance [m]
+ float h; // height over target [m]
+ float ax; // acceleration in x direction [m/s^2]
+ float vx; // ground speed in x direction [m/s]
+ float x; // traveled distance in x direction [m]
+ float vw; // wind speed [m/s]
+ float vrx; // relative velocity in x direction [m/s]
+ float v; // relative speed vector [m/s]
+ float Fd; // Drag force [N]
+ float Fdx; // Drag force in x direction [N]
+ float Fdz; // Drag force in z direction [N]
+ float vr; // absolute wind speed [m/s]
+ float x_drop, y_drop; // coordinates of the drop point in reference to the target (projection of NED)
+ float x_t,y_t; // coordinates of the target in reference to the target x_t = 0, y_t = 0 (projection of NED)
+ float x_l,y_l; // local position in projected coordinates
+ float x_f,y_f; // to-be position of the UAV after dt2 seconds in projected coordinates
+ double x_f_NED, y_f_NED; // to-be position of the UAV after dt2 seconds in NED
+ float distance_open_door; // The distance the UAV travels during its doors open [m]
+ float distance_real = 0; // The distance between the UAVs position and the drop point [m]
+ float future_distance = 0; // The distance between the UAVs to-be position and the drop point [m]
+
+ // states
+ bool state_door = false; // Doors are closed = false, open = true
+ bool state_drop = false; // Drop occurred = true, Drop din't occur = false
+ bool state_run = false; // A drop was attempted = true, the drop is still in progress = false
+
+ unsigned counter = 0;
+
+ param_t param_height = param_find("BD_HEIGHT");
+ param_t param_gproperties = param_find("BD_GPROPERTIES");
+ param_t param_turn_radius = param_find("BD_TURNRADIUS");
+ param_t param_precision = param_find("BD_PRECISION");
+ param_t param_approval = param_find("BD_APPROVAL");
+
+
+ param_get(param_approval, &drop_approval);
+ param_get(param_precision, &precision);
+ param_get(param_turn_radius, &turn_radius);
+ param_get(param_height, &height);
+ param_get(param_gproperties, &z_0);
+
+
+ struct vehicle_attitude_s att;
+ memset(&att, 0, sizeof(att));
+ int vehicle_attitude_sub = orb_subscribe(ORB_ID(vehicle_attitude));
+ orb_set_interval(vehicle_attitude_sub, 20);
+
+ struct vehicle_global_position_s globalpos;
+ memset(&globalpos, 0, sizeof(globalpos));
+ int vehicle_global_position_sub = orb_subscribe(ORB_ID(vehicle_global_position));
+
+ struct parameter_update_s update;
+ memset(&update, 0, sizeof(update));
+ int parameter_update_sub = orb_subscribe(ORB_ID(parameter_update));
+
+ struct actuator_controls_s actuators;
+ memset(&actuators, 0, sizeof(actuators));
+ orb_advert_t actuator_pub = orb_advertise(ORB_ID(actuator_controls_1), &actuators);
+
+ struct mission_item_s flight_vector_s;
+ struct mission_item_s flight_vector_e;
+
+ flight_vector_s.nav_cmd = NAV_CMD_WAYPOINT;
+ flight_vector_s.radius = 50; // TODO: make parameter
+ flight_vector_s.autocontinue = true;
+ flight_vector_e.nav_cmd = NAV_CMD_WAYPOINT;
+ flight_vector_e.radius = 50; // TODO: make parameter
+ flight_vector_e.autocontinue = true;
+
+ struct mission_s onboard_mission;
+ memset(&onboard_mission, 0, sizeof(onboard_mission));
+
+ orb_advert_t onboard_mission_pub = orb_advertise(ORB_ID(onboard_mission), &onboard_mission);
+
+ struct pollfd fds[] = {
+ { .fd = vehicle_attitude_sub, .events = POLLIN }
+ };
+
+ double latitude;
+ double longitude;
+
+
+ while (!thread_should_exit) {
+
+// warnx("in while!\n");
+ // values from -1 to 1
+
+ int ret = poll(fds, 1, 500);
+
+ if (ret < 0) {
+ /* poll error, count it in perf */
+ warnx("poll error");
+
+ } else if (ret > 0) {
+
+ orb_copy(ORB_ID(vehicle_attitude), vehicle_attitude_sub, &att);
+
+ orb_check(vehicle_global_position_sub, &updated);
+ if (updated){
+ /* copy global position */
+ orb_copy(ORB_ID(vehicle_global_position), vehicle_global_position_sub, &globalpos);
+
+ latitude = (double)globalpos.lat / 1e7;
+ longitude = (double)globalpos.lon / 1e7;
+ }
+
+ orb_check(parameter_update_sub, &updated);
+ if (updated){
+ /* copy global position */
+ orb_copy(ORB_ID(parameter_update), parameter_update_sub, &update);
+
+ /* update all parameters */
+ param_get(param_height, &height);
+ param_get(param_gproperties, &z_0);
+ param_get(param_turn_radius, &turn_radius);
+ param_get(param_approval, &drop_approval);
+ param_get(param_precision, &precision);
+
+
+ }
+
+ // Initialization
+
+
+ vr = sqrtf(powf(wind_speed.vx,2) + powf(wind_speed.vy,2)); // absolute wind speed [m/s]
+ distance_open_door = fabsf(t_door * globalpos.vx);
+
+
+ //warnx("absolut wind speed = %.4f", vr); //////////////////////////////////////////////////////////////////// DEBUGGING
+
+
+ //warnx("Initialization complete\n"); //////////////////////////////////////////////////////////////////// DEBUGGING
+
+
+ if (drop_approval && !state_drop)
+ {
+ //warnx("approval given\n"); //////////////////////////////////////////////////////////////////// DEBUGGING
+ // drop here
+ //open_now = true;
+ //drop = false;
+ //drop_start = hrt_absolute_time();
+
+
+ if (counter % 50 == 0) {
+
+ az = g; // acceleration in z direction[m/s^2]
+ vz = 0; // velocity in z direction [m/s]
+ z = 0; // fallen distance [m]
+ h_0 = globalpos.alt - target_position.alt; // height over target at start[m]
+ h = h_0; // height over target [m]
+ ax = 0; // acceleration in x direction [m/s^2]
+ vx = sqrtf(powf(globalpos.vx,2.0f) + powf(globalpos.vy,2.0f)); // ground speed in x direction [m/s]
+ x = 0; // traveled distance in x direction [m]
+ vw = 0; // wind speed [m/s]
+ vrx = 0; // relative velocity in x direction [m/s]
+ v = sqrtf(powf(globalpos.vx,2.0f) + powf(globalpos.vy,2.0f)); // relative speed vector [m/s]
+ Fd = 0; // Drag force [N]
+ Fdx = 0; // Drag force in x direction [N]
+ Fdz = 0; // Drag force in z direction [N]
+
+
+ // Compute the distance the bottle will travel after it is dropped in body frame coordinates --> x
+ while( h > 0.05f)
+ {
+ // z-direction
+ vz = vz + az*dt;
+ z = z + vz*dt;
+ h = h_0 - z;
+
+ // x-direction
+ vw = vr*logf(h/z_0)/logf(wind_speed.altitude/z_0);
+ vx = vx + ax*dt;
+ x = x + vx*dt;
+ vrx = vx + vw;
+
+ //Drag force
+ v = sqrtf(powf(vz,2.0f) + powf(vrx,2.0f));
+ Fd = 0.5f*rho*A*cd*powf(v,2.0f);
+ Fdx = Fd*vrx/v;
+ Fdz = Fd*vz/v;
+
+ //acceleration
+ az = g - Fdz/m;
+ ax = -Fdx/m;
+ }
+ // Compute Drop point
+ x = sqrtf(powf(globalpos.vx,2.0f) + powf(globalpos.vy,2.0f))*t_signal + x;
+ map_projection_init(target_position.lat, target_position.lon);
+ }
+
+ map_projection_project(target_position.lat, target_position.lon, &x_t, &y_t);
+ if( vr < 0.001f) // if there is no wind, an arbitrarily direction is chosen
+ {
+ vr = 1;
+ wind_speed.vx = 1;
+ wind_speed.vy = 0;
+ }
+ x_drop = x_t + x*wind_speed.vx/vr;
+ y_drop = y_t + x*wind_speed.vy/vr;
+ map_projection_reproject(x_drop, y_drop, &drop_position.lat, &drop_position.lon);
+ drop_position.alt = height;
+ //warnx("drop point: lat = %.7f , lon = %.7f", drop_position.lat, drop_position.lon); //////////////////////////////////////////////////////////////////// DEBUGGING
+
+
+
+ // Compute flight vector
+ map_projection_reproject(x_drop + 2*turn_radius*wind_speed.vx/vr, y_drop + 2*turn_radius*wind_speed.vy/vr, &(flight_vector_s.lat), &(flight_vector_s.lon));
+ flight_vector_s.altitude = height;
+ map_projection_reproject(x_drop - turn_radius*wind_speed.vx/vr, y_drop - turn_radius*wind_speed.vy/vr, &flight_vector_e.lat, &flight_vector_e.lon);
+ flight_vector_e.altitude = height;
+ //warnx("Flight vector: starting point = %.7f %.7f , end point = %.7f %.7f", flight_vector_s.lat,flight_vector_s.lon,flight_vector_e.lat,flight_vector_e.lon); //////////////////////////////////////////////////////////////////// DEBUGGING
+
+ // Drop Cancellation if terms are not met
+
+ // warnx("latitude:%.2f", latitude);
+ // warnx("longitude:%.2f", longitude);
+ // warnx("drop_position.lat:%.2f", drop_position.lat);
+ // warnx("drop_position.lon:%.2f", drop_position.lon);
+
+ distance_real = fabsf(get_distance_to_next_waypoint(latitude, longitude, drop_position.lat, drop_position.lon));
+ map_projection_project(latitude, longitude, &x_l, &y_l);
+ x_f = x_l + globalpos.vx*dt2;
+ y_f = y_l + globalpos.vy*dt2;
+ map_projection_reproject(x_f, y_f, &x_f_NED, &y_f_NED);
+ future_distance = fabsf(get_distance_to_next_waypoint(x_f_NED, y_f_NED, drop_position.lat, drop_position.lon));
+ //warnx("position to-be: = %.7f %.7f" ,x_f_NED, y_f_NED ); //////////////////////////////////////////////////////////////////// DEBUGGING
+
+ // if (counter % 10 ==0) {
+ // warnx("x: %.4f", x);
+ // warnx("drop_position.lat: %.4f, drop_position.lon: %.4f", drop_position.lat, drop_position.lon);
+ // warnx("latitude %.4f, longitude: %.4f", latitude, longitude);
+ // warnx("future_distance: %.2f, precision: %.2f", future_distance, precision);
+ // }
+
+ /* Save WPs in datamanager */
+ const size_t len = sizeof(struct mission_item_s);
+
+ if (dm_write(DM_KEY_WAYPOINTS_ONBOARD, 0, DM_PERSIST_IN_FLIGHT_RESET, &flight_vector_s, len) != len) {
+ warnx("ERROR: could not save onboard WP");
+ }
+
+ if (dm_write(DM_KEY_WAYPOINTS_ONBOARD, 1, DM_PERSIST_IN_FLIGHT_RESET, &flight_vector_e, len) != len) {
+ warnx("ERROR: could not save onboard WP");
+ }
+
+ onboard_mission.count = 2;
+
+ if (state_run && !state_drop) {
+ onboard_mission.current_index = 0;
+ } else {
+ onboard_mission.current_index = -1;
+ }
+
+ if (counter % 10 ==0)
+ warnx("Distance real: %.2f, distance_open_door: %.2f, angle to wind: %.2f", distance_real, distance_open_door, fabsf(_wrap_pi(globalpos.yaw-atan2f(wind_speed.vy,wind_speed.vx)+M_PI_F)));
+
+ orb_publish(ORB_ID(onboard_mission), onboard_mission_pub, &onboard_mission);
+
+ }
+
+ if(isfinite(distance_real) && distance_real < distance_open_door && drop_approval)
+ {
+ actuators.control[0] = -1.0f; // open door
+ actuators.control[1] = 1.0f;
+ state_door = true;
+ warnx("open doors");
+ }
+ else
+ { // closed door and locked survival kit
+ actuators.control[0] = 0.5f;
+ actuators.control[1] = -0.5f;
+ actuators.control[2] = -0.5f;
+ state_door = false;
+ }
+ if(isfinite(distance_real) && distance_real < precision && distance_real < future_distance && state_door) // Drop only if the distance between drop point and actual position is getting larger again
+ {
+ if(fabsf(_wrap_pi(globalpos.yaw-atan2f(wind_speed.vy,wind_speed.vx)+M_PI_F)) < 10.0f/180.0f*M_PI_F) // if flight trajectory deviates more than 10 degrees from calculated path, it will no drop
+ {
+ actuators.control[2] = 0.5f;
+ state_drop = true;
+ state_run = true;
+ warnx("dropping now");
+ }
+ else
+ {
+ state_run = true;
+ }
+ }
+
+ actuators.timestamp = hrt_absolute_time();
+ orb_publish(ORB_ID(actuator_controls_1), actuator_pub, &actuators);
+
+ counter++;
+ }
+ }
+
+ warnx("exiting.\n");
+
+ thread_running = false;
+
+
+ return 0;
+}
diff --git a/src/modules/bottle_drop/bottle_drop.cpp b/src/modules/bottle_drop/bottle_drop.cpp
new file mode 100644
index 000000000..ce760adc3
--- /dev/null
+++ b/src/modules/bottle_drop/bottle_drop.cpp
@@ -0,0 +1,393 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file bottle_drop.cpp
+ *
+ * Bottle drop module for Outback Challenge 2014, Team Swiss Fang
+ *
+ * @author Dominik Juchli <juchlid@ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
+ */
+
+#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 <sys/ioctl.h>
+#include <drivers/device/device.h>
+#include <drivers/drv_hrt.h>
+#include <arch/board/board.h>
+#include <uORB/uORB.h>
+#include <uORB/topics/vehicle_command.h>
+#include <uORB/topics/actuator_controls.h>
+#include <systemlib/systemlib.h>
+#include <systemlib/param/param.h>
+#include <systemlib/err.h>
+#include <geo/geo.h>
+#include <mathlib/mathlib.h>
+#include <mavlink/mavlink_log.h>
+
+
+/**
+ * bottle_drop app start / stop handling function
+ *
+ * @ingroup apps
+ */
+extern "C" __EXPORT int bottle_drop_main(int argc, char *argv[]);
+
+class BottleDrop
+{
+public:
+ /**
+ * Constructor
+ */
+ BottleDrop();
+
+ /**
+ * Destructor, also kills task.
+ */
+ ~BottleDrop();
+
+ /**
+ * Start the task.
+ *
+ * @return OK on success.
+ */
+ int start();
+
+ /**
+ * Display status.
+ */
+ void status();
+
+private:
+ bool _task_should_exit; /**< if true, task should exit */
+ int _main_task; /**< handle for task */
+ int _mavlink_fd;
+
+ int _command_sub;
+ struct vehicle_command_s _command;
+
+ orb_advert_t _actuator_pub;
+ struct actuator_controls_s _actuators;
+
+ bool _open_door;
+ bool _drop;
+ hrt_abstime _doors_opened;
+
+ void task_main();
+
+ void handle_command(struct vehicle_command_s *cmd);
+
+ void answer_command(struct vehicle_command_s *cmd, enum VEHICLE_CMD_RESULT result);
+
+ /**
+ * Shim for calling task_main from task_create.
+ */
+ static void task_main_trampoline(int argc, char *argv[]);
+};
+
+namespace bottle_drop
+{
+BottleDrop *g_bottle_drop;
+}
+
+BottleDrop::BottleDrop() :
+
+ _task_should_exit(false),
+ _main_task(-1),
+ _mavlink_fd(-1),
+ _command_sub(-1),
+ _command({}),
+ _actuator_pub(-1),
+ _actuators({}),
+ _open_door(false),
+ _drop(false),
+ _doors_opened(0)
+{
+}
+
+BottleDrop::~BottleDrop()
+{
+ if (_main_task != -1) {
+
+ /* task wakes up every 100ms or so at the longest */
+ _task_should_exit = true;
+
+ /* wait for a second for the task to quit at our request */
+ unsigned i = 0;
+
+ do {
+ /* wait 20ms */
+ usleep(20000);
+
+ /* if we have given up, kill it */
+ if (++i > 50) {
+ task_delete(_main_task);
+ break;
+ }
+ } while (_main_task != -1);
+ }
+
+ bottle_drop::g_bottle_drop = nullptr;
+}
+
+int
+BottleDrop::start()
+{
+ ASSERT(_main_task == -1);
+
+ /* start the task */
+ _main_task = task_spawn_cmd("bottle_drop",
+ SCHED_DEFAULT,
+ SCHED_PRIORITY_MAX - 5,
+ 2048,
+ (main_t)&BottleDrop::task_main_trampoline,
+ nullptr);
+
+ if (_main_task < 0) {
+ warn("task start failed");
+ return -errno;
+ }
+
+ return OK;
+}
+
+
+void
+BottleDrop::status()
+{
+ warnx("Doors: %s", _open_door ? "OPEN" : "CLOSED");
+ warnx("Dropping: %s", _drop ? "YES" : "NO");
+}
+
+void
+BottleDrop::task_main()
+{
+ /* inform about start */
+ warnx("Initializing..");
+ fflush(stdout);
+
+ _mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
+ mavlink_log_info(_mavlink_fd, "[bottle_drop] started");
+
+ _command_sub = orb_subscribe(ORB_ID(vehicle_command));
+
+ /* wakeup source(s) */
+ struct pollfd fds[1];
+
+ /* Setup of loop */
+ fds[0].fd = _command_sub;
+ fds[0].events = POLLIN;
+
+ while (!_task_should_exit) {
+
+ /* wait for up to 100ms for data */
+ int pret = poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 50);
+
+ /* this is undesirable but not much we can do - might want to flag unhappy status */
+ if (pret < 0) {
+ warn("poll error %d, %d", pret, errno);
+ continue;
+ }
+
+ /* vehicle commands updated */
+ if (fds[0].revents & POLLIN) {
+ orb_copy(ORB_ID(vehicle_command), _command_sub, &_command);
+ handle_command(&_command);
+ }
+
+ /* update door actuators */
+ if (_open_door) {
+ _actuators.control[0] = -1.0f;
+ _actuators.control[1] = 1.0f;
+
+ if (_doors_opened == 0) {
+ _doors_opened = hrt_absolute_time();
+ }
+ } else {
+ _actuators.control[0] = 1.0f;
+ _actuators.control[1] = -1.0f;
+
+ _doors_opened = 0;
+ }
+
+ /* update drop actuator, wait 0.5s until the doors are open before dropping */
+ if (_drop && _doors_opened != 0 && hrt_elapsed_time(&_doors_opened) > 500000) {
+ _actuators.control[2] = -0.5f;
+ } else {
+ _actuators.control[2] = 0.5f;
+ }
+
+ /* 20s after drop, reset and close everything again */
+ if (_drop && _doors_opened != 0 && hrt_elapsed_time(&_doors_opened) > 20000000) {
+ _open_door = false;
+ _drop = false;
+ }
+
+ /* lazily publish _actuators only once available */
+ if (_actuator_pub > 0) {
+ orb_publish(ORB_ID(actuator_controls_1), _actuator_pub, &_actuators);
+
+ } else {
+ _actuator_pub = orb_advertise(ORB_ID(actuator_controls_1), &_actuators);
+ }
+ }
+
+ warnx("exiting.");
+
+ _main_task = -1;
+ _exit(0);
+}
+
+void
+BottleDrop::handle_command(struct vehicle_command_s *cmd)
+{
+ switch (cmd->command) {
+ case VEHICLE_CMD_CUSTOM_0:
+
+ /*
+ * param1 and param2 set to 1: open and drop
+ * param1 set to 1: open
+ * else: close (and don't drop)
+ */
+ if (cmd->param1 > 0.5f && cmd->param2 > 0.5f) {
+ _open_door = true;
+ _drop = true;
+ mavlink_log_info(_mavlink_fd, "#audio: drop bottle");
+ }
+ else if (cmd->param1 > 0.5f) {
+ _open_door = true;
+ _drop = false;
+ mavlink_log_info(_mavlink_fd, "#audio: open doors");
+ } else {
+ _open_door = false;
+ _drop = false;
+ mavlink_log_info(_mavlink_fd, "#audio: close doors");
+ }
+
+ answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
+ break;
+ default:
+ break;
+ }
+}
+
+void
+BottleDrop::answer_command(struct vehicle_command_s *cmd, enum VEHICLE_CMD_RESULT result)
+{
+ switch (result) {
+ case VEHICLE_CMD_RESULT_ACCEPTED:
+ break;
+
+ case VEHICLE_CMD_RESULT_DENIED:
+ mavlink_log_critical(_mavlink_fd, "#audio: command denied: %u", cmd->command);
+ break;
+
+ case VEHICLE_CMD_RESULT_FAILED:
+ mavlink_log_critical(_mavlink_fd, "#audio: command failed: %u", cmd->command);
+ break;
+
+ case VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED:
+ mavlink_log_critical(_mavlink_fd, "#audio: command temporarily rejected: %u", cmd->command);
+ break;
+
+ case VEHICLE_CMD_RESULT_UNSUPPORTED:
+ mavlink_log_critical(_mavlink_fd, "#audio: command unsupported: %u", cmd->command);
+ break;
+
+ default:
+ break;
+ }
+}
+
+void
+BottleDrop::task_main_trampoline(int argc, char *argv[])
+{
+ bottle_drop::g_bottle_drop->task_main();
+}
+
+static void usage()
+{
+ errx(1, "usage: bottle_drop {start|stop|status}");
+}
+
+int bottle_drop_main(int argc, char *argv[])
+{
+ if (argc < 2) {
+ usage();
+ }
+
+ if (!strcmp(argv[1], "start")) {
+
+ if (bottle_drop::g_bottle_drop != nullptr) {
+ errx(1, "already running");
+ }
+
+ bottle_drop::g_bottle_drop = new BottleDrop;
+
+ if (bottle_drop::g_bottle_drop == nullptr) {
+ errx(1, "alloc failed");
+ }
+
+ if (OK != bottle_drop::g_bottle_drop->start()) {
+ delete bottle_drop::g_bottle_drop;
+ bottle_drop::g_bottle_drop = nullptr;
+ err(1, "start failed");
+ }
+
+ return 0;
+ }
+
+ if (bottle_drop::g_bottle_drop == nullptr)
+ errx(1, "not running");
+
+ if (!strcmp(argv[1], "stop")) {
+ delete bottle_drop::g_bottle_drop;
+ bottle_drop::g_bottle_drop = nullptr;
+
+ } else if (!strcmp(argv[1], "status")) {
+ bottle_drop::g_bottle_drop->status();
+ } else {
+ usage();
+ }
+
+ return 0;
+}
diff --git a/src/modules/bottle_drop/module.mk b/src/modules/bottle_drop/module.mk
new file mode 100644
index 000000000..bb1f6c6b5
--- /dev/null
+++ b/src/modules/bottle_drop/module.mk
@@ -0,0 +1,40 @@
+############################################################################
+#
+# Copyright (c) 2013, 2014 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.
+#
+############################################################################
+
+#
+# Daemon application
+#
+
+MODULE_COMMAND = bottle_drop
+
+SRCS = bottle_drop.cpp
diff --git a/src/modules/fw_att_control/fw_att_control_main.cpp b/src/modules/fw_att_control/fw_att_control_main.cpp
index 0cea13cc4..e9480336a 100644
--- a/src/modules/fw_att_control/fw_att_control_main.cpp
+++ b/src/modules/fw_att_control/fw_att_control_main.cpp
@@ -910,18 +910,18 @@ FixedwingAttitudeControl::task_main()
_actuators_0_pub = orb_advertise(ORB_ID(actuator_controls_0), &_actuators);
}
- if (_actuators_1_pub > 0) {
- /* publish the attitude setpoint */
- orb_publish(ORB_ID(actuator_controls_1), _actuators_1_pub, &_actuators_airframe);
-// warnx("%.2f %.2f %.2f %.2f %.2f %.2f %.2f %.2f",
-// (double)_actuators_airframe.control[0], (double)_actuators_airframe.control[1], (double)_actuators_airframe.control[2],
-// (double)_actuators_airframe.control[3], (double)_actuators_airframe.control[4], (double)_actuators_airframe.control[5],
-// (double)_actuators_airframe.control[6], (double)_actuators_airframe.control[7]);
-
- } else {
- /* advertise and publish */
- _actuators_1_pub = orb_advertise(ORB_ID(actuator_controls_1), &_actuators_airframe);
- }
+// if (_actuators_1_pub > 0) {
+// /* publish the attitude setpoint */
+// orb_publish(ORB_ID(actuator_controls_1), _actuators_1_pub, &_actuators_airframe);
+//// warnx("%.2f %.2f %.2f %.2f %.2f %.2f %.2f %.2f",
+//// (double)_actuators_airframe.control[0], (double)_actuators_airframe.control[1], (double)_actuators_airframe.control[2],
+//// (double)_actuators_airframe.control[3], (double)_actuators_airframe.control[4], (double)_actuators_airframe.control[5],
+//// (double)_actuators_airframe.control[6], (double)_actuators_airframe.control[7]);
+//
+// } else {
+// /* advertise and publish */
+// _actuators_1_pub = orb_advertise(ORB_ID(actuator_controls_1), &_actuators_airframe);
+// }
}
diff --git a/src/modules/uORB/topics/vehicle_command.h b/src/modules/uORB/topics/vehicle_command.h
index 7db33d98b..15cdc517f 100644
--- a/src/modules/uORB/topics/vehicle_command.h
+++ b/src/modules/uORB/topics/vehicle_command.h
@@ -1,9 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2008-2012 PX4 Development Team. All rights reserved.
- * Author: @author Thomas Gubler <thomasgubler@student.ethz.ch>
- * @author Julian Oes <joes@student.ethz.ch>
- * @author Lorenz Meier <lm@inf.ethz.ch>
+ * Copyright (C) 2012-2014 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
@@ -37,6 +34,10 @@
/**
* @file vehicle_command.h
* Definition of the vehicle command uORB topic.
+ *
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
+ * @author Lorenz Meier <lm@inf.ethz.ch>
*/
#ifndef TOPIC_VEHICLE_COMMAND_H_
@@ -87,7 +88,8 @@ enum VEHICLE_CMD {
VEHICLE_CMD_MISSION_START = 300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| */
VEHICLE_CMD_COMPONENT_ARM_DISARM = 400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */
VEHICLE_CMD_START_RX_PAIR = 500, /* Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| */
- VEHICLE_CMD_ENUM_END = 501, /* | */
+ VEHICLE_CMD_PAYLOAD_PREPARE_DEPLOY = 30001, /**< Prepare a payload deployment in the flight plan */
+ VEHICLE_CMD_PAYLOAD_CONTROL_DEPLOY = 30002 /**< Control a pre-programmed payload deployment */
};
/**