aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rwxr-xr-xROMFS/px4fmu_common/init.d/rcS5
-rw-r--r--makefiles/config_px4fmu-v1_backside.mk1
-rw-r--r--makefiles/config_px4fmu-v1_default.mk1
-rw-r--r--makefiles/config_px4fmu-v2_default.mk1
-rw-r--r--src/drivers/px4io/px4io.cpp147
-rw-r--r--src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp109
-rw-r--r--src/lib/ecl/attitude_fw/ecl_pitch_controller.h28
-rw-r--r--src/lib/ecl/attitude_fw/ecl_roll_controller.cpp75
-rw-r--r--src/lib/ecl/attitude_fw/ecl_roll_controller.h27
-rw-r--r--src/lib/ecl/attitude_fw/ecl_yaw_controller.cpp116
-rw-r--r--src/lib/ecl/attitude_fw/ecl_yaw_controller.h74
-rw-r--r--src/lib/ecl/l1/ecl_l1_pos_controller.cpp4
-rw-r--r--src/lib/external_lgpl/tecs/tecs.cpp143
-rw-r--r--src/lib/external_lgpl/tecs/tecs.h12
-rw-r--r--src/lib/geo/geo.c61
-rw-r--r--src/lib/geo/geo.h28
-rw-r--r--src/modules/commander/commander.cpp19
-rw-r--r--src/modules/commander/state_machine_helper.cpp56
-rw-r--r--src/modules/commander/state_machine_helper.h4
-rw-r--r--src/modules/controllib/uorb/blocks.cpp18
-rw-r--r--src/modules/controllib/uorb/blocks.hpp9
-rw-r--r--src/modules/dataman/dataman.c739
-rw-r--r--src/modules/dataman/dataman.h116
-rw-r--r--src/modules/dataman/module.mk42
-rw-r--r--src/modules/fixedwing_backside/fixedwing.cpp10
-rw-r--r--src/modules/fixedwing_backside/fixedwing.hpp2
-rw-r--r--src/modules/fw_att_control/fw_att_control_main.cpp268
-rw-r--r--src/modules/fw_att_control/fw_att_control_params.c42
-rw-r--r--src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp510
-rw-r--r--src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c9
-rw-r--r--src/modules/mavlink/mavlink.c17
-rw-r--r--src/modules/mavlink/missionlib.c84
-rw-r--r--src/modules/mavlink/orb_topics.h2
-rw-r--r--src/modules/mavlink/waypoints.c810
-rw-r--r--src/modules/mavlink/waypoints.h33
-rw-r--r--src/modules/navigator/module.mk2
-rw-r--r--src/modules/navigator/navigator_main.cpp1236
-rw-r--r--src/modules/navigator/navigator_params.c9
-rw-r--r--src/modules/px4iofirmware/dsm.c2
-rw-r--r--src/modules/px4iofirmware/mixer.cpp33
-rw-r--r--src/modules/px4iofirmware/protocol.h54
-rw-r--r--src/modules/px4iofirmware/px4io.h6
-rw-r--r--src/modules/px4iofirmware/registers.c18
-rw-r--r--src/modules/px4iofirmware/sbus.c2
-rw-r--r--src/modules/uORB/objects_common.cpp11
-rw-r--r--src/modules/uORB/topics/fence.h80
-rw-r--r--src/modules/uORB/topics/mission.h35
-rw-r--r--src/modules/uORB/topics/mission_item_triplet.h (renamed from src/modules/uORB/topics/vehicle_global_position_set_triplet.h)29
-rw-r--r--src/modules/uORB/topics/mission_result.h67
-rw-r--r--src/modules/uORB/topics/vehicle_control_mode.h1
-rw-r--r--src/modules/uORB/topics/vehicle_status.h8
-rw-r--r--src/systemcmds/tests/module.mk3
-rw-r--r--src/systemcmds/tests/test_dataman.c179
-rw-r--r--src/systemcmds/tests/tests.h1
-rw-r--r--src/systemcmds/tests/tests_main.c1
55 files changed, 4184 insertions, 1215 deletions
diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS
index f1df99048..fc05d0b84 100755
--- a/ROMFS/px4fmu_common/init.d/rcS
+++ b/ROMFS/px4fmu_common/init.d/rcS
@@ -111,6 +111,11 @@ then
#
commander start
+ #
+ # Start the Navigator
+ #
+ navigator start
+
if param compare SYS_AUTOSTART 1000
then
sh /etc/init.d/1000_rc_fw_easystar.hil
diff --git a/makefiles/config_px4fmu-v1_backside.mk b/makefiles/config_px4fmu-v1_backside.mk
index 5ecf93a3a..6da78b287 100644
--- a/makefiles/config_px4fmu-v1_backside.mk
+++ b/makefiles/config_px4fmu-v1_backside.mk
@@ -107,6 +107,7 @@ MODULES += modules/systemlib
MODULES += modules/systemlib/mixer
MODULES += modules/controllib
MODULES += modules/uORB
+MODULES += modules/dataman
#
# Libraries
diff --git a/makefiles/config_px4fmu-v1_default.mk b/makefiles/config_px4fmu-v1_default.mk
index 25c22f1fd..f724962b2 100644
--- a/makefiles/config_px4fmu-v1_default.mk
+++ b/makefiles/config_px4fmu-v1_default.mk
@@ -106,6 +106,7 @@ MODULES += modules/systemlib
MODULES += modules/systemlib/mixer
MODULES += modules/controllib
MODULES += modules/uORB
+MODULES += modules/dataman
#
# Libraries
diff --git a/makefiles/config_px4fmu-v2_default.mk b/makefiles/config_px4fmu-v2_default.mk
index 015a7387a..1f3e4f808 100644
--- a/makefiles/config_px4fmu-v2_default.mk
+++ b/makefiles/config_px4fmu-v2_default.mk
@@ -103,6 +103,7 @@ MODULES += modules/systemlib
MODULES += modules/systemlib/mixer
MODULES += modules/controllib
MODULES += modules/uORB
+MODULES += modules/dataman
#
# Libraries
diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp
index 5d35ecb8d..b8edeed69 100644
--- a/src/drivers/px4io/px4io.cpp
+++ b/src/drivers/px4io/px4io.cpp
@@ -228,30 +228,33 @@ private:
device::Device *_interface;
// XXX
- unsigned _hardware; ///< Hardware revision
- unsigned _max_actuators; ///<Maximum # of actuators supported by PX4IO
- unsigned _max_controls; ///<Maximum # of controls supported by PX4IO
- unsigned _max_rc_input; ///<Maximum receiver channels supported by PX4IO
- unsigned _max_relays; ///<Maximum relays supported by PX4IO
- unsigned _max_transfer; ///<Maximum number of I2C transfers supported by PX4IO
+ unsigned _hardware; ///< Hardware revision
+ unsigned _max_actuators; ///< Maximum # of actuators supported by PX4IO
+ unsigned _max_controls; ///< Maximum # of controls supported by PX4IO
+ unsigned _max_rc_input; ///< Maximum receiver channels supported by PX4IO
+ unsigned _max_relays; ///< Maximum relays supported by PX4IO
+ unsigned _max_transfer; ///< Maximum number of I2C transfers supported by PX4IO
unsigned _update_interval; ///< Subscription interval limiting send rate
bool _rc_handling_disabled; ///< If set, IO does not evaluate, but only forward the RC values
- volatile int _task; ///<worker task id
- volatile bool _task_should_exit; ///<worker terminate flag
+ volatile int _task; ///< worker task id
+ volatile bool _task_should_exit; ///< worker terminate flag
- int _mavlink_fd; ///<mavlink file descriptor. This is opened by class instantiation and Doesn't appear to be usable in main thread.
- int _thread_mavlink_fd; ///<mavlink file descriptor for thread.
+ int _mavlink_fd; ///< mavlink file descriptor. This is opened by class instantiation and Doesn't appear to be usable in main thread.
+ int _thread_mavlink_fd; ///< mavlink file descriptor for thread.
- perf_counter_t _perf_update; ///<local performance counter
+ perf_counter_t _perf_update; ///< local performance counter
/* cached IO state */
- uint16_t _status; ///<Various IO status flags
- uint16_t _alarms; ///<Various IO alarms
+ uint16_t _status; ///< Various IO status flags
+ uint16_t _alarms; ///< Various IO alarms
/* subscribed topics */
- int _t_actuators; ///< actuator controls topic
+ int _t_actuator_controls_0; ///< actuator controls group 0 topic
+ int _t_actuator_controls_1; ///< actuator controls group 1 topic
+ int _t_actuator_controls_2; ///< actuator controls group 2 topic
+ int _t_actuator_controls_3; ///< actuator controls group 3 topic
int _t_actuator_armed; ///< system armed control topic
int _t_vehicle_control_mode;///< vehicle control mode topic
int _t_param; ///< parameter update topic
@@ -266,15 +269,15 @@ private:
actuator_outputs_s _outputs; ///<mixed outputs
- bool _primary_pwm_device; ///<true if we are the default PWM output
+ bool _primary_pwm_device; ///< true if we are the default PWM output
- float _battery_amp_per_volt; ///<current sensor amps/volt
- float _battery_amp_bias; ///<current sensor bias
- float _battery_mamphour_total;///<amp hours consumed so far
- uint64_t _battery_last_timestamp;///<last amp hour calculation timestamp
+ float _battery_amp_per_volt; ///< current sensor amps/volt
+ float _battery_amp_bias; ///< current sensor bias
+ float _battery_mamphour_total;///< amp hours consumed so far
+ uint64_t _battery_last_timestamp;///< last amp hour calculation timestamp
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
- bool _dsm_vcc_ctl; ///<true if relay 1 controls DSM satellite RX power
+ bool _dsm_vcc_ctl; ///< true if relay 1 controls DSM satellite RX power
#endif
/**
@@ -288,9 +291,14 @@ private:
void task_main();
/**
- * Send controls to IO
+ * Send controls for one group to IO
*/
- int io_set_control_state();
+ int io_set_control_state(unsigned group);
+
+ /**
+ * Send all controls to IO
+ */
+ int io_set_control_groups();
/**
* Update IO's arming-related state
@@ -461,7 +469,10 @@ PX4IO::PX4IO(device::Device *interface) :
_perf_update(perf_alloc(PC_ELAPSED, "px4io update")),
_status(0),
_alarms(0),
- _t_actuators(-1),
+ _t_actuator_controls_0(-1),
+ _t_actuator_controls_1(-1),
+ _t_actuator_controls_2(-1),
+ _t_actuator_controls_3(-1),
_t_actuator_armed(-1),
_t_vehicle_control_mode(-1),
_t_param(-1),
@@ -763,15 +774,20 @@ PX4IO::task_main()
* Subscribe to the appropriate PWM output topic based on whether we are the
* primary PWM output or not.
*/
- _t_actuators = orb_subscribe(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS :
- ORB_ID(actuator_controls_1));
- orb_set_interval(_t_actuators, 20); /* default to 50Hz */
+ _t_actuator_controls_0 = orb_subscribe(ORB_ID(actuator_controls_0));
+ orb_set_interval(_t_actuator_controls_0, 20); /* default to 50Hz */
+ _t_actuator_controls_1 = orb_subscribe(ORB_ID(actuator_controls_1));
+ orb_set_interval(_t_actuator_controls_1, 33); /* default to 30Hz */
+ _t_actuator_controls_2 = orb_subscribe(ORB_ID(actuator_controls_2));
+ orb_set_interval(_t_actuator_controls_2, 33); /* default to 30Hz */
+ _t_actuator_controls_3 = orb_subscribe(ORB_ID(actuator_controls_3));
+ orb_set_interval(_t_actuator_controls_3, 33); /* default to 30Hz */
_t_actuator_armed = orb_subscribe(ORB_ID(actuator_armed));
_t_vehicle_control_mode = orb_subscribe(ORB_ID(vehicle_control_mode));
_t_param = orb_subscribe(ORB_ID(parameter_update));
_t_vehicle_command = orb_subscribe(ORB_ID(vehicle_command));
- if ((_t_actuators < 0) ||
+ if ((_t_actuator_controls_0 < 0) ||
(_t_actuator_armed < 0) ||
(_t_vehicle_control_mode < 0) ||
(_t_param < 0) ||
@@ -782,7 +798,7 @@ PX4IO::task_main()
/* poll descriptor */
pollfd fds[1];
- fds[0].fd = _t_actuators;
+ fds[0].fd = _t_actuator_controls_0;
fds[0].events = POLLIN;
log("ready");
@@ -801,7 +817,11 @@ PX4IO::task_main()
if (_update_interval > 100)
_update_interval = 100;
- orb_set_interval(_t_actuators, _update_interval);
+ orb_set_interval(_t_actuator_controls_0, _update_interval);
+ /*
+ * NOT changing the rate of groups 1-3 here, because only attitude
+ * really needs to run fast.
+ */
_update_interval = 0;
}
@@ -821,7 +841,10 @@ PX4IO::task_main()
/* if we have new control data from the ORB, handle it */
if (fds[0].revents & POLLIN) {
- io_set_control_state();
+
+ /* we're not nice to the lower-priority control groups and only check them
+ when the primary group updated (which is now). */
+ io_set_control_groups();
}
if (now >= poll_last + IO_POLL_INTERVAL) {
@@ -864,7 +887,7 @@ PX4IO::task_main()
orb_copy(ORB_ID(vehicle_command), _t_vehicle_command, &cmd);
// Check for a DSM pairing command
- if ((cmd.command == VEHICLE_CMD_START_RX_PAIR) && (cmd.param1 == 0.0f)) {
+ if (((int)cmd.command == VEHICLE_CMD_START_RX_PAIR) && ((int)cmd.param1 == 0)) {
dsm_bind_ioctl((int)cmd.param2);
}
}
@@ -915,20 +938,74 @@ out:
}
int
-PX4IO::io_set_control_state()
+PX4IO::io_set_control_groups()
+{
+ bool attitude_ok = io_set_control_state(0);
+
+ /* send auxiliary control groups */
+ (void)io_set_control_state(1);
+ (void)io_set_control_state(2);
+ (void)io_set_control_state(3);
+
+ return attitude_ok;
+}
+
+int
+PX4IO::io_set_control_state(unsigned group)
{
actuator_controls_s controls; ///< actuator outputs
uint16_t regs[_max_actuators];
/* get controls */
- orb_copy(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS :
- ORB_ID(actuator_controls_1), _t_actuators, &controls);
+ bool changed;
+
+ switch (group) {
+ case 0:
+ {
+ orb_check(_t_actuator_controls_0, &changed);
+
+ if (changed) {
+ orb_copy(ORB_ID(actuator_controls_0), _t_actuator_controls_0, &controls);
+ }
+ }
+ break;
+ case 1:
+ {
+ orb_check(_t_actuator_controls_1, &changed);
+
+ if (changed) {
+ orb_copy(ORB_ID(actuator_controls_1), _t_actuator_controls_1, &controls);
+ }
+ }
+ break;
+ case 2:
+ {
+ orb_check(_t_actuator_controls_2, &changed);
+
+ if (changed) {
+ orb_copy(ORB_ID(actuator_controls_2), _t_actuator_controls_2, &controls);
+ }
+ }
+ break;
+ case 3:
+ {
+ orb_check(_t_actuator_controls_3, &changed);
+
+ if (changed) {
+ orb_copy(ORB_ID(actuator_controls_3), _t_actuator_controls_3, &controls);
+ }
+ }
+ break;
+ }
+
+ if (!changed)
+ return -1;
for (unsigned i = 0; i < _max_controls; i++)
regs[i] = FLOAT_TO_REG(controls.control[i]);
/* copy values to registers in IO */
- return io_reg_set(PX4IO_PAGE_CONTROLS, 0, regs, _max_controls);
+ return io_reg_set(PX4IO_PAGE_CONTROLS, group * PX4IO_PROTOCOL_MAX_CONTROL_COUNT, regs, _max_controls);
}
diff --git a/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp b/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp
index 2eb58abd6..d7dbbebd4 100644
--- a/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp
+++ b/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp
@@ -45,39 +45,30 @@
#include <geo/geo.h>
#include <ecl/ecl.h>
#include <mathlib/mathlib.h>
+#include <systemlib/err.h>
ECL_PitchController::ECL_PitchController() :
_last_run(0),
+ _tc(0.1f),
+ _k_p(0.0f),
+ _k_i(0.0f),
+ _k_d(0.0f),
+ _k_ff(0.0f),
+ _integrator_max(0.0f),
+ _max_rate_pos(0.0f),
+ _max_rate_neg(0.0f),
+ _roll_ff(0.0f),
_last_output(0.0f),
_integrator(0.0f),
_rate_error(0.0f),
_rate_setpoint(0.0f),
- _max_deflection_rad(math::radians(45.0f))
+ _bodyrate_setpoint(0.0f)
{
}
-float ECL_PitchController::control(float pitch_setpoint, float pitch, float pitch_rate, float roll, float scaler,
- bool lock_integrator, float airspeed_min, float airspeed_max, float airspeed)
+float ECL_PitchController::control_attitude(float pitch_setpoint, float roll, float pitch, float airspeed)
{
- /* get the usual dt estimate */
- uint64_t dt_micros = ecl_elapsed_time(&_last_run);
- _last_run = ecl_absolute_time();
- float dt = (float)dt_micros * 1e-6f;
-
- /* lock integral for long intervals */
- if (dt_micros > 500000)
- lock_integrator = true;
- float k_roll_ff = math::max((_k_p - _k_i * _tc) * _tc - _k_d, 0.0f);
- float k_i_rate = _k_i * _tc;
-
- /* input conditioning */
- if (!isfinite(airspeed)) {
- /* airspeed is NaN, +- INF or not available, pick center of band */
- airspeed = 0.5f * (airspeed_min + airspeed_max);
- } else if (airspeed < airspeed_min) {
- airspeed = airspeed_min;
- }
/* flying inverted (wings upside down) ? */
bool inverted = false;
@@ -105,29 +96,72 @@ float ECL_PitchController::control(float pitch_setpoint, float pitch, float pitc
if (inverted)
turn_offset = -turn_offset;
+ /* Calculate the error */
float pitch_error = pitch_setpoint - pitch;
- /* rate setpoint from current error and time constant */
- _rate_setpoint = pitch_error / _tc;
+
+ /* Apply P controller: rate setpoint from current error and time constant */
+ _rate_setpoint = pitch_error / _tc;
/* add turn offset */
_rate_setpoint += turn_offset;
- _rate_error = _rate_setpoint - pitch_rate;
+ /* limit the rate */ //XXX: move to body angluar rates
+ if (_max_rate_pos > 0.01f && _max_rate_neg > 0.01f) {
+ if (_rate_setpoint > 0.0f) {
+ _rate_setpoint = (_rate_setpoint > _max_rate_pos) ? _max_rate_pos : _rate_setpoint;
+ } else {
+ _rate_setpoint = (_rate_setpoint < -_max_rate_neg) ? -_max_rate_neg : _rate_setpoint;
+ }
- float ilimit_scaled = _integrator_max * scaler;
+ }
- if (!lock_integrator && k_i_rate > 0.0f && airspeed > 0.5f * airspeed_min) {
+ return _rate_setpoint;
+}
- float id = _rate_error * k_i_rate * dt * scaler;
+float ECL_PitchController::control_bodyrate(float roll, float pitch,
+ float pitch_rate, float yaw_rate,
+ float yaw_rate_setpoint,
+ float airspeed_min, float airspeed_max, float airspeed, float scaler, bool lock_integrator)
+{
+ /* get the usual dt estimate */
+ uint64_t dt_micros = ecl_elapsed_time(&_last_run);
+ _last_run = ecl_absolute_time();
+ float dt = (float)dt_micros * 1e-6f;
+
+ /* lock integral for long intervals */
+ if (dt_micros > 500000)
+ lock_integrator = true;
+
+// float k_ff = math::max((_k_p - _k_i * _tc) * _tc - _k_d, 0.0f);
+ float k_ff = 0;
+
+ /* input conditioning */
+ if (!isfinite(airspeed)) {
+ /* airspeed is NaN, +- INF or not available, pick center of band */
+ airspeed = 0.5f * (airspeed_min + airspeed_max);
+ } else if (airspeed < airspeed_min) {
+ airspeed = airspeed_min;
+ }
+
+ /* Transform setpoint to body angular rates */
+ _bodyrate_setpoint = cosf(roll) * _rate_setpoint + cosf(pitch) * sinf(roll) * yaw_rate_setpoint; //jacobian
+
+ /* Transform estimation to body angular rates */
+ float pitch_bodyrate = cosf(roll) * pitch_rate + cosf(pitch) * sinf(roll) * yaw_rate; //jacobian
+
+ _rate_error = _bodyrate_setpoint - pitch_bodyrate;
+
+ if (!lock_integrator && _k_i > 0.0f && airspeed > 0.5f * airspeed_min) {
+
+ float id = _rate_error * dt;
/*
- * anti-windup: do not allow integrator to increase into the
- * wrong direction if actuator is at limit
+ * anti-windup: do not allow integrator to increase if actuator is at limit
*/
- if (_last_output < -_max_deflection_rad) {
+ if (_last_output < -1.0f) {
/* only allow motion to center: increase value */
id = math::max(id, 0.0f);
- } else if (_last_output > _max_deflection_rad) {
+ } else if (_last_output > 1.0f) {
/* only allow motion to center: decrease value */
id = math::min(id, 0.0f);
}
@@ -136,11 +170,14 @@ float ECL_PitchController::control(float pitch_setpoint, float pitch, float pitc
}
/* integrator limit */
- _integrator = math::constrain(_integrator, -ilimit_scaled, ilimit_scaled);
- /* store non-limited output */
- _last_output = ((_rate_error * _k_d * scaler) + _integrator + (_rate_setpoint * k_roll_ff)) * scaler;
-
- return math::constrain(_last_output, -_max_deflection_rad, _max_deflection_rad);
+ //xxx: until start detection is available: integral part in control signal is limited here
+ float integrator_constrained = math::constrain(_integrator * _k_i, -_integrator_max, _integrator_max);
+
+ /* Apply PI rate controller and store non-limited output */
+ _last_output = (_bodyrate_setpoint * _k_ff +_rate_error * _k_p + integrator_constrained + _rate_setpoint * k_ff) * scaler * scaler; //scaler is proportional to 1/airspeed
+// warnx("pitch: _integrator: %.4f, _integrator_max: %.4f, airspeed %.4f, _k_i %.4f, _k_p: %.4f", (double)_integrator, (double)_integrator_max, (double)airspeed, (double)_k_i, (double)_k_p);
+// warnx("roll: _last_output %.4f", (double)_last_output);
+ return math::constrain(_last_output, -1.0f, 1.0f);
}
void ECL_PitchController::reset_integrator()
diff --git a/src/lib/ecl/attitude_fw/ecl_pitch_controller.h b/src/lib/ecl/attitude_fw/ecl_pitch_controller.h
index 1e6cec6a1..2ca0490fd 100644
--- a/src/lib/ecl/attitude_fw/ecl_pitch_controller.h
+++ b/src/lib/ecl/attitude_fw/ecl_pitch_controller.h
@@ -36,6 +36,7 @@
* Definition of a simple orthogonal pitch PID controller.
*
* @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Thomas Gubler <thomasgubler@gmail.com>
*
* Acknowledgements:
*
@@ -51,13 +52,18 @@
#include <stdbool.h>
#include <stdint.h>
-class __EXPORT ECL_PitchController
+class __EXPORT ECL_PitchController //XXX: create controller superclass
{
public:
ECL_PitchController();
- float control(float pitch_setpoint, float pitch, float pitch_rate, float roll, float scaler = 1.0f,
- bool lock_integrator = false, float airspeed_min = 0.0f, float airspeed_max = 0.0f, float airspeed = (0.0f / 0.0f));
+ float control_attitude(float pitch_setpoint, float roll, float pitch, float airspeed);
+
+
+ float control_bodyrate(float roll, float pitch,
+ float pitch_rate, float yaw_rate,
+ float yaw_rate_setpoint,
+ float airspeed_min = 0.0f, float airspeed_max = 0.0f, float airspeed = (0.0f / 0.0f), float scaler = 1.0f, bool lock_integrator = false);
void reset_integrator();
@@ -67,21 +73,30 @@ public:
void set_k_p(float k_p) {
_k_p = k_p;
}
+
void set_k_i(float k_i) {
_k_i = k_i;
}
void set_k_d(float k_d) {
_k_d = k_d;
}
+
+ void set_k_ff(float k_ff) {
+ _k_ff = k_ff;
+ }
+
void set_integrator_max(float max) {
_integrator_max = max;
}
+
void set_max_rate_pos(float max_rate_pos) {
_max_rate_pos = max_rate_pos;
}
+
void set_max_rate_neg(float max_rate_neg) {
_max_rate_neg = max_rate_neg;
}
+
void set_roll_ff(float roll_ff) {
_roll_ff = roll_ff;
}
@@ -94,6 +109,10 @@ public:
return _rate_setpoint;
}
+ float get_desired_bodyrate() {
+ return _bodyrate_setpoint;
+ }
+
private:
uint64_t _last_run;
@@ -101,6 +120,7 @@ private:
float _k_p;
float _k_i;
float _k_d;
+ float _k_ff;
float _integrator_max;
float _max_rate_pos;
float _max_rate_neg;
@@ -109,7 +129,7 @@ private:
float _integrator;
float _rate_error;
float _rate_setpoint;
- float _max_deflection_rad;
+ float _bodyrate_setpoint;
};
#endif // ECL_PITCH_CONTROLLER_H
diff --git a/src/lib/ecl/attitude_fw/ecl_roll_controller.cpp b/src/lib/ecl/attitude_fw/ecl_roll_controller.cpp
index 0b1ffa7a4..bd6c9da71 100644
--- a/src/lib/ecl/attitude_fw/ecl_roll_controller.cpp
+++ b/src/lib/ecl/attitude_fw/ecl_roll_controller.cpp
@@ -45,21 +45,47 @@
#include <geo/geo.h>
#include <ecl/ecl.h>
#include <mathlib/mathlib.h>
+#include <systemlib/err.h>
ECL_RollController::ECL_RollController() :
_last_run(0),
_tc(0.1f),
+ _k_p(0.0f),
+ _k_i(0.0f),
+ _k_d(0.0f),
+ _k_ff(0.0f),
+ _integrator_max(0.0f),
+ _max_rate(0.0f),
_last_output(0.0f),
_integrator(0.0f),
_rate_error(0.0f),
_rate_setpoint(0.0f),
- _max_deflection_rad(math::radians(45.0f))
+ _bodyrate_setpoint(0.0f)
{
+}
+
+float ECL_RollController::control_attitude(float roll_setpoint, float roll)
+{
+
+ /* Calculate error */
+ float roll_error = roll_setpoint - roll;
+
+ /* Apply P controller */
+ _rate_setpoint = roll_error / _tc;
+
+ /* limit the rate */ //XXX: move to body angluar rates
+ if (_max_rate > 0.01f) {
+ _rate_setpoint = (_rate_setpoint > _max_rate) ? _max_rate : _rate_setpoint;
+ _rate_setpoint = (_rate_setpoint < -_max_rate) ? -_max_rate : _rate_setpoint;
+ }
+ return _rate_setpoint;
}
-float ECL_RollController::control(float roll_setpoint, float roll, float roll_rate,
- float scaler, bool lock_integrator, float airspeed_min, float airspeed_max, float airspeed)
+float ECL_RollController::control_bodyrate(float pitch,
+ float roll_rate, float yaw_rate,
+ float yaw_rate_setpoint,
+ float airspeed_min, float airspeed_max, float airspeed, float scaler, bool lock_integrator)
{
/* get the usual dt estimate */
uint64_t dt_micros = ecl_elapsed_time(&_last_run);
@@ -70,10 +96,11 @@ float ECL_RollController::control(float roll_setpoint, float roll, float roll_ra
if (dt_micros > 500000)
lock_integrator = true;
- float k_ff = math::max((_k_p - _k_i * _tc) * _tc - _k_d, 0.0f);
- float k_i_rate = _k_i * _tc;
+// float k_ff = math::max((_k_p - _k_i * _tc) * _tc - _k_d, 0.0f);
+ float k_ff = 0; //xxx: param
/* input conditioning */
+// warnx("airspeed pre %.4f", (double)airspeed);
if (!isfinite(airspeed)) {
/* airspeed is NaN, +- INF or not available, pick center of band */
airspeed = 0.5f * (airspeed_min + airspeed_max);
@@ -81,32 +108,27 @@ float ECL_RollController::control(float roll_setpoint, float roll, float roll_ra
airspeed = airspeed_min;
}
- float roll_error = roll_setpoint - roll;
- _rate_setpoint = roll_error / _tc;
-
- /* limit the rate */
- if (_max_rate > 0.01f) {
- _rate_setpoint = (_rate_setpoint > _max_rate) ? _max_rate : _rate_setpoint;
- _rate_setpoint = (_rate_setpoint < -_max_rate) ? -_max_rate : _rate_setpoint;
- }
- _rate_error = _rate_setpoint - roll_rate;
+ /* Transform setpoint to body angular rates */
+ _bodyrate_setpoint = _rate_setpoint - sinf(pitch) * yaw_rate_setpoint; //jacobian
+ /* Transform estimation to body angular rates */
+ float roll_bodyrate = roll_rate - sinf(pitch) * yaw_rate; //jacobian
- float ilimit_scaled = _integrator_max * scaler;
+ /* Calculate body angular rate error */
+ _rate_error = _bodyrate_setpoint - roll_bodyrate; //body angular rate error
- if (!lock_integrator && k_i_rate > 0.0f && airspeed > 0.5f * airspeed_min) {
+ if (!lock_integrator && _k_i > 0.0f && airspeed > 0.5f * airspeed_min) {
- float id = _rate_error * k_i_rate * dt * scaler;
+ float id = _rate_error * dt;
/*
- * anti-windup: do not allow integrator to increase into the
- * wrong direction if actuator is at limit
+ * anti-windup: do not allow integrator to increase if actuator is at limit
*/
- if (_last_output < -_max_deflection_rad) {
+ if (_last_output < -1.0f) {
/* only allow motion to center: increase value */
id = math::max(id, 0.0f);
- } else if (_last_output > _max_deflection_rad) {
+ } else if (_last_output > 1.0f) {
/* only allow motion to center: decrease value */
id = math::min(id, 0.0f);
}
@@ -115,11 +137,14 @@ float ECL_RollController::control(float roll_setpoint, float roll, float roll_ra
}
/* integrator limit */
- _integrator = math::constrain(_integrator, -ilimit_scaled, ilimit_scaled);
- /* store non-limited output */
- _last_output = ((_rate_error * _k_d * scaler) + _integrator + (_rate_setpoint * k_ff)) * scaler;
+ //xxx: until start detection is available: integral part in control signal is limited here
+ float integrator_constrained = math::constrain(_integrator * _k_i, -_integrator_max, _integrator_max);
+ //warnx("roll: _integrator: %.4f, _integrator_max: %.4f", (double)_integrator, (double)_integrator_max);
+
+ /* Apply PI rate controller and store non-limited output */
+ _last_output = (_bodyrate_setpoint * _k_ff + _rate_error * _k_p + integrator_constrained + _rate_setpoint * k_ff) * scaler * scaler; //scaler is proportional to 1/airspeed
- return math::constrain(_last_output, -_max_deflection_rad, _max_deflection_rad);
+ return math::constrain(_last_output, -1.0f, 1.0f);
}
void ECL_RollController::reset_integrator()
diff --git a/src/lib/ecl/attitude_fw/ecl_roll_controller.h b/src/lib/ecl/attitude_fw/ecl_roll_controller.h
index 0d4ea9333..efc7b8944 100644
--- a/src/lib/ecl/attitude_fw/ecl_roll_controller.h
+++ b/src/lib/ecl/attitude_fw/ecl_roll_controller.h
@@ -36,6 +36,7 @@
* Definition of a simple orthogonal roll PID controller.
*
* @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Thomas Gubler <thomasgubler@gmail.com>
*
* Acknowledgements:
*
@@ -51,13 +52,17 @@
#include <stdbool.h>
#include <stdint.h>
-class __EXPORT ECL_RollController
+class __EXPORT ECL_RollController //XXX: create controller superclass
{
public:
ECL_RollController();
- float control(float roll_setpoint, float roll, float roll_rate,
- float scaler = 1.0f, bool lock_integrator = false, float airspeed_min = 0.0f, float airspeed_max = 0.0f, float airspeed = (0.0f / 0.0f));
+ float control_attitude(float roll_setpoint, float roll);
+
+ float control_bodyrate(float pitch,
+ float roll_rate, float yaw_rate,
+ float yaw_rate_setpoint,
+ float airspeed_min = 0.0f, float airspeed_max = 0.0f, float airspeed = (0.0f / 0.0f), float scaler = 1.0f, bool lock_integrator = false);
void reset_integrator();
@@ -66,18 +71,27 @@ public:
_tc = time_constant;
}
}
+
void set_k_p(float k_p) {
_k_p = k_p;
}
+
void set_k_i(float k_i) {
_k_i = k_i;
}
+
void set_k_d(float k_d) {
_k_d = k_d;
}
+
+ void set_k_ff(float k_ff) {
+ _k_ff = k_ff;
+ }
+
void set_integrator_max(float max) {
_integrator_max = max;
}
+
void set_max_rate(float max_rate) {
_max_rate = max_rate;
}
@@ -90,19 +104,24 @@ public:
return _rate_setpoint;
}
+ float get_desired_bodyrate() {
+ return _bodyrate_setpoint;
+ }
+
private:
uint64_t _last_run;
float _tc;
float _k_p;
float _k_i;
float _k_d;
+ float _k_ff;
float _integrator_max;
float _max_rate;
float _last_output;
float _integrator;
float _rate_error;
float _rate_setpoint;
- float _max_deflection_rad;
+ float _bodyrate_setpoint;
};
#endif // ECL_ROLL_CONTROLLER_H
diff --git a/src/lib/ecl/attitude_fw/ecl_yaw_controller.cpp b/src/lib/ecl/attitude_fw/ecl_yaw_controller.cpp
index b786acf24..7c366aaf2 100644
--- a/src/lib/ecl/attitude_fw/ecl_yaw_controller.cpp
+++ b/src/lib/ecl/attitude_fw/ecl_yaw_controller.cpp
@@ -44,29 +44,127 @@
#include <geo/geo.h>
#include <ecl/ecl.h>
#include <mathlib/mathlib.h>
+#include <systemlib/err.h>
ECL_YawController::ECL_YawController() :
_last_run(0),
- _last_error(0.0f),
+ _k_p(0.0f),
+ _k_i(0.0f),
+ _k_d(0.0f),
+ _k_ff(0.0f),
+ _integrator_max(0.0f),
+ _max_rate(0.0f),
+ _roll_ff(0.0f),
_last_output(0.0f),
- _last_rate_hp_out(0.0f),
- _last_rate_hp_in(0.0f),
- _k_d_last(0.0f),
- _integrator(0.0f)
+ _integrator(0.0f),
+ _rate_error(0.0f),
+ _rate_setpoint(0.0f),
+ _bodyrate_setpoint(0.0f),
+ _coordinated_min_speed(1.0f)
{
+}
+
+float ECL_YawController::control_attitude(float roll, float pitch,
+ float speed_body_u, float speed_body_v, float speed_body_w,
+ float roll_rate_setpoint, float pitch_rate_setpoint)
+{
+// static int counter = 0;
+ /* Calculate desired yaw rate from coordinated turn constraint / (no side forces) */
+ _rate_setpoint = 0.0f;
+ if (sqrtf(speed_body_u * speed_body_u + speed_body_v * speed_body_v + speed_body_w * speed_body_w) > _coordinated_min_speed) {
+ float denumerator = (speed_body_u * cosf(roll) * cosf(pitch) + speed_body_w * sinf(pitch));
+ if(denumerator != 0.0f) { //XXX: floating point comparison
+ _rate_setpoint = (speed_body_w * roll_rate_setpoint + 9.81f * sinf(roll) * cosf(pitch) + speed_body_u * pitch_rate_setpoint * sinf(roll)) / denumerator;
+// warnx("yaw: speed_body_u %.f speed_body_w %1.f roll %.1f pitch %.1f denumerator %.1f _rate_setpoint %.1f", speed_body_u, speed_body_w, denumerator, _rate_setpoint);
+ }
+
+// if(counter % 20 == 0) {
+// warnx("denumerator: %.4f, speed_body_u: %.4f, speed_body_w: %.4f, cosf(roll): %.4f, cosf(pitch): %.4f, sinf(pitch): %.4f", (double)denumerator, (double)speed_body_u, (double)speed_body_w, (double)cosf(roll), (double)cosf(pitch), (double)sinf(pitch));
+// }
+ }
+
+ /* limit the rate */ //XXX: move to body angluar rates
+ if (_max_rate > 0.01f) {
+ _rate_setpoint = (_rate_setpoint > _max_rate) ? _max_rate : _rate_setpoint;
+ _rate_setpoint = (_rate_setpoint < -_max_rate) ? -_max_rate : _rate_setpoint;
+ }
+
+// counter++;
+
+ if(!isfinite(_rate_setpoint)){
+ warnx("yaw rate sepoint not finite");
+ _rate_setpoint = 0.0f;
+ }
+
+ return _rate_setpoint;
}
-float ECL_YawController::control(float roll, float yaw_rate, float accel_y, float scaler, bool lock_integrator,
- float airspeed_min, float airspeed_max, float aspeed)
+float ECL_YawController::control_bodyrate(float roll, float pitch,
+ float pitch_rate, float yaw_rate,
+ float pitch_rate_setpoint,
+ float airspeed_min, float airspeed_max, float airspeed, float scaler, bool lock_integrator)
{
/* get the usual dt estimate */
uint64_t dt_micros = ecl_elapsed_time(&_last_run);
_last_run = ecl_absolute_time();
+ float dt = (float)dt_micros * 1e-6f;
+
+ /* lock integral for long intervals */
+ if (dt_micros > 500000)
+ lock_integrator = true;
+
+
+// float k_ff = math::max((_k_p - _k_i * _tc) * _tc - _k_d, 0.0f);
+ float k_ff = 0;
+
+
+ /* input conditioning */
+ if (!isfinite(airspeed)) {
+ /* airspeed is NaN, +- INF or not available, pick center of band */
+ airspeed = 0.5f * (airspeed_min + airspeed_max);
+ } else if (airspeed < airspeed_min) {
+ airspeed = airspeed_min;
+ }
+
+
+ /* Transform setpoint to body angular rates */
+ _bodyrate_setpoint = -sinf(roll) * pitch_rate_setpoint + cosf(roll)*cosf(pitch) * _rate_setpoint; //jacobian
+
+ /* Transform estimation to body angular rates */
+ float yaw_bodyrate = -sinf(roll) * pitch_rate + cosf(roll)*cosf(pitch) * yaw_rate; //jacobian
+
+ /* Calculate body angular rate error */
+ _rate_error = _bodyrate_setpoint - yaw_bodyrate; //body angular rate error
+
+ if (!lock_integrator && _k_i > 0.0f && airspeed > 0.5f * airspeed_min) {
+
+ float id = _rate_error * dt;
+
+ /*
+ * anti-windup: do not allow integrator to increase if actuator is at limit
+ */
+ if (_last_output < -1.0f) {
+ /* only allow motion to center: increase value */
+ id = math::max(id, 0.0f);
+ } else if (_last_output > 1.0f) {
+ /* only allow motion to center: decrease value */
+ id = math::min(id, 0.0f);
+ }
+
+ _integrator += id;
+ }
+
+ /* integrator limit */
+ //xxx: until start detection is available: integral part in control signal is limited here
+ float integrator_constrained = math::constrain(_integrator * _k_i, -_integrator_max, _integrator_max);
+
+ /* Apply PI rate controller and store non-limited output */
+ _last_output = (_bodyrate_setpoint * _k_ff + _rate_error * _k_p + integrator_constrained + _rate_setpoint * k_ff) * scaler * scaler; //scaler is proportional to 1/airspeed
+ //warnx("yaw:_last_output: %.4f, _integrator: %.4f, _integrator_max: %.4f, airspeed %.4f, _k_i %.4f, _k_p: %.4f", (double)_last_output, (double)_integrator, (double)_integrator_max, (double)airspeed, (double)_k_i, (double)_k_p);
- float dt = (dt_micros > 500000) ? 0.0f : dt_micros / 1000000;
- return 0.0f;
+ return math::constrain(_last_output, -1.0f, 1.0f);
}
void ECL_YawController::reset_integrator()
diff --git a/src/lib/ecl/attitude_fw/ecl_yaw_controller.h b/src/lib/ecl/attitude_fw/ecl_yaw_controller.h
index 66b227918..f15645fcf 100644
--- a/src/lib/ecl/attitude_fw/ecl_yaw_controller.h
+++ b/src/lib/ecl/attitude_fw/ecl_yaw_controller.h
@@ -35,6 +35,15 @@
* @file ecl_yaw_controller.h
* Definition of a simple orthogonal coordinated turn yaw PID controller.
*
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Thomas Gubler <thomasgubler@gmail.com>
+ *
+ * Acknowledgements:
+ *
+ * The control design is based on a design
+ * by Paul Riseborough and Andrew Tridgell, 2013,
+ * which in turn is based on initial work of
+ * Jonathan Challinger, 2012.
*/
#ifndef ECL_YAW_CONTROLLER_H
#define ECL_YAW_CONTROLLER_H
@@ -42,47 +51,82 @@
#include <stdbool.h>
#include <stdint.h>
-class __EXPORT ECL_YawController
+class __EXPORT ECL_YawController //XXX: create controller superclass
{
public:
ECL_YawController();
- float control(float roll, float yaw_rate, float accel_y, float scaler = 1.0f, bool lock_integrator = false,
- float airspeed_min = 0, float airspeed_max = 0, float aspeed = (0.0f / 0.0f));
+ float control_attitude(float roll, float pitch,
+ float speed_body_u, float speed_body_v, float speed_body_w,
+ float roll_rate_setpoint, float pitch_rate_setpoint);
+
+ float control_bodyrate( float roll, float pitch,
+ float pitch_rate, float yaw_rate,
+ float pitch_rate_setpoint,
+ float airspeed_min, float airspeed_max, float airspeed, float scaler, bool lock_integrator);
void reset_integrator();
- void set_k_side(float k_a) {
- _k_side = k_a;
+ void set_k_p(float k_p) {
+ _k_p = k_p;
}
+
void set_k_i(float k_i) {
_k_i = k_i;
}
+
void set_k_d(float k_d) {
_k_d = k_d;
}
- void set_k_roll_ff(float k_roll_ff) {
- _k_roll_ff = k_roll_ff;
+
+ void set_k_ff(float k_ff) {
+ _k_ff = k_ff;
}
+
void set_integrator_max(float max) {
_integrator_max = max;
}
+ void set_max_rate(float max_rate) {
+ _max_rate = max_rate;
+ }
+
+ void set_k_roll_ff(float roll_ff) {
+ _roll_ff = roll_ff;
+ }
+
+ void set_coordinated_min_speed(float coordinated_min_speed) {
+ _coordinated_min_speed = coordinated_min_speed;
+ }
+
+
+ float get_rate_error() {
+ return _rate_error;
+ }
+
+ float get_desired_rate() {
+ return _rate_setpoint;
+ }
+
+ float get_desired_bodyrate() {
+ return _bodyrate_setpoint;
+ }
+
private:
uint64_t _last_run;
-
- float _k_side;
+ float _k_p;
float _k_i;
float _k_d;
- float _k_roll_ff;
+ float _k_ff;
float _integrator_max;
-
- float _last_error;
+ float _max_rate;
+ float _roll_ff;
float _last_output;
- float _last_rate_hp_out;
- float _last_rate_hp_in;
- float _k_d_last;
float _integrator;
+ float _rate_error;
+ float _rate_setpoint;
+ float _bodyrate_setpoint;
+ float _coordinated_min_speed;
};
diff --git a/src/lib/ecl/l1/ecl_l1_pos_controller.cpp b/src/lib/ecl/l1/ecl_l1_pos_controller.cpp
index 27d76f959..11def2371 100644
--- a/src/lib/ecl/l1/ecl_l1_pos_controller.cpp
+++ b/src/lib/ecl/l1/ecl_l1_pos_controller.cpp
@@ -70,7 +70,7 @@ float ECL_L1_Pos_Controller::target_bearing()
float ECL_L1_Pos_Controller::switch_distance(float wp_radius)
{
/* following [2], switching on L1 distance */
- return math::max(wp_radius, _L1_distance);
+ return math::min(wp_radius, _L1_distance);
}
bool ECL_L1_Pos_Controller::reached_loiter_target(void)
@@ -280,7 +280,7 @@ void ECL_L1_Pos_Controller::navigate_loiter(const math::Vector2f &vector_A, cons
*/
// XXX check switch over
- if ((lateral_accel_sp_center < lateral_accel_sp_circle && loiter_direction > 0 && xtrack_err_circle > 0.0f) |
+ if ((lateral_accel_sp_center < lateral_accel_sp_circle && loiter_direction > 0 && xtrack_err_circle > 0.0f) ||
(lateral_accel_sp_center > lateral_accel_sp_circle && loiter_direction < 0 && xtrack_err_circle > 0.0f)) {
_lateral_accel = lateral_accel_sp_center;
_circle_mode = false;
diff --git a/src/lib/external_lgpl/tecs/tecs.cpp b/src/lib/external_lgpl/tecs/tecs.cpp
index a733ef1d2..d089be080 100644
--- a/src/lib/external_lgpl/tecs/tecs.cpp
+++ b/src/lib/external_lgpl/tecs/tecs.cpp
@@ -2,6 +2,7 @@
#include "tecs.h"
#include <ecl/ecl.h>
+#include <systemlib/err.h>
using namespace math;
@@ -168,64 +169,88 @@ void TECS::_update_speed_demand(void)
// calculate velocity rate limits based on physical performance limits
// provision to use a different rate limit if bad descent or underspeed condition exists
// Use 50% of maximum energy rate to allow margin for total energy contgroller
- float velRateMax;
- float velRateMin;
-
- if ((_badDescent) || (_underspeed)) {
- velRateMax = 0.5f * _STEdot_max / _integ5_state;
- velRateMin = 0.5f * _STEdot_min / _integ5_state;
-
- } else {
- velRateMax = 0.5f * _STEdot_max / _integ5_state;
- velRateMin = 0.5f * _STEdot_min / _integ5_state;
- }
-
- // Apply rate limit
- if ((_TAS_dem - _TAS_dem_adj) > (velRateMax * 0.1f)) {
- _TAS_dem_adj = _TAS_dem_adj + velRateMax * 0.1f;
- _TAS_rate_dem = velRateMax;
-
- } else if ((_TAS_dem - _TAS_dem_adj) < (velRateMin * 0.1f)) {
- _TAS_dem_adj = _TAS_dem_adj + velRateMin * 0.1f;
- _TAS_rate_dem = velRateMin;
-
- } else {
- _TAS_dem_adj = _TAS_dem;
- _TAS_rate_dem = (_TAS_dem - _TAS_dem_last) / 0.1f;
- }
+// float velRateMax;
+// float velRateMin;
+//
+// if ((_badDescent) || (_underspeed)) {
+// velRateMax = 0.5f * _STEdot_max / _integ5_state;
+// velRateMin = 0.5f * _STEdot_min / _integ5_state;
+//
+// } else {
+// velRateMax = 0.5f * _STEdot_max / _integ5_state;
+// velRateMin = 0.5f * _STEdot_min / _integ5_state;
+// }
+//
+// // Apply rate limit
+// if ((_TAS_dem - _TAS_dem_adj) > (velRateMax * 0.1f)) {
+// _TAS_dem_adj = _TAS_dem_adj + velRateMax * 0.1f;
+// _TAS_rate_dem = velRateMax;
+//
+// } else if ((_TAS_dem - _TAS_dem_adj) < (velRateMin * 0.1f)) {
+// _TAS_dem_adj = _TAS_dem_adj + velRateMin * 0.1f;
+// _TAS_rate_dem = velRateMin;
+//
+// } else {
+// _TAS_dem_adj = _TAS_dem;
+//
+//
+// _TAS_rate_dem = (_TAS_dem - _TAS_dem_last) / 0.1f;
+// }
+
+ _TAS_dem_adj = _TAS_dem;
+ _TAS_rate_dem = (_TAS_dem_adj-_integ5_state)*_speedrate_p; //xxx: using a p loop for now
// Constrain speed demand again to protect against bad values on initialisation.
_TAS_dem_adj = constrain(_TAS_dem_adj, _TASmin, _TASmax);
- _TAS_dem_last = _TAS_dem;
+// _TAS_dem_last = _TAS_dem;
+
+// warnx("_TAS_rate_dem: %.1f, _TAS_dem_adj %.1f, _integ5_state %.1f, _badDescent %u , _underspeed %u, velRateMin %.1f",
+// (double)_TAS_rate_dem, (double)_TAS_dem_adj, (double)_integ5_state, _badDescent, _underspeed, velRateMin);
+// warnx("_TAS_rate_dem: %.1f, _TAS_dem_adj %.1f, _integ5_state %.1f, _badDescent %u , _underspeed %u",
+// (double)_TAS_rate_dem, (double)_TAS_dem_adj, (double)_integ5_state, _badDescent , _underspeed);
}
-void TECS::_update_height_demand(float demand)
+void TECS::_update_height_demand(float demand, float state)
{
- // Apply 2 point moving average to demanded height
- // This is required because height demand is only updated at 5Hz
- _hgt_dem = 0.5f * (demand + _hgt_dem_in_old);
- _hgt_dem_in_old = _hgt_dem;
-
- // printf("hgt_dem: %6.2f hgt_dem_last: %6.2f max_climb_rate: %6.2f\n", _hgt_dem, _hgt_dem_prev,
- // _maxClimbRate);
+// // Apply 2 point moving average to demanded height
+// // This is required because height demand is only updated at 5Hz
+// _hgt_dem = 0.5f * (demand + _hgt_dem_in_old);
+// _hgt_dem_in_old = _hgt_dem;
+//
+// // printf("hgt_dem: %6.2f hgt_dem_last: %6.2f max_climb_rate: %6.2f\n", _hgt_dem, _hgt_dem_prev,
+// // _maxClimbRate);
+//
+// // Limit height rate of change
+// if ((_hgt_dem - _hgt_dem_prev) > (_maxClimbRate * 0.1f)) {
+// _hgt_dem = _hgt_dem_prev + _maxClimbRate * 0.1f;
+//
+// } else if ((_hgt_dem - _hgt_dem_prev) < (-_maxSinkRate * 0.1f)) {
+// _hgt_dem = _hgt_dem_prev - _maxSinkRate * 0.1f;
+// }
+//
+// _hgt_dem_prev = _hgt_dem;
+//
+// // Apply first order lag to height demand
+// _hgt_dem_adj = 0.05f * _hgt_dem + 0.95f * _hgt_dem_adj_last;
+// _hgt_rate_dem = (_hgt_dem_adj - _hgt_dem_adj_last) / 0.1f;
+// _hgt_dem_adj_last = _hgt_dem_adj;
+//
+// // printf("hgt_dem: %6.2f hgt_dem_adj: %6.2f hgt_dem_last: %6.2f hgt_rate_dem: %6.2f\n", _hgt_dem, _hgt_dem_adj, _hgt_dem_adj_last,
+// // _hgt_rate_dem);
+
+ _hgt_dem_adj = demand;//0.025f * demand + 0.975f * _hgt_dem_adj_last;
+ _hgt_dem_adj_last = _hgt_dem_adj;
+ _hgt_rate_dem = (_hgt_dem_adj-state)*_heightrate_p;
// Limit height rate of change
- if ((_hgt_dem - _hgt_dem_prev) > (_maxClimbRate * 0.1f)) {
- _hgt_dem = _hgt_dem_prev + _maxClimbRate * 0.1f;
+ if (_hgt_rate_dem > _maxClimbRate) {
+ _hgt_rate_dem = _maxClimbRate;
- } else if ((_hgt_dem - _hgt_dem_prev) < (-_maxSinkRate * 0.1f)) {
- _hgt_dem = _hgt_dem_prev - _maxSinkRate * 0.1f;
+ } else if (_hgt_rate_dem < -_maxSinkRate) {
+ _hgt_rate_dem = -_maxSinkRate;
}
- _hgt_dem_prev = _hgt_dem;
-
- // Apply first order lag to height demand
- _hgt_dem_adj = 0.05f * _hgt_dem + 0.95f * _hgt_dem_adj_last;
- _hgt_rate_dem = (_hgt_dem_adj - _hgt_dem_adj_last) / 0.1f;
- _hgt_dem_adj_last = _hgt_dem_adj;
-
- // printf("hgt_dem: %6.2f hgt_dem_adj: %6.2f hgt_dem_last: %6.2f hgt_rate_dem: %6.2f\n", _hgt_dem, _hgt_dem_adj, _hgt_dem_adj_last,
- // _hgt_rate_dem);
+ //warnx("_hgt_rate_dem: %.4f, _hgt_dem_adj %.4f", _hgt_rate_dem, _hgt_dem_adj);
}
void TECS::_detect_underspeed(void)
@@ -285,7 +310,7 @@ void TECS::_update_throttle(float throttle_cruise, const math::Dcm &rotMat)
// additional component which scales with (1/cos(bank angle) - 1) to compensate for induced
// drag increase during turns.
float cosPhi = sqrtf((rotMat(0, 1) * rotMat(0, 1)) + (rotMat(1, 1) * rotMat(1, 1)));
- STEdot_dem = STEdot_dem + _rollComp * (1.0f / constrain(cosPhi * cosPhi , 0.1f, 1.0f) - 1.0f);
+ STEdot_dem = STEdot_dem + _rollComp * (1.0f / constrain(cosPhi , 0.1f, 1.0f) - 1.0f);
if (STEdot_dem >= 0) {
ff_throttle = nomThr + STEdot_dem / _STEdot_max * (1.0f - nomThr);
@@ -353,14 +378,18 @@ void TECS::_detect_bad_descent(void)
// 1) Underspeed protection not active
// 2) Specific total energy error > 0
// This mode will produce an undulating speed and height response as it cuts in and out but will prevent the aircraft from descending into the ground if an unachievable speed demand is set
- float STEdot = _SPEdot + _SKEdot;
-
- if ((!_underspeed && (_STE_error > 200.0f) && (STEdot < 0.0f) && (_throttle_dem >= _THRmaxf * 0.9f)) || (_badDescent && !_underspeed && (_STE_error > 0.0f))) {
- _badDescent = true;
-
- } else {
- _badDescent = false;
- }
+// float STEdot = _SPEdot + _SKEdot;
+//
+// if ((!_underspeed && (_STE_error > 200.0f) && (STEdot < 0.0f) && (_throttle_dem >= _THRmaxf * 0.9f)) || (_badDescent && !_underspeed && (_STE_error > 0.0f))) {
+//
+// warnx("bad descent detected: _STE_error %.1f, STEdot %.1f, _throttle_dem %.1f", _STE_error, STEdot, _throttle_dem);
+// _badDescent = true;
+//
+// } else {
+// _badDescent = false;
+// }
+
+ _badDescent = false;
}
void TECS::_update_pitch(void)
@@ -500,7 +529,7 @@ void TECS::update_pitch_throttle(const math::Dcm &rotMat, float pitch, float bar
_update_speed_demand();
// Calculate the height demand
- _update_height_demand(hgt_dem);
+ _update_height_demand(hgt_dem, baro_altitude);
// Detect underspeed condition
_detect_underspeed();
diff --git a/src/lib/external_lgpl/tecs/tecs.h b/src/lib/external_lgpl/tecs/tecs.h
index f8f832ed7..4fc009da9 100644
--- a/src/lib/external_lgpl/tecs/tecs.h
+++ b/src/lib/external_lgpl/tecs/tecs.h
@@ -180,6 +180,14 @@ public:
_indicated_airspeed_max = airspeed;
}
+ void set_heightrate_p(float heightrate_p) {
+ _heightrate_p = heightrate_p;
+ }
+
+ void set_speedrate_p(float speedrate_p) {
+ _speedrate_p = speedrate_p;
+ }
+
private:
// Last time update_50Hz was called
uint64_t _update_50hz_last_usec;
@@ -203,6 +211,8 @@ private:
float _vertAccLim;
float _rollComp;
float _spdWeight;
+ float _heightrate_p;
+ float _speedrate_p;
// throttle demand in the range from 0.0 to 1.0
float _throttle_dem;
@@ -329,7 +339,7 @@ private:
void _update_speed_demand(void);
// Update the demanded height
- void _update_height_demand(float demand);
+ void _update_height_demand(float demand, float state);
// Detect an underspeed condition
void _detect_underspeed(void);
diff --git a/src/lib/geo/geo.c b/src/lib/geo/geo.c
index 43105fdba..85b17f9ae 100644
--- a/src/lib/geo/geo.c
+++ b/src/lib/geo/geo.c
@@ -387,6 +387,45 @@ __EXPORT int get_distance_to_arc(struct crosstrack_error_s * crosstrack_error, d
return return_value;
}
+__EXPORT float get_distance_to_point_global_wgs84(double lat_now, double lon_now, float alt_now,
+ double lat_next, double lon_next, float alt_next,
+ float *dist_xy, float *dist_z)
+{
+ double current_x_rad = lat_next / 180.0 * M_PI;
+ double current_y_rad = lon_next / 180.0 * M_PI;
+ double x_rad = lat_now / 180.0 * M_PI;
+ double y_rad = lon_now / 180.0 * M_PI;
+
+ double d_lat = x_rad - current_x_rad;
+ double d_lon = y_rad - current_y_rad;
+
+ double a = sin(d_lat / 2.0) * sin(d_lat / 2.0) + sin(d_lon / 2.0) * sin(d_lon / 2.0f) * cos(current_x_rad) * cos(x_rad);
+ double c = 2 * atan2(sqrt(a), sqrt(1 - a));
+
+ float dxy = CONSTANTS_RADIUS_OF_EARTH * c;
+ float dz = alt_now - alt_next;
+
+ *dist_xy = fabsf(dxy);
+ *dist_z = fabsf(dz);
+
+ return sqrtf(dxy * dxy + dz * dz);
+}
+
+
+__EXPORT float mavlink_wpm_distance_to_point_local(float x_now, float y_now, float z_now,
+ float x_next, float y_next, float z_next,
+ float *dist_xy, float *dist_z)
+{
+ float dx = x_now - x_next;
+ float dy = y_now - y_next;
+ float dz = z_now - z_next;
+
+ *dist_xy = sqrtf(dx * dx + dy * dy);
+ *dist_z = fabsf(dz);
+
+ return sqrtf(dx * dx + dy * dy + dz * dz);
+}
+
__EXPORT float _wrap_pi(float bearing)
{
/* value is inf or NaN */
@@ -465,4 +504,26 @@ __EXPORT float _wrap_360(float bearing)
return bearing;
}
+__EXPORT bool inside_geofence(const struct vehicle_global_position_s *vehicle, const struct fence_s *fence)
+{
+
+ /* Adaptation of algorithm originally presented as
+ * PNPOLY - Point Inclusion in Polygon Test
+ * W. Randolph Franklin (WRF) */
+
+ unsigned int i, j, vertices = fence->count;
+ bool c = false;
+ double lat = vehicle->lat / 1e7;
+ double lon = vehicle->lon / 1e7;
+
+ // skip vertex 0 (return point)
+ for (i = 0, j = vertices - 1; i < vertices; j = i++)
+ if (((fence->vertices[i].lon) >= lon != (fence->vertices[j].lon >= lon)) &&
+ (lat <= (fence->vertices[j].lat - fence->vertices[i].lat) * (lon - fence->vertices[i].lon) /
+ (fence->vertices[j].lon - fence->vertices[i].lon) + fence->vertices[i].lat))
+ c = !c;
+ return c;
+}
+
+
diff --git a/src/lib/geo/geo.h b/src/lib/geo/geo.h
index 123ff80f1..5f92e14cf 100644
--- a/src/lib/geo/geo.h
+++ b/src/lib/geo/geo.h
@@ -47,6 +47,9 @@
#pragma once
+#include "uORB/topics/fence.h"
+#include "uORB/topics/vehicle_global_position.h"
+
__BEGIN_DECLS
#include <stdbool.h>
@@ -121,9 +124,34 @@ __EXPORT int get_distance_to_line(struct crosstrack_error_s * crosstrack_error,
__EXPORT int get_distance_to_arc(struct crosstrack_error_s * crosstrack_error, double lat_now, double lon_now, double lat_center, double lon_center,
float radius, float arc_start_bearing, float arc_sweep);
+/*
+ * Calculate distance in global frame
+ */
+__EXPORT float get_distance_to_point_global_wgs84(double lat_now, double lon_now, float alt_now,
+ double lat_next, double lon_next, float alt_next,
+ float *dist_xy, float *dist_z);
+
+/*
+ * Calculate distance in local frame (NED)
+ */
+__EXPORT float mavlink_wpm_distance_to_point_local(float x_now, float y_now, float z_now,
+ float x_next, float y_next, float z_next,
+ float *dist_xy, float *dist_z);
+
__EXPORT float _wrap_180(float bearing);
__EXPORT float _wrap_360(float bearing);
__EXPORT float _wrap_pi(float bearing);
__EXPORT float _wrap_2pi(float bearing);
+/**
+ * Return whether craft is inside geofence.
+ *
+ * Calculate whether point is inside arbitrary polygon
+ * @param craft pointer craft coordinates
+ * @param fence pointer to array of coordinates, one per vertex. First and last vertex are assumed connected
+ * @return true: craft is inside fence, false:craft is outside fence
+ */
+__EXPORT bool inside_geofence(const struct vehicle_global_position_s *craft, const struct fence_s *fence);
+
+
__END_DECLS
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index dfd4d2f73..40562a4e1 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -509,6 +509,21 @@ void handle_command(struct vehicle_status_s *status, const struct safety_s *safe
}
break;
+ /* Flight termination */
+ case VEHICLE_CMD_DO_SET_SERVO: { //xxx: needs its own mavlink command
+
+ if (armed->armed && cmd->param3 > 0.5) { //xxx: for safety only for now, param3 is unused by VEHICLE_CMD_DO_SET_SERVO
+ transition_result_t flighttermination_res = flighttermination_state_transition(status, FLIGHTTERMINATION_STATE_ON, control_mode);
+ result = VEHICLE_CMD_RESULT_ACCEPTED;
+
+ } else {
+ /* reject parachute depoyment not armed */
+ result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
+ }
+
+ }
+ break;
+
default:
break;
}
@@ -1199,6 +1214,7 @@ int commander_thread_main(int argc, char *argv[])
bool arming_state_changed = check_arming_state_changed();
bool main_state_changed = check_main_state_changed();
bool navigation_state_changed = check_navigation_state_changed();
+ bool flighttermination_state_changed = check_flighttermination_state_changed();
hrt_abstime t1 = hrt_absolute_time();
@@ -1725,7 +1741,8 @@ void *commander_low_prio_loop(void *arg)
/* ignore commands the high-prio loop handles */
if (cmd.command == VEHICLE_CMD_DO_SET_MODE ||
cmd.command == VEHICLE_CMD_COMPONENT_ARM_DISARM ||
- cmd.command == VEHICLE_CMD_NAV_TAKEOFF)
+ cmd.command == VEHICLE_CMD_NAV_TAKEOFF ||
+ cmd.command == VEHICLE_CMD_DO_SET_SERVO)
continue;
/* only handle low-priority commands here */
diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp
index 490fc8fc6..6c21dfab0 100644
--- a/src/modules/commander/state_machine_helper.cpp
+++ b/src/modules/commander/state_machine_helper.cpp
@@ -65,6 +65,7 @@ static const int ERROR = -1;
static bool arming_state_changed = true;
static bool main_state_changed = true;
static bool navigation_state_changed = true;
+static bool flighttermination_state_changed = true;
transition_result_t
arming_state_transition(struct vehicle_status_s *status, const struct safety_s *safety,
@@ -239,8 +240,9 @@ main_state_transition(struct vehicle_status_s *current_state, main_state_t new_m
case MAIN_STATE_SEATBELT:
/* need at minimum altitude estimate */
- if (current_state->condition_local_altitude_valid ||
- current_state->condition_global_position_valid) {
+ if (!current_state->is_rotary_wing ||
+ (current_state->condition_local_altitude_valid ||
+ current_state->condition_global_position_valid)) {
ret = TRANSITION_CHANGED;
}
@@ -450,6 +452,18 @@ check_navigation_state_changed()
}
}
+bool
+check_flighttermination_state_changed()
+{
+ if (flighttermination_state_changed) {
+ flighttermination_state_changed = false;
+ return true;
+
+ } else {
+ return false;
+ }
+}
+
void
set_navigation_state_changed()
{
@@ -522,6 +536,44 @@ int hil_state_transition(hil_state_t new_state, int status_pub, struct vehicle_s
}
+/**
+* Transition from one flightermination state to another
+*/
+transition_result_t flighttermination_state_transition(struct vehicle_status_s *status, flighttermination_state_t new_flighttermination_state, struct vehicle_control_mode_s *control_mode)
+{
+ transition_result_t ret = TRANSITION_DENIED;
+
+ /* only check transition if the new state is actually different from the current one */
+ if (new_flighttermination_state == status->navigation_state) {
+ ret = TRANSITION_NOT_CHANGED;
+
+ } else {
+
+ switch (new_flighttermination_state) {
+ case FLIGHTTERMINATION_STATE_ON:
+ ret = TRANSITION_CHANGED;
+ status->flighttermination_state = FLIGHTTERMINATION_STATE_ON;
+ warnx("state machine helper: change to FLIGHTTERMINATION_STATE_ON");
+ break;
+ case FLIGHTTERMINATION_STATE_OFF:
+ ret = TRANSITION_CHANGED;
+ status->flighttermination_state = FLIGHTTERMINATION_STATE_OFF;
+ break;
+
+ default:
+ break;
+ }
+
+ if (ret == TRANSITION_CHANGED) {
+ flighttermination_state_changed = true;
+ control_mode->flag_control_flighttermination_enabled = status->flighttermination_state == FLIGHTTERMINATION_STATE_ON;
+ }
+ }
+
+ return ret;
+}
+
+
// /*
// * Wrapper functions (to be used in the commander), all functions assume lock on current_status
diff --git a/src/modules/commander/state_machine_helper.h b/src/modules/commander/state_machine_helper.h
index 0bfdf36a8..e1ec9d4ad 100644
--- a/src/modules/commander/state_machine_helper.h
+++ b/src/modules/commander/state_machine_helper.h
@@ -70,8 +70,12 @@ bool check_main_state_changed();
transition_result_t navigation_state_transition(struct vehicle_status_s *status, navigation_state_t new_navigation_state, struct vehicle_control_mode_s *control_mode);
+transition_result_t flighttermination_state_transition(struct vehicle_status_s *status, flighttermination_state_t new_flighttermination_state, struct vehicle_control_mode_s *control_mode);
+
bool check_navigation_state_changed();
+bool check_flighttermination_state_changed();
+
void set_navigation_state_changed();
int hil_state_transition(hil_state_t new_state, int status_pub, struct vehicle_status_s *current_state, int control_mode_pub, struct vehicle_control_mode_s *current_control_mode, const int mavlink_fd);
diff --git a/src/modules/controllib/uorb/blocks.cpp b/src/modules/controllib/uorb/blocks.cpp
index 448a42a99..e213ac17f 100644
--- a/src/modules/controllib/uorb/blocks.cpp
+++ b/src/modules/controllib/uorb/blocks.cpp
@@ -54,26 +54,26 @@ BlockWaypointGuidance::~BlockWaypointGuidance() {};
void BlockWaypointGuidance::update(vehicle_global_position_s &pos,
vehicle_attitude_s &att,
- vehicle_global_position_setpoint_s &posCmd,
- vehicle_global_position_setpoint_s &lastPosCmd)
+ mission_item_s &missionCmd,
+ mission_item_s &lastMissionCmd)
{
// heading to waypoint
float psiTrack = get_bearing_to_next_waypoint(
(double)pos.lat / (double)1e7d,
(double)pos.lon / (double)1e7d,
- (double)posCmd.lat / (double)1e7d,
- (double)posCmd.lon / (double)1e7d);
+ missionCmd.lat,
+ missionCmd.lon);
// cross track
struct crosstrack_error_s xtrackError;
get_distance_to_line(&xtrackError,
(double)pos.lat / (double)1e7d,
(double)pos.lon / (double)1e7d,
- (double)lastPosCmd.lat / (double)1e7d,
- (double)lastPosCmd.lon / (double)1e7d,
- (double)posCmd.lat / (double)1e7d,
- (double)posCmd.lon / (double)1e7d);
+ lastMissionCmd.lat,
+ lastMissionCmd.lon,
+ missionCmd.lat,
+ missionCmd.lon);
_psiCmd = _wrap_2pi(psiTrack -
_xtYawLimit.update(_xt2Yaw.update(xtrackError.distance)));
@@ -86,7 +86,7 @@ BlockUorbEnabledAutopilot::BlockUorbEnabledAutopilot(SuperBlock *parent, const c
_attCmd(&getSubscriptions(), ORB_ID(vehicle_attitude_setpoint), 20),
_ratesCmd(&getSubscriptions(), ORB_ID(vehicle_rates_setpoint), 20),
_pos(&getSubscriptions() , ORB_ID(vehicle_global_position), 20),
- _posCmd(&getSubscriptions(), ORB_ID(vehicle_global_position_set_triplet), 20),
+ _missionCmd(&getSubscriptions(), ORB_ID(mission_item_triplet), 20),
_manual(&getSubscriptions(), ORB_ID(manual_control_setpoint), 20),
_status(&getSubscriptions(), ORB_ID(vehicle_status), 20),
_param_update(&getSubscriptions(), ORB_ID(parameter_update), 1000), // limit to 1 Hz
diff --git a/src/modules/controllib/uorb/blocks.hpp b/src/modules/controllib/uorb/blocks.hpp
index 46dc1bec2..335439fb7 100644
--- a/src/modules/controllib/uorb/blocks.hpp
+++ b/src/modules/controllib/uorb/blocks.hpp
@@ -43,7 +43,8 @@
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_rates_setpoint.h>
#include <uORB/topics/vehicle_global_position.h>
-#include <uORB/topics/vehicle_global_position_set_triplet.h>
+#include <uORB/topics/vehicle_global_position_setpoint.h>
+#include <uORB/topics/mission_item_triplet.h>
#include <uORB/topics/manual_control_setpoint.h>
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/actuator_controls.h>
@@ -82,8 +83,8 @@ public:
virtual ~BlockWaypointGuidance();
void update(vehicle_global_position_s &pos,
vehicle_attitude_s &att,
- vehicle_global_position_setpoint_s &posCmd,
- vehicle_global_position_setpoint_s &lastPosCmd);
+ mission_item_s &missionCmd,
+ mission_item_s &lastMissionCmd);
float getPsiCmd() { return _psiCmd; }
};
@@ -98,7 +99,7 @@ protected:
UOrbSubscription<vehicle_attitude_setpoint_s> _attCmd;
UOrbSubscription<vehicle_rates_setpoint_s> _ratesCmd;
UOrbSubscription<vehicle_global_position_s> _pos;
- UOrbSubscription<vehicle_global_position_set_triplet_s> _posCmd;
+ UOrbSubscription<mission_item_triplet_s> _missionCmd;
UOrbSubscription<manual_control_setpoint_s> _manual;
UOrbSubscription<vehicle_status_s> _status;
UOrbSubscription<parameter_update_s> _param_update;
diff --git a/src/modules/dataman/dataman.c b/src/modules/dataman/dataman.c
new file mode 100644
index 000000000..05b77da20
--- /dev/null
+++ b/src/modules/dataman/dataman.c
@@ -0,0 +1,739 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ * Author: Lorenz Meier
+ * Jean Cyr
+ *
+ * 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 navigator_main.c
+ * Implementation of the main navigation state machine.
+ *
+ * Handles missions, geo fencing and failsafe navigation behavior.
+ */
+
+#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 <systemlib/systemlib.h>
+#include <systemlib/err.h>
+#include <queue.h>
+
+#include "dataman.h"
+
+/**
+ * data manager app start / stop handling function
+ *
+ * @ingroup apps
+ */
+
+__EXPORT int dataman_main(int argc, char *argv[]);
+__EXPORT ssize_t dm_read(dm_item_t item, unsigned char index, void *buffer, size_t buflen);
+__EXPORT ssize_t dm_write(dm_item_t item, unsigned char index, dm_persitence_t persistence, const void *buffer, size_t buflen);
+__EXPORT int dm_clear(dm_item_t item);
+__EXPORT int dm_restart(dm_reset_reason restart_type);
+
+/* Types of function calls supported by the worker task */
+typedef enum {
+ dm_write_func = 0,
+ dm_read_func,
+ dm_clear_func,
+ dm_restart_func,
+ dm_number_of_funcs
+} dm_function_t;
+
+/* Work task work item */
+typedef struct {
+ sq_entry_t link; /**< list linkage */
+ sem_t wait_sem;
+ dm_function_t func;
+ ssize_t result;
+ union {
+ struct {
+ dm_item_t item;
+ unsigned char index;
+ dm_persitence_t persistence;
+ const void *buf;
+ size_t count;
+ } write_params;
+ struct {
+ dm_item_t item;
+ unsigned char index;
+ void *buf;
+ size_t count;
+ } read_params;
+ struct {
+ dm_item_t item;
+ } clear_params;
+ struct {
+ dm_reset_reason reason;
+ } restart_params;
+ };
+} work_q_item_t;
+
+/* Usage statistics */
+static unsigned g_func_counts[dm_number_of_funcs];
+
+/* table of maximum number of instances for each item type */
+static const unsigned g_per_item_max_index[DM_KEY_NUM_KEYS] = {
+ DM_KEY_SAFE_POINTS_MAX,
+ DM_KEY_FENCE_POINTS_MAX,
+ DM_KEY_WAY_POINTS_MAX,
+};
+
+/* Table of offset for index 0 of each item type */
+static unsigned int g_key_offsets[DM_KEY_NUM_KEYS];
+
+/* The data manager store file handle and file name */
+static int g_fd = -1, g_task_fd = -1;
+static const char *k_data_manager_device_path = "/fs/microsd/dataman";
+
+/* The data manager work queues */
+
+typedef struct {
+ sq_queue_t q;
+ sem_t mutex; /* Mutual exclusion on work queue adds and deletes */
+ unsigned size;
+ unsigned max_size;
+} work_q_t;
+
+static work_q_t g_free_q;
+static work_q_t g_work_q;
+
+sem_t g_work_queued_sema;
+sem_t g_init_sema;
+
+static bool g_task_should_exit; /**< if true, sensor task should exit */
+
+#define DM_SECTOR_HDR_SIZE 4
+static const unsigned k_sector_size = DM_MAX_DATA_SIZE + DM_SECTOR_HDR_SIZE;
+
+static void init_q(work_q_t *q)
+{
+ sq_init(&(q->q));
+ sem_init(&(q->mutex), 1, 1);
+ q->size = q->max_size = 0;
+}
+
+static void destroy_q(work_q_t *q)
+{
+ sem_destroy(&(q->mutex));
+}
+
+static inline void
+lock_queue(work_q_t *q)
+{
+ sem_wait(&(q->mutex));
+}
+
+static inline void
+unlock_queue(work_q_t *q)
+{
+ sem_post(&(q->mutex));
+}
+
+static work_q_item_t *
+create_work_item(void)
+{
+ work_q_item_t *item;
+
+ lock_queue(&g_free_q);
+ if ((item = (work_q_item_t *)sq_remfirst(&(g_free_q.q))))
+ g_free_q.size--;
+ unlock_queue(&g_free_q);
+
+ if (item == NULL)
+ item = (work_q_item_t *)malloc(sizeof(work_q_item_t));
+
+ if (item)
+ sem_init(&item->wait_sem, 1, 0); /* Caller will wait on this... initially locked */
+
+ return item;
+}
+
+/* Work queue management functions */
+static void
+enqueue_work_item(work_q_item_t *item)
+{
+ /* put the work item on the work queue */
+ lock_queue(&g_work_q);
+ sq_addlast(&item->link, &(g_work_q.q));
+
+ if (++g_work_q.size > g_work_q.max_size)
+ g_work_q.max_size = g_work_q.size;
+
+ unlock_queue(&g_work_q);
+
+ /* tell the work thread that work is available */
+ sem_post(&g_work_queued_sema);
+}
+
+static void
+destroy_work_item(work_q_item_t *item)
+{
+ sem_destroy(&item->wait_sem);
+ lock_queue(&g_free_q);
+ sq_addfirst(&item->link, &(g_free_q.q));
+
+ if (++g_free_q.size > g_free_q.max_size)
+ g_free_q.max_size = g_free_q.size;
+
+ unlock_queue(&g_free_q);
+}
+
+static work_q_item_t *
+dequeue_work_item(void)
+{
+ work_q_item_t *work;
+ lock_queue(&g_work_q);
+
+ if ((work = (work_q_item_t *)sq_remfirst(&g_work_q.q)))
+ g_work_q.size--;
+
+ unlock_queue(&g_work_q);
+ return work;
+}
+
+/* Calculate the offset in file of specific item */
+static int
+calculate_offset(dm_item_t item, unsigned char index)
+{
+
+ /* Make sure the item type is valid */
+ if (item >= DM_KEY_NUM_KEYS)
+ return -1;
+
+ /* Make sure the index for this item type is valid */
+ if (index >= g_per_item_max_index[item])
+ return -1;
+
+ /* Calculate and return the item index based on type and index */
+ return g_key_offsets[item] + (index * k_sector_size);
+}
+
+/* Each data item is stored as follows
+ *
+ * byte 0: Length of user data item
+ * byte 1: Persistence of this data item
+ * byte DM_SECTOR_HDR_SIZE... : data item value
+ *
+ * The total size must not exceed k_sector_size
+ */
+
+/* write to the data manager file */
+static ssize_t
+_write(dm_item_t item, unsigned char index, dm_persitence_t persistence, const void *buf, size_t count)
+{
+ unsigned char buffer[k_sector_size];
+ size_t len;
+ int offset;
+
+ /* Get the offset for this item */
+ offset = calculate_offset(item, index);
+
+ if (offset < 0)
+ return -1;
+
+ /* Make sure caller has not given us more data than we can handle */
+ if (count > DM_MAX_DATA_SIZE)
+ return -1;
+
+ /* Write out the data, prefixed with length and persistence level */
+ buffer[0] = count;
+ buffer[1] = persistence;
+ buffer[2] = 0;
+ buffer[3] = 0;
+ memcpy(buffer + DM_SECTOR_HDR_SIZE, buf, count);
+ count += DM_SECTOR_HDR_SIZE;
+
+ len = -1;
+
+ if (lseek(g_task_fd, offset, SEEK_SET) == offset)
+ if ((len = write(g_task_fd, buffer, count)) == count)
+ fsync(g_task_fd);
+
+ if (len != count)
+ return -1;
+
+ /* All is well... return the number of user data written */
+ return count - DM_SECTOR_HDR_SIZE;
+}
+
+/* Retrieve from the data manager file */
+static ssize_t
+_read(dm_item_t item, unsigned char index, void *buf, size_t count)
+{
+ unsigned char buffer[k_sector_size];
+ int len, offset;
+
+ /* Get the offset for this item */
+ offset = calculate_offset(item, index);
+
+ if (offset < 0)
+ return -1;
+
+ /* Make sure the caller hasn't asked for more data than we can handle */
+ if (count > DM_MAX_DATA_SIZE)
+ return -1;
+
+ /* Read the prefix and data */
+ len = -1;
+ if (lseek(g_task_fd, offset, SEEK_SET) == offset)
+ len = read(g_task_fd, buffer, count + DM_SECTOR_HDR_SIZE);
+
+ /* Check for length issues */
+ if (len < 0)
+ return -1;
+
+ if (len == 0)
+ buffer[0] = 0;
+
+ if (buffer[0] > 0) {
+ if (buffer[0] > count)
+ return -1;
+
+ /* Looks good, copy it to the caller's buffer */
+ memcpy(buf, buffer + DM_SECTOR_HDR_SIZE, buffer[0]);
+ }
+
+ /* Return the number of bytes of caller data read */
+ return buffer[0];
+}
+
+static int
+_clear(dm_item_t item)
+{
+ int i, result = 0;
+
+ int offset = calculate_offset(item, 0);
+
+ if (offset < 0)
+ return -1;
+
+ for (i = 0; (unsigned)i < g_per_item_max_index[item]; i++) {
+ char buf[1];
+
+ if (lseek(g_task_fd, offset, SEEK_SET) != offset) {
+ result = -1;
+ break;
+ }
+
+ if (read(g_task_fd, buf, 1) < 1)
+ break;
+
+ if (buf[0]) {
+ if (lseek(g_task_fd, offset, SEEK_SET) != offset) {
+ result = -1;
+ break;
+ }
+
+ buf[0] = 0;
+
+ if (write(g_task_fd, buf, 1) != 1) {
+ result = -1;
+ break;
+ }
+ }
+
+ offset += k_sector_size;
+ }
+
+ fsync(g_task_fd);
+ return result;
+}
+
+/* Tell the data manager about the type of the last reset */
+static int
+_restart(dm_reset_reason reason)
+{
+ unsigned char buffer[2];
+ int offset, result = 0;
+
+ /* We need to scan the entire file and invalidate and data that should not persist after the last reset */
+
+ /* Loop through all of the data segments and delete those that are not persistent */
+ offset = 0;
+
+ while (1) {
+ size_t len;
+
+ /* Get data segment at current offset */
+ if (lseek(g_task_fd, offset, SEEK_SET) != offset) {
+ result = -1;
+ break;
+ }
+
+ len = read(g_task_fd, buffer, sizeof(buffer));
+
+ if (len == 0)
+ break;
+
+ /* check if segment contains data */
+ if (buffer[0]) {
+ int clear_entry = 0;
+
+ /* Whether data gets deleted depends on reset type and data segment's persistence setting */
+ if (reason == DM_INIT_REASON_POWER_ON) {
+ if (buffer[1] != DM_PERSIST_POWER_ON_RESET) {
+ clear_entry = 1;
+ }
+
+ } else {
+ if ((buffer[1] != DM_PERSIST_POWER_ON_RESET) && (buffer[1] != DM_PERSIST_IN_FLIGHT_RESET)) {
+ clear_entry = 1;
+ }
+ }
+
+ /* Set segment to unused if data does not persist */
+ if (clear_entry) {
+ if (lseek(g_task_fd, offset, SEEK_SET) != offset) {
+ result = -1;
+ break;
+ }
+
+ buffer[0] = 0;
+
+ len = write(g_task_fd, buffer, 1);
+
+ if (len != 1) {
+ result = -1;
+ break;
+ }
+ }
+ }
+
+ offset += k_sector_size;
+ }
+
+ fsync(g_task_fd);
+
+ /* tell the caller how it went */
+ return result;
+}
+
+/* write to the data manager file */
+__EXPORT ssize_t
+dm_write(dm_item_t item, unsigned char index, dm_persitence_t persistence, const void *buf, size_t count)
+{
+ work_q_item_t *work;
+
+ if ((g_fd < 0) || g_task_should_exit)
+ return -1;
+
+ /* Will return with queues locked */
+ if ((work = create_work_item()) == NULL)
+ return -1; /* queues unlocked on failure */
+
+ work->func = dm_write_func;
+ work->write_params.item = item;
+ work->write_params.index = index;
+ work->write_params.persistence = persistence;
+ work->write_params.buf = buf;
+ work->write_params.count = count;
+ enqueue_work_item(work);
+
+ sem_wait(&work->wait_sem);
+ ssize_t result = work->result;
+ destroy_work_item(work);
+ return result;
+}
+
+/* Retrieve from the data manager file */
+__EXPORT ssize_t
+dm_read(dm_item_t item, unsigned char index, void *buf, size_t count)
+{
+ work_q_item_t *work;
+
+ if ((g_fd < 0) || g_task_should_exit)
+ return -1;
+
+ /* Will return with queues locked */
+ if ((work = create_work_item()) == NULL)
+ return -1; /* queues unlocked on failure */
+
+ work->func = dm_read_func;
+ work->read_params.item = item;
+ work->read_params.index = index;
+ work->read_params.buf = buf;
+ work->read_params.count = count;
+ enqueue_work_item(work);
+
+ sem_wait(&work->wait_sem);
+ ssize_t result = work->result;
+ destroy_work_item(work);
+ return result;
+}
+
+__EXPORT int
+dm_clear(dm_item_t item)
+{
+ work_q_item_t *work;
+
+ if ((g_fd < 0) || g_task_should_exit)
+ return -1;
+
+ /* Will return with queues locked */
+ if ((work = create_work_item()) == NULL)
+ return -1; /* queues unlocked on failure */
+
+ work->func = dm_clear_func;
+ work->clear_params.item = item;
+ enqueue_work_item(work);
+
+ sem_wait(&work->wait_sem);
+ int result = work->result;
+ destroy_work_item(work);
+ return result;
+}
+
+/* Tell the data manager about the type of the last reset */
+__EXPORT int
+dm_restart(dm_reset_reason reason)
+{
+ work_q_item_t *work;
+
+ if ((g_fd < 0) || g_task_should_exit)
+ return -1;
+
+ /* Will return with queues locked */
+ if ((work = create_work_item()) == NULL)
+ return -1; /* queues unlocked on failure */
+
+ work->func = dm_restart_func;
+ work->restart_params.reason = reason;
+ enqueue_work_item(work);
+
+ sem_wait(&work->wait_sem);
+ int result = work->result;
+ destroy_work_item(work);
+ return result;
+}
+
+static int
+task_main(int argc, char *argv[])
+{
+ work_q_item_t *work;
+
+ /* inform about start */
+ warnx("Initializing..");
+
+ /* Initialize global variables */
+ g_key_offsets[0] = 0;
+
+ for (unsigned i = 0; i < (DM_KEY_NUM_KEYS - 1); i++)
+ g_key_offsets[i + 1] = g_key_offsets[i] + (g_per_item_max_index[i] * k_sector_size);
+
+ unsigned max_offset = g_key_offsets[DM_KEY_NUM_KEYS - 1] + (g_per_item_max_index[DM_KEY_NUM_KEYS - 1] * k_sector_size);
+
+ for (unsigned i = 0; i < dm_number_of_funcs; i++)
+ g_func_counts[i] = 0;
+
+ g_task_should_exit = false;
+
+ init_q(&g_work_q);
+ init_q(&g_free_q);
+
+ sem_init(&g_work_queued_sema, 1, 0);
+
+ g_task_fd = open(k_data_manager_device_path, O_RDWR | O_CREAT | O_BINARY);
+ if (g_task_fd < 0) {
+ warnx("Could not open data manager file %s", k_data_manager_device_path);
+ return -1;
+ }
+ if (lseek(g_task_fd, max_offset, SEEK_SET) != max_offset) {
+ close(g_task_fd);
+ warnx("Could not seek data manager file %s", k_data_manager_device_path);
+ return -1;
+ }
+ fsync(g_task_fd);
+
+ g_fd = g_task_fd;
+
+ warnx("Initialized, data manager file '%s' size is %d bytes", k_data_manager_device_path, max_offset);
+
+ sem_post(&g_init_sema);
+
+ /* Start the endless loop, waiting for then processing work requests */
+ while (true) {
+
+ /* do we need to exit ??? */
+ if ((g_task_should_exit) && (g_fd >= 0)) {
+ /* Close the file handle to stop further queueing */
+ g_fd = -1;
+ }
+
+ if (!g_task_should_exit) {
+ /* wait for work */
+ sem_wait(&g_work_queued_sema);
+ }
+
+ /* Empty the work queue */
+ while ((work = dequeue_work_item())) {
+
+ switch (work->func) {
+ case dm_write_func:
+ g_func_counts[dm_write_func]++;
+ work->result =
+ _write(work->write_params.item, work->write_params.index, work->write_params.persistence, work->write_params.buf, work->write_params.count);
+ break;
+
+ case dm_read_func:
+ g_func_counts[dm_read_func]++;
+ work->result =
+ _read(work->read_params.item, work->read_params.index, work->read_params.buf, work->read_params.count);
+ break;
+
+ case dm_clear_func:
+ g_func_counts[dm_clear_func]++;
+ work->result = _clear(work->clear_params.item);
+ break;
+
+ case dm_restart_func:
+ g_func_counts[dm_restart_func]++;
+ work->result = _restart(work->restart_params.reason);
+ break;
+
+ default: /* should never happen */
+ work->result = -1;
+ break;
+ }
+
+ /* Inform the caller that work is done */
+ sem_post(&work->wait_sem);
+ }
+
+ /* time to go???? */
+ if ((g_task_should_exit) && (g_fd < 0))
+ break;
+ }
+
+ close(g_task_fd);
+ g_task_fd = -1;
+
+ /* Empty the work queue */
+ for (;;) {
+ if ((work = (work_q_item_t *)sq_remfirst(&(g_free_q.q))) == NULL)
+ break;
+
+ free(work);
+ }
+
+ destroy_q(&g_work_q);
+ destroy_q(&g_free_q);
+ sem_destroy(&g_work_queued_sema);
+
+ return 0;
+}
+
+static int
+start(void)
+{
+ int task;
+
+ sem_init(&g_init_sema, 1, 0);
+
+ /* start the task */
+ if ((task = task_spawn_cmd("dataman", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 5, 2048, task_main, NULL)) <= 0) {
+ warn("task start failed");
+ return -1;
+ }
+
+ /* wait for the thread to actuall initialize */
+ sem_wait(&g_init_sema);
+ sem_destroy(&g_init_sema);
+
+ return 0;
+}
+
+static void
+status(void)
+{
+ /* display usage statistics */
+ warnx("Writes %d", g_func_counts[dm_write_func]);
+ warnx("Reads %d", g_func_counts[dm_read_func]);
+ warnx("Clears %d", g_func_counts[dm_clear_func]);
+ warnx("Restarts %d", g_func_counts[dm_restart_func]);
+ warnx("Max Q lengths work %d, free %d", g_work_q.max_size, g_free_q.max_size);
+}
+
+static void
+stop(void)
+{
+ /* Tell the worker task to shut down */
+ g_task_should_exit = true;
+ sem_post(&g_work_queued_sema);
+}
+
+static void
+usage(void)
+{
+ errx(1, "usage: dataman {start|stop|status}");
+}
+
+int
+dataman_main(int argc, char *argv[])
+{
+ if (argc < 2)
+ usage();
+
+ if (!strcmp(argv[1], "start")) {
+
+ if (g_fd >= 0)
+ errx(1, "already running");
+
+ start();
+
+ if (g_fd < 0)
+ errx(1, "start failed");
+
+ return 0;
+ }
+
+ if (g_fd < 0)
+ errx(1, "not running");
+
+ if (!strcmp(argv[1], "stop"))
+ stop();
+ else if (!strcmp(argv[1], "status"))
+ status();
+ else
+ usage();
+
+ return 0;
+}
+
diff --git a/src/modules/dataman/dataman.h b/src/modules/dataman/dataman.h
new file mode 100644
index 000000000..41ddfaf61
--- /dev/null
+++ b/src/modules/dataman/dataman.h
@@ -0,0 +1,116 @@
+/****************************************************************************
+ *
+ * Copyright (c) 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 dataman.h
+ *
+ * DATAMANAGER driver.
+ */
+#ifndef _DATAMANAGER_H
+#define _DATAMANAGER_H
+
+#include <uORB/topics/mission.h>
+#include <uORB/topics/fence.h>
+#include <mavlink/waypoints.h>
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+ /* Types of items that the data manager can store */
+ typedef enum {
+ DM_KEY_SAFE_POINTS = 0, /* Safe points coordinates, safe point 0 is home point */
+ DM_KEY_FENCE_POINTS, /* Fence vertex coordinates */
+ DM_KEY_WAY_POINTS, /* Mission way point coordinates */
+ DM_KEY_NUM_KEYS /* Total number of item types defined */
+ } dm_item_t;
+
+ /* The maximum number of instances for each item type */
+ enum {
+ DM_KEY_SAFE_POINTS_MAX = 8,
+ DM_KEY_FENCE_POINTS_MAX = GEOFENCE_MAX_VERTICES,
+ DM_KEY_WAY_POINTS_MAX = MAVLINK_WPM_MAX_WP_COUNT,
+ };
+
+ /* Data persistence levels */
+ typedef enum {
+ DM_PERSIST_POWER_ON_RESET = 0, /* Data survives all resets */
+ DM_PERSIST_IN_FLIGHT_RESET, /* Data survives in-flight resets only */
+ DM_PERSIST_VOLATILE /* Data does not survive resets */
+ } dm_persitence_t;
+
+ /* The reason for the last reset */
+ typedef enum {
+ DM_INIT_REASON_POWER_ON = 0, /* Data survives resets */
+ DM_INIT_REASON_IN_FLIGHT /* Data survives in-flight resets only */
+ } dm_reset_reason;
+
+ /* Maximum size in bytes of a single item instance */
+ #define DM_MAX_DATA_SIZE 126
+
+ /* Retrieve from the data manager store */
+ __EXPORT ssize_t
+ dm_read(
+ dm_item_t item, /* The item type to retrieve */
+ unsigned char index, /* The index of the item */
+ void *buffer, /* Pointer to caller data buffer */
+ size_t buflen /* Length in bytes of data to retrieve */
+ );
+
+ /* write to the data manager store */
+ __EXPORT ssize_t
+ dm_write(
+ dm_item_t item, /* The item type to store */
+ unsigned char index, /* The index of the item */
+ dm_persitence_t persistence, /* The persistence level of this item */
+ const void *buffer, /* Pointer to caller data buffer */
+ size_t buflen /* Length in bytes of data to retrieve */
+ );
+
+ /* Retrieve from the data manager store */
+ __EXPORT int
+ dm_clear(
+ dm_item_t item /* The item type to clear */
+ );
+
+ /* Tell the data manager about the type of the last reset */
+ __EXPORT int
+ dm_restart(
+ dm_reset_reason restart_type /* The last reset type */
+ );
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif
diff --git a/src/modules/dataman/module.mk b/src/modules/dataman/module.mk
new file mode 100644
index 000000000..dce7a6235
--- /dev/null
+++ b/src/modules/dataman/module.mk
@@ -0,0 +1,42 @@
+############################################################################
+#
+# Copyright (c) 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.
+#
+############################################################################
+
+#
+# Main Navigation Controller
+#
+
+MODULE_COMMAND = dataman
+
+SRCS = dataman.c
+
+INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink
diff --git a/src/modules/fixedwing_backside/fixedwing.cpp b/src/modules/fixedwing_backside/fixedwing.cpp
index 6dc19df41..108e9896d 100644
--- a/src/modules/fixedwing_backside/fixedwing.cpp
+++ b/src/modules/fixedwing_backside/fixedwing.cpp
@@ -117,7 +117,7 @@ BlockMultiModeBacksideAutopilot::BlockMultiModeBacksideAutopilot(SuperBlock *par
_vCmd(this, "V_CMD"),
_crMax(this, "CR_MAX"),
_attPoll(),
- _lastPosCmd(),
+ _lastMissionCmd(),
_timeStamp(0)
{
_attPoll.fd = _att.getHandle();
@@ -141,8 +141,8 @@ void BlockMultiModeBacksideAutopilot::update()
setDt(dt);
// store old position command before update if new command sent
- if (_posCmd.updated()) {
- _lastPosCmd = _posCmd.getData();
+ if (_missionCmd.updated()) {
+ _lastMissionCmd = _missionCmd.getData();
}
// check for new updates
@@ -159,7 +159,7 @@ void BlockMultiModeBacksideAutopilot::update()
if (_status.main_state == MAIN_STATE_AUTO) {
// TODO use vehicle_control_mode here?
// update guidance
- _guide.update(_pos, _att, _posCmd.current, _lastPosCmd.current);
+ _guide.update(_pos, _att, _missionCmd.current, _lastMissionCmd.current);
}
// XXX handle STABILIZED (loiter on spot) as well
@@ -182,7 +182,7 @@ void BlockMultiModeBacksideAutopilot::update()
float vCmd = _vLimit.update(_vCmd.get());
// altitude hold
- float dThrottle = _h2Thr.update(_posCmd.current.altitude - _pos.alt);
+ float dThrottle = _h2Thr.update(_missionCmd.current.altitude - _pos.alt);
// heading hold
float psiError = _wrap_pi(_guide.getPsiCmd() - _att.yaw);
diff --git a/src/modules/fixedwing_backside/fixedwing.hpp b/src/modules/fixedwing_backside/fixedwing.hpp
index 567efeb35..b4dbc36b0 100644
--- a/src/modules/fixedwing_backside/fixedwing.hpp
+++ b/src/modules/fixedwing_backside/fixedwing.hpp
@@ -264,7 +264,7 @@ private:
BlockParamFloat _crMax;
struct pollfd _attPoll;
- vehicle_global_position_set_triplet_s _lastPosCmd;
+ mission_item_triplet_s _lastMissionCmd;
enum {CH_AIL, CH_ELV, CH_RDR, CH_THR};
uint64_t _timeStamp;
public:
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 00a0dcd61..1651cb399 100644
--- a/src/modules/fw_att_control/fw_att_control_main.cpp
+++ b/src/modules/fw_att_control/fw_att_control_main.cpp
@@ -37,6 +37,7 @@
* Implementation of a generic attitude controller based on classic orthogonal PIDs.
*
* @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Thomas Gubler <thomasgubler@gmail.com>
*
*/
@@ -62,6 +63,7 @@
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/parameter_update.h>
+#include <uORB/topics/vehicle_global_position.h>
#include <systemlib/param/param.h>
#include <systemlib/err.h>
#include <systemlib/pid/pid.h>
@@ -106,26 +108,30 @@ private:
bool _task_should_exit; /**< if true, sensor task should exit */
int _control_task; /**< task handle for sensor task */
- int _att_sub; /**< vehicle attitude subscription */
- int _accel_sub; /**< accelerometer subscription */
+ int _att_sub; /**< vehicle attitude subscription */
+ int _accel_sub; /**< accelerometer subscription */
int _att_sp_sub; /**< vehicle attitude setpoint */
int _attitude_sub; /**< raw rc channels data subscription */
int _airspeed_sub; /**< airspeed subscription */
- int _vcontrol_mode_sub; /**< vehicle status subscription */
- int _params_sub; /**< notification of parameter updates */
- int _manual_sub; /**< notification of manual control updates */
+ int _vcontrol_mode_sub; /**< vehicle status subscription */
+ int _params_sub; /**< notification of parameter updates */
+ int _manual_sub; /**< notification of manual control updates */
+ int _global_pos_sub; /**< global position subscription */
orb_advert_t _rate_sp_pub; /**< rate setpoint publication */
orb_advert_t _attitude_sp_pub; /**< attitude setpoint point */
orb_advert_t _actuators_0_pub; /**< actuator control group 0 setpoint */
+ orb_advert_t _actuators_1_pub; /**< actuator control group 1 setpoint (Airframe) */
- struct vehicle_attitude_s _att; /**< vehicle attitude */
- struct accel_report _accel; /**< body frame accelerations */
+ struct vehicle_attitude_s _att; /**< vehicle attitude */
+ struct accel_report _accel; /**< body frame accelerations */
struct vehicle_attitude_setpoint_s _att_sp; /**< vehicle attitude setpoint */
struct manual_control_setpoint_s _manual; /**< r/c channel data */
- struct airspeed_s _airspeed; /**< airspeed */
- struct vehicle_control_mode_s _vcontrol_mode; /**< vehicle control mode */
+ struct airspeed_s _airspeed; /**< airspeed */
+ struct vehicle_control_mode_s _vcontrol_mode; /**< vehicle control mode */
struct actuator_controls_s _actuators; /**< actuator control inputs */
+ struct actuator_controls_s _actuators_airframe; /**< actuator control inputs */
+ struct vehicle_global_position_s _global_pos; /**< global position */
perf_counter_t _loop_perf; /**< loop performance counter */
@@ -137,6 +143,7 @@ private:
float p_p;
float p_d;
float p_i;
+ float p_ff;
float p_rmax_pos;
float p_rmax_neg;
float p_integrator_max;
@@ -144,13 +151,17 @@ private:
float r_p;
float r_d;
float r_i;
+ float r_ff;
float r_integrator_max;
float r_rmax;
float y_p;
float y_i;
float y_d;
+ float y_ff;
float y_roll_feedforward;
float y_integrator_max;
+ float y_coordinated_min_speed;
+ float y_rmax;
float airspeed_min;
float airspeed_trim;
@@ -163,6 +174,7 @@ private:
param_t p_p;
param_t p_d;
param_t p_i;
+ param_t p_ff;
param_t p_rmax_pos;
param_t p_rmax_neg;
param_t p_integrator_max;
@@ -170,13 +182,17 @@ private:
param_t r_p;
param_t r_d;
param_t r_i;
+ param_t r_ff;
param_t r_integrator_max;
param_t r_rmax;
param_t y_p;
param_t y_i;
param_t y_d;
+ param_t y_ff;
param_t y_roll_feedforward;
param_t y_integrator_max;
+ param_t y_coordinated_min_speed;
+ param_t y_rmax;
param_t airspeed_min;
param_t airspeed_trim;
@@ -227,6 +243,11 @@ private:
void vehicle_setpoint_poll();
/**
+ * Check for global position updates.
+ */
+ void global_pos_poll();
+
+ /**
* Shim for calling task_main from task_create.
*/
static void task_main_trampoline(int argc, char *argv[]);
@@ -261,6 +282,7 @@ FixedwingAttitudeControl::FixedwingAttitudeControl() :
_vcontrol_mode_sub(-1),
_params_sub(-1),
_manual_sub(-1),
+ _global_pos_sub(-1),
/* publications */
_rate_sp_pub(-1),
@@ -273,31 +295,49 @@ FixedwingAttitudeControl::FixedwingAttitudeControl() :
_setpoint_valid(false),
_airspeed_valid(false)
{
+ /* safely initialize structs */
+ _att = {0};
+ _accel = {0};
+ _att_sp = {0};
+ _manual = {0};
+ _airspeed = {0};
+ _vcontrol_mode = {0};
+ _actuators = {0};
+ _actuators_airframe = {0};
+ _global_pos = {0};
+
+
_parameter_handles.tconst = param_find("FW_ATT_TC");
- _parameter_handles.p_p = param_find("FW_P_P");
- _parameter_handles.p_d = param_find("FW_P_D");
- _parameter_handles.p_i = param_find("FW_P_I");
+ _parameter_handles.p_p = param_find("FW_PR_P");
+ _parameter_handles.p_d = param_find("FW_PR_D");
+ _parameter_handles.p_i = param_find("FW_PR_I");
+ _parameter_handles.p_ff = param_find("FW_PR_FF");
_parameter_handles.p_rmax_pos = param_find("FW_P_RMAX_POS");
_parameter_handles.p_rmax_neg = param_find("FW_P_RMAX_NEG");
- _parameter_handles.p_integrator_max = param_find("FW_P_IMAX");
+ _parameter_handles.p_integrator_max = param_find("FW_PR_IMAX");
_parameter_handles.p_roll_feedforward = param_find("FW_P_ROLLFF");
- _parameter_handles.r_p = param_find("FW_R_P");
- _parameter_handles.r_d = param_find("FW_R_D");
- _parameter_handles.r_i = param_find("FW_R_I");
- _parameter_handles.r_integrator_max = param_find("FW_R_IMAX");
+ _parameter_handles.r_p = param_find("FW_RR_P");
+ _parameter_handles.r_d = param_find("FW_RR_D");
+ _parameter_handles.r_i = param_find("FW_RR_I");
+ _parameter_handles.r_ff = param_find("FW_RR_FF");
+ _parameter_handles.r_integrator_max = param_find("FW_RR_IMAX");
_parameter_handles.r_rmax = param_find("FW_R_RMAX");
- _parameter_handles.y_p = param_find("FW_Y_P");
- _parameter_handles.y_i = param_find("FW_Y_I");
- _parameter_handles.y_d = param_find("FW_Y_D");
+ _parameter_handles.y_p = param_find("FW_YR_P");
+ _parameter_handles.y_i = param_find("FW_YR_I");
+ _parameter_handles.y_d = param_find("FW_YR_D");
+ _parameter_handles.y_ff = param_find("FW_YR_FF");
_parameter_handles.y_roll_feedforward = param_find("FW_Y_ROLLFF");
- _parameter_handles.y_integrator_max = param_find("FW_Y_IMAX");
+ _parameter_handles.y_integrator_max = param_find("FW_YR_IMAX");
+ _parameter_handles.y_rmax = param_find("FW_Y_RMAX");
_parameter_handles.airspeed_min = param_find("FW_AIRSPD_MIN");
_parameter_handles.airspeed_trim = param_find("FW_AIRSPD_TRIM");
_parameter_handles.airspeed_max = param_find("FW_AIRSPD_MAX");
+ _parameter_handles.y_coordinated_min_speed = param_find("FW_YCO_VMIN");
+
/* fetch initial parameter values */
parameters_update();
}
@@ -335,6 +375,7 @@ FixedwingAttitudeControl::parameters_update()
param_get(_parameter_handles.p_p, &(_parameters.p_p));
param_get(_parameter_handles.p_d, &(_parameters.p_d));
param_get(_parameter_handles.p_i, &(_parameters.p_i));
+ param_get(_parameter_handles.p_ff, &(_parameters.p_ff));
param_get(_parameter_handles.p_rmax_pos, &(_parameters.p_rmax_pos));
param_get(_parameter_handles.p_rmax_neg, &(_parameters.p_rmax_neg));
param_get(_parameter_handles.p_integrator_max, &(_parameters.p_integrator_max));
@@ -343,14 +384,19 @@ FixedwingAttitudeControl::parameters_update()
param_get(_parameter_handles.r_p, &(_parameters.r_p));
param_get(_parameter_handles.r_d, &(_parameters.r_d));
param_get(_parameter_handles.r_i, &(_parameters.r_i));
+ param_get(_parameter_handles.r_ff, &(_parameters.r_ff));
+
param_get(_parameter_handles.r_integrator_max, &(_parameters.r_integrator_max));
param_get(_parameter_handles.r_rmax, &(_parameters.r_rmax));
param_get(_parameter_handles.y_p, &(_parameters.y_p));
param_get(_parameter_handles.y_i, &(_parameters.y_i));
param_get(_parameter_handles.y_d, &(_parameters.y_d));
+ param_get(_parameter_handles.y_ff, &(_parameters.y_ff));
param_get(_parameter_handles.y_roll_feedforward, &(_parameters.y_roll_feedforward));
param_get(_parameter_handles.y_integrator_max, &(_parameters.y_integrator_max));
+ param_get(_parameter_handles.y_coordinated_min_speed, &(_parameters.y_coordinated_min_speed));
+ param_get(_parameter_handles.y_rmax, &(_parameters.y_rmax));
param_get(_parameter_handles.airspeed_min, &(_parameters.airspeed_min));
param_get(_parameter_handles.airspeed_trim, &(_parameters.airspeed_trim));
@@ -358,28 +404,33 @@ FixedwingAttitudeControl::parameters_update()
/* pitch control parameters */
_pitch_ctrl.set_time_constant(_parameters.tconst);
- _pitch_ctrl.set_k_p(math::radians(_parameters.p_p));
- _pitch_ctrl.set_k_i(math::radians(_parameters.p_i));
- _pitch_ctrl.set_k_d(math::radians(_parameters.p_d));
- _pitch_ctrl.set_integrator_max(math::radians(_parameters.p_integrator_max));
+ _pitch_ctrl.set_k_p(_parameters.p_p);
+ _pitch_ctrl.set_k_i(_parameters.p_i);
+ _pitch_ctrl.set_k_d(_parameters.p_d);
+ _pitch_ctrl.set_k_ff(_parameters.p_ff);
+ _pitch_ctrl.set_integrator_max(_parameters.p_integrator_max);
_pitch_ctrl.set_max_rate_pos(math::radians(_parameters.p_rmax_pos));
_pitch_ctrl.set_max_rate_neg(math::radians(_parameters.p_rmax_neg));
- _pitch_ctrl.set_roll_ff(math::radians(_parameters.p_roll_feedforward));
+ _pitch_ctrl.set_roll_ff(_parameters.p_roll_feedforward);
/* roll control parameters */
_roll_ctrl.set_time_constant(_parameters.tconst);
- _roll_ctrl.set_k_p(math::radians(_parameters.r_p));
- _roll_ctrl.set_k_i(math::radians(_parameters.r_i));
- _roll_ctrl.set_k_d(math::radians(_parameters.r_d));
- _roll_ctrl.set_integrator_max(math::radians(_parameters.r_integrator_max));
+ _roll_ctrl.set_k_p(_parameters.r_p);
+ _roll_ctrl.set_k_i(_parameters.r_i);
+ _roll_ctrl.set_k_d(_parameters.r_d);
+ _roll_ctrl.set_k_ff(_parameters.r_ff);
+ _roll_ctrl.set_integrator_max(_parameters.r_integrator_max);
_roll_ctrl.set_max_rate(math::radians(_parameters.r_rmax));
/* yaw control parameters */
- _yaw_ctrl.set_k_side(math::radians(_parameters.y_p));
- _yaw_ctrl.set_k_i(math::radians(_parameters.y_i));
- _yaw_ctrl.set_k_d(math::radians(_parameters.y_d));
- _yaw_ctrl.set_k_roll_ff(math::radians(_parameters.y_roll_feedforward));
- _yaw_ctrl.set_integrator_max(math::radians(_parameters.y_integrator_max));
+ _yaw_ctrl.set_k_p(_parameters.y_p);
+ _yaw_ctrl.set_k_i(_parameters.y_i);
+ _yaw_ctrl.set_k_d(_parameters.y_d);
+ _yaw_ctrl.set_k_ff(_parameters.y_ff);
+ _yaw_ctrl.set_k_roll_ff(_parameters.y_roll_feedforward);
+ _yaw_ctrl.set_integrator_max(_parameters.y_integrator_max);
+ _yaw_ctrl.set_coordinated_min_speed(_parameters.y_coordinated_min_speed);
+ _yaw_ctrl.set_max_rate(math::radians(_parameters.y_rmax));
return OK;
}
@@ -421,6 +472,7 @@ FixedwingAttitudeControl::vehicle_airspeed_poll()
if (airspeed_updated) {
orb_copy(ORB_ID(airspeed), _airspeed_sub, &_airspeed);
+// warnx("airspeed poll: ind: %.4f, true: %.4f", _airspeed.indicated_airspeed_m_s, _airspeed.true_airspeed_m_s);
return true;
}
@@ -453,6 +505,18 @@ FixedwingAttitudeControl::vehicle_setpoint_poll()
}
void
+FixedwingAttitudeControl::global_pos_poll()
+{
+ /* check if there is a new global position */
+ bool global_pos_updated;
+ orb_check(_global_pos_sub, &global_pos_updated);
+
+ if (global_pos_updated) {
+ orb_copy(ORB_ID(vehicle_global_position), _global_pos_sub, &_global_pos);
+ }
+}
+
+void
FixedwingAttitudeControl::task_main_trampoline(int argc, char *argv[])
{
att_control::g_control->task_main();
@@ -476,6 +540,7 @@ FixedwingAttitudeControl::task_main()
_vcontrol_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode));
_params_sub = orb_subscribe(ORB_ID(parameter_update));
_manual_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
+ _global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position));
/* rate limit vehicle status updates to 5Hz */
orb_set_interval(_vcontrol_mode_sub, 200);
@@ -551,6 +616,8 @@ FixedwingAttitudeControl::task_main()
vehicle_manual_poll();
+ global_pos_poll();
+
/* lock integrator until control is started */
bool lock_integrator;
@@ -561,22 +628,28 @@ FixedwingAttitudeControl::task_main()
lock_integrator = true;
}
+ /* Simple handling of failsafe: deploy parachute if failsafe is on */
+ if (_vcontrol_mode.flag_control_flighttermination_enabled) {
+ _actuators_airframe.control[1] = 1.0f;
+// warnx("_actuators_airframe.control[1] = 1.0f;");
+ } else {
+ _actuators_airframe.control[1] = 0.0f;
+// warnx("_actuators_airframe.control[1] = -1.0f;");
+ }
+
/* decide if in stabilized or full manual control */
if (_vcontrol_mode.flag_control_attitude_enabled) {
- /* scale from radians to normalized -1 .. 1 range */
- const float actuator_scaling = 1.0f / (M_PI_F / 4.0f);
-
/* scale around tuning airspeed */
float airspeed;
/* if airspeed is smaller than min, the sensor is not giving good readings */
if (!_airspeed_valid ||
- (_airspeed.indicated_airspeed_m_s < _parameters.airspeed_min) ||
+ (_airspeed.indicated_airspeed_m_s < 0.1f * _parameters.airspeed_min) ||
!isfinite(_airspeed.indicated_airspeed_m_s)) {
- airspeed = _parameters.airspeed_min + (_parameters.airspeed_max - _parameters.airspeed_min) / 2.0f;
+ airspeed = _parameters.airspeed_trim;
} else {
airspeed = _airspeed.indicated_airspeed_m_s;
@@ -585,7 +658,8 @@ FixedwingAttitudeControl::task_main()
float airspeed_scaling = _parameters.airspeed_trim / airspeed;
//warnx("aspd scale: %6.2f act scale: %6.2f", airspeed_scaling, actuator_scaling);
- float roll_sp, pitch_sp;
+ float roll_sp = 0.0f;
+ float pitch_sp = 0.0f;
float throttle_sp = 0.0f;
if (_vcontrol_mode.flag_control_velocity_enabled || _vcontrol_mode.flag_control_position_enabled) {
@@ -635,46 +709,86 @@ FixedwingAttitudeControl::task_main()
}
}
- if (isfinite(roll_sp) && isfinite(pitch_sp)) {
+ /* Prepare speed_body_u and speed_body_w */
+ float speed_body_u = 0.0f;
+ float speed_body_v = 0.0f;
+ float speed_body_w = 0.0f;
+ if(_att.R_valid) {
+ speed_body_u = _att.R[0][0] * _global_pos.vx + _att.R[1][0] * _global_pos.vy + _att.R[2][0] * _global_pos.vz;
+ speed_body_v = _att.R[0][1] * _global_pos.vx + _att.R[1][1] * _global_pos.vy + _att.R[2][1] * _global_pos.vz;
+ speed_body_w = _att.R[0][2] * _global_pos.vx + _att.R[1][2] * _global_pos.vy + _att.R[2][2] * _global_pos.vz;
+ } else {
+ warnx("Did not get a valid R\n");
+ }
- float roll_rad = _roll_ctrl.control(roll_sp, _att.roll, _att.rollspeed,
- airspeed_scaling, lock_integrator, _parameters.airspeed_min, _parameters.airspeed_max, airspeed);
- _actuators.control[0] = (isfinite(roll_rad)) ? roll_rad * actuator_scaling : 0.0f;
+ /* Run attitude controllers */
+ if (isfinite(roll_sp) && isfinite(pitch_sp)) {
+ _roll_ctrl.control_attitude(roll_sp, _att.roll);
+ _pitch_ctrl.control_attitude(pitch_sp, _att.roll, _att.pitch, airspeed);
+ _yaw_ctrl.control_attitude(_att.roll, _att.pitch,
+ speed_body_u, speed_body_v, speed_body_w,
+ _roll_ctrl.get_desired_rate(), _pitch_ctrl.get_desired_rate()); //runs last, because is depending on output of roll and pitch attitude
+
+ /* Run attitude RATE controllers which need the desired attitudes from above */
+ float roll_u = _roll_ctrl.control_bodyrate(_att.pitch,
+ _att.rollspeed, _att.yawspeed,
+ _yaw_ctrl.get_desired_rate(),
+ _parameters.airspeed_min, _parameters.airspeed_max, airspeed, airspeed_scaling, lock_integrator);
+ _actuators.control[0] = (isfinite(roll_u)) ? roll_u : 0.0f;
+ if (!isfinite(roll_u)) {
+ warnx("roll_u %.4f", roll_u);
+ }
- float pitch_rad = _pitch_ctrl.control(pitch_sp, _att.pitch, _att.pitchspeed, _att.roll, airspeed_scaling,
- lock_integrator, _parameters.airspeed_min, _parameters.airspeed_max, airspeed);
- _actuators.control[1] = (isfinite(pitch_rad)) ? pitch_rad * actuator_scaling : 0.0f;
+ float pitch_u = _pitch_ctrl.control_bodyrate(_att.roll, _att.pitch,
+ _att.pitchspeed, _att.yawspeed,
+ _yaw_ctrl.get_desired_rate(),
+ _parameters.airspeed_min, _parameters.airspeed_max, airspeed, airspeed_scaling, lock_integrator);
+ _actuators.control[1] = (isfinite(pitch_u)) ? pitch_u : 0.0f;
+ if (!isfinite(pitch_u)) {
+ warnx("pitch_u %.4f, _yaw_ctrl.get_desired_rate() %.4f, airspeed %.4f, airspeed_scaling %.4f, roll_sp %.4f, pitch_sp %.4f, _roll_ctrl.get_desired_rate() %.4f, _pitch_ctrl.get_desired_rate() %.4f att_sp.roll_body %.4f",
+ pitch_u, _yaw_ctrl.get_desired_rate(), airspeed, airspeed_scaling, roll_sp, pitch_sp, _roll_ctrl.get_desired_rate(), _pitch_ctrl.get_desired_rate(), _att_sp.roll_body);
+ }
- float yaw_rad = _yaw_ctrl.control(_att.roll, _att.yawspeed, _accel.y, airspeed_scaling, lock_integrator,
- _parameters.airspeed_min, _parameters.airspeed_max, airspeed);
- _actuators.control[2] = (isfinite(yaw_rad)) ? yaw_rad * actuator_scaling : 0.0f;
+ float yaw_u = _yaw_ctrl.control_bodyrate(_att.roll, _att.pitch,
+ _att.pitchspeed, _att.yawspeed,
+ _pitch_ctrl.get_desired_rate(),
+ _parameters.airspeed_min, _parameters.airspeed_max, airspeed, airspeed_scaling, lock_integrator);
+ _actuators.control[2] = (isfinite(yaw_u)) ? yaw_u : 0.0f;
+ if (!isfinite(yaw_u)) {
+ warnx("yaw_u %.4f", yaw_u);
+ }
/* throttle passed through */
_actuators.control[3] = (isfinite(throttle_sp)) ? throttle_sp : 0.0f;
+ if (!isfinite(throttle_sp)) {
+ warnx("throttle_sp %.4f", throttle_sp);
+ }
+ } else {
+ warnx("Non-finite setpoint roll_sp: %.4f, pitch_sp %.4f", roll_sp, pitch_sp);
+ }
- // warnx("aspd: %s: %6.2f, aspd scaling: %6.2f, controls: %5.2f %5.2f %5.2f %5.2f", (_airspeed_valid) ? "valid" : "unknown",
- // airspeed, airspeed_scaling, _actuators.control[0], _actuators.control[1],
- // _actuators.control[2], _actuators.control[3]);
+ // warnx("aspd: %s: %6.2f, aspd scaling: %6.2f, controls: %5.2f %5.2f %5.2f %5.2f", (_airspeed_valid) ? "valid" : "unknown",
+ // airspeed, airspeed_scaling, _actuators.control[0], _actuators.control[1],
+ // _actuators.control[2], _actuators.control[3]);
- /*
- * Lazily publish the rate setpoint (for analysis, the actuators are published below)
- * only once available
- */
- vehicle_rates_setpoint_s rates_sp;
- rates_sp.roll = _roll_ctrl.get_desired_rate();
- rates_sp.pitch = _pitch_ctrl.get_desired_rate();
- rates_sp.yaw = 0.0f; // XXX not yet implemented
+ /*
+ * Lazily publish the rate setpoint (for analysis, the actuators are published below)
+ * only once available
+ */
+ vehicle_rates_setpoint_s rates_sp;
+ rates_sp.roll = _roll_ctrl.get_desired_rate();
+ rates_sp.pitch = _pitch_ctrl.get_desired_rate();
+ rates_sp.yaw = _yaw_ctrl.get_desired_rate();
- rates_sp.timestamp = hrt_absolute_time();
+ rates_sp.timestamp = hrt_absolute_time();
- if (_rate_sp_pub > 0) {
- /* publish the attitude setpoint */
- orb_publish(ORB_ID(vehicle_rates_setpoint), _rate_sp_pub, &rates_sp);
+ if (_rate_sp_pub > 0) {
+ /* publish the attitude setpoint */
+ orb_publish(ORB_ID(vehicle_rates_setpoint), _rate_sp_pub, &rates_sp);
- } else {
- /* advertise and publish */
- _rate_sp_pub = orb_advertise(ORB_ID(vehicle_rates_setpoint), &rates_sp);
- }
+ } else {
+ /* advertise and publish */
+ _rate_sp_pub = orb_advertise(ORB_ID(vehicle_rates_setpoint), &rates_sp);
}
} else {
@@ -692,6 +806,7 @@ FixedwingAttitudeControl::task_main()
/* lazily publish the setpoint only once available */
_actuators.timestamp = hrt_absolute_time();
+ _actuators_airframe.timestamp = hrt_absolute_time();
if (_actuators_0_pub > 0) {
/* publish the attitude setpoint */
@@ -702,6 +817,19 @@ 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);
+ }
+
}
perf_end(_loop_perf);
diff --git a/src/modules/fw_att_control/fw_att_control_params.c b/src/modules/fw_att_control/fw_att_control_params.c
index be76524da..0b37f48ba 100644
--- a/src/modules/fw_att_control/fw_att_control_params.c
+++ b/src/modules/fw_att_control/fw_att_control_params.c
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+f * Copyright (c) 2013 PX4 Development Team. All rights reserved.
* Author: Lorenz Meier <lm@inf.ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
@@ -44,11 +44,13 @@
#include <systemlib/param/param.h>
+//XXX resolve unclear naming of paramters: FW_P_P --> FW_PR_P
+
/*
* Controller parameters, accessible via MAVLink
*
*/
-
+//xxx: update descriptions
// @DisplayName Attitude Time Constant
// @Description This defines the latency between a step input and the achieved setpoint. Half a second is a good start value and fits for most average systems. Smaller systems may require smaller values, but as this will wear out servos faster, the value should only be decreased as needed.
// @Range 0.4 to 1.0 seconds, in tens of seconds
@@ -57,33 +59,33 @@ PARAM_DEFINE_FLOAT(FW_ATT_TC, 0.5f);
// @DisplayName Proportional gain.
// @Description This defines how much the elevator input will be commanded dependend on the current pitch error.
// @Range 10 to 200, 1 increments
-PARAM_DEFINE_FLOAT(FW_P_P, 40.0f);
+PARAM_DEFINE_FLOAT(FW_PR_P, 0.3f);
// @DisplayName Damping gain.
// @Description This gain damps the airframe pitch rate. In particular relevant for flying wings.
// @Range 0.0 to 10.0, 0.1 increments
-PARAM_DEFINE_FLOAT(FW_P_D, 0.0f);
+PARAM_DEFINE_FLOAT(FW_PR_D, 0.0f); //xxx: remove
// @DisplayName Integrator gain.
// @Description This gain defines how much control response will result out of a steady state error. It trims any constant error.
// @Range 0 to 50.0
-PARAM_DEFINE_FLOAT(FW_P_I, 0.0f);
+PARAM_DEFINE_FLOAT(FW_PR_I, 0.05f);
// @DisplayName Maximum positive / up pitch rate.
// @Description This limits the maximum pitch up angular rate the controller will output (in degrees per second). Setting a value of zero disables the limit.
// @Range 0 to 90.0 degrees per seconds, in 1 increments
-PARAM_DEFINE_FLOAT(FW_P_RMAX_POS, 0.0f);
+PARAM_DEFINE_FLOAT(FW_P_RMAX_POS, 60.0f);
// @DisplayName Maximum negative / down pitch rate.
// @Description This limits the maximum pitch down up angular rate the controller will output (in degrees per second). Setting a value of zero disables the limit.
// @Range 0 to 90.0 degrees per seconds, in 1 increments
-PARAM_DEFINE_FLOAT(FW_P_RMAX_NEG, 0.0f);
+PARAM_DEFINE_FLOAT(FW_P_RMAX_NEG, 60.0f);
// @DisplayName Pitch Integrator Anti-Windup
// @Description This limits the range in degrees the integrator can wind up to.
// @Range 0.0 to 45.0
// @Increment 1.0
-PARAM_DEFINE_FLOAT(FW_P_IMAX, 15.0f);
+PARAM_DEFINE_FLOAT(FW_PR_IMAX, 0.2f);
// @DisplayName Roll feedforward gain.
// @Description This compensates during turns and ensures the nose stays level.
@@ -97,27 +99,27 @@ PARAM_DEFINE_FLOAT(FW_P_ROLLFF, 1.0f);
// @Range 10.0 200.0
// @Increment 10.0
// @User User
-PARAM_DEFINE_FLOAT(FW_R_P, 40.0f);
+PARAM_DEFINE_FLOAT(FW_RR_P, 0.5f);
// @DisplayName Damping Gain
// @Description Controls the roll rate to roll actuator output. It helps to reduce motions in turbulence.
// @Range 0.0 10.0
// @Increment 1.0
// @User User
-PARAM_DEFINE_FLOAT(FW_R_D, 0.0f);
+PARAM_DEFINE_FLOAT(FW_RR_D, 0.0f); //xxx: remove
// @DisplayName Integrator Gain
// @Description This gain controls the contribution of the integral to roll actuator outputs. It trims out steady state errors.
// @Range 0.0 100.0
// @Increment 5.0
// @User User
-PARAM_DEFINE_FLOAT(FW_R_I, 0.0f);
+PARAM_DEFINE_FLOAT(FW_RR_I, 0.05f);
// @DisplayName Roll Integrator Anti-Windup
// @Description This limits the range in degrees the integrator can wind up to.
// @Range 0.0 to 45.0
// @Increment 1.0
-PARAM_DEFINE_FLOAT(FW_R_IMAX, 15.0f);
+PARAM_DEFINE_FLOAT(FW_RR_IMAX, 0.2f);
// @DisplayName Maximum Roll Rate
// @Description This limits the maximum roll rate the controller will output (in degrees per second). Setting a value of zero disables the limit.
@@ -126,11 +128,17 @@ PARAM_DEFINE_FLOAT(FW_R_IMAX, 15.0f);
PARAM_DEFINE_FLOAT(FW_R_RMAX, 60);
-PARAM_DEFINE_FLOAT(FW_Y_P, 0);
-PARAM_DEFINE_FLOAT(FW_Y_I, 0);
-PARAM_DEFINE_FLOAT(FW_Y_IMAX, 15.0f);
-PARAM_DEFINE_FLOAT(FW_Y_D, 0);
-PARAM_DEFINE_FLOAT(FW_Y_ROLLFF, 1);
+PARAM_DEFINE_FLOAT(FW_YR_P, 0.5);
+PARAM_DEFINE_FLOAT(FW_YR_I, 0.05);
+PARAM_DEFINE_FLOAT(FW_YR_IMAX, 0.2f);
+PARAM_DEFINE_FLOAT(FW_YR_D, 0); //xxx: remove
+PARAM_DEFINE_FLOAT(FW_Y_ROLLFF, 0);
PARAM_DEFINE_FLOAT(FW_AIRSPD_MIN, 9.0f);
PARAM_DEFINE_FLOAT(FW_AIRSPD_TRIM, 12.0f);
PARAM_DEFINE_FLOAT(FW_AIRSPD_MAX, 18.0f);
+PARAM_DEFINE_FLOAT(FW_Y_RMAX, 60);
+PARAM_DEFINE_FLOAT(FW_YCO_VMIN, 1.0f);
+
+PARAM_DEFINE_FLOAT(FW_RR_FF, 0.0f);
+PARAM_DEFINE_FLOAT(FW_PR_FF, 0.0f);
+PARAM_DEFINE_FLOAT(FW_YR_FF, 0.0f);
diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
index a9648b207..cdd41d16a 100644
--- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
+++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
@@ -67,7 +67,7 @@
#include <uORB/uORB.h>
#include <uORB/topics/airspeed.h>
#include <uORB/topics/vehicle_global_position.h>
-#include <uORB/topics/vehicle_global_position_set_triplet.h>
+#include <uORB/topics/mission_item_triplet.h>
#include <uORB/topics/vehicle_attitude_setpoint.h>
#include <uORB/topics/manual_control_setpoint.h>
#include <uORB/topics/actuator_controls.h>
@@ -83,6 +83,7 @@
#include <systemlib/perf_counter.h>
#include <systemlib/systemlib.h>
#include <mathlib/mathlib.h>
+#include <mavlink/mavlink_log.h>
#include <ecl/l1/ecl_l1_pos_controller.h>
#include <external_lgpl/tecs/tecs.h>
@@ -115,12 +116,13 @@ public:
int start();
private:
+ int _mavlink_fd;
bool _task_should_exit; /**< if true, sensor task should exit */
int _control_task; /**< task handle for sensor task */
int _global_pos_sub;
- int _global_set_triplet_sub;
+ int _mission_item_triplet_sub;
int _att_sub; /**< vehicle attitude subscription */
int _attitude_sub; /**< raw rc channels data subscription */
int _airspeed_sub; /**< airspeed subscription */
@@ -139,7 +141,7 @@ private:
struct airspeed_s _airspeed; /**< airspeed */
struct vehicle_control_mode_s _control_mode; /**< vehicle status */
struct vehicle_global_position_s _global_pos; /**< global vehicle position */
- struct vehicle_global_position_set_triplet_s _global_triplet; /**< triplet of global setpoints */
+ struct mission_item_triplet_s _mission_item_triplet; /**< triplet of mission items */
struct accel_report _accel; /**< body frame accelerations */
perf_counter_t _loop_perf; /**< loop performance counter */
@@ -160,7 +162,13 @@ private:
/* land states */
/* not in non-abort mode for landing yet */
- bool land_noreturn;
+ bool land_noreturn_horizontal;
+ bool land_noreturn_vertical;
+ bool land_stayonground;
+ bool land_motor_lim;
+ bool land_onslope;
+
+ float flare_curve_alt_last;
/* heading hold */
float target_bearing;
@@ -206,6 +214,16 @@ private:
float throttle_land_max;
float loiter_hold_radius;
+
+ float heightrate_p;
+ float speedrate_p;
+
+ float land_slope_angle;
+ float land_slope_length;
+ float land_H1_virt;
+ float land_flare_alt_relative;
+ float land_thrust_lim_horizontal_distance;
+
} _parameters; /**< local copies of interesting parameters */
struct {
@@ -240,6 +258,16 @@ private:
param_t throttle_land_max;
param_t loiter_hold_radius;
+
+ param_t heightrate_p;
+ param_t speedrate_p;
+
+ param_t land_slope_angle;
+ param_t land_slope_length;
+ param_t land_H1_virt;
+ param_t land_flare_alt_relative;
+ param_t land_thrust_lim_horizontal_distance;
+
} _parameter_handles; /**< handles for interesting parameters */
@@ -280,13 +308,18 @@ private:
void vehicle_setpoint_poll();
/**
+ * Get Altitude on the landing glide slope
+ */
+ float getLandingSlopeAbsoluteAltitude(float wp_distance, float wp_altitude, float landing_slope_angle_rad, float horizontal_displacement);
+
+ /**
* Control position.
*/
bool control_position(const math::Vector2f &global_pos, const math::Vector2f &ground_speed,
- const struct vehicle_global_position_set_triplet_s &global_triplet);
+ const struct mission_item_triplet_s &_mission_item_triplet);
float calculate_target_airspeed(float airspeed_demand);
- void calculate_gndspeed_undershoot();
+ void calculate_gndspeed_undershoot(const math::Vector2f &current_position, const math::Vector2f &ground_speed, const struct mission_item_triplet_s &mission_item_triplet);
/**
* Shim for calling task_main from task_create.
@@ -318,7 +351,7 @@ FixedwingPositionControl::FixedwingPositionControl() :
/* subscriptions */
_global_pos_sub(-1),
- _global_set_triplet_sub(-1),
+ _mission_item_triplet_sub(-1),
_att_sub(-1),
_airspeed_sub(-1),
_control_mode_sub(-1),
@@ -338,8 +371,28 @@ FixedwingPositionControl::FixedwingPositionControl() :
_airspeed_valid(false),
_groundspeed_undershoot(0.0f),
_global_pos_valid(false),
- land_noreturn(false)
+ land_noreturn_horizontal(false),
+ land_noreturn_vertical(false),
+ land_stayonground(false),
+ land_motor_lim(false),
+ land_onslope(false),
+ flare_curve_alt_last(0.0f),
+ _mavlink_fd(-1)
{
+ /* safely initialize structs */
+ vehicle_attitude_s _att = {0};
+ vehicle_attitude_setpoint_s _att_sp = {0};
+ navigation_capabilities_s _nav_capabilities = {0};
+ manual_control_setpoint_s _manual = {0};
+ airspeed_s _airspeed = {0};
+ vehicle_control_mode_s _control_mode = {0};
+ vehicle_global_position_s _global_pos = {0};
+ mission_item_triplet_s _mission_item_triplet = {0};
+ accel_report _accel = {0};
+
+
+
+
_nav_capabilities.turn_distance = 0.0f;
_parameter_handles.l1_period = param_find("FW_L1_PERIOD");
@@ -358,6 +411,12 @@ FixedwingPositionControl::FixedwingPositionControl() :
_parameter_handles.throttle_cruise = param_find("FW_THR_CRUISE");
_parameter_handles.throttle_land_max = param_find("FW_THR_LND_MAX");
+ _parameter_handles.land_slope_angle = param_find("FW_LND_ANG");
+ _parameter_handles.land_slope_length = param_find("FW_LND_SLLR");
+ _parameter_handles.land_H1_virt = param_find("FW_LND_HVIRT");
+ _parameter_handles.land_flare_alt_relative = param_find("FW_LND_FLALT");
+ _parameter_handles.land_thrust_lim_horizontal_distance = param_find("FW_LND_TLDIST");
+
_parameter_handles.time_const = param_find("FW_T_TIME_CONST");
_parameter_handles.min_sink_rate = param_find("FW_T_SINK_MIN");
_parameter_handles.max_sink_rate = param_find("FW_T_SINK_MAX");
@@ -370,6 +429,8 @@ FixedwingPositionControl::FixedwingPositionControl() :
_parameter_handles.roll_throttle_compensation = param_find("FW_T_RLL2THR");
_parameter_handles.speed_weight = param_find("FW_T_SPDWEIGHT");
_parameter_handles.pitch_damping = param_find("FW_T_PTCH_DAMP");
+ _parameter_handles.heightrate_p = param_find("FW_T_HRATE_P");
+ _parameter_handles.speedrate_p = param_find("FW_T_SRATE_P");
/* fetch initial parameter values */
parameters_update();
@@ -435,6 +496,15 @@ FixedwingPositionControl::parameters_update()
param_get(_parameter_handles.pitch_damping, &(_parameters.pitch_damping));
param_get(_parameter_handles.max_climb_rate, &(_parameters.max_climb_rate));
+ param_get(_parameter_handles.heightrate_p, &(_parameters.heightrate_p));
+ param_get(_parameter_handles.speedrate_p, &(_parameters.speedrate_p));
+
+ param_get(_parameter_handles.land_slope_angle, &(_parameters.land_slope_angle));
+ param_get(_parameter_handles.land_slope_length, &(_parameters.land_slope_length));
+ param_get(_parameter_handles.land_H1_virt, &(_parameters.land_H1_virt));
+ param_get(_parameter_handles.land_flare_alt_relative, &(_parameters.land_flare_alt_relative));
+ param_get(_parameter_handles.land_thrust_lim_horizontal_distance, &(_parameters.land_thrust_lim_horizontal_distance));
+
_l1_control.set_l1_damping(_parameters.l1_damping);
_l1_control.set_l1_period(_parameters.l1_period);
_l1_control.set_l1_roll_limit(math::radians(_parameters.roll_limit));
@@ -447,12 +517,14 @@ FixedwingPositionControl::parameters_update()
_tecs.set_vertical_accel_limit(_parameters.vertical_accel_limit);
_tecs.set_height_comp_filter_omega(_parameters.height_comp_filter_omega);
_tecs.set_speed_comp_filter_omega(_parameters.speed_comp_filter_omega);
- _tecs.set_roll_throttle_compensation(math::radians(_parameters.roll_throttle_compensation));
+ _tecs.set_roll_throttle_compensation(_parameters.roll_throttle_compensation);
_tecs.set_speed_weight(_parameters.speed_weight);
_tecs.set_pitch_damping(_parameters.pitch_damping);
_tecs.set_indicated_airspeed_min(_parameters.airspeed_min);
_tecs.set_indicated_airspeed_max(_parameters.airspeed_max);
_tecs.set_max_climb_rate(_parameters.max_climb_rate);
+ _tecs.set_heightrate_p(_parameters.heightrate_p);
+ _tecs.set_speedrate_p(_parameters.speedrate_p);
/* sanity check parameters */
if (_parameters.airspeed_max < _parameters.airspeed_min ||
@@ -548,11 +620,11 @@ void
FixedwingPositionControl::vehicle_setpoint_poll()
{
/* check if there is a new setpoint */
- bool global_sp_updated;
- orb_check(_global_set_triplet_sub, &global_sp_updated);
+ bool mission_item_triplet_updated;
+ orb_check(_mission_item_triplet_sub, &mission_item_triplet_updated);
- if (global_sp_updated) {
- orb_copy(ORB_ID(vehicle_global_position_set_triplet), _global_set_triplet_sub, &_global_triplet);
+ if (mission_item_triplet_updated) {
+ orb_copy(ORB_ID(mission_item_triplet), _mission_item_triplet_sub, &_mission_item_triplet);
_setpoint_valid = true;
}
}
@@ -595,17 +667,29 @@ FixedwingPositionControl::calculate_target_airspeed(float airspeed_demand)
}
void
-FixedwingPositionControl::calculate_gndspeed_undershoot()
+FixedwingPositionControl::calculate_gndspeed_undershoot(const math::Vector2f &current_position, const math::Vector2f &ground_speed, const struct mission_item_triplet_s &mission_item_triplet)
{
if (_global_pos_valid) {
- /* get ground speed vector */
- math::Vector2f ground_speed_vector(_global_pos.vx, _global_pos.vy);
- /* rotate with current attitude */
+ /* rotate ground speed vector with current attitude */
math::Vector2f yaw_vector(_R_nb(0, 0), _R_nb(1, 0));
yaw_vector.normalize();
- float ground_speed_body = yaw_vector * ground_speed_vector;
+ float ground_speed_body = yaw_vector * ground_speed;
+
+ /* The minimum desired ground speed is the minimum airspeed projected on to the ground using the altitude and horizontal difference between the waypoints if available*/
+ float distance = 0.0f;
+ float delta_altitude = 0.0f;
+ if (mission_item_triplet.previous_valid) {
+ distance = get_distance_to_next_waypoint(mission_item_triplet.previous.lat, mission_item_triplet.previous.lon, mission_item_triplet.current.lat, mission_item_triplet.current.lon);
+ delta_altitude = mission_item_triplet.current.altitude - mission_item_triplet.previous.altitude;
+ } else {
+ distance = get_distance_to_next_waypoint(current_position.getX(), current_position.getY(), mission_item_triplet.current.lat, mission_item_triplet.current.lon);
+ delta_altitude = mission_item_triplet.current.altitude - _global_pos.alt;
+ }
+
+ float ground_speed_desired = _parameters.airspeed_min * cosf(atan2f(delta_altitude, distance));
+
/*
* Ground speed undershoot is the amount of ground velocity not reached
@@ -616,20 +700,25 @@ FixedwingPositionControl::calculate_gndspeed_undershoot()
* not exceeded) travels towards a waypoint (and is not pushed more and more away
* by wind). Not countering this would lead to a fly-away.
*/
- _groundspeed_undershoot = math::max(_parameters.airspeed_min - ground_speed_body, 0.0f);
+ _groundspeed_undershoot = math::max(ground_speed_desired - ground_speed_body, 0.0f);
} else {
_groundspeed_undershoot = 0;
}
}
+float FixedwingPositionControl::getLandingSlopeAbsoluteAltitude(float wp_distance, float wp_altitude, float landing_slope_angle_rad, float horizontal_displacement)
+{
+ return (wp_distance - horizontal_displacement) * tanf(landing_slope_angle_rad) + wp_altitude; //flare_relative_alt is negative
+}
+
bool
FixedwingPositionControl::control_position(const math::Vector2f &current_position, const math::Vector2f &ground_speed,
- const struct vehicle_global_position_set_triplet_s &global_triplet)
+ const struct mission_item_triplet_s &mission_item_triplet)
{
bool setpoint = true;
- calculate_gndspeed_undershoot();
+ calculate_gndspeed_undershoot(current_position, ground_speed, mission_item_triplet);
float eas2tas = 1.0f; // XXX calculate actual number based on current measurements
@@ -641,7 +730,7 @@ FixedwingPositionControl::control_position(const math::Vector2f &current_positio
math::Vector3 accel_earth = _R_nb.transpose() * accel_body;
_tecs.update_50hz(baro_altitude, _airspeed.indicated_airspeed_m_s, _R_nb, accel_body, accel_earth);
- float altitude_error = _global_triplet.current.altitude - _global_pos.alt;
+ float altitude_error = _mission_item_triplet.current.altitude - _global_pos.alt;
/* no throttle limit as default */
float throttle_max = 1.0f;
@@ -658,252 +747,253 @@ FixedwingPositionControl::control_position(const math::Vector2f &current_positio
/* restore speed weight, in case changed intermittently (e.g. in landing handling) */
_tecs.set_speed_weight(_parameters.speed_weight);
- /* execute navigation once we have a setpoint */
- if (_setpoint_valid) {
-
- /* current waypoint (the one currently heading for) */
- math::Vector2f next_wp(global_triplet.current.lat / 1e7f, global_triplet.current.lon / 1e7f);
-
- /* previous waypoint */
- math::Vector2f prev_wp;
+ /* current waypoint (the one currently heading for) */
+ math::Vector2f next_wp(mission_item_triplet.current.lat, mission_item_triplet.current.lon);
- if (global_triplet.previous_valid) {
- prev_wp.setX(global_triplet.previous.lat / 1e7f);
- prev_wp.setY(global_triplet.previous.lon / 1e7f);
+ /* current waypoint (the one currently heading for) */
+ math::Vector2f curr_wp(mission_item_triplet.current.lat, mission_item_triplet.current.lon);
- } else {
- /*
- * No valid previous waypoint, go for the current wp.
- * This is automatically handled by the L1 library.
- */
- prev_wp.setX(global_triplet.current.lat / 1e7f);
- prev_wp.setY(global_triplet.current.lon / 1e7f);
-
- }
- // XXX add RTL switch
- if (global_triplet.current.nav_cmd == NAV_CMD_RETURN_TO_LAUNCH && _launch_valid) {
+ /* previous waypoint */
+ math::Vector2f prev_wp;
- math::Vector2f rtl_pos(_launch_lat, _launch_lon);
+ if (mission_item_triplet.previous_valid) {
+ prev_wp.setX(mission_item_triplet.previous.lat);
+ prev_wp.setY(mission_item_triplet.previous.lon);
- _l1_control.navigate_waypoints(rtl_pos, rtl_pos, current_position, ground_speed);
- _att_sp.roll_body = _l1_control.nav_roll();
- _att_sp.yaw_body = _l1_control.nav_bearing();
+ } else {
+ /*
+ * No valid previous waypoint, go for the current wp.
+ * This is automatically handled by the L1 library.
+ */
+ prev_wp.setX(mission_item_triplet.current.lat);
+ prev_wp.setY(mission_item_triplet.current.lon);
- _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _launch_alt, calculate_target_airspeed(_parameters.airspeed_trim),
- _airspeed.indicated_airspeed_m_s, eas2tas,
- false, math::radians(_parameters.pitch_limit_min),
- _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
- math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max));
+ }
- // XXX handle case when having arrived at home (loiter)
+ if (mission_item_triplet.current.nav_cmd == NAV_CMD_WAYPOINT || mission_item_triplet.current.nav_cmd == NAV_CMD_RETURN_TO_LAUNCH) {
+ /* waypoint is a plain navigation waypoint */
+ _l1_control.navigate_waypoints(prev_wp, curr_wp, current_position, ground_speed);
+ _att_sp.roll_body = _l1_control.nav_roll();
+ _att_sp.yaw_body = _l1_control.nav_bearing();
- } else if (global_triplet.current.nav_cmd == NAV_CMD_WAYPOINT) {
- /* waypoint is a plain navigation waypoint */
- _l1_control.navigate_waypoints(prev_wp, next_wp, current_position, ground_speed);
- _att_sp.roll_body = _l1_control.nav_roll();
- _att_sp.yaw_body = _l1_control.nav_bearing();
+ _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _mission_item_triplet.current.altitude, calculate_target_airspeed(_parameters.airspeed_trim),
+ _airspeed.indicated_airspeed_m_s, eas2tas,
+ false, math::radians(_parameters.pitch_limit_min),
+ _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
+ math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max));
- _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _global_triplet.current.altitude, calculate_target_airspeed(_parameters.airspeed_trim),
- _airspeed.indicated_airspeed_m_s, eas2tas,
- false, math::radians(_parameters.pitch_limit_min),
- _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
- math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max));
+ } else if (mission_item_triplet.current.nav_cmd == NAV_CMD_LOITER_TURN_COUNT ||
+ mission_item_triplet.current.nav_cmd == NAV_CMD_LOITER_TIME_LIMIT ||
+ mission_item_triplet.current.nav_cmd == NAV_CMD_LOITER_UNLIMITED) {
- } else if (global_triplet.current.nav_cmd == NAV_CMD_LOITER_TURN_COUNT ||
- global_triplet.current.nav_cmd == NAV_CMD_LOITER_TIME_LIMIT ||
- global_triplet.current.nav_cmd == NAV_CMD_LOITER_UNLIMITED) {
+ /* waypoint is a loiter waypoint */
+ _l1_control.navigate_loiter(curr_wp, current_position, mission_item_triplet.current.loiter_radius,
+ mission_item_triplet.current.loiter_direction, ground_speed);
+ _att_sp.roll_body = _l1_control.nav_roll();
+ _att_sp.yaw_body = _l1_control.nav_bearing();
- /* waypoint is a loiter waypoint */
- _l1_control.navigate_loiter(next_wp, current_position, global_triplet.current.loiter_radius,
- global_triplet.current.loiter_direction, ground_speed);
- _att_sp.roll_body = _l1_control.nav_roll();
- _att_sp.yaw_body = _l1_control.nav_bearing();
+ _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _mission_item_triplet.current.altitude, calculate_target_airspeed(_parameters.airspeed_trim),
+ _airspeed.indicated_airspeed_m_s, eas2tas,
+ false, math::radians(_parameters.pitch_limit_min),
+ _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
+ math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max));
- _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _global_triplet.current.altitude, calculate_target_airspeed(_parameters.airspeed_trim),
- _airspeed.indicated_airspeed_m_s, eas2tas,
- false, math::radians(_parameters.pitch_limit_min),
- _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
- math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max));
+ } else if (mission_item_triplet.current.nav_cmd == NAV_CMD_LAND) {
- } else if (global_triplet.current.nav_cmd == NAV_CMD_LAND) {
+ /* Horizontal landing control */
+ /* switch to heading hold for the last meters, continue heading hold after */
+ float wp_distance = get_distance_to_next_waypoint(current_position.getX(), current_position.getY(), curr_wp.getX(), curr_wp.getY());
+ //warnx("wp dist: %d, alt err: %d, noret: %s", (int)wp_distance, (int)altitude_error, (land_noreturn) ? "YES" : "NO");
+ const float heading_hold_distance = 15.0f;
+ if (wp_distance < heading_hold_distance || land_noreturn_horizontal) {
- /* switch to heading hold for the last meters, continue heading hold after */
+ /* heading hold, along the line connecting this and the last waypoint */
+
- float wp_distance = get_distance_to_next_waypoint(prev_wp.getX(), prev_wp.getY(), current_position.getX(), current_position.getY());
- //warnx("wp dist: %d, alt err: %d, noret: %s", (int)wp_distance, (int)altitude_error, (land_noreturn) ? "YES" : "NO");
- if (wp_distance < 15.0f || land_noreturn) {
+ // if (mission_item_triplet.previous_valid) {
+ // target_bearing = get_bearing_to_next_waypoint(prev_wp.getX(), prev_wp.getY(), next_wp.getX(), next_wp.getY());
+ // } else {
- /* heading hold, along the line connecting this and the last waypoint */
-
+ if (!land_noreturn_horizontal) //set target_bearing in first occurrence
+ target_bearing = _att.yaw;
+ //}
- // if (global_triplet.previous_valid) {
- // target_bearing = get_bearing_to_next_waypoint(prev_wp.getX(), prev_wp.getY(), next_wp.getX(), next_wp.getY());
- // } else {
+// warnx("NORET: %d, target_bearing: %d, yaw: %d", (int)land_noreturn_horizontal, (int)math::degrees(target_bearing), (int)math::degrees(_att.yaw));
- if (!land_noreturn)
- target_bearing = _att.yaw;
- //}
+ _l1_control.navigate_heading(target_bearing, _att.yaw, ground_speed);
- warnx("NORET: %d, target_bearing: %d, yaw: %d", (int)land_noreturn, (int)math::degrees(target_bearing), (int)math::degrees(_att.yaw));
+ /* limit roll motion to prevent wings from touching the ground first */
+ _att_sp.roll_body = math::constrain(_att_sp.roll_body, math::radians(-10.0f), math::radians(10.0f));
- _l1_control.navigate_heading(target_bearing, _att.yaw, ground_speed);
+ land_noreturn_horizontal = true;
- if (altitude_error > -5.0f)
- land_noreturn = true;
+ } else {
- } else {
+ /* normal navigation */
+ _l1_control.navigate_waypoints(prev_wp, curr_wp, current_position, ground_speed);
+ }
- /* normal navigation */
- _l1_control.navigate_waypoints(prev_wp, next_wp, current_position, ground_speed);
- }
+ _att_sp.roll_body = _l1_control.nav_roll();
+ _att_sp.yaw_body = _l1_control.nav_bearing();
- /* do not go down too early */
- if (wp_distance > 50.0f) {
- altitude_error = (_global_triplet.current.altitude + 25.0f) - _global_pos.alt;
- }
+ /* Vertical landing control */
+ //xxx: using the tecs altitude controller for slope control for now
- _att_sp.roll_body = _l1_control.nav_roll();
- _att_sp.yaw_body = _l1_control.nav_bearing();
+// /* do not go down too early */
+// if (wp_distance > 50.0f) {
+// altitude_error = (_global_triplet.current.altitude + 25.0f) - _global_pos.alt;
+// }
+ /* apply minimum pitch (flare) and limit roll if close to touch down, altitude error is negative (going down) */
+ // XXX this could make a great param
- /* apply minimum pitch (flare) and limit roll if close to touch down, altitude error is negative (going down) */
- // XXX this could make a great param
+ float flare_angle_rad = -math::radians(5.0f);//math::radians(mission_item_triplet.current.param1)
+ float land_pitch_min = math::radians(5.0f);
+ float throttle_land = _parameters.throttle_min + (_parameters.throttle_max - _parameters.throttle_min) * 0.1f;
+ float airspeed_land = 1.3f * _parameters.airspeed_min;
+ float airspeed_approach = 1.3f * _parameters.airspeed_min;
- float flare_angle_rad = math::radians(10.0f);//math::radians(global_triplet.current.param1)
- float land_pitch_min = math::radians(5.0f);
- float throttle_land = _parameters.throttle_min + (_parameters.throttle_max - _parameters.throttle_min) * 0.1f;
- float airspeed_land = _parameters.airspeed_min;
- float airspeed_approach = (_parameters.airspeed_min + _parameters.airspeed_trim) / 2.0f;
+ float landing_slope_angle_rad = math::radians(_parameters.land_slope_angle);
+ float flare_relative_alt = _parameters.land_flare_alt_relative;
+ float motor_lim_horizontal_distance = _parameters.land_thrust_lim_horizontal_distance;//be generous here as we currently have to rely on the user input for the waypoint
+ float L_wp_distance = get_distance_to_next_waypoint(prev_wp.getX(), prev_wp.getY(), curr_wp.getX(), curr_wp.getY()) * _parameters.land_slope_length;
+ float H1 = _parameters.land_H1_virt;
+ float H0 = flare_relative_alt + H1;
+ float d1 = flare_relative_alt/tanf(landing_slope_angle_rad);
+ float flare_constant = (H0 * d1)/flare_relative_alt;//-flare_length/(logf(H1/H0));
+ float flare_length = - logf(H1/H0) * flare_constant;//d1+20.0f;//-logf(0.01f/flare_relative_alt);
+ float horizontal_slope_displacement = (flare_length - d1);
+ float L_altitude = getLandingSlopeAbsoluteAltitude(L_wp_distance, _mission_item_triplet.current.altitude, landing_slope_angle_rad, horizontal_slope_displacement);
+ float landing_slope_alt_desired = getLandingSlopeAbsoluteAltitude(wp_distance, _mission_item_triplet.current.altitude, landing_slope_angle_rad, horizontal_slope_displacement);
- if (altitude_error > -4.0f) {
+ if ( (_global_pos.alt < _mission_item_triplet.current.altitude + flare_relative_alt) || land_noreturn_vertical) { //checking for land_noreturn to avoid unwanted climb out
- /* land with minimal speed */
+ /* land with minimal speed */
- /* force TECS to only control speed with pitch, altitude is only implicitely controlled now */
- _tecs.set_speed_weight(2.0f);
+// /* force TECS to only control speed with pitch, altitude is only implicitely controlled now */
+// _tecs.set_speed_weight(2.0f);
- _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _global_triplet.current.altitude, calculate_target_airspeed(airspeed_land),
- _airspeed.indicated_airspeed_m_s, eas2tas,
- false, flare_angle_rad,
- 0.0f, _parameters.throttle_max, throttle_land,
- math::radians(-10.0f), math::radians(15.0f));
+ /* kill the throttle if param requests it */
+ throttle_max = _parameters.throttle_max;
- /* kill the throttle if param requests it */
+ if (wp_distance < motor_lim_horizontal_distance || land_motor_lim) {
throttle_max = math::min(throttle_max, _parameters.throttle_land_max);
+ if (!land_motor_lim) {
+ land_motor_lim = true;
+ mavlink_log_info(_mavlink_fd, "#audio: Landing, limiting throttle");
+ }
- /* limit roll motion to prevent wings from touching the ground first */
- _att_sp.roll_body = math::constrain(_att_sp.roll_body, math::radians(-10.0f), math::radians(10.0f));
-
- } else if (wp_distance < 60.0f && altitude_error > -20.0f) {
-
- /* minimize speed to approach speed */
-
- _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _global_triplet.current.altitude, calculate_target_airspeed(airspeed_approach),
- _airspeed.indicated_airspeed_m_s, eas2tas,
- false, flare_angle_rad,
- _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
- math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max));
-
- } else {
+ }
- /* normal cruise speed */
+ float flare_curve_alt = _mission_item_triplet.current.altitude + H0 * expf(-math::max(0.0f, flare_length - wp_distance)/flare_constant) - H1;
- _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _global_triplet.current.altitude, calculate_target_airspeed(_parameters.airspeed_trim),
- _airspeed.indicated_airspeed_m_s, eas2tas,
- false, math::radians(_parameters.pitch_limit_min),
- _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
- math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max));
+ /* avoid climbout */
+ if (flare_curve_alt_last < flare_curve_alt && land_noreturn_vertical || land_stayonground)
+ {
+ flare_curve_alt = mission_item_triplet.current.altitude;
+ land_stayonground = true;
}
- } else if (global_triplet.current.nav_cmd == NAV_CMD_TAKEOFF) {
+ _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, flare_curve_alt, calculate_target_airspeed(airspeed_land),
+ _airspeed.indicated_airspeed_m_s, eas2tas,
+ false, flare_angle_rad,
+ 0.0f, throttle_max, throttle_land,
+ flare_angle_rad, math::radians(15.0f));
- _l1_control.navigate_waypoints(prev_wp, next_wp, current_position, ground_speed);
- _att_sp.roll_body = _l1_control.nav_roll();
- _att_sp.yaw_body = _l1_control.nav_bearing();
+ if (!land_noreturn_vertical) {
+ mavlink_log_info(_mavlink_fd, "#audio: Landing, flaring");
+ land_noreturn_vertical = true;
+ }
+ //warnx("Landing: flare, _global_pos.alt %.1f, flare_curve_alt %.1f, flare_curve_alt_last %.1f, flare_length %.1f, wp_distance %.1f", _global_pos.alt, flare_curve_alt, flare_curve_alt_last, flare_length, wp_distance);
- /* apply minimum pitch and limit roll if target altitude is not within 10 meters */
- if (altitude_error > 10.0f) {
+ flare_curve_alt_last = flare_curve_alt;
- /* enforce a minimum of 10 degrees pitch up on takeoff, or take parameter */
- _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _global_triplet.current.altitude, calculate_target_airspeed(_parameters.airspeed_min),
- _airspeed.indicated_airspeed_m_s, eas2tas,
- true, math::max(math::radians(global_triplet.current.param1), math::radians(10.0f)),
- _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
- math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max));
+ } else if (wp_distance < L_wp_distance) {
- /* limit roll motion to ensure enough lift */
- _att_sp.roll_body = math::constrain(_att_sp.roll_body, math::radians(-15.0f), math::radians(15.0f));
+ /* minimize speed to approach speed, stay on landing slope */
+ _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, landing_slope_alt_desired, calculate_target_airspeed(airspeed_approach),
+ _airspeed.indicated_airspeed_m_s, eas2tas,
+ false, flare_angle_rad,
+ _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
+ math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max));
+ //warnx("Landing: stay on slope, alt_desired: %.1f (wp_distance: %.1f), calculate_target_airspeed(airspeed_land) %.1f, horizontal_slope_displacement %.1f, d1 %.1f, flare_length %.1f", landing_slope_alt_desired, wp_distance, calculate_target_airspeed(airspeed_land), horizontal_slope_displacement, d1, flare_length);
- } else {
+ if (!land_onslope) {
- _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _global_triplet.current.altitude, calculate_target_airspeed(_parameters.airspeed_trim),
- _airspeed.indicated_airspeed_m_s, eas2tas,
- false, math::radians(_parameters.pitch_limit_min),
- _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
- math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max));
+ mavlink_log_info(_mavlink_fd, "#audio: Landing, on slope");
+ land_onslope = true;
}
- }
-
- // warnx("nav bearing: %8.4f bearing err: %8.4f target bearing: %8.4f", (double)_l1_control.nav_bearing(),
- // (double)_l1_control.bearing_error(), (double)_l1_control.target_bearing());
- // warnx("prev wp: %8.4f/%8.4f, next wp: %8.4f/%8.4f prev:%s", (double)prev_wp.getX(), (double)prev_wp.getY(),
- // (double)next_wp.getX(), (double)next_wp.getY(), (global_triplet.previous_valid) ? "valid" : "invalid");
- // XXX at this point we always want no loiter hold if a
- // mission is active
- _loiter_hold = false;
-
- } else if (_control_mode.flag_armed) {
-
- /* hold position, but only if armed, climb 20m in case this is engaged on ground level */
+ } else {
- // XXX rework with smarter state machine
+ /* intersect glide slope:
+ * if current position is higher or within 10m of slope follow the glide slope
+ * if current position is below slope -10m continue on maximum of previous wp altitude or L_altitude until the intersection with the slope
+ * */
+ float altitude_desired = _global_pos.alt;
+ if (_global_pos.alt > landing_slope_alt_desired - 10.0f) {
+ /* stay on slope */
+ altitude_desired = landing_slope_alt_desired;
+ //warnx("Landing: before L, stay on landing slope, alt_desired: %.1f (wp_distance: %.1f, L_wp_distance %.1f), calculate_target_airspeed(airspeed_land) %.1f, horizontal_slope_displacement %.1f", altitude_desired, wp_distance, L_wp_distance, calculate_target_airspeed(airspeed_land), horizontal_slope_displacement);
+ } else {
+ /* continue horizontally */
+ altitude_desired = math::max(_global_pos.alt, L_altitude);
+ //warnx("Landing: before L,continue at: %.4f, (landing_slope_alt_desired %.4f, wp_distance: %.4f, L_altitude: %.4f L_wp_distance: %.4f)", altitude_desired, landing_slope_alt_desired, wp_distance, L_altitude, L_wp_distance);
+ }
- if (!_loiter_hold) {
- _loiter_hold_lat = _global_pos.lat / 1e7f;
- _loiter_hold_lon = _global_pos.lon / 1e7f;
- _loiter_hold_alt = _global_pos.alt + 25.0f;
- _loiter_hold = true;
+ _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, altitude_desired, calculate_target_airspeed(airspeed_approach),
+ _airspeed.indicated_airspeed_m_s, eas2tas,
+ false, math::radians(_parameters.pitch_limit_min),
+ _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
+ math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max));
}
- altitude_error = _loiter_hold_alt - _global_pos.alt;
-
- math::Vector2f loiter_hold_pos(_loiter_hold_lat, _loiter_hold_lon);
+ } else if (mission_item_triplet.current.nav_cmd == NAV_CMD_TAKEOFF) {
- /* loiter around current position */
- _l1_control.navigate_loiter(loiter_hold_pos, current_position, _parameters.loiter_hold_radius,
- 1, ground_speed);
+ _l1_control.navigate_waypoints(prev_wp, curr_wp, current_position, ground_speed);
_att_sp.roll_body = _l1_control.nav_roll();
_att_sp.yaw_body = _l1_control.nav_bearing();
- /* climb with full throttle if the altitude error is bigger than 5 meters */
- bool climb_out = (altitude_error > 3);
+ /* apply minimum pitch and limit roll if target altitude is not within 10 meters */
+ if (altitude_error > 15.0f) {
- float min_pitch;
+ /* enforce a minimum of 10 degrees pitch up on takeoff, or take parameter */
+ _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _mission_item_triplet.current.altitude, calculate_target_airspeed(1.3f * _parameters.airspeed_min),
+ _airspeed.indicated_airspeed_m_s, eas2tas,
+ true, math::max(math::radians(mission_item_triplet.current.radius), math::radians(10.0f)),
+ _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
+ math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max));
- if (climb_out) {
- min_pitch = math::radians(20.0f);
+ /* limit roll motion to ensure enough lift */
+ _att_sp.roll_body = math::constrain(_att_sp.roll_body, math::radians(-15.0f), math::radians(15.0f));
} else {
- min_pitch = math::radians(_parameters.pitch_limit_min);
- }
- _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _loiter_hold_alt, calculate_target_airspeed(_parameters.airspeed_trim),
- _airspeed.indicated_airspeed_m_s, eas2tas,
- climb_out, min_pitch,
- _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
- math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max));
-
- if (climb_out) {
- /* limit roll motion to ensure enough lift */
- _att_sp.roll_body = math::constrain(_att_sp.roll_body, math::radians(-15.0f), math::radians(15.0f));
+ _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _mission_item_triplet.current.altitude, calculate_target_airspeed(_parameters.airspeed_trim),
+ _airspeed.indicated_airspeed_m_s, eas2tas,
+ false, math::radians(_parameters.pitch_limit_min),
+ _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
+ math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max));
}
}
+ // warnx("nav bearing: %8.4f bearing err: %8.4f target bearing: %8.4f", (double)_l1_control.nav_bearing(),
+ // (double)_l1_control.bearing_error(), (double)_l1_control.target_bearing());
+ // warnx("prev wp: %8.4f/%8.4f, next wp: %8.4f/%8.4f prev:%s", (double)prev_wp.getX(), (double)prev_wp.getY(),
+ // (double)next_wp.getX(), (double)next_wp.getY(), (mission_item_triplet.previous_valid) ? "valid" : "invalid");
+
+ // XXX at this point we always want no loiter hold if a
+ // mission is active
+ _loiter_hold = false;
+
/* reset land state */
- if (global_triplet.current.nav_cmd != NAV_CMD_LAND) {
- land_noreturn = false;
+ if (mission_item_triplet.current.nav_cmd != NAV_CMD_LAND) {
+ land_noreturn_horizontal = false;
+ land_noreturn_vertical = false;
+ land_stayonground = false;
+ land_motor_lim = false;
+ land_onslope = false;
}
if (was_circle_mode && !_l1_control.circle_mode()) {
@@ -1018,7 +1108,7 @@ FixedwingPositionControl::task_main()
* do subscriptions
*/
_global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position));
- _global_set_triplet_sub = orb_subscribe(ORB_ID(vehicle_global_position_set_triplet));
+ _mission_item_triplet_sub = orb_subscribe(ORB_ID(mission_item_triplet));
_att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
_accel_sub = orb_subscribe(ORB_ID(sensor_accel));
_control_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode));
@@ -1080,6 +1170,11 @@ FixedwingPositionControl::task_main()
/* only run controller if position changed */
if (fds[1].revents & POLLIN) {
+ /* XXX Hack to get mavlink output going */
+ if (_mavlink_fd < 0) {
+ /* try to open the mavlink log device every once in a while */
+ _mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
+ }
static uint64_t last_run = 0;
float deltaT = (hrt_absolute_time() - last_run) / 1000000.0f;
@@ -1108,7 +1203,7 @@ FixedwingPositionControl::task_main()
* Attempt to control position, on success (= sensors present and not in manual mode),
* publish setpoint.
*/
- if (control_position(current_position, ground_speed, _global_triplet)) {
+ if (control_position(current_position, ground_speed, _mission_item_triplet)) {
_att_sp.timestamp = hrt_absolute_time();
/* lazily publish the setpoint only once available */
@@ -1121,7 +1216,8 @@ FixedwingPositionControl::task_main()
_attitude_sp_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &_att_sp);
}
- float turn_distance = _l1_control.switch_distance(_global_triplet.current.turn_distance_xy);
+ /* XXX check if radius makes sense here */
+ float turn_distance = _l1_control.switch_distance(_mission_item_triplet.current.radius);
/* lazily publish navigation capabilities */
if (turn_distance != _nav_capabilities.turn_distance && turn_distance > 0) {
diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c
index 3bb872405..10a0c00fc 100644
--- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c
+++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c
@@ -111,3 +111,12 @@ PARAM_DEFINE_FLOAT(FW_T_PTCH_DAMP, 0.0f);
PARAM_DEFINE_FLOAT(FW_T_SINK_MAX, 5.0f);
+
+PARAM_DEFINE_FLOAT(FW_T_HRATE_P, 0.05f);
+PARAM_DEFINE_FLOAT(FW_T_SRATE_P, 0.05f);
+
+PARAM_DEFINE_FLOAT(FW_LND_ANG, 10.0f);
+PARAM_DEFINE_FLOAT(FW_LND_SLLR, 0.9f);
+PARAM_DEFINE_FLOAT(FW_LND_HVIRT, 10.0f);
+PARAM_DEFINE_FLOAT(FW_LND_FLALT, 15.0f);
+PARAM_DEFINE_FLOAT(FW_LND_TLDIST, 30.0f);
diff --git a/src/modules/mavlink/mavlink.c b/src/modules/mavlink/mavlink.c
index 7c10e297b..2ec00a9bc 100644
--- a/src/modules/mavlink/mavlink.c
+++ b/src/modules/mavlink/mavlink.c
@@ -74,6 +74,8 @@
#include "waypoints.h"
#include "mavlink_parameters.h"
+#include <uORB/topics/mission_result.h>
+
/* define MAVLink specific parameters */
PARAM_DEFINE_INT32(MAV_SYS_ID, 1);
PARAM_DEFINE_INT32(MAV_COMP_ID, 50);
@@ -644,6 +646,10 @@ int mavlink_thread_main(int argc, char *argv[])
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_MANUAL_CONTROL, 10000);
}
+ int mission_result_sub = orb_subscribe(ORB_ID(mission_result));
+ struct mission_result_s mission_result;
+ memset(&mission_result, 0, sizeof(mission_result));
+
thread_running = true;
/* arm counter to go off immediately */
@@ -690,6 +696,17 @@ int mavlink_thread_main(int argc, char *argv[])
lowspeed_counter++;
+ bool updated;
+ orb_check(mission_result_sub, &updated);
+
+ if (updated) {
+ orb_copy(ORB_ID(mission_result), mission_result_sub, &mission_result);
+
+ if (mission_result.mission_reached) {
+ mavlink_wpm_send_waypoint_reached((uint16_t)mission_result.mission_index);
+ }
+ }
+
mavlink_waypoint_eventloop(mavlink_missionlib_get_system_timestamp(), &global_pos, &local_pos, &nav_cap);
/* sleep quarter the time */
diff --git a/src/modules/mavlink/missionlib.c b/src/modules/mavlink/missionlib.c
index 124b3b2ae..5845429db 100644
--- a/src/modules/mavlink/missionlib.c
+++ b/src/modules/mavlink/missionlib.c
@@ -206,7 +206,7 @@ void mavlink_missionlib_current_waypoint_changed(uint16_t index, float param1,
float param6_lon_y, float param7_alt_z, uint8_t frame, uint16_t command)
{
static orb_advert_t global_position_setpoint_pub = -1;
- static orb_advert_t global_position_set_triplet_pub = -1;
+ // static orb_advert_t global_position_set_triplet_pub = -1;
static orb_advert_t local_position_setpoint_pub = -1;
static unsigned last_waypoint_index = -1;
char buf[50] = {0};
@@ -234,10 +234,10 @@ void mavlink_missionlib_current_waypoint_changed(uint16_t index, float param1,
/* fill triplet: previous, current, next waypoint */
- struct vehicle_global_position_set_triplet_s triplet;
+ // struct vehicle_global_position_set_triplet_s triplet;
/* current waypoint is same as sp */
- memcpy(&(triplet.current), &sp, sizeof(sp));
+ // memcpy(&(triplet.current), &sp, sizeof(sp));
/*
* Check if previous WP (in mission, not in execution order)
@@ -291,48 +291,48 @@ void mavlink_missionlib_current_waypoint_changed(uint16_t index, float param1,
/* populate last and next */
- triplet.previous_valid = false;
- triplet.next_valid = false;
-
- if (last_setpoint_valid) {
- triplet.previous_valid = true;
- struct vehicle_global_position_setpoint_s sp;
- sp.lat = wpm->waypoints[last_setpoint_index].x * 1e7f;
- sp.lon = wpm->waypoints[last_setpoint_index].y * 1e7f;
- sp.altitude = wpm->waypoints[last_setpoint_index].z;
- sp.altitude_is_relative = false;
- sp.yaw = _wrap_pi(wpm->waypoints[last_setpoint_index].param4 / 180.0f * M_PI_F);
- set_special_fields(wpm->waypoints[last_setpoint_index].param1,
- wpm->waypoints[last_setpoint_index].param2,
- wpm->waypoints[last_setpoint_index].param3,
- wpm->waypoints[last_setpoint_index].param4,
- wpm->waypoints[last_setpoint_index].command, &sp);
- memcpy(&(triplet.previous), &sp, sizeof(sp));
- }
-
- if (next_setpoint_valid) {
- triplet.next_valid = true;
- struct vehicle_global_position_setpoint_s sp;
- sp.lat = wpm->waypoints[next_setpoint_index].x * 1e7f;
- sp.lon = wpm->waypoints[next_setpoint_index].y * 1e7f;
- sp.altitude = wpm->waypoints[next_setpoint_index].z;
- sp.altitude_is_relative = false;
- sp.yaw = _wrap_pi(wpm->waypoints[next_setpoint_index].param4 / 180.0f * M_PI_F);
- set_special_fields(wpm->waypoints[next_setpoint_index].param1,
- wpm->waypoints[next_setpoint_index].param2,
- wpm->waypoints[next_setpoint_index].param3,
- wpm->waypoints[next_setpoint_index].param4,
- wpm->waypoints[next_setpoint_index].command, &sp);
- memcpy(&(triplet.next), &sp, sizeof(sp));
- }
+ // triplet.previous_valid = false;
+ // triplet.next_valid = false;
+
+ // if (last_setpoint_valid) {
+ // triplet.previous_valid = true;
+ // struct vehicle_global_position_setpoint_s sp;
+ // sp.lat = wpm->waypoints[last_setpoint_index].x * 1e7f;
+ // sp.lon = wpm->waypoints[last_setpoint_index].y * 1e7f;
+ // sp.altitude = wpm->waypoints[last_setpoint_index].z;
+ // sp.altitude_is_relative = false;
+ // sp.yaw = _wrap_pi(wpm->waypoints[last_setpoint_index].param4 / 180.0f * M_PI_F);
+ // set_special_fields(wpm->waypoints[last_setpoint_index].param1,
+ // wpm->waypoints[last_setpoint_index].param2,
+ // wpm->waypoints[last_setpoint_index].param3,
+ // wpm->waypoints[last_setpoint_index].param4,
+ // wpm->waypoints[last_setpoint_index].command, &sp);
+ // memcpy(&(triplet.previous), &sp, sizeof(sp));
+ // }
+
+ // if (next_setpoint_valid) {
+ // triplet.next_valid = true;
+ // struct vehicle_global_position_setpoint_s sp;
+ // sp.lat = wpm->waypoints[next_setpoint_index].x * 1e7f;
+ // sp.lon = wpm->waypoints[next_setpoint_index].y * 1e7f;
+ // sp.altitude = wpm->waypoints[next_setpoint_index].z;
+ // sp.altitude_is_relative = false;
+ // sp.yaw = _wrap_pi(wpm->waypoints[next_setpoint_index].param4 / 180.0f * M_PI_F);
+ // set_special_fields(wpm->waypoints[next_setpoint_index].param1,
+ // wpm->waypoints[next_setpoint_index].param2,
+ // wpm->waypoints[next_setpoint_index].param3,
+ // wpm->waypoints[next_setpoint_index].param4,
+ // wpm->waypoints[next_setpoint_index].command, &sp);
+ // memcpy(&(triplet.next), &sp, sizeof(sp));
+ // }
/* Initialize triplet publication if necessary */
- if (global_position_set_triplet_pub < 0) {
- global_position_set_triplet_pub = orb_advertise(ORB_ID(vehicle_global_position_set_triplet), &triplet);
+ // if (global_position_set_triplet_pub < 0) {
+ // global_position_set_triplet_pub = orb_advertise(ORB_ID(vehicle_global_position_set_triplet), &triplet);
- } else {
- orb_publish(ORB_ID(vehicle_global_position_set_triplet), global_position_set_triplet_pub, &triplet);
- }
+ // } else {
+ // orb_publish(ORB_ID(vehicle_global_position_set_triplet), global_position_set_triplet_pub, &triplet);
+ // }
sprintf(buf, "[mp] WP#%i lat: % 3.6f/lon % 3.6f/alt % 4.6f/hdg %3.4f\n", (int)index, (double)param5_lat_x, (double)param6_lon_y, (double)param7_alt_z, (double)param4);
diff --git a/src/modules/mavlink/orb_topics.h b/src/modules/mavlink/orb_topics.h
index 91773843b..2cba25338 100644
--- a/src/modules/mavlink/orb_topics.h
+++ b/src/modules/mavlink/orb_topics.h
@@ -52,7 +52,7 @@
#include <uORB/topics/vehicle_local_position_setpoint.h>
#include <uORB/topics/vehicle_vicon_position.h>
#include <uORB/topics/vehicle_global_position_setpoint.h>
-#include <uORB/topics/vehicle_global_position_set_triplet.h>
+#include <uORB/topics/mission_item_triplet.h>
#include <uORB/topics/vehicle_attitude_setpoint.h>
#include <uORB/topics/vehicle_rates_setpoint.h>
#include <uORB/topics/vehicle_control_mode.h>
diff --git a/src/modules/mavlink/waypoints.c b/src/modules/mavlink/waypoints.c
index 7e4a2688f..809900d7d 100644
--- a/src/modules/mavlink/waypoints.c
+++ b/src/modules/mavlink/waypoints.c
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2008-2012 PX4 Development Team. All rights reserved.
+ * Copyright (C) 2008-2013 PX4 Development Team. All rights reserved.
* Author: @author Petri Tanskanen <petri.tanskanen@inf.ethz.ch>
* @author Lorenz Meier <lm@inf.ethz.ch>
* @author Thomas Gubler <thomasgubler@student.ethz.ch>
@@ -49,6 +49,9 @@
#include "missionlib.h"
#include "waypoints.h"
#include "util.h"
+#include <uORB/uORB.h>
+#include <uORB/topics/mission.h>
+
#ifndef FM_PI
#define FM_PI 3.1415926535897932384626433832795f
@@ -57,11 +60,77 @@
bool debug = false;
bool verbose = false;
+orb_advert_t mission_pub = -1;
+struct mission_s mission;
+
+#define NUM_MISSIONS_SUPPORTED 10
-#define MAVLINK_WPM_NO_PRINTF
+//#define MAVLINK_WPM_NO_PRINTF
+#define MAVLINK_WPM_VERBOSE 1
uint8_t mavlink_wpm_comp_id = MAV_COMP_ID_MISSIONPLANNER;
+int map_mavlink_mission_item_to_mission_item(const mavlink_mission_item_t *mavlink_mission_item, struct mission_item_s *mission_item)
+{
+ /* only support global waypoints for now */
+ switch (mavlink_mission_item->frame) {
+ case MAV_FRAME_GLOBAL:
+ mission_item->lat = (double)mavlink_mission_item->x;
+ mission_item->lon = (double)mavlink_mission_item->y;
+ mission_item->altitude = mavlink_mission_item->z;
+ mission_item->altitude_is_relative = false;
+ break;
+
+ case MAV_FRAME_GLOBAL_RELATIVE_ALT:
+ mission_item->lat = (double)mavlink_mission_item->x;
+ mission_item->lon = (double)mavlink_mission_item->y;
+ mission_item->altitude = mavlink_mission_item->z;
+ mission_item->altitude_is_relative = true;
+ break;
+
+ case MAV_FRAME_LOCAL_NED:
+ case MAV_FRAME_LOCAL_ENU:
+ return MAV_MISSION_UNSUPPORTED_FRAME;
+ case MAV_FRAME_MISSION:
+ default:
+ return MAV_MISSION_ERROR;
+ }
+
+ mission_item->yaw = mavlink_mission_item->param4*M_DEG_TO_RAD_F;
+ mission_item->loiter_radius = fabsf(mavlink_mission_item->param3);
+ mission_item->loiter_direction = (mavlink_mission_item->param3 > 0) ? 1 : -1; /* 1 if positive CW, -1 if negative CCW */
+ mission_item->nav_cmd = mavlink_mission_item->command;
+ mission_item->radius = mavlink_mission_item->param1;
+ mission_item->time_inside = mavlink_mission_item->param2 / 1e3f; /* from milliseconds to seconds */
+ mission_item->autocontinue = mavlink_mission_item->autocontinue;
+ mission_item->index = mavlink_mission_item->seq;
+
+ return OK;
+}
+
+int map_mission_item_to_mavlink_mission_item(const struct mission_item_s *mission_item, mavlink_mission_item_t *mavlink_mission_item)
+{
+ if (mission_item->altitude_is_relative) {
+ mavlink_mission_item->frame = MAV_FRAME_GLOBAL;
+ } else {
+ mavlink_mission_item->frame = MAV_FRAME_GLOBAL_RELATIVE_ALT;
+ }
+
+ mavlink_mission_item->x = (float)mission_item->lat;
+ mavlink_mission_item->y = (float)mission_item->lon;
+ mavlink_mission_item->z = mission_item->altitude;
+
+ mavlink_mission_item->param4 = mission_item->yaw*M_RAD_TO_DEG_F;
+ mavlink_mission_item->param3 = mission_item->loiter_radius*(float)mission_item->loiter_direction;
+ mavlink_mission_item->command = mission_item->nav_cmd;
+ mavlink_mission_item->param1 = mission_item->radius;
+ mavlink_mission_item->param2 = mission_item->time_inside * 1e3f; /* from seconds to milliseconds */
+ mavlink_mission_item->autocontinue = mission_item->autocontinue;
+ mavlink_mission_item->seq = mission_item->index;
+
+ return OK;
+}
+
void mavlink_wpm_init(mavlink_wpm_storage *state)
{
// Set all waypoints to zero
@@ -73,16 +142,23 @@ void mavlink_wpm_init(mavlink_wpm_storage *state)
state->current_partner_sysid = 0;
state->current_partner_compid = 0;
state->timestamp_lastaction = 0;
- state->timestamp_last_send_setpoint = 0;
+ // state->timestamp_last_send_setpoint = 0;
state->timeout = MAVLINK_WPM_PROTOCOL_TIMEOUT_DEFAULT;
- state->delay_setpoint = MAVLINK_WPM_SETPOINT_DELAY_DEFAULT;
- state->idle = false; ///< indicates if the system is following the waypoints or is waiting
- state->current_active_wp_id = -1; ///< id of current waypoint
- state->yaw_reached = false; ///< boolean for yaw attitude reached
- state->pos_reached = false; ///< boolean for position reached
- state->timestamp_lastoutside_orbit = 0;///< timestamp when the MAV was last outside the orbit or had the wrong yaw value
- state->timestamp_firstinside_orbit = 0;///< timestamp when the MAV was the first time after a waypoint change inside the orbit and had the correct yaw value
-
+ // state->delay_setpoint = MAVLINK_WPM_SETPOINT_DELAY_DEFAULT;
+ // state->idle = false; ///< indicates if the system is following the waypoints or is waiting
+ // state->current_active_wp_id = -1; ///< id of current waypoint
+ // state->yaw_reached = false; ///< boolean for yaw attitude reached
+ // state->pos_reached = false; ///< boolean for position reached
+ // state->timestamp_lastoutside_orbit = 0;///< timestamp when the MAV was last outside the orbit or had the wrong yaw value
+ // state->timestamp_firstinside_orbit = 0;///< timestamp when the MAV was the first time after a waypoint change inside the orbit and had the correct yaw value
+
+ mission.count = 0;
+ mission.items = (struct mission_item_s*)malloc(sizeof(struct mission_item_s) * NUM_MISSIONS_SUPPORTED);
+ if (!mission.items) {
+ mission.count = 0;
+ /* XXX reject waypoints if this fails */
+ warnx("no free RAM to allocate mission, rejecting any waypoints");
+ }
}
/*
@@ -102,16 +178,15 @@ void mavlink_wpm_send_waypoint_ack(uint8_t sysid, uint8_t compid, uint8_t type)
// FIXME TIMING usleep(paramClient->getParamValue("PROTOCOLDELAY"));
- if (MAVLINK_WPM_TEXT_FEEDBACK) {
-#ifdef MAVLINK_WPM_NO_PRINTF
- mavlink_missionlib_send_gcs_string("Sent waypoint ACK");
-#else
+// if (MAVLINK_WPM_TEXT_FEEDBACK) {
+// #ifdef MAVLINK_WPM_NO_PRINTF
+// mavlink_missionlib_send_gcs_string("Sent waypoint ACK");
+// #else
- if (MAVLINK_WPM_VERBOSE) printf("Sent waypoint ack (%u) to ID %u\n", wpa.type, wpa.target_system);
+// if (MAVLINK_WPM_VERBOSE) printf("Sent waypoint ack (%u) to ID %u\n", wpa.type, wpa.target_system);
-#endif
- mavlink_missionlib_send_gcs_string("Sent waypoint ACK");
- }
+// #endif
+// }
}
/*
@@ -161,7 +236,7 @@ void mavlink_wpm_send_setpoint(uint16_t seq)
cur->param2, cur->param3, cur->param4, cur->x,
cur->y, cur->z, cur->frame, cur->command);
- wpm->timestamp_last_send_setpoint = mavlink_missionlib_get_system_timestamp();
+ // wpm->timestamp_last_send_setpoint = mavlink_missionlib_get_system_timestamp();
} else {
if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_missionlib_send_gcs_string("ERROR: Waypoint index out of bounds\n"); //// if (verbose) // printf("ERROR: index out of bounds\n");
@@ -175,7 +250,7 @@ void mavlink_wpm_send_waypoint_count(uint8_t sysid, uint8_t compid, uint16_t cou
wpc.target_system = wpm->current_partner_sysid;
wpc.target_component = wpm->current_partner_compid;
- wpc.count = count;
+ wpc.count = mission.count;
mavlink_msg_mission_count_encode(mavlink_system.sysid, mavlink_wpm_comp_id, &msg, &wpc);
mavlink_missionlib_send_message(&msg);
@@ -185,11 +260,12 @@ void mavlink_wpm_send_waypoint_count(uint8_t sysid, uint8_t compid, uint16_t cou
// FIXME TIMING usleep(paramClient->getParamValue("PROTOCOLDELAY"));
}
-void mavlink_wpm_send_waypoint(uint8_t sysid, uint8_t compid, uint16_t seq)
+void mavlink_wpm_send_waypoint(uint8_t sysid, uint8_t compid, mavlink_mission_item_t *wp)
{
- if (seq < wpm->size) {
+
+ // if (seq < wpm->size) {
mavlink_message_t msg;
- mavlink_mission_item_t *wp = &(wpm->waypoints[seq]);
+ // mavlink_mission_item_t *wp = &(wpm->waypoints[seq]);
wp->target_system = wpm->current_partner_sysid;
wp->target_component = wpm->current_partner_compid;
mavlink_msg_mission_item_encode(mavlink_system.sysid, mavlink_wpm_comp_id, &msg, wp);
@@ -199,9 +275,9 @@ void mavlink_wpm_send_waypoint(uint8_t sysid, uint8_t compid, uint16_t seq)
// FIXME TIMING usleep(paramClient->getParamValue("PROTOCOLDELAY"));
- } else {
- if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_missionlib_send_gcs_string("ERROR: Waypoint index out of bounds\n");
- }
+ // } else {
+ // if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_missionlib_send_gcs_string("ERROR: Waypoint index out of bounds\n");
+ // }
}
void mavlink_wpm_send_waypoint_request(uint8_t sysid, uint8_t compid, uint16_t seq)
@@ -246,250 +322,191 @@ void mavlink_wpm_send_waypoint_reached(uint16_t seq)
// FIXME TIMING usleep(paramClient->getParamValue("PROTOCOLDELAY"));
}
-/*
- * Calculate distance in global frame.
- *
- * The distance calculation is based on the WGS84 geoid (GPS)
- */
-float mavlink_wpm_distance_to_point_global_wgs84(uint16_t seq, float lat, float lon, float alt, float *dist_xy, float *dist_z)
-{
-
- if (seq < wpm->size) {
- mavlink_mission_item_t *wp = &(wpm->waypoints[seq]);
-
- double current_x_rad = wp->x / 180.0 * M_PI;
- double current_y_rad = wp->y / 180.0 * M_PI;
- double x_rad = lat / 180.0 * M_PI;
- double y_rad = lon / 180.0 * M_PI;
- double d_lat = x_rad - current_x_rad;
- double d_lon = y_rad - current_y_rad;
+// void check_waypoints_reached(uint64_t now, const struct vehicle_global_position_s *global_pos, struct vehicle_local_position_s *local_pos, float turn_distance)
+// {
+// static uint16_t counter;
- double a = sin(d_lat / 2.0) * sin(d_lat / 2.0) + sin(d_lon / 2.0) * sin(d_lon / 2.0f) * cos(current_x_rad) * cos(x_rad);
- double c = 2 * atan2(sqrt(a), sqrt(1 - a));
+// if ((!global_pos->valid && !local_pos->xy_valid) ||
+// /* no waypoint */
+// wpm->size == 0) {
+// /* nothing to check here, return */
+// return;
+// }
- const double radius_earth = 6371000.0;
+// if (wpm->current_active_wp_id < wpm->size) {
- float dxy = radius_earth * c;
- float dz = alt - wp->z;
+// float orbit;
+// if (wpm->waypoints[wpm->current_active_wp_id].command == (int)MAV_CMD_NAV_WAYPOINT) {
- *dist_xy = fabsf(dxy);
- *dist_z = fabsf(dz);
+// orbit = wpm->waypoints[wpm->current_active_wp_id].param2;
- return sqrtf(dxy * dxy + dz * dz);
+// } else if (wpm->waypoints[wpm->current_active_wp_id].command == (int)MAV_CMD_NAV_LOITER_TURNS ||
+// wpm->waypoints[wpm->current_active_wp_id].command == (int)MAV_CMD_NAV_LOITER_TIME ||
+// wpm->waypoints[wpm->current_active_wp_id].command == (int)MAV_CMD_NAV_LOITER_UNLIM) {
- } else {
- return -1.0f;
- }
-
-}
+// orbit = wpm->waypoints[wpm->current_active_wp_id].param3;
+// } else {
-/*
- * Calculate distance in local frame (NED)
- */
-float mavlink_wpm_distance_to_point_local(uint16_t seq, float x, float y, float z, float *dist_xy, float *dist_z)
-{
- if (seq < wpm->size) {
- mavlink_mission_item_t *cur = &(wpm->waypoints[seq]);
-
- float dx = (cur->x - x);
- float dy = (cur->y - y);
- float dz = (cur->z - z);
-
- *dist_xy = sqrtf(dx * dx + dy * dy);
- *dist_z = fabsf(dz);
-
- return sqrtf(dx * dx + dy * dy + dz * dz);
-
- } else {
- return -1.0f;
- }
-}
-
-void check_waypoints_reached(uint64_t now, const struct vehicle_global_position_s *global_pos, struct vehicle_local_position_s *local_pos, float turn_distance)
-{
- static uint16_t counter;
-
- if ((!global_pos->valid && !local_pos->xy_valid) ||
- /* no waypoint */
- wpm->size == 0) {
- /* nothing to check here, return */
- return;
- }
-
- if (wpm->current_active_wp_id < wpm->size) {
-
- float orbit;
- if (wpm->waypoints[wpm->current_active_wp_id].command == (int)MAV_CMD_NAV_WAYPOINT) {
-
- orbit = wpm->waypoints[wpm->current_active_wp_id].param2;
-
- } else if (wpm->waypoints[wpm->current_active_wp_id].command == (int)MAV_CMD_NAV_LOITER_TURNS ||
- wpm->waypoints[wpm->current_active_wp_id].command == (int)MAV_CMD_NAV_LOITER_TIME ||
- wpm->waypoints[wpm->current_active_wp_id].command == (int)MAV_CMD_NAV_LOITER_UNLIM) {
-
- orbit = wpm->waypoints[wpm->current_active_wp_id].param3;
- } else {
-
- // XXX set default orbit via param
- orbit = 15.0f;
- }
-
- /* keep vertical orbit */
- float vertical_switch_distance = orbit;
-
- /* Take the larger turn distance - orbit or turn_distance */
- if (orbit < turn_distance)
- orbit = turn_distance;
-
- int coordinate_frame = wpm->waypoints[wpm->current_active_wp_id].frame;
- float dist = -1.0f;
-
- float dist_xy = -1.0f;
- float dist_z = -1.0f;
-
- if (coordinate_frame == (int)MAV_FRAME_GLOBAL) {
- dist = mavlink_wpm_distance_to_point_global_wgs84(wpm->current_active_wp_id, (float)global_pos->lat * 1e-7f, (float)global_pos->lon * 1e-7f, global_pos->alt, &dist_xy, &dist_z);
-
- } else if (coordinate_frame == (int)MAV_FRAME_GLOBAL_RELATIVE_ALT) {
- dist = mavlink_wpm_distance_to_point_global_wgs84(wpm->current_active_wp_id, (float)global_pos->lat * 1e-7f, (float)global_pos->lon * 1e-7f, global_pos->relative_alt, &dist_xy, &dist_z);
-
- } else if (coordinate_frame == (int)MAV_FRAME_LOCAL_ENU || coordinate_frame == (int)MAV_FRAME_LOCAL_NED) {
- dist = mavlink_wpm_distance_to_point_local(wpm->current_active_wp_id, local_pos->x, local_pos->y, local_pos->z, &dist_xy, &dist_z);
-
- } else if (coordinate_frame == (int)MAV_FRAME_MISSION) {
- /* Check if conditions of mission item are satisfied */
- // XXX TODO
- }
-
- if (dist >= 0.f && dist_xy <= orbit && dist_z >= 0.0f && dist_z <= vertical_switch_distance) {
- wpm->pos_reached = true;
- }
-
- // check if required yaw reached
- float yaw_sp = _wrap_pi(wpm->waypoints[wpm->current_active_wp_id].param4 / 180.0f * FM_PI);
- float yaw_err = _wrap_pi(yaw_sp - local_pos->yaw);
- if (fabsf(yaw_err) < 0.05f) {
- wpm->yaw_reached = true;
- }
- }
-
- //check if the current waypoint was reached
- if (wpm->pos_reached && /*wpm->yaw_reached &&*/ !wpm->idle) {
- if (wpm->current_active_wp_id < wpm->size) {
- mavlink_mission_item_t *cur_wp = &(wpm->waypoints[wpm->current_active_wp_id]);
-
- if (wpm->timestamp_firstinside_orbit == 0) {
- // Announce that last waypoint was reached
- mavlink_wpm_send_waypoint_reached(cur_wp->seq);
- wpm->timestamp_firstinside_orbit = now;
- }
+// // XXX set default orbit via param
+// orbit = 15.0f;
+// }
- // check if the MAV was long enough inside the waypoint orbit
- //if (now-timestamp_lastoutside_orbit > (cur_wp->hold_time*1000))
+// /* keep vertical orbit */
+// float vertical_switch_distance = orbit;
- bool time_elapsed = false;
-
- if (now - wpm->timestamp_firstinside_orbit >= cur_wp->param1 * 1000 * 1000) {
- time_elapsed = true;
- } else if (cur_wp->command == (int)MAV_CMD_NAV_TAKEOFF) {
- time_elapsed = true;
- }
-
- if (time_elapsed) {
-
- /* safeguard against invalid missions with last wp autocontinue on */
- if (wpm->current_active_wp_id == wpm->size - 1) {
- /* stop handling missions here */
- cur_wp->autocontinue = false;
- }
-
- if (cur_wp->autocontinue) {
-
- cur_wp->current = 0;
-
- float navigation_lat = -1.0f;
- float navigation_lon = -1.0f;
- float navigation_alt = -1.0f;
- int navigation_frame = -1;
-
- /* initialize to current position in case we don't find a suitable navigation waypoint */
- if (global_pos->valid) {
- navigation_lat = global_pos->lat/1e7;
- navigation_lon = global_pos->lon/1e7;
- navigation_alt = global_pos->alt;
- navigation_frame = MAV_FRAME_GLOBAL;
- } else if (local_pos->xy_valid && local_pos->z_valid) {
- navigation_lat = local_pos->x;
- navigation_lon = local_pos->y;
- navigation_alt = local_pos->z;
- navigation_frame = MAV_FRAME_LOCAL_NED;
- }
-
- /* guard against missions without final land waypoint */
- /* only accept supported navigation waypoints, skip unknown ones */
- do {
-
- /* pick up the last valid navigation waypoint, this will be one we hold on to after the mission */
- if (wpm->waypoints[wpm->current_active_wp_id].command == (int)MAV_CMD_NAV_WAYPOINT ||
- wpm->waypoints[wpm->current_active_wp_id].command == (int)MAV_CMD_NAV_LOITER_TURNS ||
- wpm->waypoints[wpm->current_active_wp_id].command == (int)MAV_CMD_NAV_LOITER_TIME ||
- wpm->waypoints[wpm->current_active_wp_id].command == (int)MAV_CMD_NAV_LOITER_UNLIM ||
- wpm->waypoints[wpm->current_active_wp_id].command == (int)MAV_CMD_NAV_TAKEOFF) {
-
- /* this is a navigation waypoint */
- navigation_frame = cur_wp->frame;
- navigation_lat = cur_wp->x;
- navigation_lon = cur_wp->y;
- navigation_alt = cur_wp->z;
- }
-
- if (wpm->current_active_wp_id == wpm->size - 1) {
-
- /* if we're not landing at the last nav waypoint, we're falling back to loiter */
- if (wpm->waypoints[wpm->current_active_wp_id].command != (int)MAV_CMD_NAV_LAND) {
- /* the last waypoint was reached, if auto continue is
- * activated AND it is NOT a land waypoint, keep the system loitering there.
- */
- cur_wp->command = MAV_CMD_NAV_LOITER_UNLIM;
- cur_wp->param3 = 20.0f; // XXX magic number 20 m loiter radius
- cur_wp->frame = navigation_frame;
- cur_wp->x = navigation_lat;
- cur_wp->y = navigation_lon;
- cur_wp->z = navigation_alt;
- }
-
- /* we risk an endless loop for missions without navigation waypoints, abort. */
- break;
-
- } else {
- if ((uint16_t)(wpm->current_active_wp_id + 1) < wpm->size)
- wpm->current_active_wp_id++;
- }
+// /* Take the larger turn distance - orbit or turn_distance */
+// if (orbit < turn_distance)
+// orbit = turn_distance;
+
+// int coordinate_frame = wpm->waypoints[wpm->current_active_wp_id].frame;
+// float dist = -1.0f;
+
+// float dist_xy = -1.0f;
+// float dist_z = -1.0f;
+
+// if (coordinate_frame == (int)MAV_FRAME_GLOBAL) {
+// dist = mavlink_wpm_distance_to_point_global_wgs84(wpm->current_active_wp_id, (float)global_pos->lat * 1e-7f, (float)global_pos->lon * 1e-7f, global_pos->alt, &dist_xy, &dist_z);
+
+// } else if (coordinate_frame == (int)MAV_FRAME_GLOBAL_RELATIVE_ALT) {
+// dist = mavlink_wpm_distance_to_point_global_wgs84(wpm->current_active_wp_id, (float)global_pos->lat * 1e-7f, (float)global_pos->lon * 1e-7f, global_pos->relative_alt, &dist_xy, &dist_z);
+
+// } else if (coordinate_frame == (int)MAV_FRAME_LOCAL_ENU || coordinate_frame == (int)MAV_FRAME_LOCAL_NED) {
+// dist = mavlink_wpm_distance_to_point_local(wpm->current_active_wp_id, local_pos->x, local_pos->y, local_pos->z, &dist_xy, &dist_z);
+
+// } else if (coordinate_frame == (int)MAV_FRAME_MISSION) {
+// /* Check if conditions of mission item are satisfied */
+// // XXX TODO
+// }
+
+// if (dist >= 0.f && dist_xy <= orbit && dist_z >= 0.0f && dist_z <= vertical_switch_distance) {
+// wpm->pos_reached = true;
+// }
+
+// // check if required yaw reached
+// float yaw_sp = _wrap_pi(wpm->waypoints[wpm->current_active_wp_id].param4 / 180.0f * FM_PI);
+// float yaw_err = _wrap_pi(yaw_sp - local_pos->yaw);
+// if (fabsf(yaw_err) < 0.05f) {
+// wpm->yaw_reached = true;
+// }
+// }
+
+// //check if the current waypoint was reached
+// if (wpm->pos_reached && /*wpm->yaw_reached &&*/ !wpm->idle) {
+// if (wpm->current_active_wp_id < wpm->size) {
+// mavlink_mission_item_t *cur_wp = &(wpm->waypoints[wpm->current_active_wp_id]);
+
+// if (wpm->timestamp_firstinside_orbit == 0) {
+// // Announce that last waypoint was reached
+// mavlink_wpm_send_waypoint_reached(cur_wp->seq);
+// wpm->timestamp_firstinside_orbit = now;
+// }
+
+// // check if the MAV was long enough inside the waypoint orbit
+// //if (now-timestamp_lastoutside_orbit > (cur_wp->hold_time*1000))
+
+// bool time_elapsed = false;
+
+// if (now - wpm->timestamp_firstinside_orbit >= cur_wp->param1 * 1000 * 1000) {
+// time_elapsed = true;
+// } else if (cur_wp->command == (int)MAV_CMD_NAV_TAKEOFF) {
+// time_elapsed = true;
+// }
+
+// if (time_elapsed) {
+
+// /* safeguard against invalid missions with last wp autocontinue on */
+// if (wpm->current_active_wp_id == wpm->size - 1) {
+// /* stop handling missions here */
+// cur_wp->autocontinue = false;
+// }
+
+// if (cur_wp->autocontinue) {
+
+// cur_wp->current = 0;
+
+// float navigation_lat = -1.0f;
+// float navigation_lon = -1.0f;
+// float navigation_alt = -1.0f;
+// int navigation_frame = -1;
+
+// /* initialize to current position in case we don't find a suitable navigation waypoint */
+// if (global_pos->valid) {
+// navigation_lat = global_pos->lat/1e7;
+// navigation_lon = global_pos->lon/1e7;
+// navigation_alt = global_pos->alt;
+// navigation_frame = MAV_FRAME_GLOBAL;
+// } else if (local_pos->xy_valid && local_pos->z_valid) {
+// navigation_lat = local_pos->x;
+// navigation_lon = local_pos->y;
+// navigation_alt = local_pos->z;
+// navigation_frame = MAV_FRAME_LOCAL_NED;
+// }
+
+// /* guard against missions without final land waypoint */
+// /* only accept supported navigation waypoints, skip unknown ones */
+// do {
+
+// /* pick up the last valid navigation waypoint, this will be one we hold on to after the mission */
+// if (wpm->waypoints[wpm->current_active_wp_id].command == (int)MAV_CMD_NAV_WAYPOINT ||
+// wpm->waypoints[wpm->current_active_wp_id].command == (int)MAV_CMD_NAV_LOITER_TURNS ||
+// wpm->waypoints[wpm->current_active_wp_id].command == (int)MAV_CMD_NAV_LOITER_TIME ||
+// wpm->waypoints[wpm->current_active_wp_id].command == (int)MAV_CMD_NAV_LOITER_UNLIM ||
+// wpm->waypoints[wpm->current_active_wp_id].command == (int)MAV_CMD_NAV_TAKEOFF) {
+
+// /* this is a navigation waypoint */
+// navigation_frame = cur_wp->frame;
+// navigation_lat = cur_wp->x;
+// navigation_lon = cur_wp->y;
+// navigation_alt = cur_wp->z;
+// }
+
+// if (wpm->current_active_wp_id == wpm->size - 1) {
+
+// /* if we're not landing at the last nav waypoint, we're falling back to loiter */
+// if (wpm->waypoints[wpm->current_active_wp_id].command != (int)MAV_CMD_NAV_LAND) {
+// /* the last waypoint was reached, if auto continue is
+// * activated AND it is NOT a land waypoint, keep the system loitering there.
+// */
+// cur_wp->command = MAV_CMD_NAV_LOITER_UNLIM;
+// cur_wp->param3 = 20.0f; // XXX magic number 20 m loiter radius
+// cur_wp->frame = navigation_frame;
+// cur_wp->x = navigation_lat;
+// cur_wp->y = navigation_lon;
+// cur_wp->z = navigation_alt;
+// }
+
+// /* we risk an endless loop for missions without navigation waypoints, abort. */
+// break;
+
+// } else {
+// if ((uint16_t)(wpm->current_active_wp_id + 1) < wpm->size)
+// wpm->current_active_wp_id++;
+// }
- } while (!(wpm->waypoints[wpm->current_active_wp_id].command == (int)MAV_CMD_NAV_WAYPOINT ||
- wpm->waypoints[wpm->current_active_wp_id].command == (int)MAV_CMD_NAV_LOITER_TURNS ||
- wpm->waypoints[wpm->current_active_wp_id].command == (int)MAV_CMD_NAV_LOITER_TIME ||
- wpm->waypoints[wpm->current_active_wp_id].command == (int)MAV_CMD_NAV_LOITER_UNLIM));
-
- // Fly to next waypoint
- wpm->timestamp_firstinside_orbit = 0;
- mavlink_wpm_send_waypoint_current(wpm->current_active_wp_id);
- mavlink_wpm_send_setpoint(wpm->current_active_wp_id);
- wpm->waypoints[wpm->current_active_wp_id].current = true;
- wpm->pos_reached = false;
- wpm->yaw_reached = false;
- printf("Set new waypoint (%u)\n", wpm->current_active_wp_id);
- }
- }
- }
-
- } else {
- wpm->timestamp_lastoutside_orbit = now;
- }
-
- counter++;
-}
+// } while (!(wpm->waypoints[wpm->current_active_wp_id].command == (int)MAV_CMD_NAV_WAYPOINT ||
+// wpm->waypoints[wpm->current_active_wp_id].command == (int)MAV_CMD_NAV_LOITER_TURNS ||
+// wpm->waypoints[wpm->current_active_wp_id].command == (int)MAV_CMD_NAV_LOITER_TIME ||
+// wpm->waypoints[wpm->current_active_wp_id].command == (int)MAV_CMD_NAV_LOITER_UNLIM));
+
+// // Fly to next waypoint
+// wpm->timestamp_firstinside_orbit = 0;
+// mavlink_wpm_send_waypoint_current(wpm->current_active_wp_id);
+// mavlink_wpm_send_setpoint(wpm->current_active_wp_id);
+// wpm->waypoints[wpm->current_active_wp_id].current = true;
+// wpm->pos_reached = false;
+// wpm->yaw_reached = false;
+// printf("Set new waypoint (%u)\n", wpm->current_active_wp_id);
+// }
+// }
+// }
+
+// } else {
+// wpm->timestamp_lastoutside_orbit = now;
+// }
+
+// counter++;
+// }
int mavlink_waypoint_eventloop(uint64_t now, const struct vehicle_global_position_s *global_position, struct vehicle_local_position_s *local_position, struct navigation_capabilities_s *nav_cap)
@@ -505,17 +522,17 @@ int mavlink_waypoint_eventloop(uint64_t now, const struct vehicle_global_positio
#endif
wpm->current_state = MAVLINK_WPM_STATE_IDLE;
- wpm->current_count = 0;
+ // wpm->current_count = 0;
wpm->current_partner_sysid = 0;
wpm->current_partner_compid = 0;
- wpm->current_wp_id = -1;
+ // wpm->current_wp_id = -1;
- if (wpm->size == 0) {
- wpm->current_active_wp_id = -1;
- }
+ // if (wpm->size == 0) {
+ // wpm->current_active_wp_id = -1;
+ // }
}
- check_waypoints_reached(now, global_position, local_position, nav_cap->turn_distance);
+ // check_waypoints_reached(now, global_position, local_position, nav_cap->turn_distance);
return OK;
}
@@ -537,7 +554,7 @@ void mavlink_wpm_message_handler(const mavlink_message_t *msg, const struct vehi
if (wpm->current_state == MAVLINK_WPM_STATE_SENDLIST || wpm->current_state == MAVLINK_WPM_STATE_SENDLIST_SENDWPS) {
if (wpm->current_wp_id == wpm->size - 1) {
- mavlink_missionlib_send_gcs_string("Got last WP ACK state -> IDLE");
+ // mavlink_missionlib_send_gcs_string("Got last WP ACK state -> IDLE");
wpm->current_state = MAVLINK_WPM_STATE_IDLE;
wpm->current_wp_id = 0;
@@ -561,25 +578,38 @@ void mavlink_wpm_message_handler(const mavlink_message_t *msg, const struct vehi
if (wpm->current_state == MAVLINK_WPM_STATE_IDLE) {
if (wpc.seq < wpm->size) {
// if (verbose) // printf("Received MAVLINK_MSG_ID_MISSION_ITEM_SET_CURRENT\n");
- wpm->current_active_wp_id = wpc.seq;
- uint32_t i;
+ // wpm->current_active_wp_id = wpc.seq;
+ // uint32_t i;
- for (i = 0; i < wpm->size; i++) {
- if (i == wpm->current_active_wp_id) {
- wpm->waypoints[i].current = true;
+ // for (i = 0; i < wpm->size; i++) {
+ // if (i == wpm->current_active_wp_id) {
+ // wpm->waypoints[i].current = true;
- } else {
- wpm->waypoints[i].current = false;
- }
- }
+ // } else {
+ // wpm->waypoints[i].current = false;
+ // }
+ // }
+
+ // mavlink_missionlib_send_gcs_string("NEW WP SET");
+
+ // wpm->yaw_reached = false;
+ // wpm->pos_reached = false;
+
+ mission.current_index = wpc.seq;
+
+ /* Initialize mission publication if necessary */
+ if (mission_pub < 0) {
+ mission_pub = orb_advertise(ORB_ID(mission), &mission);
- mavlink_missionlib_send_gcs_string("NEW WP SET");
+ } else {
+ orb_publish(ORB_ID(mission), mission_pub, &mission);
+ }
+
+ mavlink_wpm_send_waypoint_ack(wpm->current_partner_sysid, wpm->current_partner_compid, MAV_MISSION_ACCEPTED);
- wpm->yaw_reached = false;
- wpm->pos_reached = false;
- mavlink_wpm_send_waypoint_current(wpm->current_active_wp_id);
- mavlink_wpm_send_setpoint(wpm->current_active_wp_id);
- wpm->timestamp_firstinside_orbit = 0;
+ //mavlink_wpm_send_waypoint_current(wpc.seq);
+ // mavlink_wpm_send_setpoint(wpm->current_active_wp_id);
+ // wpm->timestamp_firstinside_orbit = 0;
} else {
mavlink_missionlib_send_gcs_string("IGN WP CURR CMD: Not in list");
@@ -671,7 +701,17 @@ void mavlink_wpm_message_handler(const mavlink_message_t *msg, const struct vehi
wpm->current_state = MAVLINK_WPM_STATE_SENDLIST_SENDWPS;
wpm->current_wp_id = wpr.seq;
- mavlink_wpm_send_waypoint(wpm->current_partner_sysid, wpm->current_partner_compid, wpr.seq);
+
+ mavlink_mission_item_t wp;
+ map_mission_item_to_mavlink_mission_item(&mission.items[wpr.seq], &wp);
+
+ if (mission.current_index == wpr.seq) {
+ wp.current = true;
+ } else {
+ wp.current = false;
+ }
+
+ mavlink_wpm_send_waypoint(wpm->current_partner_sysid, wpm->current_partner_compid, &wp);
} else {
// if (verbose)
@@ -794,6 +834,15 @@ void mavlink_wpm_message_handler(const mavlink_message_t *msg, const struct vehi
wpm->current_partner_compid = msg->compid;
wpm->current_count = wpc.count;
+ if (wpc.count > NUM_MISSIONS_SUPPORTED) {
+ warnx("Too many waypoints: %d, supported: %d", wpc.count, NUM_MISSIONS_SUPPORTED);
+ } else {
+ /* prepare mission topic */
+ mission.count = wpc.count;
+ /* reset current index */
+ mission.current_index = -1;
+ }
+
#ifdef MAVLINK_WPM_NO_PRINTF
mavlink_missionlib_send_gcs_string("CLR RCV BUF: READY");
#else
@@ -824,9 +873,9 @@ void mavlink_wpm_message_handler(const mavlink_message_t *msg, const struct vehi
// delete waypoints->back();
// waypoints->pop_back();
// }
- wpm->current_active_wp_id = -1;
- wpm->yaw_reached = false;
- wpm->pos_reached = false;
+ // wpm->current_active_wp_id = -1;
+ // wpm->yaw_reached = false;
+ // wpm->pos_reached = false;
break;
} else {
@@ -886,7 +935,7 @@ void mavlink_wpm_message_handler(const mavlink_message_t *msg, const struct vehi
mavlink_mission_item_t wp;
mavlink_msg_mission_item_decode(msg, &wp);
- mavlink_missionlib_send_gcs_string("GOT WP");
+ // mavlink_missionlib_send_gcs_string("GOT WP");
// printf("sysid=%d, current_partner_sysid=%d\n", msg->sysid, wpm->current_partner_sysid);
// printf("compid=%d, current_partner_compid=%d\n", msg->compid, wpm->current_partner_compid);
@@ -900,7 +949,9 @@ void mavlink_wpm_message_handler(const mavlink_message_t *msg, const struct vehi
// wpm->current_state = MAVLINK_WPM_STATE_GETLIST;//removeme debug XXX TODO
//ensure that we are in the correct state and that the first waypoint has id 0 and the following waypoints have the correct ids
- if ((wpm->current_state == MAVLINK_WPM_STATE_GETLIST && wp.seq == 0) || (wpm->current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS && wp.seq == wpm->current_wp_id && wp.seq < wpm->current_count)) {
+ if ((wpm->current_state == MAVLINK_WPM_STATE_GETLIST && wp.seq == 0) ||
+ (wpm->current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS && wp.seq == wpm->current_wp_id &&
+ wp.seq < wpm->current_count)) {
//mavlink_missionlib_send_gcs_string("DEBUG 2");
// if (verbose && wpm->current_state == MAVLINK_WPM_STATE_GETLIST) // printf("Got MAVLINK_MSG_ID_MISSION_ITEM %u from %u changing state to MAVLINK_WPM_STATE_GETLIST_GETWPS\n", wp.seq, msg->sysid);
@@ -908,9 +959,25 @@ void mavlink_wpm_message_handler(const mavlink_message_t *msg, const struct vehi
// if (verbose && wpm->current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS && wp.seq-1 == wpm->current_wp_id) // printf("Got MAVLINK_MSG_ID_MISSION_ITEM %u (again) from %u\n", wp.seq, msg->sysid);
//
wpm->current_state = MAVLINK_WPM_STATE_GETLIST_GETWPS;
- mavlink_mission_item_t *newwp = &(wpm->rcv_waypoints[wp.seq]);
- memcpy(newwp, &wp, sizeof(mavlink_mission_item_t));
-// printf("WP seq: %d\n",wp.seq);
+ // mavlink_mission_item_t *newwp = &(wpm->rcv_waypoints[wp.seq]);
+ // memcpy(newwp, &wp, sizeof(mavlink_mission_item_t));
+
+ int ret = map_mavlink_mission_item_to_mission_item(&wp, &mission.items[wp.seq]);
+ if (ret != OK) {
+
+
+ mavlink_wpm_send_waypoint_ack(wpm->current_partner_sysid, wpm->current_partner_compid, ret);
+ wpm->current_state = MAVLINK_WPM_STATE_IDLE;
+ break;
+ }
+
+ if (wp.current) {
+ mission.current_index = wp.seq;
+ warnx("current is: %d", wp.seq);
+ } else {
+ warnx("not current");
+ }
+
wpm->current_wp_id = wp.seq + 1;
// if (verbose) // printf ("Added new waypoint to list. X= %f\t Y= %f\t Z= %f\t Yaw= %f\n", newwp->x, newwp->y, newwp->z, newwp->param4);
@@ -918,46 +985,62 @@ void mavlink_wpm_message_handler(const mavlink_message_t *msg, const struct vehi
// printf ("wpm->current_wp_id =%d, wpm->current_count=%d\n\n", wpm->current_wp_id, wpm->current_count);
if (wpm->current_wp_id == wpm->current_count && wpm->current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS) {
- mavlink_missionlib_send_gcs_string("GOT ALL WPS");
+ // mavlink_missionlib_send_gcs_string("GOT ALL WPS");
// if (verbose) // printf("Got all %u waypoints, changing state to MAVLINK_WPM_STATE_IDLE\n", wpm->current_count);
mavlink_wpm_send_waypoint_ack(wpm->current_partner_sysid, wpm->current_partner_compid, 0);
- if (wpm->current_active_wp_id > wpm->rcv_size - 1) {
- wpm->current_active_wp_id = wpm->rcv_size - 1;
- }
+ // if (wpm->current_active_wp_id > wpm->rcv_size - 1) {
+ // wpm->current_active_wp_id = wpm->rcv_size - 1;
+ // }
+
+ // bool copy_error = false;
+
+ // // switch the waypoints list
+ // // FIXME CHECK!!!
+ // uint32_t i;
+
+ // for (i = 0; i < wpm->current_count; ++i) {
+ // wpm->waypoints[i] = wpm->rcv_waypoints[i];
+ // if (map_mavlink_mission_item_to_mission_item(&wpm->rcv_waypoints[i], &mission.items[i]) != OK) {
+ // copy_error = true;
+ // }
+
+ // }
+ // TODO: update count?
- // switch the waypoints list
- // FIXME CHECK!!!
- uint32_t i;
+ /* Initialize mission publication if necessary */
+ if (mission_pub < 0) {
+ mission_pub = orb_advertise(ORB_ID(mission), &mission);
- for (i = 0; i < wpm->current_count; ++i) {
- wpm->waypoints[i] = wpm->rcv_waypoints[i];
+ } else {
+ orb_publish(ORB_ID(mission), mission_pub, &mission);
}
+
wpm->size = wpm->current_count;
//get the new current waypoint
- for (i = 0; i < wpm->size; i++) {
- if (wpm->waypoints[i].current == 1) {
- wpm->current_active_wp_id = i;
- //// if (verbose) // printf("New current waypoint %u\n", current_active_wp_id);
- wpm->yaw_reached = false;
- wpm->pos_reached = false;
- mavlink_wpm_send_waypoint_current(wpm->current_active_wp_id);
- mavlink_wpm_send_setpoint(wpm->current_active_wp_id);
- wpm->timestamp_firstinside_orbit = 0;
- break;
- }
- }
-
- if (i == wpm->size) {
- wpm->current_active_wp_id = -1;
- wpm->yaw_reached = false;
- wpm->pos_reached = false;
- wpm->timestamp_firstinside_orbit = 0;
- }
+ // for (i = 0; i < wpm->size; i++) {
+ // if (wpm->waypoints[i].current == 1) {
+ // wpm->current_active_wp_id = i;
+ // //// if (verbose) // printf("New current waypoint %u\n", current_active_wp_id);
+ // // wpm->yaw_reached = false;
+ // // wpm->pos_reached = false;
+ // mavlink_wpm_send_waypoint_current(wpm->current_active_wp_id);
+ // // mavlink_wpm_send_setpoint(wpm->current_active_wp_id);
+ // // wpm->timestamp_firstinside_orbit = 0;
+ // break;
+ // }
+ // }
+
+ // if (i == wpm->size) {
+ // wpm->current_active_wp_id = -1;
+ // wpm->yaw_reached = false;
+ // wpm->pos_reached = false;
+ // wpm->timestamp_firstinside_orbit = 0;
+ // }
wpm->current_state = MAVLINK_WPM_STATE_IDLE;
@@ -966,38 +1049,41 @@ void mavlink_wpm_message_handler(const mavlink_message_t *msg, const struct vehi
}
} else {
- if (wpm->current_state == MAVLINK_WPM_STATE_IDLE) {
- //we're done receiving waypoints, answer with ack.
- mavlink_wpm_send_waypoint_ack(wpm->current_partner_sysid, wpm->current_partner_compid, 0);
- printf("Received MAVLINK_MSG_ID_MISSION_ITEM while state=MAVLINK_WPM_STATE_IDLE, answered with WAYPOINT_ACK.\n");
- }
-
- // if (verbose)
- {
- if (!(wpm->current_state == MAVLINK_WPM_STATE_GETLIST || wpm->current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS)) {
-// printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM %u because i'm doing something else already (state=%i).\n", wp.seq, wpm->current_state);
- break;
- } else if (wpm->current_state == MAVLINK_WPM_STATE_GETLIST) {
- if (!(wp.seq == 0)) {
-// printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM because the first waypoint ID (%u) was not 0.\n", wp.seq);
- } else {
-// printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM %u - FIXME: missed error description\n", wp.seq);
- }
- } else if (wpm->current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS) {
- if (!(wp.seq == wpm->current_wp_id)) {
-// printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM because the waypoint ID (%u) was not the expected %u.\n", wp.seq, wpm->current_wp_id);
- mavlink_wpm_send_waypoint_request(wpm->current_partner_sysid, wpm->current_partner_compid, wpm->current_wp_id);
-
- } else if (!(wp.seq < wpm->current_count)) {
-// printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM because the waypoint ID (%u) was out of bounds.\n", wp.seq);
- } else {
-// printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM %u - FIXME: missed error description\n", wp.seq);
- }
- } else {
-// printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM %u - FIXME: missed error description\n", wp.seq);
- }
- }
+ mavlink_wpm_send_waypoint_ack(wpm->current_partner_sysid, wpm->current_partner_compid, MAV_MISSION_INVALID_SEQUENCE);
+
+ // if (wpm->current_state == MAVLINK_WPM_STATE_IDLE) {
+ // //we're done receiving waypoints, answer with ack.
+ // mavlink_wpm_send_waypoint_ack(wpm->current_partner_sysid, wpm->current_partner_compid, 0);
+ // printf("Received MAVLINK_MSG_ID_MISSION_ITEM while state=MAVLINK_WPM_STATE_IDLE, answered with WAYPOINT_ACK.\n");
+ // }
+
+// // if (verbose)
+// {
+// if (!(wpm->current_state == MAVLINK_WPM_STATE_GETLIST || wpm->current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS)) {
+// // printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM %u because i'm doing something else already (state=%i).\n", wp.seq, wpm->current_state);
+// break;
+
+// } else if (wpm->current_state == MAVLINK_WPM_STATE_GETLIST) {
+// if (!(wp.seq == 0)) {
+// // printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM because the first waypoint ID (%u) was not 0.\n", wp.seq);
+// } else {
+// // printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM %u - FIXME: missed error description\n", wp.seq);
+// }
+// } else if (wpm->current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS) {
+// if (!(wp.seq == wpm->current_wp_id)) {
+// // printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM because the waypoint ID (%u) was not the expected %u.\n", wp.seq, wpm->current_wp_id);
+// mavlink_wpm_send_waypoint_request(wpm->current_partner_sysid, wpm->current_partner_compid, wpm->current_wp_id);
+
+// } else if (!(wp.seq < wpm->current_count)) {
+// // printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM because the waypoint ID (%u) was out of bounds.\n", wp.seq);
+// } else {
+// // printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM %u - FIXME: missed error description\n", wp.seq);
+// }
+// } else {
+// // printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM %u - FIXME: missed error description\n", wp.seq);
+// }
+// }
}
} else {
//we we're target but already communicating with someone else
@@ -1021,12 +1107,30 @@ void mavlink_wpm_message_handler(const mavlink_message_t *msg, const struct vehi
// if (verbose) // printf("Got MAVLINK_MSG_ID_MISSION_ITEM_CLEAR_LIST from %u deleting all waypoints\n", msg->sysid);
// Delete all waypoints
wpm->size = 0;
- wpm->current_active_wp_id = -1;
- wpm->yaw_reached = false;
- wpm->pos_reached = false;
+ // wpm->current_active_wp_id = -1;
+ // wpm->yaw_reached = false;
+ // wpm->pos_reached = false;
+
+ /* prepare mission topic */
+ mission.count = 0;
+ memset(mission.items, 0, sizeof(struct mission_item_s)*NUM_MISSIONS_SUPPORTED);
+
+ /* Initialize mission publication if necessary */
+ if (mission_pub < 0) {
+ mission_pub = orb_advertise(ORB_ID(mission), &mission);
+
+ } else {
+ orb_publish(ORB_ID(mission), mission_pub, &mission);
+ }
+
+
+ warnx("Mission cleared");
+
+ mavlink_wpm_send_waypoint_ack(wpm->current_partner_sysid, wpm->current_partner_compid, MAV_MISSION_ACCEPTED);
} else if (wpca.target_system == mavlink_system.sysid /*&& wpca.target_component == mavlink_wpm_comp_id */ && wpm->current_state != MAVLINK_WPM_STATE_IDLE) {
// if (verbose) // printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_CLEAR_LIST from %u because i'm doing something else already (state=%i).\n", msg->sysid, wpm->current_state);
+ warnx("not cleared");
}
break;
diff --git a/src/modules/mavlink/waypoints.h b/src/modules/mavlink/waypoints.h
index d7d6b31dc..fc68285e9 100644
--- a/src/modules/mavlink/waypoints.h
+++ b/src/modules/mavlink/waypoints.h
@@ -56,6 +56,7 @@
#include <uORB/topics/vehicle_global_position.h>
#include <uORB/topics/vehicle_local_position.h>
#include <uORB/topics/navigation_capabilities.h>
+#include <uORB/topics/mission.h>
// FIXME XXX - TO BE MOVED TO XML
enum MAVLINK_WPM_STATES {
@@ -81,7 +82,7 @@ enum MAVLINK_WPM_CODES {
/* WAYPOINT MANAGER - MISSION LIB */
#define MAVLINK_WPM_MAX_WP_COUNT 15
-#define MAVLINK_WPM_CONFIG_IN_FLIGHT_UPDATE ///< Enable double buffer and in-flight updates
+// #define MAVLINK_WPM_CONFIG_IN_FLIGHT_UPDATE ///< Enable double buffer and in-flight updates
#ifndef MAVLINK_WPM_TEXT_FEEDBACK
#define MAVLINK_WPM_TEXT_FEEDBACK 0 ///< Report back status information as text
#endif
@@ -92,33 +93,37 @@ enum MAVLINK_WPM_CODES {
struct mavlink_wpm_storage {
mavlink_mission_item_t waypoints[MAVLINK_WPM_MAX_WP_COUNT]; ///< Currently active waypoints
-#ifdef MAVLINK_WPM_CONFIG_IN_FLIGHT_UPDATE
- mavlink_mission_item_t rcv_waypoints[MAVLINK_WPM_MAX_WP_COUNT]; ///< Receive buffer for next waypoints
-#endif
+// #ifdef MAVLINK_WPM_CONFIG_IN_FLIGHT_UPDATE
+ // mavlink_mission_item_t rcv_waypoints[MAVLINK_WPM_MAX_WP_COUNT]; ///< Receive buffer for next waypoints
+// #endif
uint16_t size;
uint16_t max_size;
uint16_t rcv_size;
enum MAVLINK_WPM_STATES current_state;
int16_t current_wp_id; ///< Waypoint in current transmission
- int16_t current_active_wp_id; ///< Waypoint the system is currently heading towards
+ // int16_t current_active_wp_id; ///< Waypoint the system is currently heading towards
uint16_t current_count;
uint8_t current_partner_sysid;
uint8_t current_partner_compid;
uint64_t timestamp_lastaction;
- uint64_t timestamp_last_send_setpoint;
- uint64_t timestamp_firstinside_orbit;
- uint64_t timestamp_lastoutside_orbit;
+ // uint64_t timestamp_last_send_setpoint;
+ // uint64_t timestamp_firstinside_orbit;
+ // uint64_t timestamp_lastoutside_orbit;
uint32_t timeout;
- uint32_t delay_setpoint;
- float accept_range_yaw;
- float accept_range_distance;
- bool yaw_reached;
- bool pos_reached;
- bool idle;
+ // uint32_t delay_setpoint;
+ // float accept_range_yaw;
+ // float accept_range_distance;
+ // bool yaw_reached;
+ // bool pos_reached;
+ // bool idle;
};
typedef struct mavlink_wpm_storage mavlink_wpm_storage;
+int map_mavlink_mission_item_to_mission_item(const mavlink_mission_item_t *mavlink_mission_item, struct mission_item_s *mission_item);
+int map_mission_item_to_mavlink_mission_item(const struct mission_item_s *mission_item, mavlink_mission_item_t *mavlink_mission_item);
+
+
void mavlink_wpm_init(mavlink_wpm_storage *state);
int mavlink_waypoint_eventloop(uint64_t now, const struct vehicle_global_position_s *global_position,
struct vehicle_local_position_s *local_pos, struct navigation_capabilities_s *nav_cap);
diff --git a/src/modules/navigator/module.mk b/src/modules/navigator/module.mk
index 0404b06c7..7f7443c43 100644
--- a/src/modules/navigator/module.mk
+++ b/src/modules/navigator/module.mk
@@ -39,3 +39,5 @@ MODULE_COMMAND = navigator
SRCS = navigator_main.cpp \
navigator_params.c
+
+INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink
diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp
index f6c44444a..cd4e04883 100644
--- a/src/modules/navigator/navigator_main.cpp
+++ b/src/modules/navigator/navigator_main.cpp
@@ -1,7 +1,9 @@
/****************************************************************************
*
* Copyright (c) 2013 PX4 Development Team. All rights reserved.
- * Author: Lorenz Meier
+ * Author: @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Jean Cyr <jean.m.cyr@gmail.com>
+ * @author Julian Oes <joes@student.ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -48,26 +50,42 @@
#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/airspeed.h>
#include <uORB/topics/vehicle_global_position.h>
-#include <uORB/topics/vehicle_global_position_set_triplet.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/home_position.h>
+#include <uORB/topics/mission_item_triplet.h>
+#include <uORB/topics/mission_result.h>
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/mission.h>
+#include <uORB/topics/fence.h>
#include <systemlib/param/param.h>
#include <systemlib/err.h>
#include <geo/geo.h>
#include <systemlib/perf_counter.h>
#include <systemlib/systemlib.h>
#include <mathlib/mathlib.h>
+#include <dataman/dataman.h>
+#include <mavlink/mavlink_log.h>
+
+typedef enum {
+ NAVIGATION_MODE_NONE,
+ NAVIGATION_MODE_LOITER,
+ NAVIGATION_MODE_WAYPOINT,
+ NAVIGATION_MODE_LOITER_WAYPOINT,
+ NAVIGATION_MODE_RTL,
+ NAVIGATION_MODE_LOITER_RTL
+} navigation_mode_t;
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
/**
* navigator app start / stop handling function
@@ -90,57 +108,90 @@ public:
~Navigator();
/**
- * Start the sensors task.
+ * Start the navigator task.
*
* @return OK on success.
*/
int start();
+ /**
+ * Display the navigator status.
+ */
+ void status();
+
+ /**
+ * Load fence parameters.
+ */
+ bool load_fence(unsigned vertices);
+
+ /**
+ * Specify fence vertex position.
+ */
+ void fence_point(int argc, char *argv[]);
+
private:
bool _task_should_exit; /**< if true, sensor task should exit */
- int _navigator_task; /**< task handle for sensor task */
+ int _navigator_task; /**< task handle for sensor task */
- int _global_pos_sub;
- int _att_sub; /**< vehicle attitude subscription */
- int _attitude_sub; /**< raw rc channels data subscription */
- int _airspeed_sub; /**< airspeed subscription */
+ int _mavlink_fd;
+
+ int _global_pos_sub; /**< global position subscription */
+ int _home_pos_sub; /**< home position subscription */
int _vstatus_sub; /**< vehicle status subscription */
- int _params_sub; /**< notification of parameter updates */
- int _manual_control_sub; /**< notification of manual control updates */
- int _mission_sub;
+ int _params_sub; /**< notification of parameter updates */
+ int _mission_sub; /**< notification of mission updates */
+ int _onboard_mission_sub; /**< notification of onboard mission updates */
+ int _capabilities_sub; /**< notification of vehicle capabilities updates */
- orb_advert_t _triplet_pub; /**< position setpoint */
+ orb_advert_t _triplet_pub; /**< publish position setpoint triplet */
+ orb_advert_t _fence_pub; /**< publish fence topic */
+ orb_advert_t _mission_result_pub; /**< publish mission result topic */
- struct vehicle_attitude_s _att; /**< vehicle attitude */
- struct vehicle_attitude_setpoint_s _att_sp; /**< vehicle attitude setpoint */
- struct manual_control_setpoint_s _manual; /**< r/c channel data */
- struct airspeed_s _airspeed; /**< airspeed */
struct vehicle_status_s _vstatus; /**< vehicle status */
struct vehicle_global_position_s _global_pos; /**< global vehicle position */
- struct vehicle_global_position_set_triplet_s _global_triplet; /**< triplet of global setpoints */
+ struct home_position_s _home_pos; /**< home position for RTL */
+ struct mission_item_triplet_s _mission_item_triplet; /**< triplet of mission items */
+ struct mission_result_s _mission_result; /**< mission result for commander/mavlink */
perf_counter_t _loop_perf; /**< loop performance counter */
- unsigned _mission_items_maxcount; /**< maximum number of mission items supported */
- struct mission_item_s * _mission_items; /**< storage for mission items */
- bool _mission_valid; /**< flag if mission is valid */
+ unsigned _max_mission_item_count; /**< maximum number of mission items supported */
+ unsigned _max_onboard_mission_item_count;/**< maximum number of onboard mission items supported */
+
+ unsigned _mission_item_count; /** number of mission items copied */
+ unsigned _onboard_mission_item_count; /** number of onboard mission items copied */
+ struct mission_item_s *_mission_item; /**< storage for mission */
+ struct mission_item_s *_onboard_mission_item; /**< storage for onboard mission */
+
+ struct fence_s _fence; /**< storage for fence vertices */
+ bool _fence_valid; /**< flag if fence is valid */
+ bool _inside_fence; /**< vehicle is inside fence */
+
+ struct navigation_capabilities_s _nav_caps;
- /** manual control states */
- float _seatbelt_hold_heading; /**< heading the system should hold in seatbelt mode */
- float _loiter_hold_lat;
- float _loiter_hold_lon;
- float _loiter_hold_alt;
- bool _loiter_hold;
+ bool _waypoint_position_reached;
+ bool _waypoint_yaw_reached;
+ uint64_t _time_first_inside_orbit;
+ bool _mission_item_reached;
+ bool _onboard_mission_item_reached;
+
+ navigation_mode_t _mode;
+ unsigned _current_mission_index;
+ unsigned _current_onboard_mission_index;
struct {
- float throttle_cruise;
- } _parameters; /**< local copies of interesting parameters */
+ float min_altitude;
+ float loiter_radius;
+ int onboard_mission_enabled;
+ } _parameters; /**< local copies of parameters */
struct {
- param_t throttle_cruise;
+ param_t min_altitude;
+ param_t loiter_radius;
+ param_t onboard_mission_enabled;
- } _parameter_handles; /**< handles for interesting parameters */
+ } _parameter_handles; /**< handles for parameters */
/**
@@ -149,49 +200,64 @@ private:
int parameters_update();
/**
- * Update control outputs
- *
- */
- void control_update();
+ * Retrieve mission.
+ */
+ void mission_update();
/**
- * Check for changes in vehicle status.
- */
- void vehicle_status_poll();
+ * Retrieve onboard mission.
+ */
+ void onboard_mission_update();
/**
- * Check for position updates.
+ * Shim for calling task_main from task_create.
*/
- void vehicle_attitude_poll();
+ static void task_main_trampoline(int argc, char *argv[]);
/**
- * Check for set triplet updates.
+ * Main sensor collection task.
*/
- void mission_poll();
+ void task_main() __attribute__((noreturn));
- /**
- * Control throttle.
- */
- float control_throttle(float energy_error);
+ void publish_fence(unsigned vertices);
- /**
- * Control pitch.
- */
- float control_pitch(float altitude_error);
+ void publish_safepoints(unsigned points);
- void calculate_airspeed_errors();
- void calculate_gndspeed_undershoot();
- void calculate_altitude_error();
+ bool fence_valid(const struct fence_s &fence);
- /**
- * Shim for calling task_main from task_create.
- */
- static void task_main_trampoline(int argc, char *argv[]);
+ void set_mode(navigation_mode_t new_nav_mode);
+
+ bool mission_possible();
+
+ bool onboard_mission_possible();
+
+ int set_waypoint_mission_item(unsigned mission_item_index, struct mission_item_s *new_mission_item);
+
+ void publish_mission_item_triplet();
+
+ void publish_mission_result();
+
+ int advance_current_mission_item();
+
+ void reset_mission_item_reached();
+
+ void check_mission_item_reached();
+
+ void report_mission_reached();
+
+ void start_waypoint();
+
+ void start_loiter(mission_item_s *new_loiter_position);
+
+ void start_rtl();
/**
- * Main sensor collection task.
+ * Compare two mission items if they are equivalent
+ * Two mission items can be considered equivalent for the purpose of the navigator even if some fields differ.
+ *
+ * @return true if equivalent, false otherwise
*/
- void task_main() __attribute__((noreturn));
+ bool cmp_mission_item_equivalent(const struct mission_item_s a, const struct mission_item_s b);
};
namespace navigator
@@ -211,33 +277,59 @@ Navigator::Navigator() :
_task_should_exit(false),
_navigator_task(-1),
+ _mavlink_fd(-1),
+
/* subscriptions */
_global_pos_sub(-1),
- _att_sub(-1),
- _airspeed_sub(-1),
+ _home_pos_sub(-1),
_vstatus_sub(-1),
_params_sub(-1),
- _manual_control_sub(-1),
+ _mission_sub(-1),
+ _onboard_mission_sub(-1),
+ _capabilities_sub(-1),
/* publications */
_triplet_pub(-1),
+ _fence_pub(-1),
+ _mission_result_pub(-1),
/* performance counters */
_loop_perf(perf_alloc(PC_ELAPSED, "navigator")),
/* states */
- _mission_items_maxcount(20),
- _mission_valid(false),
- _loiter_hold(false)
+ _max_mission_item_count(10),
+ _max_onboard_mission_item_count(10),
+ _mission_item_count(0),
+ _onboard_mission_item_count(0),
+ _fence_valid(false),
+ _inside_fence(true),
+ _waypoint_position_reached(false),
+ _waypoint_yaw_reached(false),
+ _time_first_inside_orbit(0),
+ _mission_item_reached(false),
+ _onboard_mission_item_reached(false),
+ _mode(NAVIGATION_MODE_NONE),
+ _current_mission_index(0),
+ _current_onboard_mission_index(0)
{
- _mission_items = (mission_item_s*)malloc(sizeof(mission_item_s) * _mission_items_maxcount);
- if (!_mission_items) {
- _mission_items_maxcount = 0;
- warnx("no free RAM to allocate mission, rejecting any waypoints");
- }
+ _global_pos.valid = false;
+ memset(&_fence, 0, sizeof(_fence));
+ _parameter_handles.min_altitude = param_find("NAV_MIN_ALT");
+ _parameter_handles.loiter_radius = param_find("NAV_LOITER_RAD");
+ _parameter_handles.onboard_mission_enabled = param_find("NAV_ONB_MIS_EN");
+
+ _mission_item = (mission_item_s*)malloc(sizeof(mission_item_s) * _max_mission_item_count);
+ _onboard_mission_item = (mission_item_s*)malloc(sizeof(mission_item_s) * _max_onboard_mission_item_count);
+
+ _mission_item_triplet.previous_valid = false;
+ _mission_item_triplet.current_valid = false;
+ _mission_item_triplet.next_valid = false;
+ memset(&_mission_item_triplet.previous, 0, sizeof(struct mission_item_s));
+ memset(&_mission_item_triplet.current, 0, sizeof(struct mission_item_s));
+ memset(&_mission_item_triplet.next, 0, sizeof(struct mission_item_s));
- _parameter_handles.throttle_cruise = param_find("NAV_DUMMY");
+ memset(&_mission_result, 0, sizeof(struct mission_result_s));
- /* fetch initial parameter values */
+ /* fetch initial values */
parameters_update();
}
@@ -270,65 +362,140 @@ int
Navigator::parameters_update()
{
- //param_get(_parameter_handles.throttle_cruise, &(_parameters.throttle_cruise));
+ param_get(_parameter_handles.min_altitude, &(_parameters.min_altitude));
+ param_get(_parameter_handles.loiter_radius, &(_parameters.loiter_radius));
+ param_get(_parameter_handles.onboard_mission_enabled, &(_parameters.onboard_mission_enabled));
return OK;
}
void
-Navigator::vehicle_status_poll()
+Navigator::mission_update()
{
- bool vstatus_updated;
+ struct mission_s mission;
+ if (orb_copy(ORB_ID(mission), _mission_sub, &mission) == OK) {
+ // XXX this is not optimal yet, but a first prototype /
+ // test implementation
+
+ if (mission.count <= _max_mission_item_count) {
+
+ /* Check if first part of mission (up to _current_mission_index - 1) changed:
+ * if the first part changed: start again at first waypoint
+ * if the first part remained unchanged: continue with the (possibly changed second part)
+ */
+ if (mission.current_index == -1 && _current_mission_index < _mission_item_count && _current_mission_index < mission.count) { //check if not finished and if the new mission is not a shorter mission
+ for (unsigned i = 0; i < _current_mission_index; i++) {
+ if (!cmp_mission_item_equivalent(_mission_item[i], mission.items[i])) {
+ /* set flag to restart mission next we're in auto */
+ _current_mission_index = 0;
+ mavlink_log_info(_mavlink_fd, "[navigator] Reset to WP %d", _current_mission_index);
+ //warnx("First part of mission differs i=%d", i);
+ break;
+ }
+// else {
+// warnx("Mission item is equivalent i=%d", i);
+// }
+ }
+ } else if (mission.current_index >= 0 && mission.current_index < mission.count) {
+ /* set flag to restart mission next we're in auto */
+ _current_mission_index = mission.current_index;
+ mavlink_log_info(_mavlink_fd, "[navigator] Reset to WP %d", _current_mission_index);
+ } else {
+ _current_mission_index = 0;
+ mavlink_log_info(_mavlink_fd, "[navigator] Reset to WP %d", _current_mission_index);
+ }
- /* Check HIL state if vehicle status has changed */
- orb_check(_vstatus_sub, &vstatus_updated);
+ /*
+ * Perform an atomic copy & state update
+ */
+ irqstate_t flags = irqsave();
- if (vstatus_updated) {
+ memcpy(_mission_item, mission.items, mission.count * sizeof(struct mission_item_s));
+ _mission_item_count = mission.count;
- orb_copy(ORB_ID(vehicle_status), _vstatus_sub, &_vstatus);
- }
-}
+ irqrestore(flags);
-void
-Navigator::vehicle_attitude_poll()
-{
- /* check if there is a new position */
- bool att_updated;
- orb_check(_att_sub, &att_updated);
+
+
+ } else {
+ warnx("ERROR: too many waypoints, not supported");
+ mavlink_log_critical(_mavlink_fd, "[navigator] too many waypoints, not supported");
+ _mission_item_count = 0;
+ }
- if (att_updated) {
- orb_copy(ORB_ID(vehicle_attitude), _att_sub, &_att);
+ if (_mode == NAVIGATION_MODE_WAYPOINT) {
+ start_waypoint();
+ }
+
+ /* TODO add checks if and how the mission has changed */
+ } else {
+ _mission_item_count = 0;
+ _current_mission_index = 0;
}
}
void
-Navigator::mission_poll()
+Navigator::onboard_mission_update()
{
- /* check if there is a new setpoint */
- bool mission_updated;
- orb_check(_mission_sub, &mission_updated);
-
- if (mission_updated) {
-
- struct mission_s mission;
- orb_copy(ORB_ID(mission), _mission_sub, &mission);
-
+ struct mission_s onboard_mission;
+ if (orb_copy(ORB_ID(onboard_mission), _onboard_mission_sub, &onboard_mission) == OK) {
// XXX this is not optimal yet, but a first prototype /
// test implementation
- if (mission.count <= _mission_items_maxcount) {
+ if (onboard_mission.count <= _max_onboard_mission_item_count) {
+
+ /* Check if first part of mission (up to _current_onboard_mission_index - 1) changed:
+ * if the first part changed: start again at first waypoint
+ * if the first part remained unchanged: continue with the (possibly changed second part)
+ */
+ if (onboard_mission.current_index == -1 && _current_onboard_mission_index < _onboard_mission_item_count && _current_onboard_mission_index < onboard_mission.count) { //check if not finished and if the new mission is not a shorter mission
+ for (unsigned i = 0; i < _current_onboard_mission_index; i++) {
+ if (!cmp_mission_item_equivalent(_onboard_mission_item[i], onboard_mission.items[i])) {
+ /* set flag to restart mission next we're in auto */
+ _current_onboard_mission_index = 0;
+ mavlink_log_info(_mavlink_fd, "[navigator] Reset to onboard WP %d", _current_onboard_mission_index);
+ //warnx("First part of onboard mission differs i=%d", i);
+ break;
+ }
+// else {
+// warnx("Onboard mission item is equivalent i=%d", i);
+// }
+ }
+ } else if (onboard_mission.current_index >= 0 && onboard_mission.current_index < onboard_mission.count) {
+ /* set flag to restart mission next we're in auto */
+ _current_onboard_mission_index = onboard_mission.current_index;
+ mavlink_log_info(_mavlink_fd, "[navigator] Reset to onboard WP %d", _current_onboard_mission_index);
+ } else {
+ _current_onboard_mission_index = 0;
+ mavlink_log_info(_mavlink_fd, "[navigator] Reset to onboard WP %d", _current_onboard_mission_index);
+ }
+
/*
* Perform an atomic copy & state update
*/
irqstate_t flags = irqsave();
- memcpy(_mission_items, mission.items, mission.count * sizeof(struct mission_item_s));
- _mission_valid = true;
+ memcpy(_onboard_mission_item, onboard_mission.items, onboard_mission.count * sizeof(struct mission_item_s));
+ _onboard_mission_item_count = onboard_mission.count;
irqrestore(flags);
+
+
+
} else {
- warnx("mission larger than storage space");
+ warnx("ERROR: too many waypoints, not supported");
+ mavlink_log_critical(_mavlink_fd, "[navigator] too many waypoints, not supported");
+ _onboard_mission_item_count = 0;
+ }
+
+ if (_mode == NAVIGATION_MODE_WAYPOINT) {
+ start_waypoint();
}
+
+ /* TODO add checks if and how the mission has changed */
+ } else {
+ _onboard_mission_item_count = 0;
+ _current_onboard_mission_index = 0;
}
}
@@ -351,11 +518,19 @@ Navigator::task_main()
*/
_global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position));
_mission_sub = orb_subscribe(ORB_ID(mission));
- _att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
- _airspeed_sub = orb_subscribe(ORB_ID(airspeed));
+ _onboard_mission_sub = orb_subscribe(ORB_ID(onboard_mission));
+ _capabilities_sub = orb_subscribe(ORB_ID(navigation_capabilities));
_vstatus_sub = orb_subscribe(ORB_ID(vehicle_status));
_params_sub = orb_subscribe(ORB_ID(parameter_update));
- _manual_control_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
+ _home_pos_sub = orb_subscribe(ORB_ID(home_position));
+
+ // Load initial states
+ if (orb_copy(ORB_ID(vehicle_status), _vstatus_sub, &_vstatus) != OK) {
+ _vstatus.arming_state = ARMING_STATE_STANDBY; // for testing... commander may not be running
+ }
+
+ mission_update();
+ onboard_mission_update();
/* rate limit vehicle status updates to 5Hz */
orb_set_interval(_vstatus_sub, 200);
@@ -364,23 +539,40 @@ Navigator::task_main()
parameters_update();
+ _fence_valid = load_fence(GEOFENCE_MAX_VERTICES);
+
+ /* load the craft capabilities */
+ orb_copy(ORB_ID(navigation_capabilities), _capabilities_sub, &_nav_caps);
+
/* wakeup source(s) */
- struct pollfd fds[2];
+ struct pollfd fds[7];
/* Setup of loop */
fds[0].fd = _params_sub;
fds[0].events = POLLIN;
fds[1].fd = _global_pos_sub;
fds[1].events = POLLIN;
+ fds[2].fd = _home_pos_sub;
+ fds[2].events = POLLIN;
+ fds[3].fd = _capabilities_sub;
+ fds[3].events = POLLIN;
+ fds[4].fd = _mission_sub;
+ fds[4].events = POLLIN;
+ fds[5].fd = _onboard_mission_sub;
+ fds[5].events = POLLIN;
+ fds[6].fd = _vstatus_sub;
+ fds[6].events = POLLIN;
+
while (!_task_should_exit) {
- /* wait for up to 500ms for data */
+ /* wait for up to 100ms for data */
int pret = poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 100);
/* timed out - periodic check for _task_should_exit, etc. */
- if (pret == 0)
+ if (pret == 0) {
continue;
+ }
/* this is undesirable but not much we can do - might want to flag unhappy status */
if (pret < 0) {
@@ -390,10 +582,68 @@ Navigator::task_main()
perf_begin(_loop_perf);
- /* check vehicle status for changes to publication state */
- vehicle_status_poll();
+ /* only update vehicle status if it changed */
+ if (fds[6].revents & POLLIN) {
+ /* read from param to clear updated flag */
+ orb_copy(ORB_ID(vehicle_status), _vstatus_sub, &_vstatus);
+
+ /* Evaluate state machine from commander and set the navigator mode accordingly */
+ if (_vstatus.main_state == MAIN_STATE_AUTO) {
+
+ switch (_vstatus.navigation_state) {
+ case NAVIGATION_STATE_DIRECT:
+ case NAVIGATION_STATE_STABILIZE:
+ case NAVIGATION_STATE_ALTHOLD:
+ case NAVIGATION_STATE_VECTOR:
+
+ set_mode(NAVIGATION_MODE_NONE);
+ break;
+
+ case NAVIGATION_STATE_AUTO_READY:
+ case NAVIGATION_STATE_AUTO_TAKEOFF:
+
+ /* TODO probably not needed since takeoff WPs will just be passed on */
+ //set_mode(NAVIGATION_MODE_TAKEOFF);
+ break;
- /* only update parameters if they changed */
+ case NAVIGATION_STATE_AUTO_LOITER:
+
+ set_mode(NAVIGATION_MODE_LOITER);
+ break;
+
+ case NAVIGATION_STATE_AUTO_MISSION:
+
+ if (onboard_mission_possible() || mission_possible()) {
+ /* Start mission or onboard mission if available */
+ set_mode(NAVIGATION_MODE_WAYPOINT);
+ } else {
+ /* else fallback to loiter */
+ set_mode(NAVIGATION_MODE_LOITER);
+ }
+ break;
+
+ case NAVIGATION_STATE_AUTO_RTL:
+
+ set_mode(NAVIGATION_MODE_RTL);
+ break;
+
+ case NAVIGATION_STATE_AUTO_LAND:
+
+ /* TODO add this */
+ //set_mode(NAVIGATION_MODE_LAND);
+ break;
+
+ default:
+ warnx("Navigation state not supported");
+ break;
+ }
+
+ } else {
+ set_mode(NAVIGATION_MODE_NONE);
+ }
+ }
+
+ /* only update parameters if it changed */
if (fds[0].revents & POLLIN) {
/* read from param to clear updated flag */
struct parameter_update_s update;
@@ -401,176 +651,682 @@ Navigator::task_main()
/* update parameters from storage */
parameters_update();
+
+ /* note that these new parameters won't be in effect until a mission triplet is published again */
}
- /* only run controller if position changed */
- if (fds[1].revents & POLLIN) {
+ /* only update craft capabilities if they have changed */
+ if (fds[3].revents & POLLIN) {
+ orb_copy(ORB_ID(navigation_capabilities), _capabilities_sub, &_nav_caps);
+ }
+ if (fds[4].revents & POLLIN) {
+ mission_update();
+ }
- static uint64_t last_run = 0;
- float deltaT = (hrt_absolute_time() - last_run) / 1000000.0f;
- last_run = hrt_absolute_time();
+ if (fds[5].revents & POLLIN) {
+ onboard_mission_update();
+ }
- /* guard against too large deltaT's */
- if (deltaT > 1.0f)
- deltaT = 0.01f;
+ if (fds[2].revents & POLLIN) {
+ orb_copy(ORB_ID(home_position), _home_pos_sub, &_home_pos);
+ }
+
+ /* only run controller if position changed */
+ if (fds[1].revents & POLLIN) {
+
+ /* XXX Hack to get mavlink output going */
+ if (_mavlink_fd < 0) {
+ /* try to open the mavlink log device every once in a while */
+ _mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
+ }
/* load local copies */
orb_copy(ORB_ID(vehicle_global_position), _global_pos_sub, &_global_pos);
+
+ /* do stuff according to mode */
+ switch (_mode) {
+ case NAVIGATION_MODE_NONE:
+ case NAVIGATION_MODE_LOITER:
+ case NAVIGATION_MODE_LOITER_WAYPOINT:
+ case NAVIGATION_MODE_LOITER_RTL:
+ break;
- vehicle_attitude_poll();
+ case NAVIGATION_MODE_WAYPOINT:
- mission_poll();
+ check_mission_item_reached();
- math::Vector2f ground_speed(_global_pos.vx, _global_pos.vy);
- // Current waypoint
- math::Vector2f next_wp(_global_triplet.current.lat / 1e7f, _global_triplet.current.lon / 1e7f);
- // Global position
- math::Vector2f current_position(_global_pos.lat / 1e7f, _global_pos.lon / 1e7f);
+ if (_mission_item_reached) {
- /* AUTONOMOUS FLIGHT */
+ report_mission_reached();
- if (1 /* autonomous flight */) {
+ mavlink_log_info(_mavlink_fd, "[navigator] reached WP %d", _current_mission_index);
+ if (advance_current_mission_item() != OK) {
+ set_mode(NAVIGATION_MODE_LOITER_WAYPOINT);
+ }
+ }
+ break;
- /* execute navigation once we have a setpoint */
- if (_mission_valid) {
+ case NAVIGATION_MODE_RTL:
- // Next waypoint
- math::Vector2f prev_wp;
+ check_mission_item_reached();
- if (_global_triplet.previous_valid) {
- prev_wp.setX(_global_triplet.previous.lat / 1e7f);
- prev_wp.setY(_global_triplet.previous.lon / 1e7f);
+ if (_mission_item_reached) {
+ mavlink_log_info(_mavlink_fd, "[navigator] reached RTL position");
+ set_mode(NAVIGATION_MODE_LOITER_RTL);
+ }
+ break;
+ default:
+ warnx("navigation mode not supported");
+ break;
+ }
+ }
+ perf_end(_loop_perf);
+ }
- } else {
- /*
- * No valid next waypoint, go for heading hold.
- * This is automatically handled by the L1 library.
- */
- prev_wp.setX(_global_triplet.current.lat / 1e7f);
- prev_wp.setY(_global_triplet.current.lon / 1e7f);
+ warnx("exiting.");
- }
+ _navigator_task = -1;
+ _exit(0);
+}
+int
+Navigator::start()
+{
+ ASSERT(_navigator_task == -1);
+ /* start the task */
+ _navigator_task = task_spawn_cmd("navigator",
+ SCHED_DEFAULT,
+ SCHED_PRIORITY_MAX - 5,
+ 2048,
+ (main_t)&Navigator::task_main_trampoline,
+ nullptr);
- /******** MAIN NAVIGATION STATE MACHINE ********/
+ if (_navigator_task < 0) {
+ warn("task start failed");
+ return -errno;
+ }
- // XXX to be put in its own class
+ return OK;
+}
- if (_global_triplet.current.nav_cmd == NAV_CMD_WAYPOINT) {
- /* waypoint is a plain navigation waypoint */
-
+void
+Navigator::status()
+{
+ warnx("Global position is %svalid", _global_pos.valid ? "" : "in");
+ if (_global_pos.valid) {
+ warnx("Longitude %5.5f degrees, latitude %5.5f degrees", _global_pos.lon / 1e7, _global_pos.lat / 1e7);
+ warnx("Altitude %5.5f meters, altitude above home %5.5f meters",
+ (double)_global_pos.alt, (double)_global_pos.relative_alt);
+ warnx("Ground velocity in m/s, x %5.5f, y %5.5f, z %5.5f",
+ (double)_global_pos.vx, (double)_global_pos.vy, (double)_global_pos.vz);
+ warnx("Compass heading in degrees %5.5f", (double)_global_pos.yaw * 57.2957795);
+ }
+ if (_fence_valid) {
+ warnx("Geofence is valid");
+ warnx("Vertex longitude latitude");
+ for (unsigned i = 0; i < _fence.count; i++)
+ warnx("%6u %9.5f %8.5f", i, (double)_fence.vertices[i].lon, (double)_fence.vertices[i].lat);
+ } else
+ warnx("Geofence not set");
+}
- } else if (_global_triplet.current.nav_cmd == NAV_CMD_LOITER_TURN_COUNT ||
- _global_triplet.current.nav_cmd == NAV_CMD_LOITER_TIME_LIMIT ||
- _global_triplet.current.nav_cmd == NAV_CMD_LOITER_UNLIMITED) {
+void
+Navigator::publish_fence(unsigned vertices)
+{
+ if (_fence_pub == -1)
+ _fence_pub = orb_advertise(ORB_ID(fence), &vertices);
+ else
+ orb_publish(ORB_ID(fence), _fence_pub, &vertices);
+}
- /* waypoint is a loiter waypoint */
-
- }
+bool
+Navigator::fence_valid(const struct fence_s &fence)
+{
+ // NULL fence is valid
+ if (fence.count == 0) {
+ return true;
+ }
- // XXX at this point we always want no loiter hold if a
- // mission is active
- _loiter_hold = false;
+ // Otherwise
+ if ((fence.count < 4) || (fence.count > GEOFENCE_MAX_VERTICES)) {
+ warnx("Fence must have at least 3 sides and not more than %d", GEOFENCE_MAX_VERTICES - 1);
+ return false;
+ }
- } else {
+ return true;
+}
- if (!_loiter_hold) {
- _loiter_hold_lat = _global_pos.lat / 1e7f;
- _loiter_hold_lon = _global_pos.lon / 1e7f;
- _loiter_hold_alt = _global_pos.alt;
- _loiter_hold = true;
- }
+bool
+Navigator::load_fence(unsigned vertices)
+{
+ struct fence_s temp_fence;
- //_parameters.loiter_hold_radius
- }
+ unsigned i;
+ for (i = 0; i < vertices; i++) {
+ if (dm_read(DM_KEY_FENCE_POINTS, i, temp_fence.vertices + i, sizeof(struct fence_vertex_s)) != sizeof(struct fence_vertex_s)) {
+ break;
+ }
+ }
- } else if (0/* seatbelt mode enabled */) {
+ temp_fence.count = i;
- /** SEATBELT FLIGHT **/
- continue;
+ if (fence_valid(temp_fence))
+ memcpy(&_fence, &temp_fence, sizeof(_fence));
+ else
+ warnx("Invalid fence file, ignored!");
- } else {
+ return _fence.count != 0;
+}
- /** MANUAL FLIGHT **/
+void
+Navigator::fence_point(int argc, char *argv[])
+{
+ int ix, last;
+ double lon, lat;
+ struct fence_vertex_s vertex;
+ char *end;
+
+ if ((argc == 1) && (strcmp("-clear", argv[0]) == 0)) {
+ dm_clear(DM_KEY_FENCE_POINTS);
+ publish_fence(0);
+ return;
+ }
- /* no flight mode applies, do not publish an attitude setpoint */
- continue;
- }
+ if (argc < 3)
+ errx(1, "Specify: -clear | sequence latitude longitude [-publish]");
+
+ ix = atoi(argv[0]);
+ if (ix >= DM_KEY_FENCE_POINTS_MAX)
+ errx(1, "Sequence must be less than %d", DM_KEY_FENCE_POINTS_MAX);
+
+ lat = strtod(argv[1], &end);
+ lon = strtod(argv[2], &end);
+
+ last = 0;
+ if ((argc > 3) && (strcmp(argv[3], "-publish") == 0))
+ last = 1;
+
+ vertex.lat = (float)lat;
+ vertex.lon = (float)lon;
+
+ if (dm_write(DM_KEY_FENCE_POINTS, ix, DM_PERSIST_POWER_ON_RESET, &vertex, sizeof(vertex)) == sizeof(vertex)) {
+ if (last)
+ publish_fence((unsigned)ix + 1);
+ return;
+ }
+
+ errx(1, "can't store fence point");
+}
+
+void
+Navigator::set_mode(navigation_mode_t new_nav_mode)
+{
+ if (new_nav_mode == _mode) {
+ /* no change, return */
+ return;
+ }
+
+ switch (new_nav_mode) {
+ case NAVIGATION_MODE_NONE:
+
+ // warnx("Set mode NONE");
+ _mode = new_nav_mode;
+ break;
+
+ case NAVIGATION_MODE_LOITER:
- /******** MAIN NAVIGATION STATE MACHINE ********/
+ /* decide depending on previous navigation mode */
+ switch (_mode) {
+ case NAVIGATION_MODE_NONE:
- if (_global_triplet.current.nav_cmd == NAV_CMD_RETURN_TO_LAUNCH) {
- // XXX define launch position and return
+ case NAVIGATION_MODE_WAYPOINT:
+ case NAVIGATION_MODE_RTL: {
- } else if (_global_triplet.current.nav_cmd == NAV_CMD_LAND) {
- // XXX flared descent on final approach
+ /* use current position and loiter around it */
+ mission_item_s global_position_mission_item;
+ global_position_mission_item.lat = (double)_global_pos.lat / 1e7;
+ global_position_mission_item.lon = (double)_global_pos.lon / 1e7;
- } else if (_global_triplet.current.nav_cmd == NAV_CMD_TAKEOFF) {
+ /* XXX get rid of ugly conversion for home position altitude */
+ float global_min_alt = _parameters.min_altitude + (float)_home_pos.alt/1e3f;
- /* apply minimum pitch if altitude has not yet been reached */
- if (_global_pos.alt < _global_triplet.current.altitude) {
- _att_sp.pitch_body = math::max(_att_sp.pitch_body, _global_triplet.current.param1);
+ /* Use current altitude if above min altitude set by parameter */
+ if (_global_pos.alt < global_min_alt) {
+ global_position_mission_item.altitude = global_min_alt;
+ mavlink_log_info(_mavlink_fd, "[navigator] loiter %.1fm higher", (double)(global_min_alt - _global_pos.alt));
+ } else {
+ global_position_mission_item.altitude = _global_pos.alt;
+ mavlink_log_info(_mavlink_fd, "[navigator] loiter here");
+ }
+ start_loiter(&global_position_mission_item);
+ _mode = new_nav_mode;
+
+ break;
}
+ case NAVIGATION_MODE_LOITER_WAYPOINT:
+ case NAVIGATION_MODE_LOITER_RTL:
+ /* already loitering, just continue */
+ _mode = new_nav_mode;
+ // warnx("continue loiter");
+ break;
+
+ case NAVIGATION_MODE_LOITER:
+ default:
+ // warnx("previous navigation mode not supported");
+ break;
+ }
+ break;
+
+ case NAVIGATION_MODE_WAYPOINT:
+
+ /* Start mission if there is one available */
+ start_waypoint();
+ _mode = new_nav_mode;
+ mavlink_log_info(_mavlink_fd, "[navigator] start waypoint mission");
+ break;
+
+ case NAVIGATION_MODE_LOITER_WAYPOINT:
+
+ start_loiter(&_mission_item_triplet.current);
+ _mode = new_nav_mode;
+ mavlink_log_info(_mavlink_fd, "[navigator] loiter at WP %d", _current_mission_index-1);
+ break;
+
+ case NAVIGATION_MODE_RTL:
+
+ /* decide depending on previous navigation mode */
+ switch (_mode) {
+ case NAVIGATION_MODE_NONE:
+ case NAVIGATION_MODE_LOITER:
+ case NAVIGATION_MODE_WAYPOINT:
+ case NAVIGATION_MODE_LOITER_WAYPOINT:
+
+ /* start RTL here */
+ start_rtl();
+ _mode = new_nav_mode;
+ mavlink_log_info(_mavlink_fd, "[navigator] start RTL");
+ break;
+
+ case NAVIGATION_MODE_LOITER_RTL:
+ /* already loitering after RTL, just continue */
+ // warnx("stay in loiter after RTL");
+ break;
+
+ case NAVIGATION_MODE_RTL:
+ default:
+ warnx("previous navigation mode not supported");
+ break;
}
+ break;
+
+ case NAVIGATION_MODE_LOITER_RTL:
+
+ /* TODO: get rid of this conversion */
+ mission_item_s home_position_mission_item;
+ home_position_mission_item.lat = (double)_home_pos.lat / 1e7;
+ home_position_mission_item.lon = (double)_home_pos.lon / 1e7;
+ home_position_mission_item.altitude = _home_pos.alt / 1e3f + _parameters.min_altitude;
+ start_loiter(&home_position_mission_item);
+ mavlink_log_info(_mavlink_fd, "[navigator] loiter after RTL");
+ _mode = new_nav_mode;
+ break;
+ }
+}
- /* lazily publish the setpoint only once available */
- if (_triplet_pub > 0) {
- /* publish the attitude setpoint */
- orb_publish(ORB_ID(vehicle_global_position_set_triplet), _triplet_pub, &_global_triplet);
+bool
+Navigator::mission_possible()
+{
+ return _mission_item_count > 0 &&
+ !(_current_mission_index >= _mission_item_count);
+}
- } else {
- /* advertise and publish */
- _triplet_pub = orb_advertise(ORB_ID(vehicle_global_position_set_triplet), &_global_triplet);
- }
+bool
+Navigator::onboard_mission_possible()
+{
+ return _onboard_mission_item_count > 0 &&
+ !(_current_onboard_mission_index >= _onboard_mission_item_count) &&
+ _parameters.onboard_mission_enabled;
+}
+int
+Navigator::set_waypoint_mission_item(unsigned index, struct mission_item_s *new_item)
+{
+ if (onboard_mission_possible()) {
+
+ if (index < _onboard_mission_item_count) {
+ memcpy(new_item, &_onboard_mission_item[index], sizeof(mission_item_s));
+
+ if (new_item->nav_cmd == NAV_CMD_RETURN_TO_LAUNCH) {
+ /* if it is a RTL waypoint, append the home position */
+ new_item->lat = (double)_home_pos.lat / 1e7;
+ new_item->lon = (double)_home_pos.lon / 1e7;
+ new_item->altitude = (float)_home_pos.alt / 1e3f + _parameters.min_altitude;
+ new_item->loiter_radius = _parameters.loiter_radius; // TODO: get rid of magic number
+ new_item->radius = 50.0f; // TODO: get rid of magic number
+ }
+ // warnx("added mission item: %d", index);
+ return OK;
}
- perf_end(_loop_perf);
+ } else if (mission_possible()) {
+
+ if (index < _mission_item_count) {
+ memcpy(new_item, &_mission_item[index], sizeof(mission_item_s));
+
+ if (new_item->nav_cmd == NAV_CMD_RETURN_TO_LAUNCH) {
+ /* if it is a RTL waypoint, append the home position */
+ new_item->lat = (double)_home_pos.lat / 1e7;
+ new_item->lon = (double)_home_pos.lon / 1e7;
+ new_item->altitude = (float)_home_pos.alt / 1e3f + _parameters.min_altitude;
+ new_item->loiter_radius = _parameters.loiter_radius; // TODO: get rid of magic number
+ new_item->radius = 50.0f; // TODO: get rid of magic number
+ }
+ // warnx("added mission item: %d", index);
+ return OK;
+ }
}
+
+ // warnx("could not add mission item: %d", index);
+ return ERROR;
+}
- warnx("exiting.\n");
+void
+Navigator::publish_mission_item_triplet()
+{
+ /* lazily publish the mission triplet only once available */
+ if (_triplet_pub > 0) {
+ /* publish the mission triplet */
+ orb_publish(ORB_ID(mission_item_triplet), _triplet_pub, &_mission_item_triplet);
+
+ } else {
+ /* advertise and publish */
+ _triplet_pub = orb_advertise(ORB_ID(mission_item_triplet), &_mission_item_triplet);
+ }
+}
- _navigator_task = -1;
- _exit(0);
+void
+Navigator::publish_mission_result()
+{
+ /* lazily publish the mission result only once available */
+ if (_mission_result_pub > 0) {
+ /* publish the mission result */
+ orb_publish(ORB_ID(mission_result), _mission_result_pub, &_mission_result);
+
+ } else {
+ /* advertise and publish */
+ _mission_result_pub = orb_advertise(ORB_ID(mission_result), &_mission_result);
+ }
}
int
-Navigator::start()
+Navigator::advance_current_mission_item()
{
- ASSERT(_navigator_task == -1);
+ reset_mission_item_reached();
- /* start the task */
- _navigator_task = task_spawn_cmd("navigator",
- SCHED_DEFAULT,
- SCHED_PRIORITY_MAX - 5,
- 2048,
- (main_t)&Navigator::task_main_trampoline,
- nullptr);
+ // warnx("advancing from %d to %d", _current_mission_index, _current_mission_index+1);
- if (_navigator_task < 0) {
- warn("task start failed");
- return -errno;
+ /* ultimately this index will be == _mission_item_count and this flags the mission as completed */
+ _current_mission_index++;
+
+ /* if there is no more mission available, don't advance and return */
+ if (!_mission_item_triplet.next_valid) {
+ // warnx("no next available");
+ return ERROR;
}
+ reset_mission_item_reached();
+
+ /* copy current mission to previous item */
+ memcpy(&_mission_item_triplet.previous, &_mission_item_triplet.current, sizeof(mission_item_s));
+ _mission_item_triplet.previous_valid = _mission_item_triplet.current_valid;
+
+ /* copy the next to current */
+ memcpy(&_mission_item_triplet.current, &_mission_item_triplet.next, sizeof(mission_item_s));
+ _mission_item_triplet.current_valid = _mission_item_triplet.next_valid;
+
+
+ if(set_waypoint_mission_item(_current_mission_index + 1, &_mission_item_triplet.next) == OK) {
+ _mission_item_triplet.next_valid = true;
+ }
+ else {
+ _mission_item_triplet.next_valid = false;
+ }
+
+ publish_mission_item_triplet();
+
return OK;
}
+
+void
+Navigator::reset_mission_item_reached()
+{
+ /* reset all states */
+ _waypoint_position_reached = false;
+ _waypoint_yaw_reached = false;
+ _time_first_inside_orbit = 0;
+
+ _mission_item_reached = false;
+
+ _mission_result.mission_reached = false;
+ _mission_result.mission_index = 0;
+}
+
+void
+Navigator::check_mission_item_reached()
+{
+ /* don't check if mission item is already reached */
+ if (_mission_item_reached) {
+ return;
+ }
+
+ /* don't try to reach the landing mission, just stay in that mode */
+ if (_mission_item_triplet.current.nav_cmd == NAV_CMD_LAND) {
+ return;
+ }
+
+ uint64_t now = hrt_absolute_time();
+ float orbit;
+
+ if (_mission_item_triplet.current.nav_cmd == NAV_CMD_WAYPOINT && _mission_item_triplet.current.radius > 0.01f) {
+
+ orbit = _mission_item_triplet.current.radius;
+
+ } else if ((_mission_item_triplet.current.nav_cmd == NAV_CMD_LOITER_TURN_COUNT ||
+ _mission_item_triplet.current.nav_cmd == NAV_CMD_LOITER_TIME_LIMIT ||
+ _mission_item_triplet.current.nav_cmd == NAV_CMD_LOITER_UNLIMITED) &&
+ _mission_item_triplet.current.loiter_radius > 0.01f) {
+
+ orbit = _mission_item_triplet.current.loiter_radius;
+ } else {
+
+ // XXX set default orbit via param
+ orbit = 15.0f;
+ }
+
+ /* keep vertical orbit */
+ float vertical_switch_distance = orbit;
+
+
+ // TODO add frame
+ // int coordinate_frame = wpm->waypoints[wpm->current_active_wp_id].frame;
+
+ float dist = -1.0f;
+ float dist_xy = -1.0f;
+ float dist_z = -1.0f;
+
+ // if (coordinate_frame == (int)MAV_FRAME_GLOBAL) {
+ dist = get_distance_to_point_global_wgs84(_mission_item_triplet.current.lat, _mission_item_triplet.current.lon, _mission_item_triplet.current.altitude,
+ (double)_global_pos.lat / 1e7, (double)_global_pos.lon / 1e7, _global_pos.alt,
+ &dist_xy, &dist_z);
+
+ // warnx("1 lat: %2.2f, lon: %2.2f, alt: %2.2f", _mission_item_triplet.current.lat, _mission_item_triplet.current.lon, _mission_item_triplet.current.altitude);
+ // warnx("2 lat: %2.2f, lon: %2.2f, alt: %2.2f", (double)_global_pos.lat / 1e7, (double)_global_pos.lon / 1e7, _global_pos.alt);
+
+ // warnx("Dist: %4.4f", dist);
+
+ // } else if (coordinate_frame == (int)MAV_FRAME_GLOBAL_RELATIVE_ALT) {
+ // dist = mavlink_wpm_distance_to_point_global_wgs84(wpm->current_active_wp_id, (float)global_pos->lat * 1e-7f, (float)global_pos->lon * 1e-7f, global_pos->relative_alt, &dist_xy, &dist_z);
+
+ // } else if (coordinate_frame == (int)MAV_FRAME_LOCAL_ENU || coordinate_frame == (int)MAV_FRAME_LOCAL_NED) {
+ // dist = mavlink_wpm_distance_to_point_local(wpm->current_active_wp_id, local_pos->x, local_pos->y, local_pos->z, &dist_xy, &dist_z);
+
+ // } else if (coordinate_frame == (int)MAV_FRAME_MISSION) {
+ // /* Check if conditions of mission item are satisfied */
+ // // XXX TODO
+ // }
+
+ if (dist >= 0.0f && dist_xy <= orbit && dist_z >= 0.0f && dist_z <= vertical_switch_distance) {
+ _waypoint_position_reached = true;
+ }
+
+ /* check if required yaw reached */
+ float yaw_sp = _wrap_pi(_mission_item_triplet.current.yaw);
+ float yaw_err = _wrap_pi(yaw_sp - _global_pos.yaw);
+
+ if (fabsf(yaw_err) < 0.05f) { /* XXX get rid of magic number */
+ _waypoint_yaw_reached = true;
+ }
+
+ /* check if the current waypoint was reached */
+ if (_waypoint_position_reached /* && _waypoint_yaw_reached */) { /* XXX what about yaw? */
+
+ if (_time_first_inside_orbit == 0) {
+ /* XXX announcment? */
+ _time_first_inside_orbit = now;
+ }
+
+ /* check if the MAV was long enough inside the waypoint orbit */
+ if ((now - _time_first_inside_orbit >= (uint64_t)_mission_item_triplet.current.time_inside * 1e6)
+ || _mission_item_triplet.current.nav_cmd == NAV_CMD_TAKEOFF) {
+
+ _mission_item_reached = true;
+ }
+ }
+
+}
+
+void
+Navigator::report_mission_reached()
+{
+ _mission_result.mission_reached = true;
+ _mission_result.mission_index = _current_mission_index;
+
+ publish_mission_result();
+}
+
+void
+Navigator::start_waypoint()
+{
+ reset_mission_item_reached();
+
+ /* this means we should start fresh */
+ if (_current_mission_index == 0) {
+
+ _mission_item_triplet.previous_valid = false;
+
+ } else {
+ set_waypoint_mission_item(_current_mission_index - 1, &_mission_item_triplet.previous);
+ _mission_item_triplet.previous_valid = true;
+ }
+
+ set_waypoint_mission_item(_current_mission_index, &_mission_item_triplet.current);
+ _mission_item_triplet.current_valid = true;
+
+ mavlink_log_info(_mavlink_fd, "[navigator] heading to WP %d", _current_mission_index);
+
+ // if (_mission_item_triplet.current.nav_cmd == NAV_CMD_LOITER_UNLIMITED) {
+
+ // if the current mission is to loiter unlimited, don't bother about a next mission item
+ // _mission_item_triplet.next_valid = false;
+ // } else {
+ /* if we are not loitering yet, try to add the next mission item */
+ // set_waypoint_mission_item(_current_mission_index + 1, &_mission_item_triplet.next);
+ // _mission_item_triplet.next_valid = true;
+ // }
+
+ if(set_waypoint_mission_item(_current_mission_index + 1, &_mission_item_triplet.next) == OK) {
+ _mission_item_triplet.next_valid = true;
+ }
+ else {
+ _mission_item_triplet.next_valid = false;
+ }
+
+ publish_mission_item_triplet();
+}
+
+void
+Navigator::start_loiter(mission_item_s *new_loiter_position)
+{
+ //reset_mission_item_reached();
+
+ _mission_item_triplet.previous_valid = false;
+ _mission_item_triplet.current_valid = true;
+ _mission_item_triplet.next_valid = false;
+
+ _mission_item_triplet.current.nav_cmd = NAV_CMD_LOITER_UNLIMITED;
+ _mission_item_triplet.current.loiter_direction = 1;
+ _mission_item_triplet.current.loiter_radius = _parameters.loiter_radius; // TODO: get rid of magic number
+ _mission_item_triplet.current.radius = 50.0f; // TODO: get rid of magic number
+ _mission_item_triplet.current.autocontinue = false;
+
+ _mission_item_triplet.current.lat = new_loiter_position->lat;
+ _mission_item_triplet.current.lon = new_loiter_position->lon;
+ _mission_item_triplet.current.altitude = new_loiter_position->altitude;
+ _mission_item_triplet.current.yaw = new_loiter_position->yaw;
+
+ publish_mission_item_triplet();
+}
+
+void
+Navigator::start_rtl()
+{
+ reset_mission_item_reached();
+
+ /* discard all mission item and insert RTL item */
+ _mission_item_triplet.previous_valid = false;
+ _mission_item_triplet.current_valid = true;
+ _mission_item_triplet.next_valid = false;
+
+ _mission_item_triplet.current.lat = (double)_home_pos.lat / 1e7;
+ _mission_item_triplet.current.lon = (double)_home_pos.lon / 1e7;
+ _mission_item_triplet.current.altitude = (float)_home_pos.alt / 1e3f + _parameters.min_altitude;
+ _mission_item_triplet.current.yaw = 0.0f;
+ _mission_item_triplet.current.nav_cmd = NAV_CMD_RETURN_TO_LAUNCH;
+ _mission_item_triplet.current.loiter_direction = 1;
+ _mission_item_triplet.current.loiter_radius = _parameters.loiter_radius; // TODO: get rid of magic number
+ _mission_item_triplet.current.radius = 50.0f; // TODO: get rid of magic number
+ _mission_item_triplet.current.autocontinue = false;
+ _mission_item_triplet.current_valid = true;
+
+ publish_mission_item_triplet();
+}
+
+
+static void usage()
+{
+ errx(1, "usage: navigator {start|stop|status|fence}");
+}
+
int navigator_main(int argc, char *argv[])
{
- if (argc < 1)
- errx(1, "usage: navigator {start|stop|status}");
+ if (argc < 2) {
+ usage();
+ }
if (!strcmp(argv[1], "start")) {
- if (navigator::g_navigator != nullptr)
+ if (navigator::g_navigator != nullptr) {
errx(1, "already running");
+ }
navigator::g_navigator = new Navigator;
- if (navigator::g_navigator == nullptr)
+ if (navigator::g_navigator == nullptr) {
errx(1, "alloc failed");
+ }
if (OK != navigator::g_navigator->start()) {
delete navigator::g_navigator;
@@ -578,27 +1334,45 @@ int navigator_main(int argc, char *argv[])
err(1, "start failed");
}
- exit(0);
+ return 0;
}
- if (!strcmp(argv[1], "stop")) {
- if (navigator::g_navigator == nullptr)
- errx(1, "not running");
+ if (navigator::g_navigator == nullptr)
+ errx(1, "not running");
+ if (!strcmp(argv[1], "stop")) {
delete navigator::g_navigator;
navigator::g_navigator = nullptr;
- exit(0);
- }
- if (!strcmp(argv[1], "status")) {
- if (navigator::g_navigator) {
- errx(0, "running");
+ } else if (!strcmp(argv[1], "status")) {
+ navigator::g_navigator->status();
- } else {
- errx(1, "not running");
- }
+ } else if (!strcmp(argv[1], "fence")) {
+ navigator::g_navigator->fence_point(argc - 2, argv + 2);
+
+ } else {
+ usage();
}
- warnx("unrecognized command");
- return 1;
+ return 0;
+}
+
+bool Navigator::cmp_mission_item_equivalent(const struct mission_item_s a, const struct mission_item_s b) {
+ if (fabsf(a.altitude_is_relative - b.altitude_is_relative) < FLT_EPSILON &&
+ fabsf(a.lat - b.lat) < FLT_EPSILON &&
+ fabsf(a.lon - b.lon) < FLT_EPSILON &&
+ fabsf(a.altitude - b.altitude) < FLT_EPSILON &&
+ fabsf(a.yaw - b.yaw) < FLT_EPSILON &&
+ fabsf(a.loiter_radius - b.loiter_radius) < FLT_EPSILON &&
+ fabsf(a.loiter_direction - b.loiter_direction) < FLT_EPSILON &&
+ fabsf(a.nav_cmd - b.nav_cmd) < FLT_EPSILON &&
+ fabsf(a.radius - b.radius) < FLT_EPSILON &&
+ fabsf(a.time_inside - b.time_inside) < FLT_EPSILON &&
+ fabsf(a.autocontinue - b.autocontinue) < FLT_EPSILON &&
+ fabsf(a.index - b.index) < FLT_EPSILON) {
+ return true;
+ } else {
+ warnx("a.index %d, b.index %d", a.index, b.index);
+ return false;
+ }
}
diff --git a/src/modules/navigator/navigator_params.c b/src/modules/navigator/navigator_params.c
index 06df9a452..b9d887379 100644
--- a/src/modules/navigator/navigator_params.c
+++ b/src/modules/navigator/navigator_params.c
@@ -1,7 +1,8 @@
/****************************************************************************
*
* Copyright (c) 2013 PX4 Development Team. All rights reserved.
- * Author: Lorenz Meier <lm@inf.ethz.ch>
+ * Author: @autho Lorenz Meier <lm@inf.ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -38,6 +39,7 @@
* Parameters defined by the navigator task.
*
* @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
*/
#include <nuttx/config.h>
@@ -49,5 +51,6 @@
*
*/
-PARAM_DEFINE_FLOAT(NAV_DUMMY, 0.0f);
-
+PARAM_DEFINE_FLOAT(NAV_MIN_ALT, 50.0f);
+PARAM_DEFINE_FLOAT(NAV_LOITER_RAD, 100.0f);
+PARAM_DEFINE_INT32(NAV_ONB_MIS_EN, 0); \ No newline at end of file
diff --git a/src/modules/px4iofirmware/dsm.c b/src/modules/px4iofirmware/dsm.c
index fd3b72015..4d306d6d0 100644
--- a/src/modules/px4iofirmware/dsm.c
+++ b/src/modules/px4iofirmware/dsm.c
@@ -355,7 +355,7 @@ dsm_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values)
continue;
/* ignore channels out of range */
- if (channel >= PX4IO_INPUT_CHANNELS)
+ if (channel >= PX4IO_RC_INPUT_CHANNELS)
continue;
/* update the decoded channel count */
diff --git a/src/modules/px4iofirmware/mixer.cpp b/src/modules/px4iofirmware/mixer.cpp
index 35ef5fcf6..e55ef784a 100644
--- a/src/modules/px4iofirmware/mixer.cpp
+++ b/src/modules/px4iofirmware/mixer.cpp
@@ -77,7 +77,8 @@ enum mixer_source {
MIX_NONE,
MIX_FMU,
MIX_OVERRIDE,
- MIX_FAILSAFE
+ MIX_FAILSAFE,
+ MIX_OVERRIDE_FMU_OK
};
static mixer_source source;
@@ -135,10 +136,19 @@ mixer_tick(void)
if ( (r_status_flags & PX4IO_P_STATUS_FLAGS_OVERRIDE) &&
(r_status_flags & PX4IO_P_STATUS_FLAGS_RC_OK) &&
(r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK) &&
- !(r_setup_arming & PX4IO_P_SETUP_ARMING_RC_HANDLING_DISABLED)) {
+ !(r_setup_arming & PX4IO_P_SETUP_ARMING_RC_HANDLING_DISABLED) &&
+ !(r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK)) {
/* if allowed, mix from RC inputs directly */
source = MIX_OVERRIDE;
+ } else if ( (r_status_flags & PX4IO_P_STATUS_FLAGS_OVERRIDE) &&
+ (r_status_flags & PX4IO_P_STATUS_FLAGS_RC_OK) &&
+ (r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK) &&
+ !(r_setup_arming & PX4IO_P_SETUP_ARMING_RC_HANDLING_DISABLED) &&
+ (r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK)) {
+
+ /* if allowed, mix from RC inputs directly up to available rc channels */
+ source = MIX_OVERRIDE_FMU_OK;
}
}
@@ -240,24 +250,35 @@ mixer_callback(uintptr_t handle,
uint8_t control_index,
float &control)
{
- if (control_group != 0)
+ if (control_group > 3)
return -1;
switch (source) {
case MIX_FMU:
- if (control_index < PX4IO_CONTROL_CHANNELS) {
- control = REG_TO_FLOAT(r_page_controls[control_index]);
+ if (control_index < PX4IO_CONTROL_CHANNELS && control_group < PX4IO_CONTROL_GROUPS ) {
+ control = REG_TO_FLOAT(r_page_controls[CONTROL_PAGE_INDEX(control_group, control_index)]);
break;
}
return -1;
case MIX_OVERRIDE:
- if (r_page_rc_input[PX4IO_P_RC_VALID] & (1 << control_index)) {
+ if (r_page_rc_input[PX4IO_P_RC_VALID] & (1 << CONTROL_PAGE_INDEX(control_group, control_index))) {
control = REG_TO_FLOAT(r_page_rc_input[PX4IO_P_RC_BASE + control_index]);
break;
}
return -1;
+ case MIX_OVERRIDE_FMU_OK:
+ /* FMU is ok but we are in override mode, use direct rc control for the available rc channels. The remaining channels are still controlled by the fmu */
+ if (r_page_rc_input[PX4IO_P_RC_VALID] & (1 << CONTROL_PAGE_INDEX(control_group, control_index))) {
+ control = REG_TO_FLOAT(r_page_rc_input[PX4IO_P_RC_BASE + control_index]);
+ break;
+ } else if (control_index < PX4IO_CONTROL_CHANNELS && control_group < PX4IO_CONTROL_GROUPS) {
+ control = REG_TO_FLOAT(r_page_controls[CONTROL_PAGE_INDEX(control_group, control_index)]);
+ break;
+ }
+ return -1;
+
case MIX_FAILSAFE:
case MIX_NONE:
control = 0.0f;
diff --git a/src/modules/px4iofirmware/protocol.h b/src/modules/px4iofirmware/protocol.h
index cffabbb45..3211df7c7 100644
--- a/src/modules/px4iofirmware/protocol.h
+++ b/src/modules/px4iofirmware/protocol.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * 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
@@ -63,7 +63,7 @@
* readable pages to be densely packed. Page numbers do not need to be
* packed.
*
- * Definitions marked 1 are only valid on PX4IOv1 boards. Likewise,
+ * Definitions marked [1] are only valid on PX4IOv1 boards. Likewise,
* [2] denotes definitions specific to the PX4IOv2 board.
*/
@@ -76,6 +76,9 @@
#define PX4IO_PROTOCOL_VERSION 4
+/* maximum allowable sizes on this protocol version */
+#define PX4IO_PROTOCOL_MAX_CONTROL_COUNT 8 /**< The protocol does not support more than set here, individual units might support less - see PX4IO_P_CONFIG_CONTROL_COUNT */
+
/* static configuration page */
#define PX4IO_PAGE_CONFIG 0
#define PX4IO_P_CONFIG_PROTOCOL_VERSION 0 /* PX4IO_PROTOCOL_VERSION */
@@ -87,6 +90,7 @@
#define PX4IO_P_CONFIG_RC_INPUT_COUNT 6 /* hardcoded max R/C input count supported */
#define PX4IO_P_CONFIG_ADC_INPUT_COUNT 7 /* hardcoded max ADC inputs */
#define PX4IO_P_CONFIG_RELAY_COUNT 8 /* hardcoded # of relay outputs */
+#define PX4IO_P_CONFIG_CONTROL_GROUP_COUNT 8 /**< hardcoded # of control groups*/
/* dynamic status page */
#define PX4IO_PAGE_STATUS 1
@@ -184,7 +188,7 @@ enum { /* DSM bind states */
dsm_bind_reinit_uart
};
/* 8 */
-#define PX4IO_P_SETUP_SET_DEBUG 9 /* debug level for IO board */
+#define PX4IO_P_SETUP_SET_DEBUG 9 /* debug level for IO board */
#define PX4IO_P_SETUP_REBOOT_BL 10 /* reboot IO into bootloader */
#define PX4IO_REBOOT_BL_MAGIC 14662 /* required argument for reboot (random) */
@@ -192,41 +196,51 @@ enum { /* DSM bind states */
#define PX4IO_P_SETUP_CRC 11 /* get CRC of IO firmware */
/* autopilot control values, -10000..10000 */
-#define PX4IO_PAGE_CONTROLS 51 /* 0..CONFIG_CONTROL_COUNT */
+#define PX4IO_PAGE_CONTROLS 51 /**< actuator control groups, one after the other, 8 wide */
+#define PX4IO_P_CONTROLS_GROUP_0 (PX4IO_PROTOCOL_MAX_CONTROL_COUNT * 0) /**< 0..PX4IO_PROTOCOL_MAX_CONTROL_COUNT - 1 */
+#define PX4IO_P_CONTROLS_GROUP_1 (PX4IO_PROTOCOL_MAX_CONTROL_COUNT * 1) /**< 0..PX4IO_PROTOCOL_MAX_CONTROL_COUNT - 1 */
+#define PX4IO_P_CONTROLS_GROUP_2 (PX4IO_PROTOCOL_MAX_CONTROL_COUNT * 2) /**< 0..PX4IO_PROTOCOL_MAX_CONTROL_COUNT - 1 */
+#define PX4IO_P_CONTROLS_GROUP_3 (PX4IO_PROTOCOL_MAX_CONTROL_COUNT * 3) /**< 0..PX4IO_PROTOCOL_MAX_CONTROL_COUNT - 1 */
+
+#define PX4IO_P_CONTROLS_GROUP_VALID 64
+#define PX4IO_P_CONTROLS_GROUP_VALID_GROUP0 (1 << 0) /* group 0 is valid / received */
+#define PX4IO_P_CONTROLS_GROUP_VALID_GROUP1 (1 << 1) /* group 1 is valid / received */
+#define PX4IO_P_CONTROLS_GROUP_VALID_GROUP2 (1 << 2) /* group 2 is valid / received */
+#define PX4IO_P_CONTROLS_GROUP_VALID_GROUP3 (1 << 3) /* group 3 is valid / received */
/* raw text load to the mixer parser - ignores offset */
-#define PX4IO_PAGE_MIXERLOAD 52
+#define PX4IO_PAGE_MIXERLOAD 52
/* R/C channel config */
-#define PX4IO_PAGE_RC_CONFIG 53 /* R/C input configuration */
-#define PX4IO_P_RC_CONFIG_MIN 0 /* lowest input value */
-#define PX4IO_P_RC_CONFIG_CENTER 1 /* center input value */
-#define PX4IO_P_RC_CONFIG_MAX 2 /* highest input value */
-#define PX4IO_P_RC_CONFIG_DEADZONE 3 /* band around center that is ignored */
-#define PX4IO_P_RC_CONFIG_ASSIGNMENT 4 /* mapped input value */
-#define PX4IO_P_RC_CONFIG_OPTIONS 5 /* channel options bitmask */
+#define PX4IO_PAGE_RC_CONFIG 53 /**< R/C input configuration */
+#define PX4IO_P_RC_CONFIG_MIN 0 /**< lowest input value */
+#define PX4IO_P_RC_CONFIG_CENTER 1 /**< center input value */
+#define PX4IO_P_RC_CONFIG_MAX 2 /**< highest input value */
+#define PX4IO_P_RC_CONFIG_DEADZONE 3 /**< band around center that is ignored */
+#define PX4IO_P_RC_CONFIG_ASSIGNMENT 4 /**< mapped input value */
+#define PX4IO_P_RC_CONFIG_OPTIONS 5 /**< channel options bitmask */
#define PX4IO_P_RC_CONFIG_OPTIONS_ENABLED (1 << 0)
#define PX4IO_P_RC_CONFIG_OPTIONS_REVERSE (1 << 1)
-#define PX4IO_P_RC_CONFIG_STRIDE 6 /* spacing between channel config data */
+#define PX4IO_P_RC_CONFIG_STRIDE 6 /**< spacing between channel config data */
/* PWM output - overrides mixer */
-#define PX4IO_PAGE_DIRECT_PWM 54 /* 0..CONFIG_ACTUATOR_COUNT-1 */
+#define PX4IO_PAGE_DIRECT_PWM 54 /**< 0..CONFIG_ACTUATOR_COUNT-1 */
/* PWM failsafe values - zero disables the output */
-#define PX4IO_PAGE_FAILSAFE_PWM 55 /* 0..CONFIG_ACTUATOR_COUNT-1 */
+#define PX4IO_PAGE_FAILSAFE_PWM 55 /**< 0..CONFIG_ACTUATOR_COUNT-1 */
/* Debug and test page - not used in normal operation */
-#define PX4IO_PAGE_TEST 127
-#define PX4IO_P_TEST_LED 0 /* set the amber LED on/off */
+#define PX4IO_PAGE_TEST 127
+#define PX4IO_P_TEST_LED 0 /**< set the amber LED on/off */
/* PWM minimum values for certain ESCs */
-#define PX4IO_PAGE_CONTROL_MIN_PWM 106 /* 0..CONFIG_ACTUATOR_COUNT-1 */
+#define PX4IO_PAGE_CONTROL_MIN_PWM 106 /**< 0..CONFIG_ACTUATOR_COUNT-1 */
/* PWM maximum values for certain ESCs */
-#define PX4IO_PAGE_CONTROL_MAX_PWM 107 /* 0..CONFIG_ACTUATOR_COUNT-1 */
+#define PX4IO_PAGE_CONTROL_MAX_PWM 107 /**< 0..CONFIG_ACTUATOR_COUNT-1 */
/* PWM disarmed values that are active, even when SAFETY_SAFE */
-#define PX4IO_PAGE_DISARMED_PWM 108 /* 0..CONFIG_ACTUATOR_COUNT-1 */
+#define PX4IO_PAGE_DISARMED_PWM 108 /* 0..CONFIG_ACTUATOR_COUNT-1 */
/**
* As-needed mixer data upload.
diff --git a/src/modules/px4iofirmware/px4io.h b/src/modules/px4iofirmware/px4io.h
index 4fea0288c..61eacd602 100644
--- a/src/modules/px4iofirmware/px4io.h
+++ b/src/modules/px4iofirmware/px4io.h
@@ -53,7 +53,9 @@
*/
#define PX4IO_SERVO_COUNT 8
#define PX4IO_CONTROL_CHANNELS 8
-#define PX4IO_INPUT_CHANNELS 8 // XXX this should be 18 channels
+#define PX4IO_CONTROL_GROUPS 2
+#define PX4IO_RC_INPUT_CHANNELS 8 // XXX this should be 18 channels
+#define PX4IO_RC_MAPPED_CONTROL_CHANNELS 8 /**< This is the maximum number of channels mapped/used */
/*
* Debug logging
@@ -169,6 +171,8 @@ extern pwm_limit_t pwm_limit;
#define BUTTON_SAFETY stm32_gpioread(GPIO_BTN_SAFETY)
+#define CONTROL_PAGE_INDEX(_group, _channel) (_group * PX4IO_CONTROL_CHANNELS + _channel)
+
/*
* Mixer
*/
diff --git a/src/modules/px4iofirmware/registers.c b/src/modules/px4iofirmware/registers.c
index 1a8519aec..916b893c4 100644
--- a/src/modules/px4iofirmware/registers.c
+++ b/src/modules/px4iofirmware/registers.c
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * 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
@@ -70,7 +70,7 @@ static const uint16_t r_page_config[] = {
[PX4IO_P_CONFIG_MAX_TRANSFER] = 64, /* XXX hardcoded magic number */
[PX4IO_P_CONFIG_CONTROL_COUNT] = PX4IO_CONTROL_CHANNELS,
[PX4IO_P_CONFIG_ACTUATOR_COUNT] = PX4IO_SERVO_COUNT,
- [PX4IO_P_CONFIG_RC_INPUT_COUNT] = PX4IO_CONTROL_CHANNELS,
+ [PX4IO_P_CONFIG_RC_INPUT_COUNT] = PX4IO_RC_INPUT_CHANNELS,
[PX4IO_P_CONFIG_ADC_INPUT_COUNT] = PX4IO_ADC_CHANNEL_COUNT,
[PX4IO_P_CONFIG_RELAY_COUNT] = PX4IO_RELAY_CHANNELS,
};
@@ -114,7 +114,7 @@ uint16_t r_page_servos[PX4IO_SERVO_COUNT];
uint16_t r_page_raw_rc_input[] =
{
[PX4IO_P_RAW_RC_COUNT] = 0,
- [PX4IO_P_RAW_RC_BASE ... (PX4IO_P_RAW_RC_BASE + PX4IO_CONTROL_CHANNELS)] = 0
+ [PX4IO_P_RAW_RC_BASE ... (PX4IO_P_RAW_RC_BASE + PX4IO_RC_INPUT_CHANNELS)] = 0
};
/**
@@ -124,7 +124,7 @@ uint16_t r_page_raw_rc_input[] =
*/
uint16_t r_page_rc_input[] = {
[PX4IO_P_RC_VALID] = 0,
- [PX4IO_P_RC_BASE ... (PX4IO_P_RC_BASE + PX4IO_CONTROL_CHANNELS)] = 0
+ [PX4IO_P_RC_BASE ... (PX4IO_P_RC_BASE + PX4IO_RC_MAPPED_CONTROL_CHANNELS)] = 0
};
/**
@@ -176,7 +176,7 @@ volatile uint16_t r_page_setup[] =
*
* Control values from the FMU.
*/
-volatile uint16_t r_page_controls[PX4IO_CONTROL_CHANNELS];
+volatile uint16_t r_page_controls[PX4IO_CONTROL_GROUPS * PX4IO_CONTROL_CHANNELS];
/*
* PAGE 102 does not have a buffer.
@@ -187,7 +187,7 @@ volatile uint16_t r_page_controls[PX4IO_CONTROL_CHANNELS];
*
* R/C channel input configuration.
*/
-uint16_t r_page_rc_input_config[PX4IO_CONTROL_CHANNELS * PX4IO_P_RC_CONFIG_STRIDE];
+uint16_t r_page_rc_input_config[PX4IO_RC_INPUT_CHANNELS * PX4IO_P_RC_CONFIG_STRIDE];
/* valid options */
#define PX4IO_P_RC_CONFIG_OPTIONS_VALID (PX4IO_P_RC_CONFIG_OPTIONS_REVERSE | PX4IO_P_RC_CONFIG_OPTIONS_ENABLED)
@@ -239,7 +239,7 @@ registers_set(uint8_t page, uint8_t offset, const uint16_t *values, unsigned num
case PX4IO_PAGE_CONTROLS:
/* copy channel data */
- while ((offset < PX4IO_CONTROL_CHANNELS) && (num_values > 0)) {
+ while ((offset < PX4IO_CONTROL_GROUPS * PX4IO_CONTROL_CHANNELS) && (num_values > 0)) {
/* XXX range-check value? */
r_page_controls[offset] = *values;
@@ -552,7 +552,7 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
unsigned index = offset - channel * PX4IO_P_RC_CONFIG_STRIDE;
uint16_t *conf = &r_page_rc_input_config[channel * PX4IO_P_RC_CONFIG_STRIDE];
- if (channel >= PX4IO_CONTROL_CHANNELS)
+ if (channel >= PX4IO_RC_INPUT_CHANNELS)
return -1;
/* disable the channel until we have a chance to sanity-check it */
@@ -600,7 +600,7 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
if (conf[PX4IO_P_RC_CONFIG_DEADZONE] > 500) {
count++;
}
- if (conf[PX4IO_P_RC_CONFIG_ASSIGNMENT] >= PX4IO_CONTROL_CHANNELS) {
+ if (conf[PX4IO_P_RC_CONFIG_ASSIGNMENT] >= PX4IO_RC_MAPPED_CONTROL_CHANNELS) {
count++;
}
diff --git a/src/modules/px4iofirmware/sbus.c b/src/modules/px4iofirmware/sbus.c
index c523df6ca..68a52c413 100644
--- a/src/modules/px4iofirmware/sbus.c
+++ b/src/modules/px4iofirmware/sbus.c
@@ -239,7 +239,7 @@ sbus_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values, uint
}
/* decode switch channels if data fields are wide enough */
- if (PX4IO_INPUT_CHANNELS > 17 && chancount > 15) {
+ if (PX4IO_RC_INPUT_CHANNELS > 17 && chancount > 15) {
chancount = 18;
/* channel 17 (index 16) */
diff --git a/src/modules/uORB/objects_common.cpp b/src/modules/uORB/objects_common.cpp
index c6a252b55..7434df1c3 100644
--- a/src/modules/uORB/objects_common.cpp
+++ b/src/modules/uORB/objects_common.cpp
@@ -120,14 +120,21 @@ ORB_DEFINE(vehicle_bodyframe_speed_setpoint, struct vehicle_bodyframe_speed_setp
#include "topics/vehicle_global_position_setpoint.h"
ORB_DEFINE(vehicle_global_position_setpoint, struct vehicle_global_position_setpoint_s);
-#include "topics/vehicle_global_position_set_triplet.h"
-ORB_DEFINE(vehicle_global_position_set_triplet, struct vehicle_global_position_set_triplet_s);
+#include "topics/mission_item_triplet.h"
+ORB_DEFINE(mission_item_triplet, struct mission_item_triplet_s);
#include "topics/vehicle_global_velocity_setpoint.h"
ORB_DEFINE(vehicle_global_velocity_setpoint, struct vehicle_global_velocity_setpoint_s);
#include "topics/mission.h"
ORB_DEFINE(mission, struct mission_s);
+ORB_DEFINE(onboard_mission, struct mission_s);
+
+#include "topics/mission_result.h"
+ORB_DEFINE(mission_result, struct mission_result_s);
+
+#include "topics/fence.h"
+ORB_DEFINE(fence, unsigned);
#include "topics/vehicle_attitude_setpoint.h"
ORB_DEFINE(vehicle_attitude_setpoint, struct vehicle_attitude_setpoint_s);
diff --git a/src/modules/uORB/topics/fence.h b/src/modules/uORB/topics/fence.h
new file mode 100644
index 000000000..6f16c51cf
--- /dev/null
+++ b/src/modules/uORB/topics/fence.h
@@ -0,0 +1,80 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Author: @author Jean Cyr <jean.m.cyr@gmail.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 fence.h
+ * Definition of geofence.
+ */
+
+#ifndef TOPIC_FENCE_H_
+#define TOPIC_FENCE_H_
+
+#include <stdint.h>
+#include <stdbool.h>
+#include "../uORB.h"
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+#define GEOFENCE_MAX_VERTICES 16
+
+/**
+ * This is the position of a geofence vertex
+ *
+ */
+struct fence_vertex_s {
+ // Worst case float precision gives us 2 meter resolution at the equator
+ float lat; /**< latitude in degrees */
+ float lon; /**< longitude in degrees */
+};
+
+/**
+ * This is the position of a geofence
+ *
+ */
+struct fence_s {
+ unsigned count; /**< number of actual vertices */
+ struct fence_vertex_s vertices[GEOFENCE_MAX_VERTICES];
+};
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(fence);
+
+#endif
diff --git a/src/modules/uORB/topics/mission.h b/src/modules/uORB/topics/mission.h
index 978a3383a..2427a1d57 100644
--- a/src/modules/uORB/topics/mission.h
+++ b/src/modules/uORB/topics/mission.h
@@ -35,8 +35,8 @@
****************************************************************************/
/**
- * @file mission_item.h
- * Definition of one mission item.
+ * @file mission.h
+ * Definition of a mission consisting of mission items.
*/
#ifndef TOPIC_MISSION_H_
@@ -46,14 +46,17 @@
#include <stdbool.h>
#include "../uORB.h"
+/* compatible to mavlink MAV_CMD */
enum NAV_CMD {
- NAV_CMD_WAYPOINT = 0,
- NAV_CMD_LOITER_TURN_COUNT,
- NAV_CMD_LOITER_TIME_LIMIT,
- NAV_CMD_LOITER_UNLIMITED,
- NAV_CMD_RETURN_TO_LAUNCH,
- NAV_CMD_LAND,
- NAV_CMD_TAKEOFF
+ NAV_CMD_WAYPOINT=16,
+ NAV_CMD_LOITER_UNLIMITED=17,
+ NAV_CMD_LOITER_TURN_COUNT=18,
+ NAV_CMD_LOITER_TIME_LIMIT=19,
+ NAV_CMD_RETURN_TO_LAUNCH=20,
+ NAV_CMD_LAND=21,
+ NAV_CMD_TAKEOFF=22,
+ NAV_CMD_ROI=80,
+ NAV_CMD_PATHPLANNING=81
};
/**
@@ -75,18 +78,19 @@ struct mission_item_s
float altitude; /**< altitude in meters */
float yaw; /**< in radians NED -PI..+PI */
float loiter_radius; /**< loiter radius in meters, 0 for a VTOL to hover */
- uint8_t loiter_direction; /**< 1: positive / clockwise, -1, negative. */
- enum NAV_CMD nav_cmd; /**< true if loitering is enabled */
- float param1;
- float param2;
- float param3;
- float param4;
+ int8_t loiter_direction; /**< 1: positive / clockwise, -1, negative. */
+ enum NAV_CMD nav_cmd; /**< navigation command */
+ float radius; /**< radius in which the mission is accepted as reached in meters */
+ float time_inside; /**< time that the MAV should stay inside the radius before advancing in seconds */
+ bool autocontinue; /**< true if next waypoint should follow after this one */
+ int index; /**< index matching the mavlink waypoint */
};
struct mission_s
{
struct mission_item_s *items;
unsigned count;
+ int current_index; /**< default -1, start at the one changed latest */
};
/**
@@ -95,5 +99,6 @@ struct mission_s
/* register this as object request broker structure */
ORB_DECLARE(mission);
+ORB_DECLARE(onboard_mission);
#endif
diff --git a/src/modules/uORB/topics/vehicle_global_position_set_triplet.h b/src/modules/uORB/topics/mission_item_triplet.h
index 8516b263f..b35eae607 100644
--- a/src/modules/uORB/topics/vehicle_global_position_set_triplet.h
+++ b/src/modules/uORB/topics/mission_item_triplet.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (C) 2013 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>
@@ -35,18 +35,18 @@
****************************************************************************/
/**
- * @file vehicle_global_position_setpoint.h
+ * @file mission_item_triplet.h
* Definition of the global WGS84 position setpoint uORB topic.
*/
-#ifndef TOPIC_VEHICLE_GLOBAL_POSITION_SET_TRIPLET_H_
-#define TOPIC_VEHICLE_GLOBAL_POSITION_SET_TRIPLET_H_
+#ifndef TOPIC_MISSION_ITEM_TRIPLET_H_
+#define TOPIC_MISSION_ITEM_TRIPLET_H_
#include <stdint.h>
#include <stdbool.h>
#include "../uORB.h"
-#include "vehicle_global_position_setpoint.h"
+#include "mission.h"
/**
* @addtogroup topics
@@ -58,14 +58,19 @@
*
* This are the three next waypoints (or just the next two or one).
*/
-struct vehicle_global_position_set_triplet_s
+struct mission_item_triplet_s
{
- bool previous_valid; /**< flag indicating previous position is valid */
- bool next_valid; /**< flag indicating next position is valid */
+ bool previous_valid;
+ bool current_valid; /**< flag indicating previous mission item is valid */
+ bool next_valid; /**< flag indicating next mission item is valid */
- struct vehicle_global_position_setpoint_s previous;
- struct vehicle_global_position_setpoint_s current;
- struct vehicle_global_position_setpoint_s next;
+ struct mission_item_s previous;
+ struct mission_item_s current;
+ struct mission_item_s next;
+
+ int previous_index;
+ int current_index;
+ int next_index;
};
/**
@@ -73,6 +78,6 @@ struct vehicle_global_position_set_triplet_s
*/
/* register this as object request broker structure */
-ORB_DECLARE(vehicle_global_position_set_triplet);
+ORB_DECLARE(mission_item_triplet);
#endif
diff --git a/src/modules/uORB/topics/mission_result.h b/src/modules/uORB/topics/mission_result.h
new file mode 100644
index 000000000..c99706b97
--- /dev/null
+++ b/src/modules/uORB/topics/mission_result.h
@@ -0,0 +1,67 @@
+/****************************************************************************
+ *
+ * Copyright (C) 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>
+ *
+ * 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 mission_result.h
+ * Mission results that navigator needs to pass on to commander and mavlink.
+ */
+
+#ifndef TOPIC_MISSION_RESULT_H
+#define TOPIC_MISSION_RESULT_H
+
+#include <stdint.h>
+#include <stdbool.h>
+#include "../uORB.h"
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+struct mission_result_s
+{
+ bool mission_reached; /**< true if mission has been reached */
+ unsigned mission_index; /**< index of the mission which has been reached */
+};
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(mission_result);
+
+#endif
diff --git a/src/modules/uORB/topics/vehicle_control_mode.h b/src/modules/uORB/topics/vehicle_control_mode.h
index 38fb74c9b..e26fb97c8 100644
--- a/src/modules/uORB/topics/vehicle_control_mode.h
+++ b/src/modules/uORB/topics/vehicle_control_mode.h
@@ -78,6 +78,7 @@ struct vehicle_control_mode_s
bool flag_control_position_enabled; /**< true if position is controlled */
bool flag_control_altitude_enabled; /**< true if altitude is controlled */
bool flag_control_climb_rate_enabled; /**< true if climb rate is controlled */
+ bool flag_control_flighttermination_enabled; /**< true if flighttermination is enabled */
bool flag_control_auto_enabled; // TEMP
uint8_t auto_state; // TEMP navigation state for AUTO modes
diff --git a/src/modules/uORB/topics/vehicle_status.h b/src/modules/uORB/topics/vehicle_status.h
index 1c184d3a7..1c3763924 100644
--- a/src/modules/uORB/topics/vehicle_status.h
+++ b/src/modules/uORB/topics/vehicle_status.h
@@ -95,6 +95,12 @@ typedef enum {
HIL_STATE_ON
} hil_state_t;
+
+typedef enum {
+ FLIGHTTERMINATION_STATE_OFF = 0,
+ FLIGHTTERMINATION_STATE_ON
+} flighttermination_state_t;
+
typedef enum {
MODE_SWITCH_MANUAL = 0,
MODE_SWITCH_ASSISTED,
@@ -229,6 +235,8 @@ struct vehicle_status_s
uint16_t errors_count2;
uint16_t errors_count3;
uint16_t errors_count4;
+
+ flighttermination_state_t flighttermination_state;
};
/**
diff --git a/src/systemcmds/tests/module.mk b/src/systemcmds/tests/module.mk
index 5d5fe50d3..c1f8074ea 100644
--- a/src/systemcmds/tests/module.mk
+++ b/src/systemcmds/tests/module.mk
@@ -24,7 +24,10 @@ SRCS = test_adc.c \
test_uart_loopback.c \
test_uart_send.c \
test_mixer.cpp \
+ test_dataman.c \
test_file.c \
tests_main.c \
test_param.c \
test_ppm_loopback.c
+
+INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink
diff --git a/src/systemcmds/tests/test_dataman.c b/src/systemcmds/tests/test_dataman.c
new file mode 100644
index 000000000..e33c5aceb
--- /dev/null
+++ b/src/systemcmds/tests/test_dataman.c
@@ -0,0 +1,179 @@
+/****************************************************************************
+ * px4/sensors/test_dataman.c
+ *
+ * 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 NuttX 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+
+#include <stdio.h>
+#include <stdlib.h>
+#include <unistd.h>
+#include <fcntl.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <arch/board/board.h>
+
+#include <drivers/drv_led.h>
+#include <systemlib/systemlib.h>
+#include <drivers/drv_hrt.h>
+#include <semaphore.h>
+
+
+#include "tests.h"
+
+#include "dataman/dataman.h"
+
+static sem_t *sems;
+
+static int
+task_main(int argc, char *argv[])
+{
+ char buffer[DM_MAX_DATA_SIZE];
+ hrt_abstime wstart, wend, rstart, rend;
+
+ warnx("Starting dataman test task %s", argv[1]);
+ /* try to read an invalid item */
+ int my_id = atoi(argv[1]);
+ /* try to read an invalid item */
+ if (dm_read(DM_KEY_NUM_KEYS, 0, buffer, sizeof(buffer)) >= 0) {
+ warnx("%d read an invalid item failed", my_id);
+ goto fail;
+ }
+ /* try to read an invalid index */
+ if (dm_read(DM_KEY_SAFE_POINTS, DM_KEY_SAFE_POINTS_MAX, buffer, sizeof(buffer)) >= 0) {
+ warnx("%d read an invalid index failed", my_id);
+ goto fail;
+ }
+ srand(hrt_absolute_time() ^ my_id);
+ unsigned hit = 0, miss = 0;
+ wstart = hrt_absolute_time();
+ for (unsigned i = 0; i < 256; i++) {
+ memset(buffer, my_id, sizeof(buffer));
+ buffer[1] = i;
+ unsigned hash = i ^ my_id;
+ unsigned len = (hash & 63) + 2;
+ if (dm_write(DM_KEY_WAY_POINTS, hash, DM_PERSIST_IN_FLIGHT_RESET, buffer, len) != len) {
+ warnx("%d write failed, index %d, length %d", my_id, hash, len);
+ goto fail;
+ }
+ usleep(rand() & ((64 * 1024) - 1));
+ }
+ rstart = hrt_absolute_time();
+ wend = rstart;
+
+ for (unsigned i = 0; i < 256; i++) {
+ unsigned hash = i ^ my_id;
+ unsigned len2, len = (hash & 63) + 2;
+ if ((len2 = dm_read(DM_KEY_WAY_POINTS, hash, buffer, sizeof(buffer))) < 2) {
+ warnx("%d read failed length test, index %d", my_id, hash);
+ goto fail;
+ }
+ if (buffer[0] == my_id) {
+ hit++;
+ if (len2 != len) {
+ warnx("%d read failed length test, index %d, wanted %d, got %d", my_id, hash, len, len2);
+ goto fail;
+ }
+ if (buffer[1] != i) {
+ warnx("%d data verification failed, index %d, wanted %d, got %d", my_id, hash, my_id, buffer[1]);
+ goto fail;
+ }
+ }
+ else
+ miss++;
+ }
+ rend = hrt_absolute_time();
+ warnx("Test %d pass, hit %d, miss %d, io time read %llums. write %llums.",
+ my_id, hit, miss, (rend - rstart) / 256000, (wend - wstart) / 256000);
+ sem_post(sems + my_id);
+ return 0;
+fail:
+ warnx("Test %d fail, buffer %02x %02x %02x %02x %02x %02x",
+ my_id, buffer[0], buffer[1], buffer[2], buffer[3], buffer[4], buffer[5]);
+ sem_post(sems + my_id);
+ return -1;
+}
+
+int test_dataman(int argc, char *argv[])
+{
+ int i, num_tasks = 4;
+ char buffer[DM_MAX_DATA_SIZE];
+
+ if (argc > 1)
+ num_tasks = atoi(argv[1]);
+
+ sems = (sem_t *)malloc(num_tasks * sizeof(sem_t));
+ warnx("Running %d tasks", num_tasks);
+ for (i = 0; i < num_tasks; i++) {
+ int task;
+ char a[16];
+ sprintf(a, "%d", i);
+ const char *av[2];
+ av[0] = a;
+ av[1] = 0;
+ sem_init(sems + i, 1, 0);
+ /* start the task */
+ if ((task = task_spawn_cmd("dataman", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 5, 2048, task_main, av)) <= 0) {
+ warn("task start failed");
+ }
+ }
+ for (i = 0; i < num_tasks; i++) {
+ sem_wait(sems + i);
+ sem_destroy(sems + i);
+ }
+ free(sems);
+ dm_restart(DM_INIT_REASON_IN_FLIGHT);
+ for (i = 0; i < 256; i++) {
+ if (dm_read(DM_KEY_WAY_POINTS, i, buffer, sizeof(buffer)) != 0)
+ break;
+ }
+ if (i >= 256) {
+ warnx("Restart in-flight failed");
+ return -1;
+
+ }
+ dm_restart(DM_INIT_REASON_POWER_ON);
+ for (i = 0; i < 256; i++) {
+ if (dm_read(DM_KEY_WAY_POINTS, i, buffer, sizeof(buffer)) != 0) {
+ warnx("Restart power-on failed");
+ return -1;
+ }
+ }
+ return 0;
+}
diff --git a/src/systemcmds/tests/tests.h b/src/systemcmds/tests/tests.h
index 5cbc5ad88..06e5d20e6 100644
--- a/src/systemcmds/tests/tests.h
+++ b/src/systemcmds/tests/tests.h
@@ -108,6 +108,7 @@ extern int test_param(int argc, char *argv[]);
extern int test_bson(int argc, char *argv[]);
extern int test_file(int argc, char *argv[]);
extern int test_mixer(int argc, char *argv[]);
+extern int test_dataman(int argc, char *argv[]);
__END_DECLS
diff --git a/src/systemcmds/tests/tests_main.c b/src/systemcmds/tests/tests_main.c
index cd998dd18..789c9d8b6 100644
--- a/src/systemcmds/tests/tests_main.c
+++ b/src/systemcmds/tests/tests_main.c
@@ -106,6 +106,7 @@ const struct {
{"file", test_file, 0},
{"mixer", test_mixer, OPT_NOJIGTEST | OPT_NOALLTEST},
{"help", test_help, OPT_NOALLTEST | OPT_NOHELP | OPT_NOJIGTEST},
+ {"dataman", test_dataman, OPT_NOALLTEST},
{NULL, NULL, 0}
};