aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--Documentation/fw_landing.pngbin0 -> 17371 bytes
-rw-r--r--ROMFS/px4fmu_common/init.d/rcS10
-rw-r--r--makefiles/config_px4fmu-v1_default.mk2
-rw-r--r--makefiles/config_px4fmu-v2_default.mk2
-rw-r--r--src/drivers/hott/messages.cpp4
-rw-r--r--src/examples/flow_position_control/flow_position_control_main.c1
-rw-r--r--src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp109
-rw-r--r--src/lib/ecl/attitude_fw/ecl_pitch_controller.h30
-rw-r--r--src/lib/ecl/attitude_fw/ecl_roll_controller.cpp74
-rw-r--r--src/lib/ecl/attitude_fw/ecl_roll_controller.h28
-rw-r--r--src/lib/ecl/attitude_fw/ecl_yaw_controller.cpp114
-rw-r--r--src/lib/ecl/attitude_fw/ecl_yaw_controller.h73
-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.c41
-rw-r--r--src/lib/geo/geo.h17
-rw-r--r--src/lib/launchdetection/CatapultLaunchMethod.cpp90
-rw-r--r--src/lib/launchdetection/CatapultLaunchMethod.h71
-rw-r--r--src/lib/launchdetection/LaunchDetector.cpp96
-rw-r--r--src/lib/launchdetection/LaunchDetector.h75
-rw-r--r--src/lib/launchdetection/LaunchMethod.h54
-rw-r--r--src/lib/launchdetection/launchdetection_params.c72
-rw-r--r--src/lib/launchdetection/module.mk40
-rw-r--r--src/modules/commander/commander.cpp356
-rw-r--r--src/modules/commander/commander_params.c2
-rw-r--r--src/modules/commander/state_machine_helper.cpp223
-rw-r--r--src/modules/commander/state_machine_helper.h9
-rw-r--r--src/modules/controllib/uorb/blocks.cpp18
-rw-r--r--src/modules/controllib/uorb/blocks.hpp8
-rw-r--r--src/modules/dataman/dataman.c741
-rw-r--r--src/modules/dataman/dataman.h119
-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.cpp267
-rw-r--r--src/modules/fw_att_control/fw_att_control_params.c134
-rw-r--r--src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp611
-rw-r--r--src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c10
-rw-r--r--src/modules/fw_pos_control_l1/landingslope.cpp82
-rw-r--r--src/modules/fw_pos_control_l1/landingslope.h109
-rw-r--r--src/modules/fw_pos_control_l1/module.mk3
-rw-r--r--src/modules/mavlink/mavlink.c40
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp3
-rw-r--r--src/modules/mavlink/missionlib.c390
-rw-r--r--src/modules/mavlink/module.mk1
-rw-r--r--src/modules/mavlink/orb_listener.c57
-rw-r--r--src/modules/mavlink/orb_topics.h11
-rw-r--r--src/modules/mavlink/waypoints.c1074
-rw-r--r--src/modules/mavlink/waypoints.h48
-rw-r--r--src/modules/mavlink_onboard/mavlink.c3
-rw-r--r--src/modules/mavlink_onboard/orb_topics.h2
-rw-r--r--src/modules/multirotor_att_control/multirotor_att_control_main.c2
-rw-r--r--src/modules/multirotor_pos_control/multirotor_pos_control.c157
-rw-r--r--src/modules/navigator/geofence.cpp299
-rw-r--r--src/modules/navigator/geofence.h93
-rw-r--r--src/modules/navigator/geofence_params.c55
-rw-r--r--src/modules/navigator/mission_feasibility_checker.cpp202
-rw-r--r--src/modules/navigator/mission_feasibility_checker.h83
-rw-r--r--src/modules/navigator/module.mk8
-rw-r--r--src/modules/navigator/navigator_main.cpp1476
-rw-r--r--src/modules/navigator/navigator_mission.cpp257
-rw-r--r--src/modules/navigator/navigator_mission.h97
-rw-r--r--src/modules/navigator/navigator_params.c13
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_main.c4
-rw-r--r--src/modules/px4iofirmware/registers.c2
-rw-r--r--src/modules/px4iofirmware/safety.c1
-rw-r--r--src/modules/sdlog2/sdlog2.c55
-rw-r--r--src/modules/sdlog2/sdlog2_messages.h11
-rw-r--r--src/modules/sensors/sensors.cpp24
-rw-r--r--src/modules/systemlib/mixer/mixer.cpp1
-rw-r--r--src/modules/systemlib/state_table.h75
-rw-r--r--src/modules/uORB/objects_common.cpp14
-rw-r--r--src/modules/uORB/topics/fence.h (renamed from src/modules/uORB/topics/vehicle_global_position_setpoint.h)50
-rw-r--r--src/modules/uORB/topics/home_position.h20
-rw-r--r--src/modules/uORB/topics/mission.h53
-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.h (renamed from src/modules/mavlink/missionlib.h)43
-rw-r--r--src/modules/uORB/topics/navigation_capabilities.h5
-rw-r--r--src/modules/uORB/topics/vehicle_control_mode.h18
-rw-r--r--src/modules/uORB/topics/vehicle_status.h26
-rw-r--r--src/systemcmds/preflight_check/preflight_check.c3
-rw-r--r--src/systemcmds/tests/test_dataman.c182
83 files changed, 6228 insertions, 2667 deletions
diff --git a/Documentation/fw_landing.png b/Documentation/fw_landing.png
new file mode 100644
index 000000000..c1165f16a
--- /dev/null
+++ b/Documentation/fw_landing.png
Binary files differ
diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS
index ed034877f..d66c2c54c 100644
--- a/ROMFS/px4fmu_common/init.d/rcS
+++ b/ROMFS/px4fmu_common/init.d/rcS
@@ -114,6 +114,16 @@ then
#
commander start
+ #
+ # Start the datamanager
+ #
+ dataman 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_default.mk b/makefiles/config_px4fmu-v1_default.mk
index a269d01ab..afe5d2dc6 100644
--- a/makefiles/config_px4fmu-v1_default.mk
+++ b/makefiles/config_px4fmu-v1_default.mk
@@ -104,6 +104,7 @@ MODULES += modules/systemlib
MODULES += modules/systemlib/mixer
MODULES += modules/controllib
MODULES += modules/uORB
+MODULES += modules/dataman
#
# Libraries
@@ -115,6 +116,7 @@ MODULES += lib/ecl
MODULES += lib/external_lgpl
MODULES += lib/geo
MODULES += lib/conversion
+MODULES += lib/launchdetection
#
# Demo apps
diff --git a/makefiles/config_px4fmu-v2_default.mk b/makefiles/config_px4fmu-v2_default.mk
index e90312226..23c2dc4ef 100644
--- a/makefiles/config_px4fmu-v2_default.mk
+++ b/makefiles/config_px4fmu-v2_default.mk
@@ -105,6 +105,7 @@ MODULES += modules/systemlib
MODULES += modules/systemlib/mixer
MODULES += modules/controllib
MODULES += modules/uORB
+MODULES += modules/dataman
#
# Libraries
@@ -116,6 +117,7 @@ MODULES += lib/ecl
MODULES += lib/external_lgpl
MODULES += lib/geo
MODULES += lib/conversion
+MODULES += lib/launchdetection
#
# Demo apps
diff --git a/src/drivers/hott/messages.cpp b/src/drivers/hott/messages.cpp
index bb8d45bea..90a744015 100644
--- a/src/drivers/hott/messages.cpp
+++ b/src/drivers/hott/messages.cpp
@@ -295,8 +295,8 @@ build_gps_response(uint8_t *buffer, size_t *size)
memset(&home, 0, sizeof(home));
orb_copy(ORB_ID(home_position), _home_sub, &home);
- _home_lat = ((double)(home.lat))*1e-7d;
- _home_lon = ((double)(home.lon))*1e-7d;
+ _home_lat = home.lat;
+ _home_lon = home.lon;
_home_position_set = true;
}
diff --git a/src/examples/flow_position_control/flow_position_control_main.c b/src/examples/flow_position_control/flow_position_control_main.c
index 3125ce246..391e40ac1 100644
--- a/src/examples/flow_position_control/flow_position_control_main.c
+++ b/src/examples/flow_position_control/flow_position_control_main.c
@@ -61,7 +61,6 @@
#include <uORB/topics/manual_control_setpoint.h>
#include <uORB/topics/vehicle_local_position.h>
#include <uORB/topics/vehicle_bodyframe_speed_setpoint.h>
-#include <uORB/topics/vehicle_local_position_setpoint.h>
#include <uORB/topics/filtered_bottom_flow.h>
#include <systemlib/systemlib.h>
#include <systemlib/perf_counter.h>
diff --git a/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp b/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp
index 2eb58abd6..b66d1dba5 100644
--- a/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp
+++ b/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp
@@ -45,39 +45,29 @@
#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_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;
@@ -100,34 +90,78 @@ float ECL_PitchController::control(float pitch_setpoint, float pitch, float pitc
}
/* calculate the offset in the rate resulting from rolling */
+ //xxx needs explanation and conversion to body angular rates or should be removed
float turn_offset = fabsf((CONSTANTS_ONE_G / airspeed) *
tanf(roll) * sinf(roll)) * _roll_ff;
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..30a82a86a 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,27 @@ 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,13 +106,17 @@ 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_pos;
float _max_rate_neg;
@@ -109,7 +125,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..9e7d35f68 100644
--- a/src/lib/ecl/attitude_fw/ecl_roll_controller.cpp
+++ b/src/lib/ecl/attitude_fw/ecl_roll_controller.cpp
@@ -45,21 +45,46 @@
#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_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 +95,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 +107,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 +136,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..92c64b95f 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,23 @@ 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 +100,23 @@ 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..5e2200727 100644
--- a/src/lib/ecl/attitude_fw/ecl_yaw_controller.cpp
+++ b/src/lib/ecl/attitude_fw/ecl_yaw_controller.cpp
@@ -44,29 +44,125 @@
#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_ff(0.0f),
+ _integrator_max(0.0f),
+ _max_rate(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..03f3202d0 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,73 @@
#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_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 1d5c85699..5a56dce65 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)
@@ -508,7 +537,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..08fe2b696 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 */
@@ -464,5 +503,3 @@ __EXPORT float _wrap_360(float bearing)
return bearing;
}
-
-
diff --git a/src/lib/geo/geo.h b/src/lib/geo/geo.h
index 123ff80f1..5f4bce698 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,6 +124,20 @@ __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);
diff --git a/src/lib/launchdetection/CatapultLaunchMethod.cpp b/src/lib/launchdetection/CatapultLaunchMethod.cpp
new file mode 100644
index 000000000..d5c759b17
--- /dev/null
+++ b/src/lib/launchdetection/CatapultLaunchMethod.cpp
@@ -0,0 +1,90 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 Estimation and Control Library (ECL). 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 documentation4 and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name ECL 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 CatapultLaunchMethod.cpp
+ * Catpult Launch detection
+ *
+ * Authors and acknowledgements in header.
+ */
+
+#include "CatapultLaunchMethod.h"
+#include <systemlib/err.h>
+
+CatapultLaunchMethod::CatapultLaunchMethod() :
+ last_timestamp(0),
+ integrator(0.0f),
+ launchDetected(false),
+ threshold_accel(NULL, "LAUN_CAT_A", false),
+ threshold_time(NULL, "LAUN_CAT_T", false)
+{
+
+}
+
+CatapultLaunchMethod::~CatapultLaunchMethod() {
+
+}
+
+void CatapultLaunchMethod::update(float accel_x)
+{
+ float dt = (float)hrt_elapsed_time(&last_timestamp) * 1e-6f;
+ last_timestamp = hrt_absolute_time();
+
+ if (accel_x > threshold_accel.get()) {
+ integrator += accel_x * dt;
+// warnx("*** integrator %.3f, threshold_accel %.3f, threshold_time %.3f, accel_x %.3f, dt %.3f",
+// (double)integrator, (double)threshold_accel.get(), (double)threshold_time.get(), (double)accel_x, (double)dt);
+ if (integrator > threshold_accel.get() * threshold_time.get()) {
+ launchDetected = true;
+ }
+
+ } else {
+// warnx("integrator %.3f, threshold_accel %.3f, threshold_time %.3f, accel_x %.3f, dt %.3f",
+// (double)integrator, (double)threshold_accel.get(), (double)threshold_time.get(), (double)accel_x, (double)dt);
+ /* reset integrator */
+ integrator = 0.0f;
+ launchDetected = false;
+ }
+
+}
+
+bool CatapultLaunchMethod::getLaunchDetected()
+{
+ return launchDetected;
+}
+
+void CatapultLaunchMethod::updateParams()
+{
+ threshold_accel.update();
+ threshold_time.update();
+}
diff --git a/src/lib/launchdetection/CatapultLaunchMethod.h b/src/lib/launchdetection/CatapultLaunchMethod.h
new file mode 100644
index 000000000..e943f11e9
--- /dev/null
+++ b/src/lib/launchdetection/CatapultLaunchMethod.h
@@ -0,0 +1,71 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 Estimation and Control Library (ECL). 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 documentation4 and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name ECL 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 CatapultLaunchMethod.h
+ * Catpult Launch detection
+ *
+ * @author Thomas Gubler <thomasgubler@gmail.com>
+ */
+
+#ifndef CATAPULTLAUNCHMETHOD_H_
+#define CATAPULTLAUNCHMETHOD_H_
+
+#include "LaunchMethod.h"
+
+#include <drivers/drv_hrt.h>
+#include <controllib/block/BlockParam.hpp>
+
+class CatapultLaunchMethod : public LaunchMethod
+{
+public:
+ CatapultLaunchMethod();
+ ~CatapultLaunchMethod();
+
+ void update(float accel_x);
+ bool getLaunchDetected();
+ void updateParams();
+
+private:
+ hrt_abstime last_timestamp;
+// float threshold_accel_raw;
+// float threshold_time;
+ float integrator;
+ bool launchDetected;
+
+ control::BlockParamFloat threshold_accel;
+ control::BlockParamFloat threshold_time;
+
+};
+
+#endif /* CATAPULTLAUNCHMETHOD_H_ */
diff --git a/src/lib/launchdetection/LaunchDetector.cpp b/src/lib/launchdetection/LaunchDetector.cpp
new file mode 100644
index 000000000..67b32ad82
--- /dev/null
+++ b/src/lib/launchdetection/LaunchDetector.cpp
@@ -0,0 +1,96 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 Estimation and Control Library (ECL). 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 ECL 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 launchDetection.cpp
+ * Auto Detection for different launch methods (e.g. catapult)
+ *
+ * Authors and acknowledgements in header.
+ */
+
+#include "LaunchDetector.h"
+#include "CatapultLaunchMethod.h"
+#include <systemlib/err.h>
+
+LaunchDetector::LaunchDetector() :
+ launchdetection_on(NULL, "LAUN_ALL_ON", false),
+ throttlePreTakeoff(NULL, "LAUN_THR_PRE", false)
+{
+ /* init all detectors */
+ launchMethods[0] = new CatapultLaunchMethod();
+
+
+ /* update all parameters of all detectors */
+ updateParams();
+}
+
+LaunchDetector::~LaunchDetector()
+{
+
+}
+
+void LaunchDetector::update(float accel_x)
+{
+ if (launchdetection_on.get() == 1) {
+ for (uint8_t i = 0; i < sizeof(launchMethods)/sizeof(LaunchMethod); i++) {
+ launchMethods[i]->update(accel_x);
+ }
+ }
+}
+
+bool LaunchDetector::getLaunchDetected()
+{
+ if (launchdetection_on.get() == 1) {
+ for (uint8_t i = 0; i < sizeof(launchMethods)/sizeof(LaunchMethod); i++) {
+ if(launchMethods[i]->getLaunchDetected()) {
+ return true;
+ }
+ }
+ }
+
+ return false;
+}
+
+void LaunchDetector::updateParams() {
+
+ warnx(" LaunchDetector::updateParams()");
+ launchdetection_on.update();
+ throttlePreTakeoff.update();
+
+ for (uint8_t i = 0; i < sizeof(launchMethods)/sizeof(LaunchMethod); i++) {
+ launchMethods[i]->updateParams();
+ warnx("updating component %d", i);
+ }
+
+ warnx(" LaunchDetector::updateParams() ended");
+}
diff --git a/src/lib/launchdetection/LaunchDetector.h b/src/lib/launchdetection/LaunchDetector.h
new file mode 100644
index 000000000..7c2ff826c
--- /dev/null
+++ b/src/lib/launchdetection/LaunchDetector.h
@@ -0,0 +1,75 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 Estimation and Control Library (ECL). 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 documentation4 and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name ECL 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 LaunchDetector.h
+ * Auto Detection for different launch methods (e.g. catapult)
+ *
+ * @author Thomas Gubler <thomasgubler@gmail.com>
+ */
+
+#ifndef LAUNCHDETECTOR_H
+#define LAUNCHDETECTOR_H
+
+#include <stdbool.h>
+#include <stdint.h>
+
+#include "LaunchMethod.h"
+
+#include <controllib/block/BlockParam.hpp>
+
+class __EXPORT LaunchDetector
+{
+public:
+ LaunchDetector();
+ ~LaunchDetector();
+
+ void update(float accel_x);
+ bool getLaunchDetected();
+ void updateParams();
+ bool launchDetectionEnabled() { return (bool)launchdetection_on.get(); };
+
+ float getThrottlePreTakeoff() {return throttlePreTakeoff.get(); }
+
+// virtual bool getLaunchDetected();
+protected:
+private:
+ LaunchMethod* launchMethods[1];
+ control::BlockParamInt launchdetection_on;
+ control::BlockParamFloat throttlePreTakeoff;
+
+
+};
+
+
+#endif // LAUNCHDETECTOR_H
diff --git a/src/lib/launchdetection/LaunchMethod.h b/src/lib/launchdetection/LaunchMethod.h
new file mode 100644
index 000000000..bfb5f8cb4
--- /dev/null
+++ b/src/lib/launchdetection/LaunchMethod.h
@@ -0,0 +1,54 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 Estimation and Control Library (ECL). 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 documentation4 and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name ECL 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 LaunchMethod.h
+ * Base class for different launch methods
+ *
+ * @author Thomas Gubler <thomasgubler@gmail.com>
+ */
+
+#ifndef LAUNCHMETHOD_H_
+#define LAUNCHMETHOD_H_
+
+class LaunchMethod
+{
+public:
+ virtual void update(float accel_x) = 0;
+ virtual bool getLaunchDetected() = 0;
+ virtual void updateParams() = 0;
+protected:
+private:
+};
+
+#endif /* LAUNCHMETHOD_H_ */
diff --git a/src/lib/launchdetection/launchdetection_params.c b/src/lib/launchdetection/launchdetection_params.c
new file mode 100644
index 000000000..63a8981aa
--- /dev/null
+++ b/src/lib/launchdetection/launchdetection_params.c
@@ -0,0 +1,72 @@
+/****************************************************************************
+ *
+ * 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
+ * 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 launchdetection_params.c
+ *
+ * Parameters for launchdetection
+ *
+ * @author Thomas Gubler <thomasgubler@gmail.com>
+ */
+
+#include <nuttx/config.h>
+
+#include <systemlib/param/param.h>
+
+/*
+ * Launch detection parameters, accessible via MAVLink
+ *
+ */
+
+/* Catapult Launch detection */
+
+// @DisplayName Switch to enable launchdetection
+// @Description if set to 1 launchdetection is enabled
+// @Range 0 or 1
+PARAM_DEFINE_INT32(LAUN_ALL_ON, 0);
+
+// @DisplayName Catapult Accelerometer Threshold
+// @Description LAUN_CAT_A * LAUN_CAT_T serves as threshold to trigger launch detection
+// @Range > 0
+PARAM_DEFINE_FLOAT(LAUN_CAT_A, 30.0f);
+
+// @DisplayName Catapult Time Threshold
+// @Description LAUN_CAT_A * LAUN_CAT_T serves as threshold to trigger launch detection
+// @Range > 0, in seconds
+PARAM_DEFINE_FLOAT(LAUN_CAT_T, 0.05f);
+
+// @DisplayName Throttle setting while detecting the launch
+// @Description The throttle is set to this value while the system is waiting for the takeoff
+// @Range 0 to 1
+PARAM_DEFINE_FLOAT(LAUN_THR_PRE, 0.0f);
diff --git a/src/lib/launchdetection/module.mk b/src/lib/launchdetection/module.mk
new file mode 100644
index 000000000..13648b74c
--- /dev/null
+++ b/src/lib/launchdetection/module.mk
@@ -0,0 +1,40 @@
+############################################################################
+#
+# Copyright (c) 2013 Estimation and Control Library (ECL). 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.
+#
+############################################################################
+
+#
+# Launchdetection Library
+#
+
+SRCS = LaunchDetector.cpp \
+ CatapultLaunchMethod.cpp \
+ launchdetection_params.c
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index add7312de..dbfca38b1 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -69,7 +69,6 @@
#include <uORB/topics/vehicle_local_position.h>
#include <uORB/topics/vehicle_gps_position.h>
#include <uORB/topics/vehicle_command.h>
-#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/subsystem_info.h>
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/actuator_armed.h>
@@ -189,7 +188,7 @@ void usage(const char *reason);
/**
* React to commands that are sent e.g. from the mavlink module.
*/
-void handle_command(struct vehicle_status_s *status, struct vehicle_control_mode_s *control_mode, struct vehicle_command_s *cmd, struct actuator_armed_s *armed);
+bool handle_command(struct vehicle_status_s *status, struct vehicle_command_s *cmd, struct actuator_armed_s *armed);
/**
* Mainloop of commander.
@@ -210,8 +209,6 @@ void print_reject_arm(const char *msg);
void print_status();
-transition_result_t check_navigation_state_machine(struct vehicle_status_s *status, struct vehicle_control_mode_s *control_mode, struct vehicle_local_position_s *local_pos);
-
/**
* Loop that runs at a lower rate and priority for calibration and parameter tasks.
*/
@@ -341,13 +338,13 @@ void print_status()
warnx("arming: %s", armed_str);
}
-static orb_advert_t control_mode_pub;
static orb_advert_t status_pub;
-void handle_command(struct vehicle_status_s *status, const struct safety_s *safety, struct vehicle_control_mode_s *control_mode, struct vehicle_command_s *cmd, struct actuator_armed_s *armed)
+bool handle_command(struct vehicle_status_s *status, const struct safety_s *safety, struct vehicle_command_s *cmd, struct actuator_armed_s *armed)
{
/* result of the command */
- uint8_t result = VEHICLE_CMD_RESULT_UNSUPPORTED;
+ enum VEHICLE_CMD_RESULT result = VEHICLE_CMD_RESULT_UNSUPPORTED;
+ bool ret = false;
/* only handle high-priority commands here */
@@ -360,12 +357,12 @@ void handle_command(struct vehicle_status_s *status, const struct safety_s *safe
/* set HIL state */
hil_state_t new_hil_state = (base_mode & MAV_MODE_FLAG_HIL_ENABLED) ? HIL_STATE_ON : HIL_STATE_OFF;
- int hil_ret = hil_state_transition(new_hil_state, status_pub, status, control_mode_pub, control_mode, mavlink_fd);
+ int hil_ret = hil_state_transition(new_hil_state, status_pub, status, mavlink_fd);
/* if HIL got enabled, reset battery status state */
- if (hil_ret == OK && control_mode->flag_system_hil_enabled) {
+ if (hil_ret == OK && status->hil_state == HIL_STATE_ON) {
/* reset the arming mode to disarmed */
- arming_res = arming_state_transition(status, safety, control_mode, ARMING_STATE_STANDBY, armed);
+ arming_res = arming_state_transition(status, safety, ARMING_STATE_STANDBY, armed);
if (arming_res != TRANSITION_DENIED) {
mavlink_log_info(mavlink_fd, "[cmd] HIL: Reset ARMED state to standby");
@@ -374,6 +371,8 @@ void handle_command(struct vehicle_status_s *status, const struct safety_s *safe
mavlink_log_info(mavlink_fd, "[cmd] HIL: FAILED resetting armed state");
}
}
+ if (hil_ret == OK)
+ ret = true;
// TODO remove debug code
//mavlink_log_critical(mavlink_fd, "#audio: command setmode: %d %d", base_mode, custom_main_mode);
@@ -381,12 +380,12 @@ void handle_command(struct vehicle_status_s *status, const struct safety_s *safe
arming_res = TRANSITION_NOT_CHANGED;
if (base_mode & MAV_MODE_FLAG_SAFETY_ARMED) {
- if ((safety->safety_switch_available && !safety->safety_off) && !control_mode->flag_system_hil_enabled) {
+ if ((safety->safety_switch_available && !safety->safety_off) && status->hil_state == HIL_STATE_OFF) {
print_reject_arm("NOT ARMING: Press safety switch first.");
arming_res = TRANSITION_DENIED;
} else {
- arming_res = arming_state_transition(status, safety, control_mode, ARMING_STATE_ARMED, armed);
+ arming_res = arming_state_transition(status, safety, ARMING_STATE_ARMED, armed);
}
if (arming_res == TRANSITION_CHANGED) {
@@ -396,7 +395,7 @@ void handle_command(struct vehicle_status_s *status, const struct safety_s *safe
} else {
if (status->arming_state == ARMING_STATE_ARMED || status->arming_state == ARMING_STATE_ARMED_ERROR) {
arming_state_t new_arming_state = (status->arming_state == ARMING_STATE_ARMED ? ARMING_STATE_STANDBY : ARMING_STATE_STANDBY_ERROR);
- arming_res = arming_state_transition(status, safety, control_mode, new_arming_state, armed);
+ arming_res = arming_state_transition(status, safety, new_arming_state, armed);
if (arming_res == TRANSITION_CHANGED) {
mavlink_log_info(mavlink_fd, "[cmd] DISARMED by command");
@@ -406,6 +405,8 @@ void handle_command(struct vehicle_status_s *status, const struct safety_s *safe
arming_res = TRANSITION_NOT_CHANGED;
}
}
+ if (arming_res == TRANSITION_CHANGED)
+ ret = true;
/* set main state */
transition_result_t main_res = TRANSITION_DENIED;
@@ -446,6 +447,8 @@ void handle_command(struct vehicle_status_s *status, const struct safety_s *safe
}
}
}
+ if (main_res == TRANSITION_CHANGED)
+ ret = true;
if (arming_res != TRANSITION_DENIED && main_res != TRANSITION_DENIED) {
result = VEHICLE_CMD_RESULT_ACCEPTED;
@@ -457,29 +460,6 @@ void handle_command(struct vehicle_status_s *status, const struct safety_s *safe
break;
}
- case VEHICLE_CMD_NAV_TAKEOFF: {
- if (armed->armed) {
- transition_result_t nav_res = navigation_state_transition(status, NAVIGATION_STATE_AUTO_TAKEOFF, control_mode);
-
- if (nav_res == TRANSITION_CHANGED) {
- mavlink_log_info(mavlink_fd, "[cmd] TAKEOFF on command");
- }
-
- if (nav_res != TRANSITION_DENIED) {
- result = VEHICLE_CMD_RESULT_ACCEPTED;
-
- } else {
- result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
- }
-
- } else {
- /* reject TAKEOFF not armed */
- result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
- }
-
- break;
- }
-
case VEHICLE_CMD_COMPONENT_ARM_DISARM: {
transition_result_t arming_res = TRANSITION_NOT_CHANGED;
@@ -489,12 +469,13 @@ void handle_command(struct vehicle_status_s *status, const struct safety_s *safe
arming_res = TRANSITION_DENIED;
} else {
- arming_res = arming_state_transition(status, safety, control_mode, ARMING_STATE_ARMED, armed);
+ arming_res = arming_state_transition(status, safety, ARMING_STATE_ARMED, armed);
}
if (arming_res == TRANSITION_CHANGED) {
mavlink_log_critical(mavlink_fd, "#audio: ARMED by component arm cmd");
result = VEHICLE_CMD_RESULT_ACCEPTED;
+ ret = true;
} else {
mavlink_log_critical(mavlink_fd, "#audio: REJECTING component arm cmd");
@@ -504,29 +485,61 @@ void handle_command(struct vehicle_status_s *status, const struct safety_s *safe
}
break;
- default:
- break;
- }
+ case VEHICLE_CMD_OVERRIDE_GOTO: {
+ // TODO listen vehicle_command topic directly from navigator (?)
+ unsigned int mav_goto = cmd->param1;
+ if (mav_goto == 0) { // MAV_GOTO_DO_HOLD
+ status->set_nav_state = NAV_STATE_LOITER;
+ status->set_nav_state_timestamp = hrt_absolute_time();
+ mavlink_log_critical(mavlink_fd, "#audio: pause mission cmd");
+ result = VEHICLE_CMD_RESULT_ACCEPTED;
+ ret = true;
- /* supported command handling stop */
- if (result == VEHICLE_CMD_RESULT_ACCEPTED) {
- tune_positive();
+ } else if (mav_goto == 1) { // MAV_GOTO_DO_CONTINUE
+ status->set_nav_state = NAV_STATE_MISSION;
+ status->set_nav_state_timestamp = hrt_absolute_time();
+ mavlink_log_critical(mavlink_fd, "#audio: continue mission cmd");
+ result = VEHICLE_CMD_RESULT_ACCEPTED;
+ ret = true;
- } else if (result == VEHICLE_CMD_RESULT_UNSUPPORTED) {
- /* we do not care in the high prio loop about commands we don't know */
- } else {
- tune_negative();
+ } else {
+ mavlink_log_info(mavlink_fd, "Unsupported OVERRIDE_GOTO: %f %f %f %f %f %f %f %f", cmd->param1, cmd->param2, cmd->param3, cmd->param4, cmd->param5, cmd->param6, cmd->param7);
+ }
+ }
+ break;
- if (result == VEHICLE_CMD_RESULT_DENIED) {
- mavlink_log_critical(mavlink_fd, "#audio: command denied: %u", cmd->command);
+ /* Flight termination */
+ case VEHICLE_CMD_DO_SET_SERVO: { //xxx: needs its own mavlink command
- } else if (result == VEHICLE_CMD_RESULT_FAILED) {
- mavlink_log_critical(mavlink_fd, "#audio: command failed: %u", cmd->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);
+ result = VEHICLE_CMD_RESULT_ACCEPTED;
+ ret = true;
- } else if (result == VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED) {
- mavlink_log_critical(mavlink_fd, "#audio: command temporarily rejected: %u", cmd->command);
+ } else {
+ /* reject parachute depoyment not armed */
+ result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
+ }
}
+ break;
+
+ case VEHICLE_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
+ case VEHICLE_CMD_PREFLIGHT_CALIBRATION:
+ case VEHICLE_CMD_PREFLIGHT_SET_SENSOR_OFFSETS:
+ case VEHICLE_CMD_PREFLIGHT_STORAGE:
+ /* ignore commands that handled in low prio loop */
+ break;
+
+ default:
+ /* warn about unsupported commands */
+ answer_command(*cmd, VEHICLE_CMD_RESULT_UNSUPPORTED);
+ break;
+ }
+
+ if (result != VEHICLE_CMD_RESULT_UNSUPPORTED) {
+ /* already warned about unsupported commands in "default" case */
+ answer_command(*cmd, result);
}
/* send any requested ACKs */
@@ -544,9 +557,6 @@ static struct actuator_armed_s armed;
static struct safety_s safety;
-/* flags for control apps */
-struct vehicle_control_mode_s control_mode;
-
int commander_thread_main(int argc, char *argv[])
{
/* not yet initialized */
@@ -589,11 +599,9 @@ int commander_thread_main(int argc, char *argv[])
/* Initialize armed with all false */
memset(&armed, 0, sizeof(armed));
- /* Initialize all flags to false */
- memset(&control_mode, 0, sizeof(control_mode));
-
status.main_state = MAIN_STATE_MANUAL;
- status.navigation_state = NAVIGATION_STATE_DIRECT;
+ status.set_nav_state = NAV_STATE_NONE;
+ status.set_nav_state_timestamp = 0;
status.arming_state = ARMING_STATE_INIT;
status.hil_state = HIL_STATE_OFF;
@@ -605,9 +613,6 @@ int commander_thread_main(int argc, char *argv[])
status.rc_signal_lost = true;
status.offboard_control_signal_lost = true;
- /* allow manual override initially */
- control_mode.flag_external_manual_override_ok = true;
-
/* set battery warning flag */
status.battery_warning = VEHICLE_BATTERY_WARNING_NONE;
status.condition_battery_voltage_valid = false;
@@ -615,9 +620,6 @@ int commander_thread_main(int argc, char *argv[])
// XXX for now just set sensors as initialized
status.condition_system_sensors_initialized = true;
- // XXX just disable offboard control for now
- control_mode.flag_control_offboard_enabled = false;
-
/* advertise to ORB */
status_pub = orb_advertise(ORB_ID(vehicle_status), &status);
/* publish current state machine */
@@ -629,8 +631,6 @@ int commander_thread_main(int argc, char *argv[])
armed_pub = orb_advertise(ORB_ID(actuator_armed), &armed);
- control_mode_pub = orb_advertise(ORB_ID(vehicle_control_mode), &control_mode);
-
/* home position */
orb_advert_t home_pub = -1;
struct home_position_s home;
@@ -780,11 +780,9 @@ int commander_thread_main(int argc, char *argv[])
status.system_type == VEHICLE_TYPE_QUADROTOR ||
status.system_type == VEHICLE_TYPE_HEXAROTOR ||
status.system_type == VEHICLE_TYPE_OCTOROTOR) {
- control_mode.flag_external_manual_override_ok = false;
status.is_rotary_wing = true;
} else {
- control_mode.flag_external_manual_override_ok = true;
status.is_rotary_wing = false;
}
@@ -836,7 +834,7 @@ int commander_thread_main(int argc, char *argv[])
// XXX this would be the right approach to do it, but do we *WANT* this?
// /* disarm if safety is now on and still armed */
// if (safety.safety_switch_available && !safety.safety_off) {
- // (void)arming_state_transition(&status, &safety, &control_mode, ARMING_STATE_STANDBY, &armed);
+ // (void)arming_state_transition(&status, &safety, ARMING_STATE_STANDBY, &armed);
// }
}
@@ -956,10 +954,10 @@ int commander_thread_main(int argc, char *argv[])
battery_tune_played = false;
if (armed.armed) {
- arming_state_transition(&status, &safety, &control_mode, ARMING_STATE_ARMED_ERROR, &armed);
+ arming_state_transition(&status, &safety, ARMING_STATE_ARMED_ERROR, &armed);
} else {
- arming_state_transition(&status, &safety, &control_mode, ARMING_STATE_STANDBY_ERROR, &armed);
+ arming_state_transition(&status, &safety, ARMING_STATE_STANDBY_ERROR, &armed);
}
status_changed = true;
@@ -970,7 +968,7 @@ int commander_thread_main(int argc, char *argv[])
/* If in INIT state, try to proceed to STANDBY state */
if (status.arming_state == ARMING_STATE_INIT && low_prio_task == LOW_PRIO_TASK_NONE) {
// XXX check for sensors
- arming_state_transition(&status, &safety, &control_mode, ARMING_STATE_STANDBY, &armed);
+ arming_state_transition(&status, &safety, ARMING_STATE_STANDBY, &armed);
} else {
// XXX: Add emergency stuff if sensors are lost
@@ -1006,23 +1004,17 @@ int commander_thread_main(int argc, char *argv[])
if (!home_position_set && gps_position.fix_type >= 3 &&
(gps_position.eph_m < hdop_threshold_m) && (gps_position.epv_m < vdop_threshold_m) && // XXX note that vdop is 0 for mtk
- (hrt_absolute_time() < gps_position.timestamp_position + POSITION_TIMEOUT) && !armed.armed) {
+ (hrt_absolute_time() < gps_position.timestamp_position + POSITION_TIMEOUT) && !armed.armed
+ && global_position.valid) {
/* copy position data to uORB home message, store it locally as well */
- // TODO use global position estimate
- home.lat = gps_position.lat;
- home.lon = gps_position.lon;
- home.alt = gps_position.alt;
- home.eph_m = gps_position.eph_m;
- home.epv_m = gps_position.epv_m;
- home.s_variance_m_s = gps_position.s_variance_m_s;
- home.p_variance_m = gps_position.p_variance_m;
+ home.lat = (double)global_position.lat / 1e7d;
+ home.lon = (double)global_position.lon / 1e7d;
+ home.altitude = (float)global_position.alt;
- double home_lat_d = home.lat * 1e-7;
- double home_lon_d = home.lon * 1e-7;
- warnx("home: lat = %.7f, lon = %.7f", home_lat_d, home_lon_d);
- mavlink_log_info(mavlink_fd, "[cmd] home: %.7f, %.7f", home_lat_d, home_lon_d);
+ warnx("home: lat = %.7f, lon = %.7f, alt = %.4f ", home.lat, home.lon, (double)home.altitude);
+ mavlink_log_info(mavlink_fd, "[cmd] home: %.7f, %.7f, %.4f", home.lat, home.lon, (double)home.altitude);
/* announce new home position */
if (home_pub > 0) {
@@ -1066,15 +1058,13 @@ int commander_thread_main(int argc, char *argv[])
* do it only for rotary wings */
if (status.is_rotary_wing &&
(status.arming_state == ARMING_STATE_ARMED || status.arming_state == ARMING_STATE_ARMED_ERROR) &&
- (status.main_state == MAIN_STATE_MANUAL || status.navigation_state == NAVIGATION_STATE_AUTO_READY ||
- (status.condition_landed && (
- status.navigation_state == NAVIGATION_STATE_ALTHOLD ||
- status.navigation_state == NAVIGATION_STATE_VECTOR
- ))) && sp_man.yaw < -STICK_ON_OFF_LIMIT && sp_man.throttle < STICK_THRUST_RANGE * 0.1f) {
+ (status.main_state == MAIN_STATE_MANUAL || status.condition_landed) &&
+ sp_man.yaw < -STICK_ON_OFF_LIMIT && sp_man.throttle < STICK_THRUST_RANGE * 0.1f) {
+
if (stick_off_counter > STICK_ON_OFF_COUNTER_LIMIT) {
/* disarm to STANDBY if ARMED or to STANDBY_ERROR if ARMED_ERROR */
arming_state_t new_arming_state = (status.arming_state == ARMING_STATE_ARMED ? ARMING_STATE_STANDBY : ARMING_STATE_STANDBY_ERROR);
- res = arming_state_transition(&status, &safety, &control_mode, new_arming_state, &armed);
+ res = arming_state_transition(&status, &safety, new_arming_state, &armed);
stick_off_counter = 0;
} else {
@@ -1096,7 +1086,7 @@ int commander_thread_main(int argc, char *argv[])
print_reject_arm("NOT ARMING: Switch to MANUAL mode first.");
} else {
- res = arming_state_transition(&status, &safety, &control_mode, ARMING_STATE_ARMED, &armed);
+ res = arming_state_transition(&status, &safety, ARMING_STATE_ARMED, &armed);
}
stick_on_counter = 0;
@@ -1147,6 +1137,16 @@ int commander_thread_main(int argc, char *argv[])
}
}
+ /* Flight termination in manual mode if assisted switch is on easy position //xxx hack! */
+ if (armed.armed && status.main_state == MAIN_STATE_MANUAL && sp_man.assisted_switch > STICK_ON_OFF_LIMIT) {
+ transition_result_t flighttermination_res = flighttermination_state_transition(&status, FLIGHTTERMINATION_STATE_ON);
+ if (flighttermination_res == TRANSITION_CHANGED) {
+ tune_positive();
+ }
+ } else {
+ flighttermination_state_transition(&status, FLIGHTTERMINATION_STATE_OFF);
+ }
+
/* handle commands last, as the system needs to be updated to handle them */
orb_check(cmd_sub, &updated);
@@ -1156,31 +1156,19 @@ int commander_thread_main(int argc, char *argv[])
orb_copy(ORB_ID(vehicle_command), cmd_sub, &cmd);
/* handle it */
- handle_command(&status, &safety, &control_mode, &cmd, &armed);
- }
-
- /* evaluate the navigation state machine */
- transition_result_t res = check_navigation_state_machine(&status, &control_mode, &local_position);
-
- if (res == TRANSITION_DENIED) {
- /* DENIED here indicates bug in the commander */
- warnx("ERROR: nav denied: arm %d main %d nav %d", status.arming_state, status.main_state, status.navigation_state);
- mavlink_log_critical(mavlink_fd, "#audio: ERROR: nav denied: arm %d main %d nav %d", status.arming_state, status.main_state, status.navigation_state);
+ if (handle_command(&status, &safety, &cmd, &armed))
+ status_changed = true;
}
/* check which state machines for changes, clear "changed" flag */
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();
- if (navigation_state_changed || arming_state_changed) {
- control_mode.flag_armed = armed.armed; // copy armed state to vehicle_control_mode topic
- }
-
- if (arming_state_changed || main_state_changed || navigation_state_changed) {
- mavlink_log_info(mavlink_fd, "[cmd] state: arm %d, main %d, nav %d", status.arming_state, status.main_state, status.navigation_state);
+ if (arming_state_changed || main_state_changed) {
+ mavlink_log_info(mavlink_fd, "[cmd] state: arm %d, main %d", status.arming_state, status.main_state);
status_changed = true;
}
@@ -1188,8 +1176,6 @@ int commander_thread_main(int argc, char *argv[])
if (counter % (200000 / COMMANDER_MONITORING_INTERVAL) == 0 || status_changed) {
status.timestamp = t1;
orb_publish(ORB_ID(vehicle_status), status_pub, &status);
- control_mode.timestamp = t1;
- orb_publish(ORB_ID(vehicle_control_mode), control_mode_pub, &control_mode);
armed.timestamp = t1;
orb_publish(ORB_ID(actuator_armed), armed_pub, &armed);
}
@@ -1379,7 +1365,7 @@ check_mode_switches(struct manual_control_setpoint_s *sp_man, struct vehicle_sta
current_status->mode_switch = MODE_SWITCH_ASSISTED;
}
- /* land switch */
+ /* return switch */
if (!isfinite(sp_man->return_switch)) {
current_status->return_switch = RETURN_SWITCH_NONE;
@@ -1387,7 +1373,7 @@ check_mode_switches(struct manual_control_setpoint_s *sp_man, struct vehicle_sta
current_status->return_switch = RETURN_SWITCH_RETURN;
} else {
- current_status->return_switch = RETURN_SWITCH_NONE;
+ current_status->return_switch = RETURN_SWITCH_NORMAL;
}
/* assisted switch */
@@ -1403,10 +1389,10 @@ check_mode_switches(struct manual_control_setpoint_s *sp_man, struct vehicle_sta
/* mission switch */
if (!isfinite(sp_man->mission_switch)) {
- current_status->mission_switch = MISSION_SWITCH_MISSION;
+ current_status->mission_switch = MISSION_SWITCH_NONE;
} else if (sp_man->mission_switch > STICK_ON_OFF_LIMIT) {
- current_status->mission_switch = MISSION_SWITCH_NONE;
+ current_status->mission_switch = MISSION_SWITCH_LOITER;
} else {
current_status->mission_switch = MISSION_SWITCH_MISSION;
@@ -1502,133 +1488,6 @@ print_reject_arm(const char *msg)
}
}
-transition_result_t
-check_navigation_state_machine(struct vehicle_status_s *status, struct vehicle_control_mode_s *control_mode, struct vehicle_local_position_s *local_pos)
-{
- transition_result_t res = TRANSITION_DENIED;
-
- if (status->main_state == MAIN_STATE_AUTO) {
- if (status->arming_state == ARMING_STATE_ARMED || status->arming_state == ARMING_STATE_ARMED_ERROR) {
- // TODO AUTO_LAND handling
- if (status->navigation_state == NAVIGATION_STATE_AUTO_TAKEOFF) {
- /* don't switch to other states until takeoff not completed */
- // XXX: only respect the condition_landed when the local position is actually valid
- if (status->is_rotary_wing && status->condition_local_altitude_valid && (local_pos->z > -takeoff_alt || status->condition_landed)) {
- return TRANSITION_NOT_CHANGED;
- }
- }
-
- if (status->navigation_state != NAVIGATION_STATE_AUTO_TAKEOFF &&
- status->navigation_state != NAVIGATION_STATE_AUTO_LOITER &&
- status->navigation_state != NAVIGATION_STATE_AUTO_MISSION &&
- status->navigation_state != NAVIGATION_STATE_AUTO_RTL) {
- /* possibly on ground, switch to TAKEOFF if needed */
- if (status->is_rotary_wing && status->condition_local_altitude_valid && (local_pos->z > -takeoff_alt || status->condition_landed)) {
- res = navigation_state_transition(status, NAVIGATION_STATE_AUTO_TAKEOFF, control_mode);
- return res;
- }
- }
-
- /* switch to AUTO mode */
- if (status->rc_signal_found_once && !status->rc_signal_lost) {
- /* act depending on switches when manual control enabled */
- if (status->return_switch == RETURN_SWITCH_RETURN) {
- /* RTL */
- res = navigation_state_transition(status, NAVIGATION_STATE_AUTO_RTL, control_mode);
-
- } else {
- if (status->mission_switch == MISSION_SWITCH_MISSION) {
- /* MISSION */
- res = navigation_state_transition(status, NAVIGATION_STATE_AUTO_MISSION, control_mode);
-
- } else {
- /* LOITER */
- res = navigation_state_transition(status, NAVIGATION_STATE_AUTO_LOITER, control_mode);
- }
- }
-
- } else {
- /* switch to MISSION when no RC control and first time in some AUTO mode */
- if (status->navigation_state == NAVIGATION_STATE_AUTO_LOITER ||
- status->navigation_state == NAVIGATION_STATE_AUTO_MISSION ||
- status->navigation_state == NAVIGATION_STATE_AUTO_RTL ||
- status->navigation_state == NAVIGATION_STATE_AUTO_LAND) {
- res = TRANSITION_NOT_CHANGED;
-
- } else {
- res = navigation_state_transition(status, NAVIGATION_STATE_AUTO_MISSION, control_mode);
- }
- }
-
- } else {
- /* disarmed, always switch to AUTO_READY */
- res = navigation_state_transition(status, NAVIGATION_STATE_AUTO_READY, control_mode);
- }
-
- } else {
- /* manual control modes */
- if (status->rc_signal_lost && (status->arming_state == ARMING_STATE_ARMED || status->arming_state == ARMING_STATE_ARMED_ERROR)) {
- /* switch to failsafe mode */
- bool manual_control_old = control_mode->flag_control_manual_enabled;
-
- if (!status->condition_landed && status->condition_local_position_valid) {
- /* in air: try to hold position if possible */
- res = navigation_state_transition(status, NAVIGATION_STATE_VECTOR, control_mode);
-
- } else {
- /* landed: don't try to hold position but land (if taking off) */
- res = TRANSITION_DENIED;
- }
-
- if (res == TRANSITION_DENIED) {
- res = navigation_state_transition(status, NAVIGATION_STATE_ALTHOLD, control_mode);
- }
-
- control_mode->flag_control_manual_enabled = false;
-
- if (res == TRANSITION_NOT_CHANGED && manual_control_old) {
- /* mark navigation state as changed to force immediate flag publishing */
- set_navigation_state_changed();
- res = TRANSITION_CHANGED;
- }
-
- if (res == TRANSITION_CHANGED) {
- if (control_mode->flag_control_position_enabled) {
- mavlink_log_critical(mavlink_fd, "#audio: FAILSAFE: POS HOLD");
-
- } else {
- if (status->condition_landed) {
- mavlink_log_critical(mavlink_fd, "#audio: FAILSAFE: ALT HOLD (LAND)");
-
- } else {
- mavlink_log_critical(mavlink_fd, "#audio: FAILSAFE: ALT HOLD");
- }
- }
- }
-
- } else {
- switch (status->main_state) {
- case MAIN_STATE_MANUAL:
- res = navigation_state_transition(status, status->is_rotary_wing ? NAVIGATION_STATE_STABILIZE : NAVIGATION_STATE_DIRECT, control_mode);
- break;
-
- case MAIN_STATE_SEATBELT:
- res = navigation_state_transition(status, NAVIGATION_STATE_ALTHOLD, control_mode);
- break;
-
- case MAIN_STATE_EASY:
- res = navigation_state_transition(status, NAVIGATION_STATE_VECTOR, control_mode);
- break;
-
- default:
- break;
- }
- }
- }
-
- return res;
-}
-
void answer_command(struct vehicle_command_s &cmd, enum VEHICLE_CMD_RESULT result)
{
switch (result) {
@@ -1698,7 +1557,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 */
@@ -1736,7 +1596,7 @@ void *commander_low_prio_loop(void *arg)
/* try to go to INIT/PREFLIGHT arming state */
// XXX disable interrupts in arming_state_transition
- if (TRANSITION_DENIED == arming_state_transition(&status, &safety, &control_mode, ARMING_STATE_INIT, &armed)) {
+ if (TRANSITION_DENIED == arming_state_transition(&status, &safety, ARMING_STATE_INIT, &armed)) {
answer_command(cmd, VEHICLE_CMD_RESULT_DENIED);
break;
}
@@ -1776,7 +1636,7 @@ void *commander_low_prio_loop(void *arg)
else
tune_negative();
- arming_state_transition(&status, &safety, &control_mode, ARMING_STATE_STANDBY, &armed);
+ arming_state_transition(&status, &safety, ARMING_STATE_STANDBY, &armed);
break;
}
@@ -1828,7 +1688,7 @@ void *commander_low_prio_loop(void *arg)
}
default:
- answer_command(cmd, VEHICLE_CMD_RESULT_UNSUPPORTED);
+ /* don't answer on unsupported commands, it will be done in main loop */
break;
}
diff --git a/src/modules/commander/commander_params.c b/src/modules/commander/commander_params.c
index e10b7f18d..d3155f7bf 100644
--- a/src/modules/commander/commander_params.c
+++ b/src/modules/commander/commander_params.c
@@ -45,8 +45,6 @@
#include <nuttx/config.h>
#include <systemlib/param/param.h>
-PARAM_DEFINE_FLOAT(NAV_TAKEOFF_ALT, 5.0f);
-PARAM_DEFINE_FLOAT(NAV_TAKEOFF_GAP, 3.0f);
PARAM_DEFINE_FLOAT(TRIM_ROLL, 0.0f);
PARAM_DEFINE_FLOAT(TRIM_PITCH, 0.0f);
PARAM_DEFINE_FLOAT(TRIM_YAW, 0.0f);
diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp
index 490fc8fc6..731e0e3ff 100644
--- a/src/modules/commander/state_machine_helper.cpp
+++ b/src/modules/commander/state_machine_helper.cpp
@@ -46,7 +46,6 @@
#include <uORB/uORB.h>
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/actuator_controls.h>
-#include <uORB/topics/vehicle_control_mode.h>
#include <systemlib/systemlib.h>
#include <systemlib/param/param.h>
#include <systemlib/err.h>
@@ -64,11 +63,10 @@ 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,
- const struct vehicle_control_mode_s *control_mode,
arming_state_t new_arming_state, struct actuator_armed_s *armed)
{
/*
@@ -85,7 +83,7 @@ arming_state_transition(struct vehicle_status_s *status, const struct safety_s *
} else {
/* enforce lockdown in HIL */
- if (control_mode->flag_system_hil_enabled) {
+ if (status->hil_state == HIL_STATE_ON) {
armed->lockdown = true;
} else {
armed->lockdown = false;
@@ -108,7 +106,7 @@ arming_state_transition(struct vehicle_status_s *status, const struct safety_s *
/* allow coming from INIT and disarming from ARMED */
if (status->arming_state == ARMING_STATE_INIT
|| status->arming_state == ARMING_STATE_ARMED
- || control_mode->flag_system_hil_enabled) {
+ || status->hil_state == HIL_STATE_ON) {
/* sensors need to be initialized for STANDBY state */
if (status->condition_system_sensors_initialized) {
@@ -125,7 +123,7 @@ arming_state_transition(struct vehicle_status_s *status, const struct safety_s *
/* allow arming from STANDBY and IN-AIR-RESTORE */
if ((status->arming_state == ARMING_STATE_STANDBY
|| status->arming_state == ARMING_STATE_IN_AIR_RESTORE)
- && (!safety->safety_switch_available || safety->safety_off || control_mode->flag_system_hil_enabled)) { /* only allow arming if safety is off */
+ && (!safety->safety_switch_available || safety->safety_off || status->hil_state == HIL_STATE_ON)) { /* only allow arming if safety is off */
ret = TRANSITION_CHANGED;
armed->armed = true;
armed->ready_to_arm = true;
@@ -239,8 +237,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;
}
@@ -287,162 +286,11 @@ 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 ret = TRANSITION_DENIED;
-
- /* only check transition if the new state is actually different from the current one */
- if (new_navigation_state == status->navigation_state) {
- ret = TRANSITION_NOT_CHANGED;
-
- } else {
-
- switch (new_navigation_state) {
- case NAVIGATION_STATE_DIRECT:
- ret = TRANSITION_CHANGED;
- control_mode->flag_control_rates_enabled = true;
- control_mode->flag_control_attitude_enabled = false;
- control_mode->flag_control_velocity_enabled = false;
- control_mode->flag_control_position_enabled = false;
- control_mode->flag_control_altitude_enabled = false;
- control_mode->flag_control_climb_rate_enabled = false;
- control_mode->flag_control_manual_enabled = true;
- control_mode->flag_control_auto_enabled = false;
- break;
-
- case NAVIGATION_STATE_STABILIZE:
- ret = TRANSITION_CHANGED;
- control_mode->flag_control_rates_enabled = true;
- control_mode->flag_control_attitude_enabled = true;
- control_mode->flag_control_velocity_enabled = false;
- control_mode->flag_control_position_enabled = false;
- control_mode->flag_control_altitude_enabled = false;
- control_mode->flag_control_climb_rate_enabled = false;
- control_mode->flag_control_manual_enabled = true;
- control_mode->flag_control_auto_enabled = false;
- break;
-
- case NAVIGATION_STATE_ALTHOLD:
- ret = TRANSITION_CHANGED;
- control_mode->flag_control_rates_enabled = true;
- control_mode->flag_control_attitude_enabled = true;
- control_mode->flag_control_velocity_enabled = false;
- control_mode->flag_control_position_enabled = false;
- control_mode->flag_control_altitude_enabled = true;
- control_mode->flag_control_climb_rate_enabled = true;
- control_mode->flag_control_manual_enabled = true;
- control_mode->flag_control_auto_enabled = false;
- break;
-
- case NAVIGATION_STATE_VECTOR:
- ret = TRANSITION_CHANGED;
- control_mode->flag_control_rates_enabled = true;
- control_mode->flag_control_attitude_enabled = true;
- control_mode->flag_control_velocity_enabled = true;
- control_mode->flag_control_position_enabled = true;
- control_mode->flag_control_altitude_enabled = true;
- control_mode->flag_control_climb_rate_enabled = true;
- control_mode->flag_control_manual_enabled = true;
- control_mode->flag_control_auto_enabled = false;
- break;
-
- case NAVIGATION_STATE_AUTO_READY:
- ret = TRANSITION_CHANGED;
- control_mode->flag_control_rates_enabled = false;
- control_mode->flag_control_attitude_enabled = false;
- control_mode->flag_control_velocity_enabled = false;
- control_mode->flag_control_position_enabled = false;
- control_mode->flag_control_altitude_enabled = false;
- control_mode->flag_control_climb_rate_enabled = false;
- control_mode->flag_control_manual_enabled = false;
- control_mode->flag_control_auto_enabled = true;
- break;
-
- case NAVIGATION_STATE_AUTO_TAKEOFF:
- ret = TRANSITION_CHANGED;
- control_mode->flag_control_rates_enabled = true;
- control_mode->flag_control_attitude_enabled = true;
- control_mode->flag_control_velocity_enabled = true;
- control_mode->flag_control_position_enabled = true;
- control_mode->flag_control_altitude_enabled = true;
- control_mode->flag_control_climb_rate_enabled = true;
- control_mode->flag_control_manual_enabled = false;
- control_mode->flag_control_auto_enabled = true;
- break;
-
- case NAVIGATION_STATE_AUTO_LOITER:
- ret = TRANSITION_CHANGED;
- control_mode->flag_control_rates_enabled = true;
- control_mode->flag_control_attitude_enabled = true;
- control_mode->flag_control_velocity_enabled = true;
- control_mode->flag_control_position_enabled = true;
- control_mode->flag_control_altitude_enabled = true;
- control_mode->flag_control_climb_rate_enabled = true;
- control_mode->flag_control_manual_enabled = false;
- control_mode->flag_control_auto_enabled = false;
- break;
-
- case NAVIGATION_STATE_AUTO_MISSION:
- ret = TRANSITION_CHANGED;
- control_mode->flag_control_rates_enabled = true;
- control_mode->flag_control_attitude_enabled = true;
- control_mode->flag_control_velocity_enabled = true;
- control_mode->flag_control_position_enabled = true;
- control_mode->flag_control_altitude_enabled = true;
- control_mode->flag_control_climb_rate_enabled = true;
- control_mode->flag_control_manual_enabled = false;
- control_mode->flag_control_auto_enabled = true;
- break;
-
- case NAVIGATION_STATE_AUTO_RTL:
- ret = TRANSITION_CHANGED;
- control_mode->flag_control_rates_enabled = true;
- control_mode->flag_control_attitude_enabled = true;
- control_mode->flag_control_velocity_enabled = true;
- control_mode->flag_control_position_enabled = true;
- control_mode->flag_control_altitude_enabled = true;
- control_mode->flag_control_climb_rate_enabled = true;
- control_mode->flag_control_manual_enabled = false;
- control_mode->flag_control_auto_enabled = true;
- break;
-
- case NAVIGATION_STATE_AUTO_LAND:
-
- /* deny transitions from landed state */
- if (status->navigation_state != NAVIGATION_STATE_AUTO_READY) {
- ret = TRANSITION_CHANGED;
- control_mode->flag_control_rates_enabled = true;
- control_mode->flag_control_attitude_enabled = true;
- control_mode->flag_control_velocity_enabled = true;
- control_mode->flag_control_position_enabled = true;
- control_mode->flag_control_altitude_enabled = true;
- control_mode->flag_control_climb_rate_enabled = true;
- control_mode->flag_control_manual_enabled = false;
- control_mode->flag_control_auto_enabled = true;
- }
-
- break;
-
- default:
- break;
- }
-
- if (ret == TRANSITION_CHANGED) {
- status->navigation_state = new_navigation_state;
- control_mode->auto_state = status->navigation_state;
- navigation_state_changed = true;
- }
- }
-
- return ret;
-}
-
bool
-check_navigation_state_changed()
+check_flighttermination_state_changed()
{
- if (navigation_state_changed) {
- navigation_state_changed = false;
+ if (flighttermination_state_changed) {
+ flighttermination_state_changed = false;
return true;
} else {
@@ -450,16 +298,10 @@ check_navigation_state_changed()
}
}
-void
-set_navigation_state_changed()
-{
- navigation_state_changed = true;
-}
-
/**
* Transition from one hil state to another
*/
-int hil_state_transition(hil_state_t new_state, int status_pub, struct vehicle_status_s *current_status, int control_mode_pub, struct vehicle_control_mode_s *current_control_mode, const int mavlink_fd)
+int hil_state_transition(hil_state_t new_state, int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd)
{
bool valid_transition = false;
int ret = ERROR;
@@ -488,7 +330,6 @@ int hil_state_transition(hil_state_t new_state, int status_pub, struct vehicle_s
|| current_status->arming_state == ARMING_STATE_STANDBY
|| current_status->arming_state == ARMING_STATE_STANDBY_ERROR) {
- current_control_mode->flag_system_hil_enabled = true;
mavlink_log_critical(mavlink_fd, "Switched to ON hil state");
valid_transition = true;
}
@@ -507,9 +348,6 @@ int hil_state_transition(hil_state_t new_state, int status_pub, struct vehicle_s
current_status->timestamp = hrt_absolute_time();
orb_publish(ORB_ID(vehicle_status), status_pub, current_status);
- current_control_mode->timestamp = hrt_absolute_time();
- orb_publish(ORB_ID(vehicle_control_mode), control_mode_pub, current_control_mode);
-
// XXX also set lockdown here
ret = OK;
@@ -522,6 +360,45 @@ 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)
+{
+ 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->flighttermination_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;
+ // TODO
+ //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..e569fb4f3 100644
--- a/src/modules/commander/state_machine_helper.h
+++ b/src/modules/commander/state_machine_helper.h
@@ -48,7 +48,6 @@
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/actuator_armed.h>
#include <uORB/topics/safety.h>
-#include <uORB/topics/vehicle_control_mode.h>
typedef enum {
TRANSITION_DENIED = -1,
@@ -58,7 +57,7 @@ typedef enum {
} transition_result_t;
transition_result_t arming_state_transition(struct vehicle_status_s *current_state, const struct safety_s *safety,
- const struct vehicle_control_mode_s *control_mode, arming_state_t new_arming_state, struct actuator_armed_s *armed);
+ arming_state_t new_arming_state, struct actuator_armed_s *armed);
bool is_safe(const struct vehicle_status_s *current_state, const struct safety_s *safety, const struct actuator_armed_s *armed);
@@ -68,12 +67,14 @@ transition_result_t main_state_transition(struct vehicle_status_s *current_state
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);
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);
+int hil_state_transition(hil_state_t new_state, int status_pub, struct vehicle_status_s *current_state, const int mavlink_fd);
#endif /* STATE_MACHINE_HELPER_H_ */
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..8cc0d77d4 100644
--- a/src/modules/controllib/uorb/blocks.hpp
+++ b/src/modules/controllib/uorb/blocks.hpp
@@ -43,7 +43,7 @@
#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/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 +82,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 +98,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..dc2d6c312
--- /dev/null
+++ b/src/modules/dataman/dataman.c
@@ -0,0 +1,741 @@
+/****************************************************************************
+ *
+ * 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 dataman.c
+ * DATAMANAGER driver.
+ */
+
+#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_WAYPOINTS_OFFBOARD_0_MAX,
+ DM_KEY_WAYPOINTS_OFFBOARD_1_MAX,
+ DM_KEY_WAYPOINTS_ONBOARD_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, dataman 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);
+ sem_post(&g_init_sema);
+ 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);
+ sem_post(&g_init_sema);
+ 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");
+
+ exit(0);
+ }
+
+ if (g_fd < 0)
+ errx(1, "not running");
+
+ if (!strcmp(argv[1], "stop"))
+ stop();
+ else if (!strcmp(argv[1], "status"))
+ status();
+ else
+ usage();
+
+ exit(1);
+}
+
diff --git a/src/modules/dataman/dataman.h b/src/modules/dataman/dataman.h
new file mode 100644
index 000000000..a70638ccc
--- /dev/null
+++ b/src/modules/dataman/dataman.h
@@ -0,0 +1,119 @@
+/****************************************************************************
+ *
+ * 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>
+
+#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_WAYPOINTS_OFFBOARD_0, /* Mission way point coordinates sent over mavlink */
+ DM_KEY_WAYPOINTS_OFFBOARD_1, /* (alernate between 0 and 1) */
+ DM_KEY_WAYPOINTS_ONBOARD, /* Mission way point coordinates generated onboard */
+ 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_WAYPOINTS_OFFBOARD_0_MAX = NUM_MISSIONS_SUPPORTED,
+ DM_KEY_WAYPOINTS_OFFBOARD_1_MAX = NUM_MISSIONS_SUPPORTED,
+ DM_KEY_WAYPOINTS_ONBOARD_MAX = NUM_MISSIONS_SUPPORTED
+ };
+
+ /* 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 60c902ce5..c94180d68 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,11 +282,13 @@ FixedwingAttitudeControl::FixedwingAttitudeControl() :
_vcontrol_mode_sub(-1),
_params_sub(-1),
_manual_sub(-1),
+ _global_pos_sub(-1),
/* publications */
_rate_sp_pub(-1),
_actuators_0_pub(-1),
_attitude_sp_pub(-1),
+ _actuators_1_pub(-1),
/* performance counters */
_loop_perf(perf_alloc(PC_ELAPSED, "fw att control")),
@@ -273,31 +296,45 @@ 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_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_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_roll_feedforward = param_find("FW_Y_ROLLFF");
- _parameter_handles.y_integrator_max = param_find("FW_Y_IMAX");
+ _parameter_handles.y_p = param_find("FW_YR_P");
+ _parameter_handles.y_i = param_find("FW_YR_I");
+ _parameter_handles.y_ff = param_find("FW_YR_FF");
+ _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();
}
@@ -333,24 +370,26 @@ FixedwingAttitudeControl::parameters_update()
param_get(_parameter_handles.tconst, &(_parameters.tconst));
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));
param_get(_parameter_handles.p_roll_feedforward, &(_parameters.p_roll_feedforward));
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_roll_feedforward, &(_parameters.y_roll_feedforward));
+ param_get(_parameter_handles.y_ff, &(_parameters.y_ff));
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 +397,29 @@ 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_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_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_ff(_parameters.y_ff);
+ _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 +461,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 +494,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 +529,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);
@@ -552,6 +606,8 @@ FixedwingAttitudeControl::task_main()
vehicle_manual_poll();
+ global_pos_poll();
+
/* lock integrator until control is started */
bool lock_integrator;
@@ -562,22 +618,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;
@@ -586,7 +648,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) {
@@ -636,46 +699,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 {
@@ -693,6 +796,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 */
@@ -703,6 +807,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..1c615094c 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
@@ -38,36 +38,32 @@
* Parameters defined by the fixed-wing attitude control task
*
* @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Thomas Gubler <thomasgubler@gmail.com>
*/
#include <nuttx/config.h>
#include <systemlib/param/param.h>
+
/*
* Controller parameters, accessible via MAVLink
*
*/
-
// @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.
+// @Description This defines the latency between a step input and the achieved setpoint (inverse to a P gain). 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
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.
+// @DisplayName Pitch rate proportional gain.
+// @Description This defines how much the elevator input will be commanded depending on the current body angular rate error.
// @Range 10 to 200, 1 increments
-PARAM_DEFINE_FLOAT(FW_P_P, 40.0f);
-
-// @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_P, 0.05f);
-// @DisplayName Integrator gain.
+// @DisplayName Pitch rate 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.0f);
// @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.
@@ -79,58 +75,104 @@ PARAM_DEFINE_FLOAT(FW_P_RMAX_POS, 0.0f);
// @Range 0 to 90.0 degrees per seconds, in 1 increments
PARAM_DEFINE_FLOAT(FW_P_RMAX_NEG, 0.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);
+// @DisplayName Pitch rate integrator limit
+// @Description The portion of the integrator part in the control surface deflection is limited to this value
+// @Range 0.0 to 1
+// @Increment 0.1
+PARAM_DEFINE_FLOAT(FW_PR_IMAX, 0.2f);
-// @DisplayName Roll feedforward gain.
+// @DisplayName Roll to Pitch feedforward gain.
// @Description This compensates during turns and ensures the nose stays level.
// @Range 0.5 2.0
// @Increment 0.05
// @User User
-PARAM_DEFINE_FLOAT(FW_P_ROLLFF, 1.0f);
+PARAM_DEFINE_FLOAT(FW_P_ROLLFF, 0.0f); //xxx: set to 0 as default, see comment in ECL_PitchController::control_attitude (float turn_offset = ...)
-// @DisplayName Proportional Gain.
-// @Description This gain controls the roll angle to roll actuator output.
+// @DisplayName Roll rate proportional Gain.
+// @Description This defines how much the aileron input will be commanded depending on the current body angular rate error.
// @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.05f);
-// @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);
-
-// @DisplayName Integrator Gain
-// @Description This gain controls the contribution of the integral to roll actuator outputs. It trims out steady state errors.
+// @DisplayName Roll rate 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.0 100.0
// @Increment 5.0
// @User User
-PARAM_DEFINE_FLOAT(FW_R_I, 0.0f);
+PARAM_DEFINE_FLOAT(FW_RR_I, 0.0f);
// @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);
+// @Description The portion of the integrator part in the control surface deflection is limited to this value.
+// @Range 0.0 to 1.0
+// @Increment 0.1
+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.
// @Range 0 to 90.0 degrees per seconds
// @Increment 1.0
-PARAM_DEFINE_FLOAT(FW_R_RMAX, 60);
+PARAM_DEFINE_FLOAT(FW_R_RMAX, 0);
+
+// @DisplayName Yaw rate proportional gain.
+// @Description This defines how much the rudder input will be commanded depending on the current body angular rate error.
+// @Range 10 to 200, 1 increments
+PARAM_DEFINE_FLOAT(FW_YR_P, 0.05);
+
+// @DisplayName Yaw rate 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_YR_I, 0.0f);
+
+// @DisplayName Yaw rate integrator limit
+// @Description The portion of the integrator part in the control surface deflection is limited to this value
+// @Range 0.0 to 1
+// @Increment 0.1
+PARAM_DEFINE_FLOAT(FW_YR_IMAX, 0.2f);
+
+// @DisplayName Maximum Yaw Rate
+// @Description This limits the maximum yaw 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
+// @Increment 1.0
+PARAM_DEFINE_FLOAT(FW_Y_RMAX, 0);
+
+// @DisplayName Roll rate feed forward
+// @Description Direct feed forward from rate setpoint to control surface output
+// @Range 0 to 10
+// @Increment 0.1
+PARAM_DEFINE_FLOAT(FW_RR_FF, 0.3f);
+
+// @DisplayName Pitch rate feed forward
+// @Description Direct feed forward from rate setpoint to control surface output
+// @Range 0 to 10
+// @Increment 0.1
+PARAM_DEFINE_FLOAT(FW_PR_FF, 0.4f);
+
+// @DisplayName Yaw rate feed forward
+// @Description Direct feed forward from rate setpoint to control surface output
+// @Range 0 to 10
+// @Increment 0.1
+PARAM_DEFINE_FLOAT(FW_YR_FF, 0.3f);
+
+// @DisplayName Minimal speed for yaw coordination
+// @Description For airspeeds above this value the yaw rate is calculated for a coordinated turn. Set to a very high value to disable.
+// @Range 0 to 90.0 degrees per seconds
+// @Increment 1.0
+PARAM_DEFINE_FLOAT(FW_YCO_VMIN, 1000.0f);
+
+/* Airspeed parameters: the following parameters about airspeed are used by the attitude and the positon controller */
+
+// @DisplayName Minimum Airspeed
+// @Description If the airspeed falls below this value the TECS controller will try to increase airspeed more aggressively
+// @Range 0.0 to 30
+PARAM_DEFINE_FLOAT(FW_AIRSPD_MIN, 13.0f);
+// @DisplayName Trim Airspeed
+// @Description The TECS controller tries to fly at this airspeed
+// @Range 0.0 to 30
+PARAM_DEFINE_FLOAT(FW_AIRSPD_TRIM, 20.0f);
-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_AIRSPD_MIN, 9.0f);
-PARAM_DEFINE_FLOAT(FW_AIRSPD_TRIM, 12.0f);
-PARAM_DEFINE_FLOAT(FW_AIRSPD_MAX, 18.0f);
+// @DisplayName Maximum Airspeed
+// @Description If the airspeed is above this value the TECS controller will try to decrease airspeed more aggressively
+// @Range 0.0 to 30
+PARAM_DEFINE_FLOAT(FW_AIRSPD_MAX, 50.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..c90b0313a 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
@@ -49,6 +49,7 @@
* More details and acknowledgements in the referenced library headers.
*
* @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Thomas Gubler <thomasgubler@gmail.com>
*/
#include <nuttx/config.h>
@@ -67,7 +68,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>
@@ -75,6 +76,7 @@
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/navigation_capabilities.h>
+#include <uORB/topics/sensor_combined.h>
#include <uORB/topics/parameter_update.h>
#include <systemlib/param/param.h>
#include <systemlib/err.h>
@@ -83,9 +85,12 @@
#include <systemlib/perf_counter.h>
#include <systemlib/systemlib.h>
#include <mathlib/mathlib.h>
-
+#include <mavlink/mavlink_log.h>
+#include <launchdetection/LaunchDetector.h>
#include <ecl/l1/ecl_l1_pos_controller.h>
#include <external_lgpl/tecs/tecs.h>
+#include "landingslope.h"
+
/**
* L1 control app start / stop handling function
@@ -115,19 +120,20 @@ 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 */
int _control_mode_sub; /**< vehicle status subscription */
int _params_sub; /**< notification of parameter updates */
int _manual_control_sub; /**< notification of manual control updates */
- int _accel_sub; /**< body frame accelerations */
+ int _sensor_combined_sub; /**< for body frame accelerations */
orb_advert_t _attitude_sp_pub; /**< attitude setpoint */
orb_advert_t _nav_capabilities_pub; /**< navigation capabilities publication */
@@ -139,8 +145,8 @@ 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 accel_report _accel; /**< body frame accelerations */
+ struct mission_item_triplet_s _mission_item_triplet; /**< triplet of mission items */
+ struct sensor_combined_s _sensor_combined; /**< for body frame accelerations */
perf_counter_t _loop_perf; /**< loop performance counter */
@@ -160,10 +166,26 @@ 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;
+
+ /* takeoff/launch states */
+ bool launch_detected;
+ bool usePreTakeoffThrust;
+
+ /* Landingslope object */
+ Landingslope landingslope;
+
+ float flare_curve_alt_last;
/* heading hold */
float target_bearing;
+ /* Launch detection */
+ LaunchDetector launchDetector;
+
/* throttle and airspeed states */
float _airspeed_error; ///< airspeed error to setpoint in m/s
bool _airspeed_valid; ///< flag if a valid airspeed estimate exists
@@ -206,6 +228,17 @@ 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;
+ float land_heading_hold_horizontal_distance;
+
} _parameters; /**< local copies of interesting parameters */
struct {
@@ -240,6 +273,17 @@ 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;
+ param_t land_heading_hold_horizontal_distance;
+
} _parameter_handles; /**< handles for interesting parameters */
@@ -272,7 +316,7 @@ private:
/**
* Check for accel updates.
*/
- void vehicle_accel_poll();
+ void vehicle_sensor_combined_poll();
/**
* Check for set triplet updates.
@@ -280,13 +324,18 @@ private:
void vehicle_setpoint_poll();
/**
+ * Publish navigation capabilities
+ */
+ void navigation_capabilities_publish();
+
+ /**
* 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 +367,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 +387,31 @@ 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),
+ launchDetector(),
+ launch_detected(false),
+ usePreTakeoffThrust(false)
{
+ /* 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};
+ sensor_combined_s _sensor_combined = {0};
+
+
+
+
_nav_capabilities.turn_distance = 0.0f;
_parameter_handles.l1_period = param_find("FW_L1_PERIOD");
@@ -358,6 +430,13 @@ 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.land_heading_hold_horizontal_distance = param_find("FW_LND_HHDIST");
+
_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 +449,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 +516,16 @@ 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));
+ param_get(_parameter_handles.land_heading_hold_horizontal_distance, &(_parameters.land_heading_hold_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 +538,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 ||
@@ -464,6 +557,18 @@ FixedwingPositionControl::parameters_update()
return 1;
}
+ /* Update the landing slope */
+ landingslope.update(math::radians(_parameters.land_slope_angle), _parameters.land_flare_alt_relative, _parameters.land_thrust_lim_horizontal_distance, _parameters.land_H1_virt);
+
+ /* Update and publish the navigation capabilities */
+ _nav_capabilities.landing_slope_angle_rad = landingslope.landing_slope_angle_rad();
+ _nav_capabilities.landing_horizontal_slope_displacement = landingslope.horizontal_slope_displacement();
+ _nav_capabilities.landing_flare_length = landingslope.flare_length();
+ navigation_capabilities_publish();
+
+ /* Update Launch Detector Parameters */
+ launchDetector.updateParams();
+
return OK;
}
@@ -533,14 +638,14 @@ FixedwingPositionControl::vehicle_attitude_poll()
}
void
-FixedwingPositionControl::vehicle_accel_poll()
+FixedwingPositionControl::vehicle_sensor_combined_poll()
{
/* check if there is a new position */
- bool accel_updated;
- orb_check(_accel_sub, &accel_updated);
+ bool sensors_updated;
+ orb_check(_sensor_combined_sub, &sensors_updated);
- if (accel_updated) {
- orb_copy(ORB_ID(sensor_accel), _accel_sub, &_accel);
+ if (sensors_updated) {
+ orb_copy(ORB_ID(sensor_combined), _sensor_combined_sub, &_sensor_combined);
}
}
@@ -548,11 +653,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 +700,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 +733,29 @@ 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;
}
}
+void FixedwingPositionControl::navigation_capabilities_publish()
+{
+ if (_nav_capabilities_pub > 0) {
+ orb_publish(ORB_ID(navigation_capabilities), _nav_capabilities_pub, &_nav_capabilities);
+ } else {
+ _nav_capabilities_pub = orb_advertise(ORB_ID(navigation_capabilities), &_nav_capabilities);
+ }
+}
+
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
@@ -637,11 +763,11 @@ FixedwingPositionControl::control_position(const math::Vector2f &current_positio
float baro_altitude = _global_pos.alt;
/* filter speed and altitude for controller */
- math::Vector3 accel_body(_accel.x, _accel.y, _accel.z);
- math::Vector3 accel_earth = _R_nb.transpose() * accel_body;
+ math::Vector3 accel_body(_sensor_combined.accelerometer_m_s2[0], _sensor_combined.accelerometer_m_s2[1], _sensor_combined.accelerometer_m_s2[2]);
+ math::Vector3 accel_earth = _R_nb * 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 +784,278 @@ 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);
+ /* current waypoint (the one currently heading for) */
+ math::Vector2f next_wp(mission_item_triplet.current.lat, mission_item_triplet.current.lon);
- /* previous waypoint */
- math::Vector2f prev_wp;
+ /* current waypoint (the one currently heading for) */
+ math::Vector2f curr_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);
- } 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);
-
- }
+ /* previous waypoint */
+ math::Vector2f prev_wp;
- // XXX add RTL switch
- if (global_triplet.current.nav_cmd == NAV_CMD_RETURN_TO_LAUNCH && _launch_valid) {
+ if (mission_item_triplet.previous_valid) {
+ prev_wp.setX(mission_item_triplet.previous.lat);
+ prev_wp.setY(mission_item_triplet.previous.lon);
- math::Vector2f rtl_pos(_launch_lat, _launch_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();
-
- _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)
-
- } 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();
+ } 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, _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 (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) {
+ 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();
- /* 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_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_LAND) {
+ /* 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();
- /* switch to heading hold for the last meters, continue heading hold after */
+ _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));
- 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) {
+ } else if (mission_item_triplet.current.nav_cmd == NAV_CMD_LAND) {
- /* heading hold, along the line connecting this and the last waypoint */
-
+ /* 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");
+ if (wp_distance < _parameters.land_heading_hold_horizontal_distance || land_noreturn_horizontal) {
- // 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 {
+ /* heading hold, along the line connecting this and the last waypoint */
- if (!land_noreturn)
+ if (!land_noreturn_horizontal) {//set target_bearing in first occurrence
+ if (mission_item_triplet.previous_valid) {
+ target_bearing = get_bearing_to_next_waypoint(prev_wp.getX(), prev_wp.getY(), curr_wp.getX(), curr_wp.getY());
+ } else {
target_bearing = _att.yaw;
- //}
+ }
+ mavlink_log_info(_mavlink_fd, "#audio: Landing, heading hold");
+ }
- warnx("NORET: %d, target_bearing: %d, yaw: %d", (int)land_noreturn, (int)math::degrees(target_bearing), (int)math::degrees(_att.yaw));
+// warnx("NORET: %d, target_bearing: %d, yaw: %d", (int)land_noreturn_horizontal, (int)math::degrees(target_bearing), (int)math::degrees(_att.yaw));
- _l1_control.navigate_heading(target_bearing, _att.yaw, ground_speed);
+ _l1_control.navigate_heading(target_bearing, _att.yaw, ground_speed);
- if (altitude_error > -5.0f)
- land_noreturn = true;
+ /* 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 {
+ land_noreturn_horizontal = true;
- /* normal navigation */
- _l1_control.navigate_waypoints(prev_wp, next_wp, current_position, ground_speed);
- }
+ } else {
- /* do not go down too early */
- if (wp_distance > 50.0f) {
- altitude_error = (_global_triplet.current.altitude + 25.0f) - _global_pos.alt;
- }
+ /* normal navigation */
+ _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();
- _att_sp.roll_body = _l1_control.nav_roll();
- _att_sp.yaw_body = _l1_control.nav_bearing();
- /* 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
+ /* Vertical landing control */
+ //xxx: using the tecs altitude controller for slope control for now
- 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;
+// /* 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
- if (altitude_error > -4.0f) {
+ float flare_pitch_angle_rad = -math::radians(5.0f);//math::radians(mission_item_triplet.current.param1)
+ 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;
- /* land with minimal speed */
+ 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 L_altitude = landingslope.getLandingSlopeAbsoluteAltitude(L_wp_distance, _mission_item_triplet.current.altitude);//getLandingSlopeAbsoluteAltitude(L_wp_distance, _mission_item_triplet.current.altitude, landing_slope_angle_rad, horizontal_slope_displacement);
+ float landing_slope_alt_desired = landingslope.getLandingSlopeAbsoluteAltitude(wp_distance, _mission_item_triplet.current.altitude);//getLandingSlopeAbsoluteAltitude(wp_distance, _mission_item_triplet.current.altitude, landing_slope_angle_rad, horizontal_slope_displacement);
- /* 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 = math::min(throttle_max, _parameters.throttle_land_max);
+ if ( (_global_pos.alt < _mission_item_triplet.current.altitude + landingslope.flare_relative_alt()) || land_noreturn_vertical) { //checking for land_noreturn to avoid unwanted climb out
- /* 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));
+ /* land with minimal speed */
- } else if (wp_distance < 60.0f && altitude_error > -20.0f) {
+// /* force TECS to only control speed with pitch, altitude is only implicitely controlled now */
+// _tecs.set_speed_weight(2.0f);
- /* minimize speed to approach speed */
+ /* kill the throttle if param requests it */
+ throttle_max = _parameters.throttle_max;
- _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));
+ if (wp_distance < landingslope.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");
+ }
- } else {
+ }
- /* normal cruise speed */
+ float flare_curve_alt = landingslope.getFlareCurveAltitude(wp_distance, _mission_item_triplet.current.altitude);
- _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_pitch_angle_rad,
+ 0.0f, throttle_max, throttle_land,
+ flare_pitch_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_pitch_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) {
+
+ /* Perform launch detection */
+// warnx("Launch detection running");
+ if(!launch_detected) { //do not do further checks once a launch was detected
+ if (launchDetector.launchDetectionEnabled()) {
+ static hrt_abstime last_sent = 0;
+ if(hrt_absolute_time() - last_sent > 4e6) {
+// warnx("Launch detection running");
+ mavlink_log_info(_mavlink_fd, "#audio: Launchdetection running");
+ last_sent = hrt_absolute_time();
+ }
+ launchDetector.update(_sensor_combined.accelerometer_m_s2[0]);
+ if (launchDetector.getLaunchDetected()) {
+ launch_detected = true;
+ mavlink_log_info(_mavlink_fd, "#audio: Takeoff");
+ }
+ } else {
+ /* no takeoff detection --> fly */
+ launch_detected = true;
+ }
+ }
- /* 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);
+ if (launch_detected) {
+ usePreTakeoffThrust = false;
- float min_pitch;
+ /* apply minimum pitch and limit roll if target altitude is not within 10 meters */
+ if (altitude_error > 15.0f) {
- if (climb_out) {
- min_pitch = math::radians(20.0f);
+ /* 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.pitch_min), 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 {
- min_pitch = math::radians(_parameters.pitch_limit_min);
- }
+ /* 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, _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));
+ } else {
+
+ _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));
+ }
- 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));
+ } else {
+ usePreTakeoffThrust = 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(), (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;
+ }
+
+ /* reset takeoff/launch state */
+ if (mission_item_triplet.current.nav_cmd != NAV_CMD_TAKEOFF) {
+ launch_detected = false;
+ usePreTakeoffThrust = false;
}
if (was_circle_mode && !_l1_control.circle_mode()) {
@@ -1000,8 +1152,14 @@ FixedwingPositionControl::control_position(const math::Vector2f &current_positio
setpoint = false;
}
+ if (usePreTakeoffThrust) {
+ _att_sp.thrust = launchDetector.getThrottlePreTakeoff();
+ }
+ else {
+ _att_sp.thrust = math::min(_tecs.get_throttle_demand(), throttle_max);
+ }
_att_sp.pitch_body = _tecs.get_pitch_demand();
- _att_sp.thrust = math::min(_tecs.get_throttle_demand(), throttle_max);
+
return setpoint;
}
@@ -1018,9 +1176,9 @@ 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));
+ _sensor_combined_sub = orb_subscribe(ORB_ID(sensor_combined));
_control_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode));
_airspeed_sub = orb_subscribe(ORB_ID(airspeed));
_params_sub = orb_subscribe(ORB_ID(parameter_update));
@@ -1080,6 +1238,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;
@@ -1097,7 +1260,7 @@ FixedwingPositionControl::task_main()
vehicle_attitude_poll();
vehicle_setpoint_poll();
- vehicle_accel_poll();
+ vehicle_sensor_combined_poll();
vehicle_airspeed_poll();
// vehicle_baro_poll();
@@ -1108,7 +1271,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 +1284,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.acceptance_radius);
/* lazily publish navigation capabilities */
if (turn_distance != _nav_capabilities.turn_distance && turn_distance > 0) {
@@ -1129,11 +1293,8 @@ FixedwingPositionControl::task_main()
/* set new turn distance */
_nav_capabilities.turn_distance = turn_distance;
- if (_nav_capabilities_pub > 0) {
- orb_publish(ORB_ID(navigation_capabilities), _nav_capabilities_pub, &_nav_capabilities);
- } else {
- _nav_capabilities_pub = orb_advertise(ORB_ID(navigation_capabilities), &_nav_capabilities);
- }
+ navigation_capabilities_publish();
+
}
}
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 31a9cdefa..7954d75c2 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
@@ -164,3 +164,13 @@ 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);
+PARAM_DEFINE_FLOAT(FW_LND_HHDIST, 15.0f);
diff --git a/src/modules/fw_pos_control_l1/landingslope.cpp b/src/modules/fw_pos_control_l1/landingslope.cpp
new file mode 100644
index 000000000..b139a6397
--- /dev/null
+++ b/src/modules/fw_pos_control_l1/landingslope.cpp
@@ -0,0 +1,82 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2008-2012 PX4 Development Team. All rights reserved.
+ * Author: @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/*
+ * @file: landingslope.cpp
+ *
+ */
+
+#include "landingslope.h"
+
+#include <nuttx/config.h>
+#include <stdlib.h>
+#include <errno.h>
+#include <math.h>
+#include <unistd.h>
+#include <mathlib/mathlib.h>
+
+void Landingslope::update(float landing_slope_angle_rad,
+ float flare_relative_alt,
+ float motor_lim_horizontal_distance,
+ float H1_virt)
+{
+
+ _landing_slope_angle_rad = landing_slope_angle_rad;
+ _flare_relative_alt = flare_relative_alt;
+ _motor_lim_horizontal_distance = motor_lim_horizontal_distance;
+ _H1_virt = H1_virt;
+
+ calculateSlopeValues();
+}
+
+void Landingslope::calculateSlopeValues()
+{
+ _H0 = _flare_relative_alt + _H1_virt;
+ _d1 = _flare_relative_alt/tanf(_landing_slope_angle_rad);
+ _flare_constant = (_H0 * _d1)/_flare_relative_alt;
+ _flare_length = - logf(_H1_virt/_H0) * _flare_constant;
+ _horizontal_slope_displacement = (_flare_length - _d1);
+}
+
+float Landingslope::getLandingSlopeAbsoluteAltitude(float wp_distance, float wp_altitude)
+{
+ return Landingslope::getLandingSlopeAbsoluteAltitude(wp_distance, wp_altitude, _horizontal_slope_displacement, _landing_slope_angle_rad);
+}
+
+float Landingslope::getFlareCurveAltitude(float wp_landing_distance, float wp_landing_altitude)
+{
+ return wp_landing_altitude + _H0 * expf(-math::max(0.0f, _flare_length - wp_landing_distance)/_flare_constant) - _H1_virt;
+
+}
+
diff --git a/src/modules/fw_pos_control_l1/landingslope.h b/src/modules/fw_pos_control_l1/landingslope.h
new file mode 100644
index 000000000..1a149fc7c
--- /dev/null
+++ b/src/modules/fw_pos_control_l1/landingslope.h
@@ -0,0 +1,109 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2008-2012 PX4 Development Team. All rights reserved.
+ * Author: @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/*
+ * @file: landingslope.h
+ *
+ */
+
+#ifndef LANDINGSLOPE_H_
+#define LANDINGSLOPE_H_
+
+#include <math.h>
+#include <systemlib/err.h>
+
+class Landingslope
+{
+private:
+ /* see Documentation/fw_landing.png for a plot of the landing slope */
+ float _landing_slope_angle_rad; /**< phi in the plot */
+ float _flare_relative_alt; /**< h_flare,rel in the plot */
+ float _motor_lim_horizontal_distance;
+ float _H1_virt; /**< H1 in the plot */
+ float _H0; /**< h_flare,rel + H1 in the plot */
+ float _d1; /**< d1 in the plot */
+ float _flare_constant;
+ float _flare_length; /**< d1 + delta d in the plot */
+ float _horizontal_slope_displacement; /**< delta d in the plot */
+
+ void calculateSlopeValues();
+
+public:
+ Landingslope() {}
+ ~Landingslope() {}
+
+ float getLandingSlopeAbsoluteAltitude(float wp_landing_distance, float wp_landing_altitude);
+
+ /**
+ *
+ * @return Absolute altitude of point on landing slope at distance to landing waypoint=wp_landing_distance
+ */
+ __EXPORT static float getLandingSlopeAbsoluteAltitude(float wp_landing_distance, float wp_landing_altitude, float horizontal_slope_displacement, float landing_slope_angle_rad)
+ {
+ return (wp_landing_distance - horizontal_slope_displacement) * tanf(landing_slope_angle_rad) + wp_landing_altitude; //flare_relative_alt is negative
+ }
+
+ /**
+ *
+ * @return distance to landing waypoint of point on landing slope at altitude=slope_altitude
+ */
+ __EXPORT static float getLandingSlopeWPDistance(float slope_altitude, float wp_landing_altitude, float horizontal_slope_displacement, float landing_slope_angle_rad)
+ {
+ return (slope_altitude - wp_landing_altitude)/tanf(landing_slope_angle_rad) + horizontal_slope_displacement;
+
+ }
+
+
+ float getFlareCurveAltitude(float wp_distance, float wp_altitude);
+
+ void update(float landing_slope_angle_rad,
+ float flare_relative_alt,
+ float motor_lim_horizontal_distance,
+ float H1_virt);
+
+
+ inline float landing_slope_angle_rad() {return _landing_slope_angle_rad;}
+ inline float flare_relative_alt() {return _flare_relative_alt;}
+ inline float motor_lim_horizontal_distance() {return _motor_lim_horizontal_distance;}
+ inline float H1_virt() {return _H1_virt;}
+ inline float H0() {return _H0;}
+ inline float d1() {return _d1;}
+ inline float flare_constant() {return _flare_constant;}
+ inline float flare_length() {return _flare_length;}
+ inline float horizontal_slope_displacement() {return _horizontal_slope_displacement;}
+
+};
+
+
+#endif /* LANDINGSLOPE_H_ */
diff --git a/src/modules/fw_pos_control_l1/module.mk b/src/modules/fw_pos_control_l1/module.mk
index b00b9aa5a..cf419ec7e 100644
--- a/src/modules/fw_pos_control_l1/module.mk
+++ b/src/modules/fw_pos_control_l1/module.mk
@@ -38,4 +38,5 @@
MODULE_COMMAND = fw_pos_control_l1
SRCS = fw_pos_control_l1_main.cpp \
- fw_pos_control_l1_params.c
+ fw_pos_control_l1_params.c \
+ landingslope.cpp
diff --git a/src/modules/mavlink/mavlink.c b/src/modules/mavlink/mavlink.c
index 20853379d..4f8091716 100644
--- a/src/modules/mavlink/mavlink.c
+++ b/src/modules/mavlink/mavlink.c
@@ -68,12 +68,13 @@
#include "waypoints.h"
#include "orb_topics.h"
-#include "missionlib.h"
#include "mavlink_hil.h"
#include "util.h"
#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);
@@ -219,18 +220,16 @@ get_mavlink_mode_and_state(uint8_t *mavlink_state, uint8_t *mavlink_base_mode, u
} else if (v_status.main_state == MAIN_STATE_AUTO) {
*mavlink_base_mode |= MAV_MODE_FLAG_AUTO_ENABLED | MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_GUIDED_ENABLED;
custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_AUTO;
- if (v_status.navigation_state == NAVIGATION_STATE_AUTO_READY) {
+ if (control_mode.nav_state == NAV_STATE_NONE) { // failsafe, shouldn't happen
+ custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_READY;
+ } else if (control_mode.nav_state == NAV_STATE_READY) {
custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_READY;
- } else if (v_status.navigation_state == NAVIGATION_STATE_AUTO_TAKEOFF) {
- custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF;
- } else if (v_status.navigation_state == NAVIGATION_STATE_AUTO_LOITER) {
+ } else if (control_mode.nav_state == NAV_STATE_LOITER) {
custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_LOITER;
- } else if (v_status.navigation_state == NAVIGATION_STATE_AUTO_MISSION) {
+ } else if (control_mode.nav_state == NAV_STATE_MISSION) {
custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_MISSION;
- } else if (v_status.navigation_state == NAVIGATION_STATE_AUTO_RTL) {
+ } else if (control_mode.nav_state == NAV_STATE_RTL) {
custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_RTL;
- } else if (v_status.navigation_state == NAVIGATION_STATE_AUTO_LAND) {
- custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_LAND;
}
}
*mavlink_custom_mode = custom_mode.data;
@@ -644,6 +643,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,25 +693,36 @@ int mavlink_thread_main(int argc, char *argv[])
lowspeed_counter++;
- mavlink_waypoint_eventloop(mavlink_missionlib_get_system_timestamp(), &global_pos, &local_pos, &nav_cap);
+ 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(hrt_absolute_time());
/* sleep quarter the time */
usleep(25000);
/* check if waypoint has been reached against the last positions */
- mavlink_waypoint_eventloop(mavlink_missionlib_get_system_timestamp(), &global_pos, &local_pos, &nav_cap);
+ mavlink_waypoint_eventloop(hrt_absolute_time());
/* sleep quarter the time */
usleep(25000);
/* send parameters at 20 Hz (if queued for sending) */
mavlink_pm_queued_send();
- mavlink_waypoint_eventloop(mavlink_missionlib_get_system_timestamp(), &global_pos, &local_pos, &nav_cap);
+ mavlink_waypoint_eventloop(hrt_absolute_time());
/* sleep quarter the time */
usleep(25000);
- mavlink_waypoint_eventloop(mavlink_missionlib_get_system_timestamp(), &global_pos, &local_pos, &nav_cap);
+ mavlink_waypoint_eventloop(hrt_absolute_time());
if (baudrate > 57600) {
mavlink_pm_queued_send();
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index 7b6fad658..771989430 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -79,7 +79,6 @@ __BEGIN_DECLS
#include "mavlink_bridge_header.h"
#include "waypoints.h"
#include "orb_topics.h"
-#include "missionlib.h"
#include "mavlink_hil.h"
#include "mavlink_parameters.h"
#include "util.h"
@@ -844,7 +843,7 @@ receive_thread(void *arg)
handle_message(&msg);
/* handle packet with waypoint component */
- mavlink_wpm_message_handler(&msg, &global_pos, &local_pos);
+ mavlink_wpm_message_handler(&msg);
/* handle packet with parameter component */
mavlink_pm_message_handler(MAVLINK_COMM_0, &msg);
diff --git a/src/modules/mavlink/missionlib.c b/src/modules/mavlink/missionlib.c
deleted file mode 100644
index 124b3b2ae..000000000
--- a/src/modules/mavlink/missionlib.c
+++ /dev/null
@@ -1,390 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: @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 missionlib.h
- * MAVLink missionlib components
- */
-
-// XXX trim includes
-#include <nuttx/config.h>
-#include <unistd.h>
-#include <pthread.h>
-#include <stdio.h>
-#include <math.h>
-#include <stdbool.h>
-#include <fcntl.h>
-#include <mqueue.h>
-#include <string.h>
-#include "mavlink_bridge_header.h"
-#include <drivers/drv_hrt.h>
-#include <time.h>
-#include <float.h>
-#include <unistd.h>
-#include <nuttx/sched.h>
-#include <sys/prctl.h>
-#include <termios.h>
-#include <errno.h>
-#include <stdlib.h>
-#include <poll.h>
-
-#include <systemlib/err.h>
-#include <systemlib/param/param.h>
-#include <systemlib/systemlib.h>
-#include <mavlink/mavlink_log.h>
-
-#include "geo/geo.h"
-#include "waypoints.h"
-#include "orb_topics.h"
-#include "missionlib.h"
-#include "mavlink_hil.h"
-#include "util.h"
-#include "waypoints.h"
-#include "mavlink_parameters.h"
-
-static uint8_t missionlib_msg_buf[MAVLINK_MAX_PACKET_LEN];
-static uint64_t loiter_start_time;
-
-static bool set_special_fields(float param1, float param2, float param3, float param4, uint16_t command,
- struct vehicle_global_position_setpoint_s *sp);
-
-int
-mavlink_missionlib_send_message(mavlink_message_t *msg)
-{
- uint16_t len = mavlink_msg_to_send_buffer(missionlib_msg_buf, msg);
-
- mavlink_send_uart_bytes(chan, missionlib_msg_buf, len);
- return 0;
-}
-
-int
-mavlink_missionlib_send_gcs_string(const char *string)
-{
- const int len = MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN;
- mavlink_statustext_t statustext;
- int i = 0;
-
- while (i < len - 1) {
- statustext.text[i] = string[i];
-
- if (string[i] == '\0')
- break;
-
- i++;
- }
-
- if (i > 1) {
- /* Enforce null termination */
- statustext.text[i] = '\0';
- mavlink_message_t msg;
-
- mavlink_msg_statustext_encode(mavlink_system.sysid, mavlink_system.compid, &msg, &statustext);
- return mavlink_missionlib_send_message(&msg);
-
- } else {
- return 1;
- }
-}
-
-/**
- * Get system time since boot in microseconds
- *
- * @return the system time since boot in microseconds
- */
-uint64_t mavlink_missionlib_get_system_timestamp()
-{
- return hrt_absolute_time();
-}
-
-/**
- * Set special vehicle setpoint fields based on current mission item.
- *
- * @return true if the mission item could be interpreted
- * successfully, it return false on failure.
- */
-bool set_special_fields(float param1, float param2, float param3, float param4, uint16_t command,
- struct vehicle_global_position_setpoint_s *sp)
-{
- switch (command) {
- case MAV_CMD_NAV_LOITER_UNLIM:
- sp->nav_cmd = NAV_CMD_LOITER_UNLIMITED;
- break;
- case MAV_CMD_NAV_LOITER_TIME:
- sp->nav_cmd = NAV_CMD_LOITER_TIME_LIMIT;
- loiter_start_time = hrt_absolute_time();
- break;
- // case MAV_CMD_NAV_LOITER_TURNS:
- // sp->nav_cmd = NAV_CMD_LOITER_TURN_COUNT;
- // break;
- case MAV_CMD_NAV_WAYPOINT:
- sp->nav_cmd = NAV_CMD_WAYPOINT;
- break;
- case MAV_CMD_NAV_RETURN_TO_LAUNCH:
- sp->nav_cmd = NAV_CMD_RETURN_TO_LAUNCH;
- break;
- case MAV_CMD_NAV_LAND:
- sp->nav_cmd = NAV_CMD_LAND;
- break;
- case MAV_CMD_NAV_TAKEOFF:
- sp->nav_cmd = NAV_CMD_TAKEOFF;
- break;
- default:
- /* abort */
- return false;
- }
-
- sp->loiter_radius = param3;
- sp->loiter_direction = (param3 >= 0) ? 1 : -1;
-
- sp->param1 = param1;
- sp->param2 = param2;
- sp->param3 = param3;
- sp->param4 = param4;
-
-
- /* define the turn distance */
- float orbit = 15.0f;
-
- if (command == (int)MAV_CMD_NAV_WAYPOINT) {
-
- orbit = param2;
-
- } else if (command == (int)MAV_CMD_NAV_LOITER_TURNS ||
- command == (int)MAV_CMD_NAV_LOITER_TIME ||
- command == (int)MAV_CMD_NAV_LOITER_UNLIM) {
-
- orbit = param3;
- } else {
-
- // XXX set default orbit via param
- // 15 initialized above
- }
-
- sp->turn_distance_xy = orbit;
- sp->turn_distance_z = orbit;
-}
-
-/**
- * This callback is executed each time a waypoint changes.
- *
- * It publishes the vehicle_global_position_setpoint_s or the
- * vehicle_local_position_setpoint_s topic, depending on the type of waypoint
- */
-void mavlink_missionlib_current_waypoint_changed(uint16_t index, float param1,
- float param2, float param3, float param4, float param5_lat_x,
- 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 local_position_setpoint_pub = -1;
- static unsigned last_waypoint_index = -1;
- char buf[50] = {0};
-
- // XXX include check if WP is supported, jump to next if not
-
- /* Update controller setpoints */
- if (frame == (int)MAV_FRAME_GLOBAL) {
- /* global, absolute waypoint */
- struct vehicle_global_position_setpoint_s sp;
- sp.lat = param5_lat_x * 1e7f;
- sp.lon = param6_lon_y * 1e7f;
- sp.altitude = param7_alt_z;
- sp.altitude_is_relative = false;
- sp.yaw = _wrap_pi(param4 / 180.0f * M_PI_F);
- set_special_fields(param1, param2, param3, param4, command, &sp);
-
- /* Initialize setpoint publication if necessary */
- if (global_position_setpoint_pub < 0) {
- global_position_setpoint_pub = orb_advertise(ORB_ID(vehicle_global_position_setpoint), &sp);
-
- } else {
- orb_publish(ORB_ID(vehicle_global_position_setpoint), global_position_setpoint_pub, &sp);
- }
-
-
- /* fill triplet: previous, current, next waypoint */
- struct vehicle_global_position_set_triplet_s triplet;
-
- /* current waypoint is same as sp */
- memcpy(&(triplet.current), &sp, sizeof(sp));
-
- /*
- * Check if previous WP (in mission, not in execution order)
- * is available and identify correct index
- */
- int last_setpoint_index = -1;
- bool last_setpoint_valid = false;
-
- if (index > 0) {
- last_setpoint_index = index - 1;
- }
-
- while (last_setpoint_index >= 0) {
-
- if (wpm->waypoints[last_setpoint_index].frame == (int)MAV_FRAME_GLOBAL &&
- (wpm->waypoints[last_setpoint_index].command == (int)MAV_CMD_NAV_WAYPOINT ||
- wpm->waypoints[last_setpoint_index].command == (int)MAV_CMD_NAV_LOITER_TURNS ||
- wpm->waypoints[last_setpoint_index].command == (int)MAV_CMD_NAV_LOITER_TIME ||
- wpm->waypoints[last_setpoint_index].command == (int)MAV_CMD_NAV_LOITER_UNLIM)) {
- last_setpoint_valid = true;
- break;
- }
-
- last_setpoint_index--;
- }
-
- /*
- * Check if next WP (in mission, not in execution order)
- * is available and identify correct index
- */
- int next_setpoint_index = -1;
- bool next_setpoint_valid = false;
-
- /* next waypoint */
- if (wpm->size > 1) {
- next_setpoint_index = index + 1;
- }
-
- while (next_setpoint_index < wpm->size) {
-
- if (wpm->waypoints[next_setpoint_index].frame == (int)MAV_FRAME_GLOBAL && (wpm->waypoints[next_setpoint_index].command == (int)MAV_CMD_NAV_WAYPOINT ||
- wpm->waypoints[next_setpoint_index].command == (int)MAV_CMD_NAV_LOITER_TURNS ||
- wpm->waypoints[next_setpoint_index].command == (int)MAV_CMD_NAV_LOITER_TIME ||
- wpm->waypoints[next_setpoint_index].command == (int)MAV_CMD_NAV_LOITER_UNLIM)) {
- next_setpoint_valid = true;
- break;
- }
-
- next_setpoint_index++;
- }
-
- /* 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));
- }
-
- /* 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);
-
- } 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);
-
- } else if (frame == (int)MAV_FRAME_GLOBAL_RELATIVE_ALT) {
- /* global, relative alt (in relation to HOME) waypoint */
- struct vehicle_global_position_setpoint_s sp;
- sp.lat = param5_lat_x * 1e7f;
- sp.lon = param6_lon_y * 1e7f;
- sp.altitude = param7_alt_z;
- sp.altitude_is_relative = true;
- sp.yaw = _wrap_pi(param4 / 180.0f * M_PI_F);
- set_special_fields(param1, param2, param3, param4, command, &sp);
-
- /* Initialize publication if necessary */
- if (global_position_setpoint_pub < 0) {
- global_position_setpoint_pub = orb_advertise(ORB_ID(vehicle_global_position_setpoint), &sp);
-
- } else {
- orb_publish(ORB_ID(vehicle_global_position_setpoint), global_position_setpoint_pub, &sp);
- }
-
-
-
- sprintf(buf, "[mp] WP#%i (lat: %f/lon %f/rel alt %f/hdg %f\n", (int)index, (double)param5_lat_x, (double)param6_lon_y, (double)param7_alt_z, (double)param4);
-
- } else if (frame == (int)MAV_FRAME_LOCAL_ENU || frame == (int)MAV_FRAME_LOCAL_NED) {
- /* local, absolute waypoint */
- struct vehicle_local_position_setpoint_s sp;
- sp.x = param5_lat_x;
- sp.y = param6_lon_y;
- sp.z = param7_alt_z;
- sp.yaw = _wrap_pi(param4 / 180.0f * M_PI_F);
-
- /* Initialize publication if necessary */
- if (local_position_setpoint_pub < 0) {
- local_position_setpoint_pub = orb_advertise(ORB_ID(vehicle_local_position_setpoint), &sp);
-
- } else {
- orb_publish(ORB_ID(vehicle_local_position_setpoint), local_position_setpoint_pub, &sp);
- }
-
- sprintf(buf, "[mp] WP#%i (x: %f/y %f/z %f/hdg %f\n", (int)index, (double)param5_lat_x, (double)param6_lon_y, (double)param7_alt_z, (double)param4);
- } else {
- warnx("non-navigation WP, ignoring");
- mavlink_missionlib_send_gcs_string("[mp] Unknown waypoint type, ignoring.");
- return;
- }
-
- /* only set this for known waypoint types (non-navigation types would have returned earlier) */
- last_waypoint_index = index;
-
- mavlink_missionlib_send_gcs_string(buf);
- printf("%s\n", buf);
- //printf("[mavlink mp] new setpoint\n");//: frame: %d, lat: %d, lon: %d, alt: %d, yaw: %d\n", frame, param5_lat_x*1000, param6_lon_y*1000, param7_alt_z*1000, param4*1000);
-}
diff --git a/src/modules/mavlink/module.mk b/src/modules/mavlink/module.mk
index 5d3d6a73c..89a097c24 100644
--- a/src/modules/mavlink/module.mk
+++ b/src/modules/mavlink/module.mk
@@ -37,7 +37,6 @@
MODULE_COMMAND = mavlink
SRCS += mavlink.c \
- missionlib.c \
mavlink_parameters.c \
mavlink_receiver.cpp \
orb_listener.c \
diff --git a/src/modules/mavlink/orb_listener.c b/src/modules/mavlink/orb_listener.c
index 92b1b45be..6e177bc4d 100644
--- a/src/modules/mavlink/orb_listener.c
+++ b/src/modules/mavlink/orb_listener.c
@@ -60,7 +60,6 @@
#include "waypoints.h"
#include "orb_topics.h"
-#include "missionlib.h"
#include "mavlink_hil.h"
#include "util.h"
@@ -70,6 +69,7 @@ struct vehicle_global_position_s global_pos;
struct vehicle_local_position_s local_pos;
struct navigation_capabilities_s nav_cap;
struct vehicle_status_s v_status;
+struct vehicle_control_mode_s control_mode;
struct rc_channels_s rc;
struct rc_input_values rc_raw;
struct actuator_armed_s armed;
@@ -126,6 +126,7 @@ static void l_vehicle_rates_setpoint(const struct listener *l);
static void l_home(const struct listener *l);
static void l_airspeed(const struct listener *l);
static void l_nav_cap(const struct listener *l);
+static void l_control_mode(const struct listener *l);
static const struct listener listeners[] = {
{l_sensor_combined, &mavlink_subs.sensor_sub, 0},
@@ -136,7 +137,7 @@ static const struct listener listeners[] = {
{l_input_rc, &mavlink_subs.input_rc_sub, 0},
{l_global_position, &mavlink_subs.global_pos_sub, 0},
{l_local_position, &mavlink_subs.local_pos_sub, 0},
- {l_global_position_setpoint, &mavlink_subs.spg_sub, 0},
+ {l_global_position_setpoint, &mavlink_subs.triplet_sub, 0},
{l_local_position_setpoint, &mavlink_subs.spl_sub, 0},
{l_attitude_setpoint, &mavlink_subs.spa_sub, 0},
{l_actuator_outputs, &mavlink_subs.act_0_sub, 0},
@@ -152,6 +153,7 @@ static const struct listener listeners[] = {
{l_home, &mavlink_subs.home_sub, 0},
{l_airspeed, &mavlink_subs.airspeed_sub, 0},
{l_nav_cap, &mavlink_subs.navigation_capabilities_sub, 0},
+ {l_control_mode, &mavlink_subs.control_mode_sub, 0},
};
static const unsigned n_listeners = sizeof(listeners) / sizeof(listeners[0]);
@@ -408,23 +410,24 @@ l_local_position(const struct listener *l)
void
l_global_position_setpoint(const struct listener *l)
{
- struct vehicle_global_position_setpoint_s global_sp;
-
- /* copy local position data into local buffer */
- orb_copy(ORB_ID(vehicle_global_position_setpoint), mavlink_subs.spg_sub, &global_sp);
+ struct mission_item_triplet_s triplet;
+ orb_copy(ORB_ID(mission_item_triplet), mavlink_subs.triplet_sub, &triplet);
uint8_t coordinate_frame = MAV_FRAME_GLOBAL;
+
+ if (!triplet.current_valid)
+ return;
- if (global_sp.altitude_is_relative)
+ if (triplet.current.altitude_is_relative)
coordinate_frame = MAV_FRAME_GLOBAL_RELATIVE_ALT;
if (gcs_link)
mavlink_msg_global_position_setpoint_int_send(MAVLINK_COMM_0,
coordinate_frame,
- global_sp.lat,
- global_sp.lon,
- global_sp.altitude * 1000.0f,
- global_sp.yaw * M_RAD_TO_DEG_F * 100.0f);
+ (int32_t)(triplet.current.lat * 1e7d),
+ (int32_t)(triplet.current.lon * 1e7d),
+ (int32_t)(triplet.current.altitude * 1e3f),
+ (int16_t)(triplet.current.yaw * M_RAD_TO_DEG_F * 1e2f));
}
void
@@ -663,7 +666,7 @@ l_home(const struct listener *l)
orb_copy(ORB_ID(home_position), mavlink_subs.home_sub, &home);
- mavlink_msg_gps_global_origin_send(MAVLINK_COMM_0, home.lat, home.lon, home.alt);
+ mavlink_msg_gps_global_origin_send(MAVLINK_COMM_0, (int32_t)(home.lat*1e7d), (int32_t)(home.lon*1e7d), (int32_t)(home.altitude)*1e3f);
}
void
@@ -685,6 +688,26 @@ l_nav_cap(const struct listener *l)
}
+void
+l_control_mode(const struct listener *l)
+{
+ orb_copy(ORB_ID(vehicle_control_mode), mavlink_subs.control_mode_sub, &control_mode);
+
+ /* translate the current syste state to mavlink state and mode */
+ uint8_t mavlink_state = 0;
+ uint8_t mavlink_base_mode = 0;
+ uint32_t mavlink_custom_mode = 0;
+ get_mavlink_mode_and_state(&mavlink_state, &mavlink_base_mode, &mavlink_custom_mode);
+
+ /* send heartbeat */
+ mavlink_msg_heartbeat_send(chan,
+ mavlink_system.type,
+ MAV_AUTOPILOT_PX4,
+ mavlink_base_mode,
+ mavlink_custom_mode,
+ mavlink_state);
+}
+
static void *
uorb_receive_thread(void *arg)
{
@@ -760,6 +783,10 @@ uorb_receive_start(void)
status_sub = orb_subscribe(ORB_ID(vehicle_status));
orb_set_interval(status_sub, 300); /* max 3.33 Hz updates */
+ /* --- CONTROL MODE --- */
+ mavlink_subs.control_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode));
+ orb_set_interval(mavlink_subs.control_mode_sub, 300); /* max 3.33 Hz updates */
+
/* --- RC CHANNELS VALUE --- */
rc_sub = orb_subscribe(ORB_ID(rc_channels));
orb_set_interval(rc_sub, 100); /* 10Hz updates */
@@ -777,9 +804,9 @@ uorb_receive_start(void)
orb_set_interval(mavlink_subs.local_pos_sub, 1000); /* 1Hz active updates */
/* --- GLOBAL SETPOINT VALUE --- */
- mavlink_subs.spg_sub = orb_subscribe(ORB_ID(vehicle_global_position_setpoint));
- orb_set_interval(mavlink_subs.spg_sub, 2000); /* 0.5 Hz updates */
-
+ mavlink_subs.triplet_sub = orb_subscribe(ORB_ID(mission_item_triplet));
+ orb_set_interval(mavlink_subs.triplet_sub, 2000); /* 0.5 Hz updates */
+
/* --- LOCAL SETPOINT VALUE --- */
mavlink_subs.spl_sub = orb_subscribe(ORB_ID(vehicle_local_position_setpoint));
orb_set_interval(mavlink_subs.spl_sub, 2000); /* 0.5 Hz updates */
diff --git a/src/modules/mavlink/orb_topics.h b/src/modules/mavlink/orb_topics.h
index 91773843b..4d428406a 100644
--- a/src/modules/mavlink/orb_topics.h
+++ b/src/modules/mavlink/orb_topics.h
@@ -45,14 +45,15 @@
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_gps_position.h>
#include <uORB/topics/vehicle_global_position.h>
+#include <uORB/topics/vehicle_local_position.h>
#include <uORB/topics/home_position.h>
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/offboard_control_setpoint.h>
#include <uORB/topics/vehicle_command.h>
#include <uORB/topics/vehicle_local_position_setpoint.h>
+#include <uORB/topics/mission_item_triplet.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>
@@ -86,7 +87,7 @@ struct mavlink_subscriptions {
int local_pos_sub;
int spa_sub;
int spl_sub;
- int spg_sub;
+ int triplet_sub;
int debug_key_value;
int input_rc_sub;
int optical_flow;
@@ -94,6 +95,7 @@ struct mavlink_subscriptions {
int home_sub;
int airspeed_sub;
int navigation_capabilities_sub;
+ int control_mode_sub;
};
extern struct mavlink_subscriptions mavlink_subs;
@@ -110,6 +112,9 @@ extern struct navigation_capabilities_s nav_cap;
/** Vehicle status */
extern struct vehicle_status_s v_status;
+/** Vehicle control mode */
+extern struct vehicle_control_mode_s control_mode;
+
/** RC channels */
extern struct rc_channels_s rc;
diff --git a/src/modules/mavlink/waypoints.c b/src/modules/mavlink/waypoints.c
index 7e4a2688f..168666d4e 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>
@@ -44,29 +44,155 @@
#include <sys/prctl.h>
#include <unistd.h>
#include <stdio.h>
-
#include "mavlink_bridge_header.h"
-#include "missionlib.h"
#include "waypoints.h"
#include "util.h"
+#include <uORB/uORB.h>
+#include <uORB/topics/mission.h>
+#include <geo/geo.h>
+#include <dataman/dataman.h>
+#include <drivers/drv_hrt.h>
+#include <systemlib/err.h>
-#ifndef FM_PI
-#define FM_PI 3.1415926535897932384626433832795f
-#endif
+bool verbose = true;
-bool debug = false;
-bool verbose = false;
+orb_advert_t mission_pub = -1;
+struct mission_s mission;
+uint8_t mavlink_wpm_comp_id = MAV_COMP_ID_MISSIONPLANNER;
-#define MAVLINK_WPM_NO_PRINTF
+void
+mavlink_missionlib_send_message(mavlink_message_t *msg)
+{
+ uint16_t len = mavlink_msg_to_send_buffer(missionlib_msg_buf, msg);
-uint8_t mavlink_wpm_comp_id = MAV_COMP_ID_MISSIONPLANNER;
+ mavlink_send_uart_bytes(chan, missionlib_msg_buf, len);
+}
-void mavlink_wpm_init(mavlink_wpm_storage *state)
+
+
+int
+mavlink_missionlib_send_gcs_string(const char *string)
+{
+ const int len = MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN;
+ mavlink_statustext_t statustext;
+ int i = 0;
+
+ while (i < len - 1) {
+ statustext.text[i] = string[i];
+
+ if (string[i] == '\0')
+ break;
+
+ i++;
+ }
+
+ if (i > 1) {
+ /* Enforce null termination */
+ statustext.text[i] = '\0';
+ mavlink_message_t msg;
+
+ mavlink_msg_statustext_encode(mavlink_system.sysid, mavlink_system.compid, &msg, &statustext);
+ mavlink_missionlib_send_message(&msg);
+ return OK;
+
+ } else {
+ return 1;
+ }
+}
+
+void publish_mission()
+{
+ /* 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);
+ }
+}
+
+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;
+ }
+
+ switch (mavlink_mission_item->command) {
+ case MAV_CMD_NAV_TAKEOFF:
+ mission_item->pitch_min = mavlink_mission_item->param2;
+ break;
+ default:
+ mission_item->acceptance_radius = mavlink_mission_item->param2;
+ break;
+ }
+
+ mission_item->yaw = _wrap_pi(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->time_inside = mavlink_mission_item->param1;
+ mission_item->autocontinue = mavlink_mission_item->autocontinue;
+ // mission_item->index = mavlink_mission_item->seq;
+ mission_item->origin = ORIGIN_MAVLINK;
+
+ return OK;
+}
+
+int map_mission_item_to_mavlink_mission_item(const struct mission_item_s *mission_item, mavlink_mission_item_t *mavlink_mission_item)
{
- // Set all waypoints to zero
+ if (mission_item->altitude_is_relative) {
+ mavlink_mission_item->frame = MAV_FRAME_GLOBAL;
+ } else {
+ mavlink_mission_item->frame = MAV_FRAME_GLOBAL_RELATIVE_ALT;
+ }
+
+ switch (mission_item->nav_cmd) {
+ case NAV_CMD_TAKEOFF:
+ mavlink_mission_item->param2 = mission_item->pitch_min;
+ break;
+ default:
+ mavlink_mission_item->param2 = mission_item->acceptance_radius;
+ break;
+ }
+
+ 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->time_inside;
+ mavlink_mission_item->autocontinue = mission_item->autocontinue;
+ // mavlink_mission_item->seq = mission_item->index;
+
+ return OK;
+}
- // Set count to zero
+void mavlink_wpm_init(mavlink_wpm_storage *state)
+{
state->size = 0;
state->max_size = MAVLINK_WPM_MAX_WP_COUNT;
state->current_state = MAVLINK_WPM_STATE_IDLE;
@@ -75,14 +201,7 @@ void mavlink_wpm_init(mavlink_wpm_storage *state)
state->timestamp_lastaction = 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->current_dataman_id = 0;
}
/*
@@ -93,25 +212,14 @@ void mavlink_wpm_send_waypoint_ack(uint8_t sysid, uint8_t compid, uint8_t type)
mavlink_message_t msg;
mavlink_mission_ack_t wpa;
- wpa.target_system = wpm->current_partner_sysid;
- wpa.target_component = wpm->current_partner_compid;
+ wpa.target_system = sysid;
+ wpa.target_component = compid;
wpa.type = type;
mavlink_msg_mission_ack_encode(mavlink_system.sysid, mavlink_wpm_comp_id, &msg, &wpa);
mavlink_missionlib_send_message(&msg);
- // 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_VERBOSE) printf("Sent waypoint ack (%u) to ID %u\n", wpa.type, wpa.target_system);
-
-#endif
- mavlink_missionlib_send_gcs_string("Sent waypoint ACK");
- }
+ if (verbose) warnx("Sent waypoint ack (%u) to ID %u", wpa.type, wpa.target_system);
}
/*
@@ -126,45 +234,19 @@ void mavlink_wpm_send_waypoint_ack(uint8_t sysid, uint8_t compid, uint8_t type)
void mavlink_wpm_send_waypoint_current(uint16_t seq)
{
if (seq < wpm->size) {
- mavlink_mission_item_t *cur = &(wpm->waypoints[seq]);
-
mavlink_message_t msg;
mavlink_mission_current_t wpc;
- wpc.seq = cur->seq;
+ wpc.seq = seq;
mavlink_msg_mission_current_encode(mavlink_system.sysid, mavlink_wpm_comp_id, &msg, &wpc);
mavlink_missionlib_send_message(&msg);
- // FIXME TIMING usleep(paramClient->getParamValue("PROTOCOLDELAY"));
-
- if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_missionlib_send_gcs_string("Set current waypoint\n"); //// printf("Broadcasted new current waypoint %u\n", wpc.seq);
+ if (verbose) warnx("Broadcasted new current waypoint %u", wpc.seq);
} else {
- if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_missionlib_send_gcs_string("ERROR: wp index out of bounds\n");
- }
-}
-
-/*
- * @brief Directs the MAV to fly to a position
- *
- * Sends a message to the controller, advising it to fly to the coordinates
- * of the waypoint with a given orientation
- *
- * @param seq The waypoint sequence number the MAV should fly to.
- */
-void mavlink_wpm_send_setpoint(uint16_t seq)
-{
- if (seq < wpm->size) {
- mavlink_mission_item_t *cur = &(wpm->waypoints[seq]);
- mavlink_missionlib_current_waypoint_changed(cur->seq, cur->param1,
- 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();
-
- } 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");
+ mavlink_missionlib_send_gcs_string("ERROR: wp index out of bounds");
+ if (verbose) warnx("ERROR: index out of bounds");
}
}
@@ -173,34 +255,47 @@ void mavlink_wpm_send_waypoint_count(uint8_t sysid, uint8_t compid, uint16_t cou
mavlink_message_t msg;
mavlink_mission_count_t wpc;
- wpc.target_system = wpm->current_partner_sysid;
- wpc.target_component = wpm->current_partner_compid;
- wpc.count = count;
+ wpc.target_system = sysid;
+ wpc.target_component = compid;
+ wpc.count = mission.count;
mavlink_msg_mission_count_encode(mavlink_system.sysid, mavlink_wpm_comp_id, &msg, &wpc);
mavlink_missionlib_send_message(&msg);
- if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_missionlib_send_gcs_string("Sent waypoint count"); //// if (verbose) // printf("Sent waypoint count (%u) to ID %u\n", wpc.count, wpc.target_system);
-
- // FIXME TIMING usleep(paramClient->getParamValue("PROTOCOLDELAY"));
+ if (verbose) warnx("Sent waypoint count (%u) to ID %u", wpc.count, wpc.target_system);
}
void mavlink_wpm_send_waypoint(uint8_t sysid, uint8_t compid, uint16_t seq)
{
- if (seq < wpm->size) {
- mavlink_message_t msg;
- 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);
- mavlink_missionlib_send_message(&msg);
- if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_missionlib_send_gcs_string("Sent waypoint"); //// if (verbose) // printf("Sent waypoint %u to ID %u\n", wp->seq, wp->target_system);
+ struct mission_item_s mission_item;
+ ssize_t len = sizeof(struct mission_item_s);
+
+ dm_item_t dm_current;
+
+ if (wpm->current_dataman_id == 0) {
+ dm_current = DM_KEY_WAYPOINTS_OFFBOARD_0;
+ } else {
+ dm_current = DM_KEY_WAYPOINTS_OFFBOARD_1;
+ }
+
+ if (dm_read(dm_current, seq, &mission_item, len) == len) {
- // FIXME TIMING usleep(paramClient->getParamValue("PROTOCOLDELAY"));
+ /* create mission_item_s from mavlink_mission_item_t */
+ mavlink_mission_item_t wp;
+ map_mission_item_to_mavlink_mission_item(&mission_item, &wp);
+ mavlink_message_t msg;
+ wp.target_system = sysid;
+ wp.target_component = compid;
+ wp.seq = seq;
+ mavlink_msg_mission_item_encode(mavlink_system.sysid, mavlink_wpm_comp_id, &msg, &wp);
+ mavlink_missionlib_send_message(&msg);
+
+ if (verbose) warnx("Sent waypoint %u to ID %u", wp.seq, wp.target_system);
} else {
- if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_missionlib_send_gcs_string("ERROR: Waypoint index out of bounds\n");
+ mavlink_wpm_send_waypoint_ack(wpm->current_partner_sysid, wpm->current_partner_compid, MAV_MISSION_ERROR);
+ if (verbose) warnx("ERROR: could not read WP%u", seq);
}
}
@@ -209,18 +304,17 @@ void mavlink_wpm_send_waypoint_request(uint8_t sysid, uint8_t compid, uint16_t s
if (seq < wpm->max_size) {
mavlink_message_t msg;
mavlink_mission_request_t wpr;
- wpr.target_system = wpm->current_partner_sysid;
- wpr.target_component = wpm->current_partner_compid;
+ wpr.target_system = sysid;
+ wpr.target_component = compid;
wpr.seq = seq;
mavlink_msg_mission_request_encode(mavlink_system.sysid, mavlink_wpm_comp_id, &msg, &wpr);
mavlink_missionlib_send_message(&msg);
- if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_missionlib_send_gcs_string("Sent waypoint request"); //// if (verbose) // printf("Sent waypoint request %u to ID %u\n", wpr.seq, wpr.target_system);
-
- // FIXME TIMING usleep(paramClient->getParamValue("PROTOCOLDELAY"));
+ if (verbose) warnx("Sent waypoint request %u to ID %u", wpr.seq, wpr.target_system);
} else {
- if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_missionlib_send_gcs_string("ERROR: Waypoint index exceeds list capacity\n");
+ mavlink_missionlib_send_gcs_string("ERROR: Waypoint index exceeds list capacity");
+ if (verbose) warnx("ERROR: Waypoint index exceeds list capacity");
}
}
@@ -241,293 +335,33 @@ void mavlink_wpm_send_waypoint_reached(uint16_t seq)
mavlink_msg_mission_item_reached_encode(mavlink_system.sysid, mavlink_wpm_comp_id, &msg, &wp_reached);
mavlink_missionlib_send_message(&msg);
- if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_missionlib_send_gcs_string("Sent waypoint reached message"); //// if (verbose) // printf("Sent waypoint %u reached message\n", wp_reached.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;
-
- 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));
-
- const double radius_earth = 6371000.0;
-
- float dxy = radius_earth * c;
- float dz = alt - wp->z;
-
- *dist_xy = fabsf(dxy);
- *dist_z = fabsf(dz);
-
- return sqrtf(dxy * dxy + dz * dz);
-
- } else {
- return -1.0f;
- }
-
-}
-
-/*
- * 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;
- }
-
- // 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++;
+ if (verbose) warnx("Sent waypoint %u reached message", wp_reached.seq);
}
-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)
+void mavlink_waypoint_eventloop(uint64_t now)
{
/* check for timed-out operations */
if (now - wpm->timestamp_lastaction > wpm->timeout && wpm->current_state != MAVLINK_WPM_STATE_IDLE) {
-#ifdef MAVLINK_WPM_NO_PRINTF
- mavlink_missionlib_send_gcs_string("Operation timeout switching -> IDLE");
-#else
+ mavlink_missionlib_send_gcs_string("Operation timeout");
- if (MAVLINK_WPM_VERBOSE) printf("Last operation (state=%u) timed out, changing state to MAVLINK_WPM_STATE_IDLE\n", wpm->current_state);
+ if (verbose) warnx("Last operation (state=%u) timed out, changing state to MAVLINK_WPM_STATE_IDLE", wpm->current_state);
-#endif
wpm->current_state = MAVLINK_WPM_STATE_IDLE;
- wpm->current_count = 0;
wpm->current_partner_sysid = 0;
wpm->current_partner_compid = 0;
- wpm->current_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);
-
- return OK;
}
-void mavlink_wpm_message_handler(const mavlink_message_t *msg, const struct vehicle_global_position_s *global_pos , struct vehicle_local_position_s *local_pos)
+void mavlink_wpm_message_handler(const mavlink_message_t *msg)
{
- uint64_t now = mavlink_missionlib_get_system_timestamp();
+ uint64_t now = hrt_absolute_time();
switch (msg->msgid) {
- case MAVLINK_MSG_ID_MISSION_ACK: {
+ case MAVLINK_MSG_ID_MISSION_ACK: {
mavlink_mission_ack_t wpa;
mavlink_msg_mission_ack_decode(msg, &wpa);
@@ -537,8 +371,6 @@ 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");
-
wpm->current_state = MAVLINK_WPM_STATE_IDLE;
wpm->current_wp_id = 0;
}
@@ -546,12 +378,13 @@ void mavlink_wpm_message_handler(const mavlink_message_t *msg, const struct vehi
} else {
mavlink_missionlib_send_gcs_string("REJ. WP CMD: curr partner id mismatch");
+ if (verbose) warnx("REJ. WP CMD: curr partner id mismatch");
}
break;
}
- case MAVLINK_MSG_ID_MISSION_SET_CURRENT: {
+ case MAVLINK_MSG_ID_MISSION_SET_CURRENT: {
mavlink_mission_set_current_t wpc;
mavlink_msg_mission_set_current_decode(msg, &wpc);
@@ -560,44 +393,32 @@ 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;
-
- 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;
- }
- }
-
- mavlink_missionlib_send_gcs_string("NEW WP SET");
-
- 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;
+ mission.current_index = wpc.seq;
+ publish_mission();
+
+ mavlink_wpm_send_waypoint_current(wpc.seq);
} else {
mavlink_missionlib_send_gcs_string("IGN WP CURR CMD: Not in list");
+ if (verbose) warnx("IGN WP CURR CMD: Not in list");
}
} else {
mavlink_missionlib_send_gcs_string("IGN WP CURR CMD: Busy");
+ if (verbose) warnx("IGN WP CURR CMD: Busy");
}
} else {
mavlink_missionlib_send_gcs_string("REJ. WP CMD: target id mismatch");
+ if (verbose) warnx("REJ. WP CMD: target id mismatch");
}
break;
}
- case MAVLINK_MSG_ID_MISSION_REQUEST_LIST: {
+ case MAVLINK_MSG_ID_MISSION_REQUEST_LIST: {
mavlink_mission_request_list_t wprl;
mavlink_msg_mission_request_list_decode(msg, &wprl);
@@ -606,437 +427,304 @@ void mavlink_wpm_message_handler(const mavlink_message_t *msg, const struct vehi
if (wpm->current_state == MAVLINK_WPM_STATE_IDLE || wpm->current_state == MAVLINK_WPM_STATE_SENDLIST) {
if (wpm->size > 0) {
- //if (verbose && wpm->current_state == MAVLINK_WPM_STATE_IDLE) // printf("Got MAVLINK_MSG_ID_MISSION_ITEM_REQUEST_LIST from %u changing state to MAVLINK_WPM_STATE_SENDLIST\n", msg->sysid);
-// if (verbose && wpm->current_state == MAVLINK_WPM_STATE_SENDLIST) // printf("Got MAVLINK_MSG_ID_MISSION_ITEM_REQUEST_LIST again from %u staying in state MAVLINK_WPM_STATE_SENDLIST\n", msg->sysid);
+
wpm->current_state = MAVLINK_WPM_STATE_SENDLIST;
wpm->current_wp_id = 0;
wpm->current_partner_sysid = msg->sysid;
wpm->current_partner_compid = msg->compid;
} else {
- // if (verbose) // printf("Got MAVLINK_MSG_ID_MISSION_ITEM_REQUEST_LIST from %u but have no waypoints, staying in \n", msg->sysid);
+ if (verbose) warnx("No waypoints send");
}
wpm->current_count = wpm->size;
mavlink_wpm_send_waypoint_count(msg->sysid, msg->compid, wpm->current_count);
} else {
- // if (verbose) // printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_REQUEST_LIST because i'm doing something else already (state=%i).\n", wpm->current_state);
+ mavlink_missionlib_send_gcs_string("IGN REQUEST LIST: Busy");
+ if (verbose) warnx("IGN REQUEST LIST: Busy");
}
} else {
- // if (verbose) // printf("IGNORED WAYPOINT COMMAND BECAUSE TARGET SYSTEM AND COMPONENT MISMATCH\n");
+ mavlink_missionlib_send_gcs_string("REJ. REQUEST LIST: target id mismatch");
+ if (verbose) warnx("REJ. REQUEST LIST: target id mismatch");
}
break;
}
- case MAVLINK_MSG_ID_MISSION_REQUEST: {
+ case MAVLINK_MSG_ID_MISSION_REQUEST: {
mavlink_mission_request_t wpr;
mavlink_msg_mission_request_decode(msg, &wpr);
if (msg->sysid == wpm->current_partner_sysid && msg->compid == wpm->current_partner_compid && wpr.target_system == mavlink_system.sysid /*&& wpr.target_component == mavlink_wpm_comp_id*/) {
wpm->timestamp_lastaction = now;
- //ensure that we are in the correct state and that the first request has id 0 and the following requests have either the last id (re-send last waypoint) or last_id+1 (next waypoint)
- if ((wpm->current_state == MAVLINK_WPM_STATE_SENDLIST && wpr.seq == 0) || (wpm->current_state == MAVLINK_WPM_STATE_SENDLIST_SENDWPS && (wpr.seq == wpm->current_wp_id || wpr.seq == wpm->current_wp_id + 1) && wpr.seq < wpm->size)) {
- if (wpm->current_state == MAVLINK_WPM_STATE_SENDLIST) {
-#ifdef MAVLINK_WPM_NO_PRINTF
- mavlink_missionlib_send_gcs_string("GOT WP REQ, state -> SEND");
-#else
+ if (wpr.seq >= wpm->size) {
- if (MAVLINK_WPM_VERBOSE) printf("Got MAVLINK_MSG_ID_MISSION_ITEM_REQUEST of waypoint %u from %u changing state to MAVLINK_WPM_STATE_SENDLIST_SENDWPS\n", wpr.seq, msg->sysid);
+ mavlink_missionlib_send_gcs_string("REJ. WP CMD: Req. WP not in list");
+ if (verbose) warnx("Ignored MAVLINK_MSG_ID_MISSION_ITEM_REQUEST because the requested waypoint ID (%u) was out of bounds.", wpr.seq);
+ break;
+ }
-#endif
- }
+ /*
+ * Ensure that we are in the correct state and that the first request has id 0
+ * and the following requests have either the last id (re-send last waypoint) or last_id+1 (next waypoint)
+ */
+ if (wpm->current_state == MAVLINK_WPM_STATE_SENDLIST) {
- if (wpm->current_state == MAVLINK_WPM_STATE_SENDLIST_SENDWPS && wpr.seq == wpm->current_wp_id + 1) {
-#ifdef MAVLINK_WPM_NO_PRINTF
- mavlink_missionlib_send_gcs_string("GOT 2nd WP REQ");
-#else
+ if (wpr.seq == 0) {
+ if (verbose) warnx("Got MAVLINK_MSG_ID_MISSION_ITEM_REQUEST of waypoint %u from %u changing state to MAVLINK_WPM_STATE_SENDLIST_SENDWPS", wpr.seq, msg->sysid);
+ wpm->current_state = MAVLINK_WPM_STATE_SENDLIST_SENDWPS;
+ } else {
+ mavlink_missionlib_send_gcs_string("REJ. WP CMD: First id != 0");
+ if (verbose) warnx("REJ. WP CMD: First id != 0");
+ break;
+ }
- if (MAVLINK_WPM_VERBOSE) printf("Got MAVLINK_MSG_ID_MISSION_ITEM_REQUEST of waypoint %u from %u staying in state MAVLINK_WPM_STATE_SENDLIST_SENDWPS\n", wpr.seq, msg->sysid);
+ } else if (wpm->current_state == MAVLINK_WPM_STATE_SENDLIST_SENDWPS) {
-#endif
- }
+ if (wpr.seq == wpm->current_wp_id) {
- if (wpm->current_state == MAVLINK_WPM_STATE_SENDLIST_SENDWPS && wpr.seq == wpm->current_wp_id) {
-#ifdef MAVLINK_WPM_NO_PRINTF
- mavlink_missionlib_send_gcs_string("GOT 2nd WP REQ");
-#else
+ if (verbose) warnx("Got MAVLINK_MSG_ID_MISSION_ITEM_REQUEST of waypoint %u (again) from %u staying in state MAVLINK_WPM_STATE_SENDLIST_SENDWPS", wpr.seq, msg->sysid);
- if (MAVLINK_WPM_VERBOSE) printf("Got MAVLINK_MSG_ID_MISSION_ITEM_REQUEST of waypoint %u (again) from %u staying in state MAVLINK_WPM_STATE_SENDLIST_SENDWPS\n", wpr.seq, msg->sysid);
+ } else if (wpr.seq == wpm->current_wp_id + 1) {
-#endif
+ if (verbose) warnx("Got MAVLINK_MSG_ID_MISSION_ITEM_REQUEST of waypoint %u from %u staying in state MAVLINK_WPM_STATE_SENDLIST_SENDWPS", wpr.seq, msg->sysid);
+
+ } else {
+ mavlink_missionlib_send_gcs_string("REJ. WP CMD: Req. WP was unexpected");
+ if (verbose) warnx("Ignored MAVLINK_MSG_ID_MISSION_ITEM_REQUEST because the requested waypoint ID (%u) was not the expected (%u or %u).", wpr.seq, wpm->current_wp_id, wpm->current_wp_id + 1);
+ break;
}
- 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);
-
} else {
- // if (verbose)
- {
- if (!(wpm->current_state == MAVLINK_WPM_STATE_SENDLIST || wpm->current_state == MAVLINK_WPM_STATE_SENDLIST_SENDWPS)) {
-#ifdef MAVLINK_WPM_NO_PRINTF
- mavlink_missionlib_send_gcs_string("REJ. WP CMD: Busy");
-#else
-
- if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_REQUEST because i'm doing something else already (state=%i).\n", wpm->current_state);
-
-#endif
- break;
- } else if (wpm->current_state == MAVLINK_WPM_STATE_SENDLIST) {
- if (wpr.seq != 0) {
-#ifdef MAVLINK_WPM_NO_PRINTF
- mavlink_missionlib_send_gcs_string("REJ. WP CMD: First id != 0");
-#else
-
- if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_REQUEST because the first requested waypoint ID (%u) was not 0.\n", wpr.seq);
-
-#endif
- }
-
- } else if (wpm->current_state == MAVLINK_WPM_STATE_SENDLIST_SENDWPS) {
- if (wpr.seq != wpm->current_wp_id && wpr.seq != wpm->current_wp_id + 1) {
-#ifdef MAVLINK_WPM_NO_PRINTF
- mavlink_missionlib_send_gcs_string("REJ. WP CMD: Req. WP was unexpected");
-#else
-
- if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_REQUEST because the requested waypoint ID (%u) was not the expected (%u or %u).\n", wpr.seq, wpm->current_wp_id, wpm->current_wp_id + 1);
-
-#endif
-
- } else if (wpr.seq >= wpm->size) {
-#ifdef MAVLINK_WPM_NO_PRINTF
- mavlink_missionlib_send_gcs_string("REJ. WP CMD: Req. WP not in list");
-#else
-
- if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_REQUEST because the requested waypoint ID (%u) was out of bounds.\n", wpr.seq);
+ mavlink_missionlib_send_gcs_string("REJ. WP CMD: Busy");
+ if (verbose) warnx("Ignored MAVLINK_MSG_ID_MISSION_ITEM_REQUEST because i'm doing something else already (state=%i).", wpm->current_state);
+ break;
+ }
-#endif
- }
+ wpm->current_wp_id = wpr.seq;
+ wpm->current_state = MAVLINK_WPM_STATE_SENDLIST_SENDWPS;
- } else {
-#ifdef MAVLINK_WPM_NO_PRINTF
- mavlink_missionlib_send_gcs_string("REJ. WP CMD: ?");
-#else
+ if (wpr.seq < wpm->size) {
- if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_REQUEST - FIXME: missed error description\n");
+ mavlink_wpm_send_waypoint(wpm->current_partner_sysid, wpm->current_partner_compid,wpm->current_wp_id);
-#endif
- }
- }
+ } else {
+ mavlink_wpm_send_waypoint_ack(wpm->current_partner_sysid, wpm->current_partner_compid, MAV_MISSION_ERROR);
+ if (verbose) warnx("ERROR: Waypoint %u out of bounds", wpr.seq);
}
+
} else {
//we we're target but already communicating with someone else
if ((wpr.target_system == mavlink_system.sysid /*&& wpr.target_component == mavlink_wpm_comp_id*/) && !(msg->sysid == wpm->current_partner_sysid && msg->compid == wpm->current_partner_compid)) {
-#ifdef MAVLINK_WPM_NO_PRINTF
- mavlink_missionlib_send_gcs_string("REJ. WP CMD: Busy");
-#else
-
- if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_REQUEST from ID %u because i'm already talking to ID %u.\n", msg->sysid, wpm->current_partner_sysid);
-#endif
+ mavlink_missionlib_send_gcs_string("REJ. WP CMD: Busy");
+ if (verbose) warnx("Ignored MAVLINK_MSG_ID_MISSION_ITEM_REQUEST from ID %u because i'm already talking to ID %u.", msg->sysid, wpm->current_partner_sysid);
} else {
-#ifdef MAVLINK_WPM_NO_PRINTF
- mavlink_missionlib_send_gcs_string("REJ. WP CMD: target id mismatch");
-#else
- if (MAVLINK_WPM_VERBOSE) printf("IGNORED WAYPOINT COMMAND BECAUSE TARGET SYSTEM AND COMPONENT OR COMM PARTNER ID MISMATCH\n");
-
-#endif
+ mavlink_missionlib_send_gcs_string("REJ. WP CMD: target id mismatch");
+ if (verbose) warnx("IGNORED WAYPOINT COMMAND BECAUSE TARGET SYSTEM AND COMPONENT OR COMM PARTNER ID MISMATCH");
}
-
}
-
break;
}
- case MAVLINK_MSG_ID_MISSION_COUNT: {
+ case MAVLINK_MSG_ID_MISSION_COUNT: {
mavlink_mission_count_t wpc;
mavlink_msg_mission_count_decode(msg, &wpc);
if (wpc.target_system == mavlink_system.sysid/* && wpc.target_component == mavlink_wpm_comp_id*/) {
wpm->timestamp_lastaction = now;
- if (wpm->current_state == MAVLINK_WPM_STATE_IDLE || (wpm->current_state == MAVLINK_WPM_STATE_GETLIST && wpm->current_wp_id == 0)) {
-// printf("wpc count in: %d\n",wpc.count);
-// printf("Comp id: %d\n",msg->compid);
-// printf("Current partner sysid: %d\n",wpm->current_partner_sysid);
-
- if (wpc.count > 0) {
- if (wpm->current_state == MAVLINK_WPM_STATE_IDLE) {
-#ifdef MAVLINK_WPM_NO_PRINTF
- mavlink_missionlib_send_gcs_string("WP CMD OK: state -> GETLIST");
-#else
+ if (wpm->current_state == MAVLINK_WPM_STATE_IDLE) {
- if (MAVLINK_WPM_VERBOSE) printf("Got MAVLINK_MSG_ID_MISSION_ITEM_COUNT (%u) from %u changing state to MAVLINK_WPM_STATE_GETLIST\n", wpc.count, msg->sysid);
+ if (wpc.count > NUM_MISSIONS_SUPPORTED) {
+ if (verbose) warnx("Too many waypoints: %d, supported: %d", wpc.count, NUM_MISSIONS_SUPPORTED);
+ mavlink_wpm_send_waypoint_ack(wpm->current_partner_sysid, wpm->current_partner_compid, MAV_MISSION_NO_SPACE);
+ break;
+ }
-#endif
- }
+ if (wpc.count == 0) {
+ mavlink_missionlib_send_gcs_string("COUNT 0");
+ if (verbose) warnx("got waypoint count of 0, clearing waypoint list and staying in state MAVLINK_WPM_STATE_IDLE");
+ break;
+ }
+
+ if (verbose) warnx("Got MAVLINK_MSG_ID_MISSION_ITEM_COUNT (%u) from %u changing state to MAVLINK_WPM_STATE_GETLIST", wpc.count, msg->sysid);
- if (wpm->current_state == MAVLINK_WPM_STATE_GETLIST) {
-#ifdef MAVLINK_WPM_NO_PRINTF
- mavlink_missionlib_send_gcs_string("WP CMD OK AGAIN");
-#else
+ wpm->current_state = MAVLINK_WPM_STATE_GETLIST;
+ wpm->current_wp_id = 0;
+ wpm->current_partner_sysid = msg->sysid;
+ wpm->current_partner_compid = msg->compid;
+ wpm->current_count = wpc.count;
- if (MAVLINK_WPM_VERBOSE) printf("Got MAVLINK_MSG_ID_MISSION_ITEM_COUNT (%u) again from %u\n", wpc.count, msg->sysid);
+ mavlink_wpm_send_waypoint_request(wpm->current_partner_sysid, wpm->current_partner_compid, wpm->current_wp_id);
-#endif
- }
+ } else if (wpm->current_state == MAVLINK_WPM_STATE_GETLIST) {
- wpm->current_state = MAVLINK_WPM_STATE_GETLIST;
- wpm->current_wp_id = 0;
- wpm->current_partner_sysid = msg->sysid;
- wpm->current_partner_compid = msg->compid;
- wpm->current_count = wpc.count;
+ if (wpm->current_wp_id == 0) {
+ mavlink_missionlib_send_gcs_string("WP CMD OK AGAIN");
+ if (verbose) warnx("Got MAVLINK_MSG_ID_MISSION_ITEM_COUNT (%u) again from %u", wpc.count, msg->sysid);
+ } else {
+ mavlink_missionlib_send_gcs_string("REJ. WP CMD: Busy");
+ if (verbose) warnx("Ignored MAVLINK_MSG_ID_MISSION_ITEM_COUNT because i'm already receiving waypoint %u.", wpm->current_wp_id);
+ }
+ } else {
+ mavlink_missionlib_send_gcs_string("IGN MISSION_COUNT CMD: Busy");
+ if (verbose) warnx("IGN MISSION_COUNT CMD: Busy");
+ }
+ } else {
-#ifdef MAVLINK_WPM_NO_PRINTF
- mavlink_missionlib_send_gcs_string("CLR RCV BUF: READY");
-#else
+ mavlink_missionlib_send_gcs_string("REJ. WP COUNT CMD: target id mismatch");
+ if (verbose) warnx("IGNORED WAYPOINT COUNT COMMAND BECAUSE TARGET SYSTEM AND COMPONENT OR COMM PARTNER ID MISMATCH");
+ }
+ }
+ break;
- if (MAVLINK_WPM_VERBOSE) printf("clearing receive buffer and readying for receiving waypoints\n");
+ case MAVLINK_MSG_ID_MISSION_ITEM: {
+ mavlink_mission_item_t wp;
+ mavlink_msg_mission_item_decode(msg, &wp);
-#endif
- wpm->rcv_size = 0;
- //while(waypoints_receive_buffer->size() > 0)
-// {
-// delete waypoints_receive_buffer->back();
-// waypoints_receive_buffer->pop_back();
-// }
+ if (wp.target_system == mavlink_system.sysid && wp.target_component == mavlink_wpm_comp_id) {
- mavlink_wpm_send_waypoint_request(wpm->current_partner_sysid, wpm->current_partner_compid, wpm->current_wp_id);
+ wpm->timestamp_lastaction = now;
- } else if (wpc.count == 0) {
-#ifdef MAVLINK_WPM_NO_PRINTF
- mavlink_missionlib_send_gcs_string("COUNT 0");
-#else
-
- if (MAVLINK_WPM_VERBOSE) printf("got waypoint count of 0, clearing waypoint list and staying in state MAVLINK_WPM_STATE_IDLE\n");
-
-#endif
- wpm->rcv_size = 0;
- //while(waypoints_receive_buffer->size() > 0)
-// {
-// delete waypoints->back();
-// waypoints->pop_back();
-// }
- wpm->current_active_wp_id = -1;
- wpm->yaw_reached = false;
- wpm->pos_reached = false;
- break;
+ /*
+ * ensure that we are in the correct state and that the first waypoint has id 0
+ * and the following waypoints have the correct ids
+ */
- } else {
-#ifdef MAVLINK_WPM_NO_PRINTF
- mavlink_missionlib_send_gcs_string("IGN WP CMD");
-#else
+ if (wpm->current_state == MAVLINK_WPM_STATE_GETLIST) {
- if (MAVLINK_WPM_VERBOSE) printf("Ignoring MAVLINK_MSG_ID_MISSION_ITEM_COUNT from %u with count of %u\n", msg->sysid, wpc.count);
+ if (wp.seq != 0) {
+ mavlink_missionlib_send_gcs_string("Ignored MISSION_ITEM WP not 0");
+ warnx("Ignored MAVLINK_MSG_ID_MISSION_ITEM because the first waypoint ID (%u) was not 0.", wp.seq);
+ break;
+ }
+ } else if (wpm->current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS) {
-#endif
+ if (wp.seq >= wpm->current_count) {
+ mavlink_missionlib_send_gcs_string("Ignored MISSION_ITEM WP out of bounds");
+ warnx("Ignored MAVLINK_MSG_ID_MISSION_ITEM because the waypoint ID (%u) was out of bounds.", wp.seq);
+ break;
}
- } else {
- if (!(wpm->current_state == MAVLINK_WPM_STATE_IDLE || wpm->current_state == MAVLINK_WPM_STATE_GETLIST)) {
-#ifdef MAVLINK_WPM_NO_PRINTF
- mavlink_missionlib_send_gcs_string("REJ. WP CMD: Busy");
-#else
-
- if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_COUNT because i'm doing something else already (state=%i).\n", wpm->current_state);
-
-#endif
-
- } else if (wpm->current_state == MAVLINK_WPM_STATE_GETLIST && wpm->current_wp_id != 0) {
-#ifdef MAVLINK_WPM_NO_PRINTF
- mavlink_missionlib_send_gcs_string("REJ. WP CMD: Busy");
-#else
-
- if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_COUNT because i'm already receiving waypoint %u.\n", wpm->current_wp_id);
+ if (wp.seq != wpm->current_wp_id) {
+ warnx("Ignored MAVLINK_MSG_ID_MISSION_ITEM because the waypoint ID (%u) was not the expected %u.", wp.seq, wpm->current_wp_id);
+ mavlink_wpm_send_waypoint_request(wpm->current_partner_sysid, wpm->current_partner_compid, wpm->current_wp_id);
+ break;
+ }
+ }
-#endif
+ wpm->current_state = MAVLINK_WPM_STATE_GETLIST_GETWPS;
- } else {
-#ifdef MAVLINK_WPM_NO_PRINTF
- mavlink_missionlib_send_gcs_string("REJ. WP CMD: ?");
-#else
+ struct mission_item_s mission_item;
- if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_COUNT - FIXME: missed error description\n");
+ int ret = map_mavlink_mission_item_to_mission_item(&wp, &mission_item);
-#endif
- }
+ 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;
}
- } else {
-#ifdef MAVLINK_WPM_NO_PRINTF
- mavlink_missionlib_send_gcs_string("REJ. WP CMD: target id mismatch");
-#else
+ ssize_t len = sizeof(struct mission_item_s);
- if (MAVLINK_WPM_VERBOSE) printf("IGNORED WAYPOINT COMMAND BECAUSE TARGET SYSTEM AND COMPONENT OR COMM PARTNER ID MISMATCH\n");
+ dm_item_t dm_next;
-#endif
- }
+ if (wpm->current_dataman_id == 0) {
+ dm_next = DM_KEY_WAYPOINTS_OFFBOARD_1;
+ mission.dataman_id = 1;
+ } else {
+ dm_next = DM_KEY_WAYPOINTS_OFFBOARD_0;
+ mission.dataman_id = 0;
+ }
- }
- break;
+ if (dm_write(dm_next, wp.seq, DM_PERSIST_IN_FLIGHT_RESET, &mission_item, len) != len) {
+ mavlink_wpm_send_waypoint_ack(wpm->current_partner_sysid, wpm->current_partner_compid, MAV_MISSION_ERROR);
+ wpm->current_state = MAVLINK_WPM_STATE_IDLE;
+ break;
+ }
- case MAVLINK_MSG_ID_MISSION_ITEM: {
- mavlink_mission_item_t wp;
- mavlink_msg_mission_item_decode(msg, &wp);
+ if (wp.current) {
+ mission.current_index = wp.seq;
+ }
- 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);
+ wpm->current_wp_id = wp.seq + 1;
-// if((msg->sysid == wpm->current_partner_sysid && msg->compid == wpm->current_partner_compid) && (wp.target_system == mavlink_system.sysid /*&& wp.target_component == mavlink_wpm_comp_id*/))
- if (wp.target_system == mavlink_system.sysid && wp.target_component == mavlink_wpm_comp_id) {
+ if (wpm->current_wp_id == wpm->current_count && wpm->current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS) {
+
+ if (verbose) warnx("Got all %u waypoints, changing state to MAVLINK_WPM_STATE_IDLE", wpm->current_count);
- wpm->timestamp_lastaction = now;
+ mavlink_wpm_send_waypoint_ack(wpm->current_partner_sysid, wpm->current_partner_compid, MAV_MISSION_ACCEPTED);
-// printf("wpm->current_state=%u, wp.seq = %d, wpm->current_wp_id=%d\n", wpm->current_state, wp.seq, wpm->current_wp_id);
-
-// 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)) {
- //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);
-// if (verbose && wpm->current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS && wp.seq == wpm->current_wp_id) // printf("Got MAVLINK_MSG_ID_MISSION_ITEM %u from %u\n", wp.seq, msg->sysid);
-// 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);
- 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);
-// 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);
-
-// 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");
- // 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;
- }
-
- // switch the waypoints list
- // FIXME CHECK!!!
- uint32_t i;
-
- for (i = 0; i < wpm->current_count; ++i) {
- wpm->waypoints[i] = wpm->rcv_waypoints[i];
- }
-
- 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;
- }
+ mission.count = wpm->current_count;
+
+ publish_mission();
- wpm->current_state = MAVLINK_WPM_STATE_IDLE;
+ wpm->current_dataman_id = mission.dataman_id;
+ wpm->size = wpm->current_count;
- } else {
- mavlink_wpm_send_waypoint_request(wpm->current_partner_sysid, wpm->current_partner_compid, wpm->current_wp_id);
- }
+ wpm->current_state = MAVLINK_WPM_STATE_IDLE;
} 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_request(wpm->current_partner_sysid, wpm->current_partner_compid, wpm->current_wp_id);
}
+
} else {
- //we we're target but already communicating with someone else
- if ((wp.target_system == mavlink_system.sysid /*&& wp.target_component == mavlink_wpm_comp_id*/) && !(msg->sysid == wpm->current_partner_sysid && msg->compid == wpm->current_partner_compid) && wpm->current_state != MAVLINK_WPM_STATE_IDLE) {
- // if (verbose) // printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM %u from ID %u because i'm already talking to ID %u.\n", wp.seq, msg->sysid, wpm->current_partner_sysid);
- } else if (wp.target_system == mavlink_system.sysid /* && wp.target_component == mavlink_wpm_comp_id*/) {
- // if (verbose) // printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM %u from ID %u because i have no idea what to do with it\n", wp.seq, msg->sysid);
- }
+ mavlink_missionlib_send_gcs_string("REJ. WP CMD: target id mismatch");
+ if (verbose) warnx("IGNORED WAYPOINT COMMAND BECAUSE TARGET SYSTEM AND COMPONENT OR COMM PARTNER ID MISMATCH");
}
break;
}
- case MAVLINK_MSG_ID_MISSION_CLEAR_ALL: {
+ case MAVLINK_MSG_ID_MISSION_CLEAR_ALL: {
mavlink_mission_clear_all_t wpca;
mavlink_msg_mission_clear_all_decode(msg, &wpca);
- if (wpca.target_system == mavlink_system.sysid /*&& wpca.target_component == mavlink_wpm_comp_id */ && wpm->current_state == MAVLINK_WPM_STATE_IDLE) {
- wpm->timestamp_lastaction = now;
+ if (wpca.target_system == mavlink_system.sysid /*&& wpca.target_component == mavlink_wpm_comp_id */) {
+
+ if (wpm->current_state == MAVLINK_WPM_STATE_IDLE) {
+ wpm->timestamp_lastaction = now;
+
+ wpm->size = 0;
+
+ /* prepare mission topic */
+ mission.dataman_id = -1;
+ mission.count = 0;
+ mission.current_index = -1;
+ publish_mission();
+
+ if (dm_clear(DM_KEY_WAYPOINTS_OFFBOARD_0) == OK && dm_clear(DM_KEY_WAYPOINTS_OFFBOARD_1) == OK) {
+ mavlink_wpm_send_waypoint_ack(wpm->current_partner_sysid, wpm->current_partner_compid, MAV_MISSION_ACCEPTED);
+ } else {
+ mavlink_wpm_send_waypoint_ack(wpm->current_partner_sysid, wpm->current_partner_compid, MAV_MISSION_ERROR);
+ }
+
+
+ } else {
+ mavlink_missionlib_send_gcs_string("IGN WP CLEAR CMD: Busy");
+ if (verbose) warnx("IGN WP CLEAR CMD: Busy");
+ }
- // 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;
} 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);
+
+ mavlink_missionlib_send_gcs_string("REJ. WP CLERR CMD: target id mismatch");
+ if (verbose) warnx("IGNORED WAYPOINT CLEAR COMMAND BECAUSE TARGET SYSTEM AND COMPONENT OR COMM PARTNER ID MISMATCH");
}
break;
}
default: {
- // if (debug) // printf("Waypoint: received message of unknown type");
+ /* other messages might should get caught by mavlink and others */
break;
}
}
-
- // check_waypoints_reached(now, global_pos, local_pos);
}
diff --git a/src/modules/mavlink/waypoints.h b/src/modules/mavlink/waypoints.h
index d7d6b31dc..f8b58c7d9 100644
--- a/src/modules/mavlink/waypoints.h
+++ b/src/modules/mavlink/waypoints.h
@@ -46,18 +46,10 @@
or in the same folder as this source file */
#include <v1.0/mavlink_types.h>
-
-// #ifndef MAVLINK_SEND_UART_BYTES
-// #define MAVLINK_SEND_UART_BYTES(chan, buffer, len) mavlink_send_uart_bytes(chan, buffer, len)
-// #endif
-//extern mavlink_system_t mavlink_system;
#include "mavlink_bridge_header.h"
#include <stdbool.h>
-#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 {
MAVLINK_WPM_STATE_IDLE = 0,
MAVLINK_WPM_STATE_SENDLIST,
@@ -78,55 +70,43 @@ 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
-#ifndef MAVLINK_WPM_TEXT_FEEDBACK
-#define MAVLINK_WPM_TEXT_FEEDBACK 0 ///< Report back status information as text
-#endif
+#define MAVLINK_WPM_MAX_WP_COUNT 255
#define MAVLINK_WPM_PROTOCOL_TIMEOUT_DEFAULT 5000000 ///< Protocol communication timeout in useconds
#define MAVLINK_WPM_SETPOINT_DELAY_DEFAULT 1000000 ///< When to send a new setpoint
#define MAVLINK_WPM_PROTOCOL_DELAY_DEFAULT 40000
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
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
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;
uint32_t timeout;
- uint32_t delay_setpoint;
- float accept_range_yaw;
- float accept_range_distance;
- bool yaw_reached;
- bool pos_reached;
- bool idle;
+ int current_dataman_id;
};
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);
-void mavlink_wpm_message_handler(const mavlink_message_t *msg, const struct vehicle_global_position_s *global_pos ,
- struct vehicle_local_position_s *local_pos);
+void mavlink_waypoint_eventloop(uint64_t now);
+void mavlink_wpm_message_handler(const mavlink_message_t *msg);
extern void mavlink_missionlib_current_waypoint_changed(uint16_t index, float param1,
float param2, float param3, float param4, float param5_lat_x,
float param6_lon_y, float param7_alt_z, uint8_t frame, uint16_t command);
+static uint8_t missionlib_msg_buf[MAVLINK_MAX_PACKET_LEN];
+
+void mavlink_missionlib_send_message(mavlink_message_t *msg);
+int mavlink_missionlib_send_gcs_string(const char *string);
+
#endif /* WAYPOINTS_H_ */
diff --git a/src/modules/mavlink_onboard/mavlink.c b/src/modules/mavlink_onboard/mavlink.c
index 0edb53a3e..ab9ce45f3 100644
--- a/src/modules/mavlink_onboard/mavlink.c
+++ b/src/modules/mavlink_onboard/mavlink.c
@@ -441,7 +441,8 @@ int mavlink_thread_main(int argc, char *argv[])
get_mavlink_mode_and_state(&control_mode, &armed, &mavlink_state, &mavlink_mode);
/* send heartbeat */
- mavlink_msg_heartbeat_send(chan, mavlink_system.type, MAV_AUTOPILOT_PX4, mavlink_mode, v_status.navigation_state, mavlink_state);
+ // TODO fix navigation state, use control_mode topic
+ mavlink_msg_heartbeat_send(chan, mavlink_system.type, MAV_AUTOPILOT_PX4, mavlink_mode, 0, mavlink_state);
/* send status (values already copied in the section above) */
mavlink_msg_sys_status_send(chan,
diff --git a/src/modules/mavlink_onboard/orb_topics.h b/src/modules/mavlink_onboard/orb_topics.h
index 1b49c9ce4..86bfa26f2 100644
--- a/src/modules/mavlink_onboard/orb_topics.h
+++ b/src/modules/mavlink_onboard/orb_topics.h
@@ -50,7 +50,7 @@
#include <uORB/topics/vehicle_command.h>
#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/mission_item_triplet.h>
#include <uORB/topics/vehicle_attitude_setpoint.h>
#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/optical_flow.h>
diff --git a/src/modules/multirotor_att_control/multirotor_att_control_main.c b/src/modules/multirotor_att_control/multirotor_att_control_main.c
index 60a211817..111e9197f 100644
--- a/src/modules/multirotor_att_control/multirotor_att_control_main.c
+++ b/src/modules/multirotor_att_control/multirotor_att_control_main.c
@@ -316,7 +316,7 @@ mc_thread_main(int argc, char *argv[])
}
} else {
- if (!control_mode.flag_control_auto_enabled) {
+ if (!control_mode.flag_control_attitude_enabled) {
/* no control, try to stay on place */
if (!control_mode.flag_control_velocity_enabled) {
/* no velocity control, reset attitude setpoint */
diff --git a/src/modules/multirotor_pos_control/multirotor_pos_control.c b/src/modules/multirotor_pos_control/multirotor_pos_control.c
index 3d23d0c09..2ca650420 100644
--- a/src/modules/multirotor_pos_control/multirotor_pos_control.c
+++ b/src/modules/multirotor_pos_control/multirotor_pos_control.c
@@ -61,8 +61,8 @@
#include <uORB/topics/vehicle_attitude_setpoint.h>
#include <uORB/topics/vehicle_local_position.h>
#include <uORB/topics/vehicle_local_position_setpoint.h>
-#include <uORB/topics/vehicle_global_position_setpoint.h>
#include <uORB/topics/vehicle_global_velocity_setpoint.h>
+#include <uORB/topics/mission_item_triplet.h>
#include <systemlib/systemlib.h>
#include <systemlib/pid/pid.h>
#include <mavlink/mavlink_log.h>
@@ -190,12 +190,12 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[])
memset(&manual, 0, sizeof(manual));
struct vehicle_local_position_s local_pos;
memset(&local_pos, 0, sizeof(local_pos));
- struct vehicle_local_position_setpoint_s local_pos_sp;
- memset(&local_pos_sp, 0, sizeof(local_pos_sp));
- struct vehicle_global_position_setpoint_s global_pos_sp;
- memset(&global_pos_sp, 0, sizeof(global_pos_sp));
+ struct mission_item_triplet_s triplet;
+ memset(&triplet, 0, sizeof(triplet));
struct vehicle_global_velocity_setpoint_s global_vel_sp;
memset(&global_vel_sp, 0, sizeof(global_vel_sp));
+ struct vehicle_local_position_setpoint_s local_pos_sp;
+ memset(&local_pos_sp, 0, sizeof(local_pos_sp));
/* subscribe to attitude, motor setpoints and system state */
int param_sub = orb_subscribe(ORB_ID(parameter_update));
@@ -203,9 +203,7 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[])
int att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
int att_sp_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint));
int manual_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
- int local_pos_sp_sub = orb_subscribe(ORB_ID(vehicle_local_position_setpoint));
- int local_pos_sub = orb_subscribe(ORB_ID(vehicle_local_position));
- int global_pos_sp_sub = orb_subscribe(ORB_ID(vehicle_global_position_setpoint));
+ int mission_triplet_sub = orb_subscribe(ORB_ID(mission_item_triplet));
/* publish setpoint */
orb_advert_t local_pos_sp_pub = orb_advertise(ORB_ID(vehicle_local_position_setpoint), &local_pos_sp);
@@ -292,11 +290,11 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[])
orb_copy(ORB_ID(vehicle_control_mode), control_mode_sub, &control_mode);
}
- orb_check(global_pos_sp_sub, &updated);
+ orb_check(mission_triplet_sub, &updated);
if (updated) {
- orb_copy(ORB_ID(vehicle_global_position_setpoint), global_pos_sp_sub, &global_pos_sp);
- global_pos_sp_valid = true;
+ orb_copy(ORB_ID(mission_item_triplet), mission_triplet_sub, &triplet);
+ global_pos_sp_valid = triplet.current_valid;
reset_mission_sp = true;
}
@@ -329,7 +327,6 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[])
orb_copy(ORB_ID(manual_control_setpoint), manual_sub, &manual);
orb_copy(ORB_ID(vehicle_attitude), att_sub, &att);
orb_copy(ORB_ID(vehicle_attitude_setpoint), att_sp_sub, &att_sp);
- orb_copy(ORB_ID(vehicle_local_position), local_pos_sub, &local_pos);
float z_sp_offs_max = params.z_vel_max / params.z_p * 2.0f;
float xy_sp_offs_max = params.xy_vel_max / params.xy_p * 2.0f;
@@ -418,142 +415,8 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[])
/* force reprojection of global setpoint after manual mode */
reset_mission_sp = true;
-
- } else if (control_mode.flag_control_auto_enabled) {
- /* AUTO mode, use global setpoint */
- if (control_mode.auto_state == NAVIGATION_STATE_AUTO_READY) {
- reset_auto_sp_xy = true;
- reset_auto_sp_z = true;
-
- } else if (control_mode.auto_state == NAVIGATION_STATE_AUTO_TAKEOFF) {
- if (reset_takeoff_sp) {
- reset_takeoff_sp = false;
- local_pos_sp.x = local_pos.x;
- local_pos_sp.y = local_pos.y;
- local_pos_sp.z = - params.takeoff_alt - params.takeoff_gap;
- att_sp.yaw_body = att.yaw;
- mavlink_log_info(mavlink_fd, "[mpc] takeoff sp: %.2f %.2f %.2f", (double)local_pos_sp.x, (double)local_pos_sp.y, (double) - local_pos_sp.z);
- }
-
- reset_auto_sp_xy = false;
- reset_auto_sp_z = true;
-
- } else if (control_mode.auto_state == NAVIGATION_STATE_AUTO_RTL) {
- // TODO
- reset_auto_sp_xy = true;
- reset_auto_sp_z = true;
-
- } else if (control_mode.auto_state == NAVIGATION_STATE_AUTO_MISSION) {
- /* init local projection using local position ref */
- if (local_pos.ref_timestamp != local_ref_timestamp) {
- reset_mission_sp = true;
- local_ref_timestamp = local_pos.ref_timestamp;
- double lat_home = local_pos.ref_lat * 1e-7;
- double lon_home = local_pos.ref_lon * 1e-7;
- map_projection_init(lat_home, lon_home);
- mavlink_log_info(mavlink_fd, "[mpc] local pos ref: %.7f, %.7f", (double)lat_home, (double)lon_home);
- }
-
- if (reset_mission_sp) {
- reset_mission_sp = false;
- /* update global setpoint projection */
-
- if (global_pos_sp_valid) {
- /* global position setpoint valid, use it */
- double sp_lat = global_pos_sp.lat * 1e-7;
- double sp_lon = global_pos_sp.lon * 1e-7;
- /* project global setpoint to local setpoint */
- map_projection_project(sp_lat, sp_lon, &(local_pos_sp.x), &(local_pos_sp.y));
-
- if (global_pos_sp.altitude_is_relative) {
- local_pos_sp.z = -global_pos_sp.altitude;
-
- } else {
- local_pos_sp.z = local_pos.ref_alt - global_pos_sp.altitude;
- }
- /* update yaw setpoint only if value is valid */
- if (isfinite(global_pos_sp.yaw) && fabsf(global_pos_sp.yaw) < M_TWOPI) {
- att_sp.yaw_body = global_pos_sp.yaw;
- }
-
- mavlink_log_info(mavlink_fd, "[mpc] new sp: %.7f, %.7f (%.2f, %.2f)", (double)sp_lat, sp_lon, (double)local_pos_sp.x, (double)local_pos_sp.y);
-
- } else {
- if (reset_auto_sp_xy) {
- reset_auto_sp_xy = false;
- /* local position setpoint is invalid,
- * use current position as setpoint for loiter */
- local_pos_sp.x = local_pos.x;
- local_pos_sp.y = local_pos.y;
- local_pos_sp.yaw = att.yaw;
- }
-
- if (reset_auto_sp_z) {
- reset_auto_sp_z = false;
- local_pos_sp.z = local_pos.z;
- }
-
- mavlink_log_info(mavlink_fd, "[mpc] no global pos sp, loiter: %.2f, %.2f", (double)local_pos_sp.x, (double)local_pos_sp.y);
- }
- }
-
- reset_auto_sp_xy = true;
- reset_auto_sp_z = true;
- }
-
- if (control_mode.auto_state != NAVIGATION_STATE_AUTO_TAKEOFF) {
- reset_takeoff_sp = true;
- }
-
- if (control_mode.auto_state != NAVIGATION_STATE_AUTO_MISSION) {
- reset_mission_sp = true;
- }
-
- /* copy yaw setpoint to vehicle_local_position_setpoint topic */
- local_pos_sp.yaw = att_sp.yaw_body;
-
- /* reset setpoints after AUTO mode */
- reset_man_sp_xy = true;
- reset_man_sp_z = true;
-
- } else {
- /* no control (failsafe), loiter or stay on ground */
- if (local_pos.landed) {
- /* landed: move setpoint down */
- /* in air: hold altitude */
- if (local_pos_sp.z < 5.0f) {
- /* set altitude setpoint to 5m under ground,
- * don't set it too deep to avoid unexpected landing in case of false "landed" signal */
- local_pos_sp.z = 5.0f;
- mavlink_log_info(mavlink_fd, "[mpc] landed, set alt: %.2f", (double) - local_pos_sp.z);
- }
-
- reset_man_sp_z = true;
-
- } else {
- /* in air: hold altitude */
- if (reset_man_sp_z) {
- reset_man_sp_z = false;
- local_pos_sp.z = local_pos.z;
- mavlink_log_info(mavlink_fd, "[mpc] set loiter alt: %.2f", (double) - local_pos_sp.z);
- }
-
- reset_auto_sp_z = false;
- }
-
- if (control_mode.flag_control_position_enabled) {
- if (reset_man_sp_xy) {
- reset_man_sp_xy = false;
- local_pos_sp.x = local_pos.x;
- local_pos_sp.y = local_pos.y;
- local_pos_sp.yaw = att.yaw;
- att_sp.yaw_body = att.yaw;
- mavlink_log_info(mavlink_fd, "[mpc] set loiter pos: %.2f %.2f", (double)local_pos_sp.x, (double)local_pos_sp.y);
- }
-
- reset_auto_sp_xy = false;
- }
}
+ /* AUTO not implemented */
/* publish local position setpoint */
orb_publish(ORB_ID(vehicle_local_position_setpoint), local_pos_sp_pub, &local_pos_sp);
diff --git a/src/modules/navigator/geofence.cpp b/src/modules/navigator/geofence.cpp
new file mode 100644
index 000000000..9bbaf167a
--- /dev/null
+++ b/src/modules/navigator/geofence.cpp
@@ -0,0 +1,299 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ * Author: @author Jean Cyr <jean.m.cyr@gmail.com>
+ * @author Thomas Gubler <thomasgubler@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 geofence.cpp
+ * Provides functions for handling the geofence
+ */
+#include "geofence.h"
+
+#include <uORB/topics/vehicle_global_position.h>
+#include <string.h>
+#include <dataman/dataman.h>
+#include <systemlib/err.h>
+#include <stdlib.h>
+#include <stdio.h>
+#include <ctype.h>
+#include <nuttx/config.h>
+#include <unistd.h>
+
+
+/* Oddly, ERROR is not defined for C++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
+
+Geofence::Geofence() : _fence_pub(-1),
+ _altitude_min(0),
+ _altitude_max(0),
+ _verticesCount(0),
+ param_geofence_on(NULL, "GF_ON", false)
+{
+ /* Load initial params */
+ updateParams();
+}
+
+Geofence::~Geofence()
+{
+
+}
+
+
+bool Geofence::inside(const struct vehicle_global_position_s *vehicle)
+{
+ double lat = vehicle->lat / 1e7d;
+ double lon = vehicle->lon / 1e7d;
+ float alt = vehicle->alt;
+
+ return inside(lat, lon, vehicle->alt);
+}
+
+bool Geofence::inside(double lat, double lon, float altitude)
+{
+ /* Return true if geofence is disabled */
+ if (param_geofence_on.get() != 1)
+ return true;
+
+ if (valid()) {
+
+ if (!isEmpty()) {
+ /* Vertical check */
+ if (altitude > _altitude_max || altitude < _altitude_min)
+ return false;
+
+ /*Horizontal check */
+ /* Adaptation of algorithm originally presented as
+ * PNPOLY - Point Inclusion in Polygon Test
+ * W. Randolph Franklin (WRF) */
+
+ bool c = false;
+
+ struct fence_vertex_s temp_vertex_i;
+ struct fence_vertex_s temp_vertex_j;
+
+ /* Red until fence is finished */
+ for (unsigned i = 0, j = _verticesCount - 1; i < _verticesCount; j = i++) {
+ if (dm_read(DM_KEY_FENCE_POINTS, i, &temp_vertex_i, sizeof(struct fence_vertex_s)) != sizeof(struct fence_vertex_s)) {
+ break;
+ }
+ if (dm_read(DM_KEY_FENCE_POINTS, j, &temp_vertex_j, sizeof(struct fence_vertex_s)) != sizeof(struct fence_vertex_s)) {
+ break;
+ }
+
+ // skip vertex 0 (return point)
+ if (((temp_vertex_i.lon) >= lon != (temp_vertex_j.lon >= lon)) &&
+ (lat <= (temp_vertex_j.lat - temp_vertex_i.lat) * (lon - temp_vertex_i.lon) /
+ (temp_vertex_j.lon - temp_vertex_i.lon) + temp_vertex_i.lat)) {
+ c = !c;
+ }
+
+ }
+
+ return c;
+ } else {
+ /* Empty fence --> accept all points */
+ return true;
+ }
+
+ } else {
+ /* Invalid fence --> accept all points */
+ return true;
+ }
+}
+
+bool
+Geofence::valid()
+{
+ // NULL fence is valid
+ if (isEmpty())
+ return true;
+
+ // Otherwise
+ if ((_verticesCount < 4) || (_verticesCount > GEOFENCE_MAX_VERTICES)) {
+ warnx("Fence must have at least 3 sides and not more than %d", GEOFENCE_MAX_VERTICES - 1);
+ return false;
+ }
+
+ return true;
+}
+
+void
+Geofence::addPoint(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);
+ publishFence(0);
+ return;
+ }
+
+ 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)
+ publishFence((unsigned)ix + 1);
+ return;
+ }
+
+ errx(1, "can't store fence point");
+}
+
+void
+Geofence::publishFence(unsigned vertices)
+{
+ if (_fence_pub == -1)
+ _fence_pub = orb_advertise(ORB_ID(fence), &vertices);
+ else
+ orb_publish(ORB_ID(fence), _fence_pub, &vertices);
+}
+
+int
+Geofence::loadFromFile(const char *filename)
+{
+ FILE *fp;
+ char line[120];
+ int pointCounter = 0;
+ bool gotVertical = false;
+ const char commentChar = '#';
+
+ /* Make sure no data is left in the datamanager */
+ clearDm();
+
+ /* open the mixer definition file */
+ fp = fopen(GEOFENCE_FILENAME, "r");
+ if (fp == NULL) {
+ return ERROR;
+ }
+
+ /* create geofence points from valid lines and store in DM */
+ for (;;) {
+
+ /* get a line, bail on error/EOF */
+ if (fgets(line, sizeof(line), fp) == NULL)
+ break;
+
+ /* Trim leading whitespace */
+ size_t textStart = 0;
+ while((textStart < sizeof(line)/sizeof(char)) && isspace(line[textStart])) textStart++;
+
+ /* if the line starts with #, skip */
+ if (line[textStart] == commentChar)
+ continue;
+
+ if (gotVertical) {
+ /* Parse the line as a geofence point */
+ struct fence_vertex_s vertex;
+
+ /* if the line starts with DMS, this means that the coordinate is given as degree minute second instead of decimal degrees */
+ if (line[textStart] == 'D' && line[textStart + 1] == 'M' && line[textStart + 2] == 'S') {
+ /* Handle degree minute second format */
+ float lat_d, lat_m, lat_s, lon_d, lon_m, lon_s;
+
+ if (sscanf(line, "DMS %f %f %f %f %f %f", &lat_d, &lat_m, &lat_s, &lon_d, &lon_m, &lon_s) != 6)
+ return ERROR;
+
+// warnx("Geofence DMS: %.5f %.5f %.5f ; %.5f %.5f %.5f", (double)lat_d, (double)lat_m, (double)lat_s, (double)lon_d, (double)lon_m, (double)lon_s);
+
+ vertex.lat = lat_d + lat_m/60.0f + lat_s/3600.0f;
+ vertex.lon = lon_d + lon_m/60.0f + lon_s/3600.0f;
+
+ } else {
+ /* Handle decimal degree format */
+
+ if (sscanf(line, "%f %f", &(vertex.lat), &(vertex.lon)) != 2)
+ return ERROR;
+ }
+
+ if (dm_write(DM_KEY_FENCE_POINTS, pointCounter, DM_PERSIST_POWER_ON_RESET, &vertex, sizeof(vertex)) != sizeof(vertex))
+ return ERROR;
+
+ warnx("Geofence: point: %d, lat %.5f: lon: %.5f", pointCounter, (double)vertex.lat, (double)vertex.lon);
+
+ pointCounter++;
+ } else {
+ /* Parse the line as the vertical limits */
+ if (sscanf(line, "%f %f", &_altitude_min, &_altitude_max) != 2)
+ return ERROR;
+
+
+ warnx("Geofence: alt min: %.4f, alt_max: %.4f", (double)_altitude_min, (double)_altitude_max);
+ gotVertical = true;
+ }
+
+
+ }
+
+ fclose(fp);
+
+ /* Check if import was successful */
+ if(gotVertical && pointCounter > 0)
+ {
+ _verticesCount = pointCounter;
+ warnx("Geofence: imported successfully");
+ } else {
+ warnx("Geofence: import error");
+ }
+
+ return ERROR;
+}
+
+int Geofence::clearDm()
+{
+ dm_clear(DM_KEY_FENCE_POINTS);
+}
+
+void Geofence::updateParams()
+{
+ param_geofence_on.update();
+}
diff --git a/src/modules/navigator/geofence.h b/src/modules/navigator/geofence.h
new file mode 100644
index 000000000..5b56ebc7a
--- /dev/null
+++ b/src/modules/navigator/geofence.h
@@ -0,0 +1,93 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ * Author: @author Jean Cyr <jean.m.cyr@gmail.com>
+ * @author Thomas Gubler <thomasgubler@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 geofence.h
+ * Provides functions for handling the geofence
+ */
+
+#ifndef GEOFENCE_H_
+#define GEOFENCE_H_
+
+#include <uORB/topics/fence.h>
+#include <controllib/block/BlockParam.hpp>
+
+#define GEOFENCE_FILENAME "/fs/microsd/etc/geofence.txt"
+
+class Geofence {
+private:
+ orb_advert_t _fence_pub; /**< publish fence topic */
+
+ float _altitude_min;
+ float _altitude_max;
+
+ unsigned _verticesCount;
+
+ /* Params */
+ control::BlockParamInt param_geofence_on;
+public:
+ Geofence();
+ ~Geofence();
+
+ /**
+ * 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
+ */
+ bool inside(const struct vehicle_global_position_s *craft);
+ bool inside(double lat, double lon, float altitude);
+
+ int clearDm();
+
+ bool valid();
+
+ /**
+ * Specify fence vertex position.
+ */
+ void addPoint(int argc, char *argv[]);
+
+ void publishFence(unsigned vertices);
+
+ int loadFromFile(const char *filename);
+
+ bool isEmpty() {return _verticesCount == 0;}
+
+ void updateParams();
+};
+
+
+#endif /* GEOFENCE_H_ */
diff --git a/src/modules/navigator/geofence_params.c b/src/modules/navigator/geofence_params.c
new file mode 100644
index 000000000..20dd1fe2f
--- /dev/null
+++ b/src/modules/navigator/geofence_params.c
@@ -0,0 +1,55 @@
+/****************************************************************************
+ *
+ * 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
+ * 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 geofence_params.c
+ *
+ * Parameters for geofence
+ *
+ * @author Thomas Gubler <thomasgubler@gmail.com>
+ */
+
+#include <nuttx/config.h>
+
+#include <systemlib/param/param.h>
+
+/*
+ * geofence parameters, accessible via MAVLink
+ *
+ */
+
+// @DisplayName Switch to enable geofence
+// @Description if set to 1 geofence is enabled, defaults to 1 because geofence is only enabled when the geofence.txt file is present
+// @Range 0 or 1
+PARAM_DEFINE_INT32(GF_ON, 1);
diff --git a/src/modules/navigator/mission_feasibility_checker.cpp b/src/modules/navigator/mission_feasibility_checker.cpp
new file mode 100644
index 000000000..eaafa217d
--- /dev/null
+++ b/src/modules/navigator/mission_feasibility_checker.cpp
@@ -0,0 +1,202 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ * Author: @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+/**
+ * @file mission_feasibility_checker.cpp
+ * Provides checks if mission is feasible given the navigation capabilities
+ */
+
+#include "mission_feasibility_checker.h"
+
+#include <geo/geo.h>
+#include <math.h>
+#include <mathlib/mathlib.h>
+#include <mavlink/mavlink_log.h>
+#include <fw_pos_control_l1/landingslope.h>
+#include <systemlib/err.h>
+#include <stdio.h>
+#include <fcntl.h>
+#include <errno.h>
+#include <uORB/topics/fence.h>
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
+
+MissionFeasibilityChecker::MissionFeasibilityChecker() : _mavlink_fd(-1), _capabilities_sub(-1), _initDone(false)
+{
+ _nav_caps = {0};
+}
+
+
+bool MissionFeasibilityChecker::checkMissionFeasible(bool isRotarywing, dm_item_t dm_current, size_t nMissionItems, Geofence &geofence)
+{
+ /* Init if not done yet */
+ init();
+
+ /* Open mavlink fd */
+ if (_mavlink_fd < 0) {
+ /* try to open the mavlink log device every once in a while */
+ _mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
+ }
+
+
+ if (isRotarywing)
+ return checkMissionFeasibleRotarywing(dm_current, nMissionItems, geofence);
+ else
+ return checkMissionFeasibleFixedwing(dm_current, nMissionItems, geofence);
+}
+
+bool MissionFeasibilityChecker::checkMissionFeasibleRotarywing(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence)
+{
+
+ return checkGeofence(dm_current, nMissionItems, geofence);
+}
+
+bool MissionFeasibilityChecker::checkMissionFeasibleFixedwing(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence)
+{
+ /* Update fixed wing navigation capabilites */
+ updateNavigationCapabilities();
+// warnx("_nav_caps.landing_slope_angle_rad %.4f, _nav_caps.landing_horizontal_slope_displacement %.4f", _nav_caps.landing_slope_angle_rad, _nav_caps.landing_horizontal_slope_displacement);
+
+ return (checkFixedWingLanding(dm_current, nMissionItems) && checkGeofence(dm_current, nMissionItems, geofence));
+}
+
+bool MissionFeasibilityChecker::checkGeofence(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence)
+{
+ /* Check if all mission items are inside the geofence (if we have a valid geofence) */
+ if (geofence.valid()) {
+ for (size_t i = 0; i < nMissionItems; i++) {
+ static struct mission_item_s missionitem;
+ const ssize_t len = sizeof(struct mission_item_s);
+
+ if (dm_read(dm_current, i, &missionitem, len) != len) {
+ /* not supposed to happen unless the datamanager can't access the SD card, etc. */
+ return false;
+ }
+
+ if (!geofence.inside(missionitem.lat, missionitem.lon, missionitem.altitude)) { //xxx: handle relative altitude
+ mavlink_log_info(_mavlink_fd, "#audio: Geofence violation waypoint %d", i);
+ return false;
+ }
+ }
+ }
+
+ return true;
+}
+
+bool MissionFeasibilityChecker::checkFixedWingLanding(dm_item_t dm_current, size_t nMissionItems)
+{
+ /* Go through all mission items and search for a landing waypoint
+ * if landing waypoint is found: the previous waypoint is checked to be at a feasible distance and altitude given the landing slope */
+
+
+ for (size_t i = 0; i < nMissionItems; i++) {
+ static struct mission_item_s missionitem;
+ const ssize_t len = sizeof(struct mission_item_s);
+ if (dm_read(dm_current, i, &missionitem, len) != len) {
+ /* not supposed to happen unless the datamanager can't access the SD card, etc. */
+ return false;
+ }
+
+ if (missionitem.nav_cmd == NAV_CMD_LAND) {
+ struct mission_item_s missionitem_previous;
+ if (i != 0) {
+ if (dm_read(dm_current, i-1, &missionitem_previous, len) != len) {
+ /* not supposed to happen unless the datamanager can't access the SD card, etc. */
+ return false;
+ }
+
+ float wp_distance = get_distance_to_next_waypoint(missionitem_previous.lat , missionitem_previous.lon, missionitem.lat, missionitem.lon);
+ float slope_alt_req = Landingslope::getLandingSlopeAbsoluteAltitude(wp_distance, missionitem.altitude, _nav_caps.landing_horizontal_slope_displacement, _nav_caps.landing_slope_angle_rad);
+ float wp_distance_req = Landingslope::getLandingSlopeWPDistance(missionitem_previous.altitude, missionitem.altitude, _nav_caps.landing_horizontal_slope_displacement, _nav_caps.landing_slope_angle_rad);
+ float delta_altitude = missionitem.altitude - missionitem_previous.altitude;
+// warnx("wp_distance %.2f, delta_altitude %.2f, missionitem_previous.altitude %.2f, missionitem.altitude %.2f, slope_alt_req %.2f, wp_distance_req %.2f",
+// wp_distance, delta_altitude, missionitem_previous.altitude, missionitem.altitude, slope_alt_req, wp_distance_req);
+// warnx("_nav_caps.landing_horizontal_slope_displacement %.4f, _nav_caps.landing_slope_angle_rad %.4f, _nav_caps.landing_flare_length %.4f",
+// _nav_caps.landing_horizontal_slope_displacement, _nav_caps.landing_slope_angle_rad, _nav_caps.landing_flare_length);
+
+ if (wp_distance > _nav_caps.landing_flare_length) {
+ /* Last wp is before flare region */
+
+ if (delta_altitude < 0) {
+ if (missionitem_previous.altitude <= slope_alt_req) {
+ /* Landing waypoint is at or below altitude of slope at the given waypoint distance: this is ok, aircraft will intersect the slope */
+ return true;
+ } else {
+ /* Landing waypoint is above altitude of slope at the given waypoint distance */
+ mavlink_log_info(_mavlink_fd, "#audio: Landing: last waypoint too high/too close");
+ mavlink_log_info(_mavlink_fd, "Move down to %.1fm or move further away by %.1fm",
+ (double)(slope_alt_req),
+ (double)(wp_distance_req - wp_distance));
+ return false;
+ }
+ } else {
+ /* Landing waypoint is above last waypoint */
+ mavlink_log_info(_mavlink_fd, "#audio: Landing waypoint above last nav waypoint");
+ return false;
+ }
+ } else {
+ /* Last wp is in flare region */
+ //xxx give recommendations
+ mavlink_log_info(_mavlink_fd, "#audio: Warning: Landing: last waypoint in flare region");
+ return false;
+ }
+ } else {
+ mavlink_log_info(_mavlink_fd, "#audio: Warning: starting with land waypoint");
+ return false;
+ }
+ }
+ }
+
+
+// float slope_alt = wp_altitude + _H0 * expf(-math::max(0.0f, _flare_length - wp_distance)/_flare_constant) - _H1_virt;
+}
+
+void MissionFeasibilityChecker::updateNavigationCapabilities()
+{
+ int res = orb_copy(ORB_ID(navigation_capabilities), _capabilities_sub, &_nav_caps);
+}
+
+void MissionFeasibilityChecker::init()
+{
+ if (!_initDone) {
+
+ _capabilities_sub = orb_subscribe(ORB_ID(navigation_capabilities));
+
+ _initDone = true;
+ }
+}
diff --git a/src/modules/navigator/mission_feasibility_checker.h b/src/modules/navigator/mission_feasibility_checker.h
new file mode 100644
index 000000000..7a0b2a296
--- /dev/null
+++ b/src/modules/navigator/mission_feasibility_checker.h
@@ -0,0 +1,83 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ * Author: @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+/**
+ * @file mission_feasibility_checker.h
+ * Provides checks if mission is feasible given the navigation capabilities
+ */
+#ifndef MISSION_FEASIBILITY_CHECKER_H_
+#define MISSION_FEASIBILITY_CHECKER_H_
+
+#include <unistd.h>
+#include <uORB/topics/mission.h>
+#include <uORB/topics/navigation_capabilities.h>
+#include <dataman/dataman.h>
+#include "geofence.h"
+
+
+class MissionFeasibilityChecker
+{
+private:
+ int _mavlink_fd;
+
+ int _capabilities_sub;
+ struct navigation_capabilities_s _nav_caps;
+
+ bool _initDone;
+ void init();
+
+ /* Checks for all airframes */
+ bool checkGeofence(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence);
+
+ /* Checks specific to fixedwing airframes */
+ bool checkMissionFeasibleFixedwing(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence);
+ bool checkFixedWingLanding(dm_item_t dm_current, size_t nMissionItems);
+ void updateNavigationCapabilities();
+
+ /* Checks specific to rotarywing airframes */
+ bool checkMissionFeasibleRotarywing(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence);
+public:
+
+ MissionFeasibilityChecker();
+ ~MissionFeasibilityChecker() {}
+
+ /*
+ * Returns true if mission is feasible and false otherwise
+ */
+ bool checkMissionFeasible(bool isRotarywing, dm_item_t dm_current, size_t nMissionItems, Geofence &geofence);
+
+};
+
+
+#endif /* MISSION_FEASIBILITY_CHECKER_H_ */
diff --git a/src/modules/navigator/module.mk b/src/modules/navigator/module.mk
index 0404b06c7..55f8a4caa 100644
--- a/src/modules/navigator/module.mk
+++ b/src/modules/navigator/module.mk
@@ -38,4 +38,10 @@
MODULE_COMMAND = navigator
SRCS = navigator_main.cpp \
- navigator_params.c
+ navigator_params.c \
+ navigator_mission.cpp \
+ mission_feasibility_checker.cpp \
+ geofence.cpp \
+ geofence_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..bb7520a03 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
@@ -36,6 +38,7 @@
* Implementation of the main navigation state machine.
*
* Handles missions, geo fencing and failsafe navigation behavior.
+ * Published the mission item triplet for the position controller.
*/
#include <nuttx/config.h>
@@ -48,26 +51,43 @@
#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/vehicle_control_mode.h>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/mission.h>
+#include <uORB/topics/fence.h>
+#include <uORB/topics/navigation_capabilities.h>
#include <systemlib/param/param.h>
#include <systemlib/err.h>
-#include <geo/geo.h>
+#include <systemlib/state_table.h>
#include <systemlib/perf_counter.h>
#include <systemlib/systemlib.h>
+#include <geo/geo.h>
#include <mathlib/mathlib.h>
+#include <dataman/dataman.h>
+#include <mavlink/mavlink_log.h>
+#include <sys/types.h>
+#include <sys/stat.h>
+
+#include "navigator_mission.h"
+#include "mission_feasibility_checker.h"
+#include "geofence.h"
+
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
/**
* navigator app start / stop handling function
@@ -76,7 +96,7 @@
*/
extern "C" __EXPORT int navigator_main(int argc, char *argv[]);
-class Navigator
+class Navigator : public StateTable
{
public:
/**
@@ -85,103 +105,162 @@ public:
Navigator();
/**
- * Destructor, also kills the sensors task.
+ * Destructor, also kills the navigators task.
*/
~Navigator();
/**
- * Start the sensors task.
+ * Start the navigator task.
*
* @return OK on success.
*/
int start();
+ /**
+ * Display the navigator status.
+ */
+ void status();
+
+ /**
+ * Add point to geofence
+ */
+ void add_fence_point(int argc, char *argv[]);
+
+ /**
+ * Load fence from file
+ */
+ void load_fence_from_file(const char *filename);
+
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 _offboard_mission_sub; /**< notification of offboard 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 _mission_result_pub; /**< publish mission result topic */
+ orb_advert_t _control_mode_pub; /**< publish vehicle control mode 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_control_mode_s _control_mode; /**< vehicle control mode */
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 */
+
+ Geofence _geofence;
+ bool _geofence_violation_warning_sent;
+
+ bool _fence_valid; /**< flag if fence is valid */
+ bool _inside_fence; /**< vehicle is inside fence */
- 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 */
+ 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;
+ class Mission _mission;
+
+ bool _reset_loiter_pos; /**< if true then loiter position should be set to current position */
+ bool _waypoint_position_reached;
+ bool _waypoint_yaw_reached;
+ uint64_t _time_first_inside_orbit;
+ bool _need_takeoff; /**< if need to perform vertical takeoff before going to waypoint (only for MISSION mode and VTOL vehicles) */
+ bool _do_takeoff; /**< vertical takeoff state, current mission item is generated by navigator (only for MISSION mode and VTOL vehicles) */
+
+ MissionFeasibilityChecker missionFeasiblityChecker;
+
+ uint64_t _set_nav_state_timestamp; /**< timestamp of last handled navigation state request */
struct {
- float throttle_cruise;
- } _parameters; /**< local copies of interesting parameters */
+ float min_altitude;
+ float acceptance_radius;
+ float loiter_radius;
+ int onboard_mission_enabled;
+ float takeoff_alt;
+ float land_alt;
+ float rtl_alt;
+ } _parameters; /**< local copies of parameters */
struct {
- param_t throttle_cruise;
+ param_t min_altitude;
+ param_t acceptance_radius;
+ param_t loiter_radius;
+ param_t onboard_mission_enabled;
+ param_t takeoff_alt;
+ param_t land_alt;
+ param_t rtl_alt;
+ } _parameter_handles; /**< handles for parameters */
+
+ enum Event {
+ EVENT_NONE_REQUESTED,
+ EVENT_READY_REQUESTED,
+ EVENT_LOITER_REQUESTED,
+ EVENT_MISSION_REQUESTED,
+ EVENT_RTL_REQUESTED,
+ EVENT_MISSION_CHANGED,
+ EVENT_HOME_POSITION_CHANGED,
+ MAX_EVENT
+ };
+
+ /**
+ * State machine transition table
+ */
+ static StateTable::Tran const myTable[NAV_STATE_MAX][MAX_EVENT];
- } _parameter_handles; /**< handles for interesting parameters */
+ enum RTLState {
+ RTL_STATE_NONE = 0,
+ RTL_STATE_CLIMB,
+ RTL_STATE_RETURN,
+ RTL_STATE_DESCEND,
+ RTL_STATE_LAND
+ };
+ enum RTLState _rtl_state;
/**
* Update our local parameter cache.
*/
- int parameters_update();
+ void parameters_update();
/**
- * Update control outputs
- *
+ * Retrieve global position
*/
- void control_update();
+ void global_position_update();
/**
- * Check for changes in vehicle status.
+ * Retrieve home position
*/
- void vehicle_status_poll();
+ void home_position_update();
/**
- * Check for position updates.
+ * Retreive navigation capabilities
*/
- void vehicle_attitude_poll();
+ void navigation_capabilities_update();
/**
- * Check for set triplet updates.
+ * Retrieve offboard mission.
*/
- void mission_poll();
+ void offboard_mission_update(bool isrotaryWing);
/**
- * Control throttle.
+ * Retrieve onboard mission.
*/
- float control_throttle(float energy_error);
+ void onboard_mission_update();
/**
- * Control pitch.
+ * Retrieve vehicle status
*/
- float control_pitch(float altitude_error);
+ void vehicle_status_update();
- void calculate_airspeed_errors();
- void calculate_gndspeed_undershoot();
- void calculate_altitude_error();
/**
* Shim for calling task_main from task_create.
@@ -192,6 +271,79 @@ private:
* Main sensor collection task.
*/
void task_main() __attribute__((noreturn));
+
+ void publish_safepoints(unsigned points);
+
+ /**
+ * Functions that are triggered when a new state is entered.
+ */
+ void start_none();
+ void start_ready();
+ void start_loiter();
+ void start_mission();
+ void start_rtl();
+ void finish_rtl();
+
+ /**
+ * Guards offboard mission
+ */
+ bool offboard_mission_available(unsigned relative_index);
+
+ /**
+ * Guards onboard mission
+ */
+ bool onboard_mission_available(unsigned relative_index);
+
+ /**
+ * Check if current mission item has been reached.
+ */
+ bool check_mission_item_reached();
+
+ /**
+ * Perform actions when current mission item reached.
+ */
+ void on_mission_item_reached();
+
+ /**
+ * Move to next waypoint
+ */
+ void advance_mission();
+
+ /**
+ * Switch to next RTL state
+ */
+ void set_rtl_item();
+
+ /**
+ * Helper function to get a loiter item
+ */
+ void get_loiter_item(mission_item_s *item);
+
+ /**
+ * Helper function to get a takeoff item
+ */
+ void get_takeoff_item(mission_item_s *item);
+
+ /**
+ * Publish a new mission item triplet for position controller
+ */
+ void publish_mission_item_triplet();
+
+ /**
+ * Publish vehicle_control_mode topic for controllers
+ */
+ void publish_control_mode();
+
+
+ /**
+ * 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
+ */
+ bool cmp_mission_item_equivalent(const struct mission_item_s a, const struct mission_item_s b);
+
+ void add_home_pos_to_rtl(struct mission_item_s *new_mission_item);
};
namespace navigator
@@ -206,39 +358,66 @@ static const int ERROR = -1;
Navigator *g_navigator;
}
-Navigator::Navigator() :
+Navigator::Navigator() :
+
+/* state machine transition table */
+ StateTable(&myTable[0][0], NAV_STATE_MAX, MAX_EVENT),
_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),
+ _offboard_mission_sub(-1),
+ _onboard_mission_sub(-1),
+ _capabilities_sub(-1),
/* publications */
_triplet_pub(-1),
+ _mission_result_pub(-1),
+ _control_mode_pub(-1),
/* performance counters */
_loop_perf(perf_alloc(PC_ELAPSED, "navigator")),
+
/* states */
- _mission_items_maxcount(20),
- _mission_valid(false),
- _loiter_hold(false)
+ _rtl_state(RTL_STATE_NONE),
+ _fence_valid(false),
+ _inside_fence(true),
+ _mission(),
+ _reset_loiter_pos(true),
+ _waypoint_position_reached(false),
+ _waypoint_yaw_reached(false),
+ _time_first_inside_orbit(0),
+ _set_nav_state_timestamp(0),
+ _need_takeoff(true),
+ _do_takeoff(false),
+ _geofence_violation_warning_sent(false)
{
- _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");
- }
-
- _parameter_handles.throttle_cruise = param_find("NAV_DUMMY");
-
- /* fetch initial parameter values */
- parameters_update();
+ _parameter_handles.min_altitude = param_find("NAV_MIN_ALT");
+ _parameter_handles.acceptance_radius = param_find("NAV_ACCEPT_RAD");
+ _parameter_handles.loiter_radius = param_find("NAV_LOITER_RAD");
+ _parameter_handles.onboard_mission_enabled = param_find("NAV_ONB_MIS_EN");
+ _parameter_handles.takeoff_alt = param_find("NAV_TAKEOFF_ALT");
+ _parameter_handles.land_alt = param_find("NAV_LAND_ALT");
+ _parameter_handles.rtl_alt = param_find("NAV_RTL_ALT");
+
+ _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));
+
+ memset(&_mission_result, 0, sizeof(struct mission_result_s));
+
+ /* Initialize state machine */
+ myState = NAV_STATE_NONE;
+ start_none();
}
Navigator::~Navigator()
@@ -266,69 +445,93 @@ Navigator::~Navigator()
navigator::g_navigator = nullptr;
}
-int
+void
Navigator::parameters_update()
{
+ /* read from param to clear updated flag */
+ struct parameter_update_s update;
+ orb_copy(ORB_ID(parameter_update), _params_sub, &update);
- //param_get(_parameter_handles.throttle_cruise, &(_parameters.throttle_cruise));
+ param_get(_parameter_handles.min_altitude, &(_parameters.min_altitude));
+ param_get(_parameter_handles.acceptance_radius, &(_parameters.acceptance_radius));
+ param_get(_parameter_handles.loiter_radius, &(_parameters.loiter_radius));
+ param_get(_parameter_handles.onboard_mission_enabled, &(_parameters.onboard_mission_enabled));
+ param_get(_parameter_handles.takeoff_alt, &(_parameters.takeoff_alt));
+ param_get(_parameter_handles.land_alt, &(_parameters.land_alt));
+ param_get(_parameter_handles.rtl_alt, &(_parameters.rtl_alt));
- return OK;
+ _mission.set_onboard_mission_allowed((bool)_parameter_handles.onboard_mission_enabled);
+
+ _geofence.updateParams();
}
void
-Navigator::vehicle_status_poll()
+Navigator::global_position_update()
{
- bool vstatus_updated;
-
- /* Check HIL state if vehicle status has changed */
- orb_check(_vstatus_sub, &vstatus_updated);
-
- if (vstatus_updated) {
-
- orb_copy(ORB_ID(vehicle_status), _vstatus_sub, &_vstatus);
- }
+ /* load local copies */
+ orb_copy(ORB_ID(vehicle_global_position), _global_pos_sub, &_global_pos);
}
void
-Navigator::vehicle_attitude_poll()
+Navigator::home_position_update()
{
- /* check if there is a new position */
- bool att_updated;
- orb_check(_att_sub, &att_updated);
+ orb_copy(ORB_ID(home_position), _home_pos_sub, &_home_pos);
+}
- if (att_updated) {
- orb_copy(ORB_ID(vehicle_attitude), _att_sub, &_att);
- }
+void
+Navigator::navigation_capabilities_update()
+{
+ orb_copy(ORB_ID(navigation_capabilities), _capabilities_sub, &_nav_caps);
}
+
void
-Navigator::mission_poll()
+Navigator::offboard_mission_update(bool isrotaryWing)
{
- /* check if there is a new setpoint */
- bool mission_updated;
- orb_check(_mission_sub, &mission_updated);
+ struct mission_s offboard_mission;
+ if (orb_copy(ORB_ID(mission), _offboard_mission_sub, &offboard_mission) == OK) {
+
+ /* Check mission feasibility, for now do not handle the return value,
+ * however warnings are issued to the gcs via mavlink from inside the MissionFeasiblityChecker */
+ dm_item_t dm_current;
+ if (offboard_mission.dataman_id == 0) {
+ dm_current = DM_KEY_WAYPOINTS_OFFBOARD_0;
+ } else {
+ dm_current = DM_KEY_WAYPOINTS_OFFBOARD_1;
+ }
+ missionFeasiblityChecker.checkMissionFeasible(isrotaryWing, dm_current, (size_t)offboard_mission.count, _geofence);
- if (mission_updated) {
+ _mission.set_offboard_dataman_id(offboard_mission.dataman_id);
+ _mission.set_current_offboard_mission_index(offboard_mission.current_index);
+ _mission.set_offboard_mission_count(offboard_mission.count);
- struct mission_s mission;
- orb_copy(ORB_ID(mission), _mission_sub, &mission);
+ } else {
+ _mission.set_current_offboard_mission_index(0);
+ _mission.set_offboard_mission_count(0);
+ }
+}
- // XXX this is not optimal yet, but a first prototype /
- // test implementation
+void
+Navigator::onboard_mission_update()
+{
+ struct mission_s onboard_mission;
+ if (orb_copy(ORB_ID(mission), _onboard_mission_sub, &onboard_mission) == OK) {
- if (mission.count <= _mission_items_maxcount) {
- /*
- * Perform an atomic copy & state update
- */
- irqstate_t flags = irqsave();
+ _mission.set_current_onboard_mission_index(onboard_mission.current_index);
+ _mission.set_onboard_mission_count(onboard_mission.count);
- memcpy(_mission_items, mission.items, mission.count * sizeof(struct mission_item_s));
- _mission_valid = true;
+ } else {
+ _mission.set_current_onboard_mission_index(0);
+ _mission.set_onboard_mission_count(0);
+ }
+}
- irqrestore(flags);
- } else {
- warnx("mission larger than storage space");
- }
+void
+Navigator::vehicle_status_update()
+{
+ /* try to load initial states */
+ if (orb_copy(ORB_ID(vehicle_status), _vstatus_sub, &_vstatus) != OK) {
+ _vstatus.arming_state = ARMING_STATE_STANDBY; /* in case the commander is not be running */
}
}
@@ -341,46 +544,85 @@ Navigator::task_main_trampoline(int argc, char *argv[])
void
Navigator::task_main()
{
-
/* inform about start */
warnx("Initializing..");
fflush(stdout);
+ _mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
+
+ mavlink_log_info(_mavlink_fd, "[navigator] started");
+
+ /* Try to load the geofence:
+ * if /fs/microsd/etc/geofence.txt load from this file
+ * else clear geofence data in datamanager
+ */
+ struct stat buffer;
+ if( stat (GEOFENCE_FILENAME, &buffer) == 0 ) {
+ warnx("Try to load geofence.txt");
+ _geofence.loadFromFile(GEOFENCE_FILENAME);
+ } else {
+ if (_geofence.clearDm() > 0 )
+ warnx("Geofence cleared");
+ else
+ warnx("Could not clear geofence");
+ }
+
/*
* do subscriptions
*/
_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));
+ _offboard_mission_sub = orb_subscribe(ORB_ID(mission));
+ _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));
+
+ /* copy all topics first time */
+ vehicle_status_update();
+ parameters_update();
+ global_position_update();
+ home_position_update();
+ navigation_capabilities_update();
+ offboard_mission_update(_vstatus.is_rotary_wing);
+ onboard_mission_update();
- /* rate limit vehicle status updates to 5Hz */
- orb_set_interval(_vstatus_sub, 200);
/* rate limit position updates to 50 Hz */
orb_set_interval(_global_pos_sub, 20);
- parameters_update();
+ unsigned prevState = NAV_STATE_NONE;
+ bool pub_control_mode = true;
+ hrt_abstime mavlink_open_time = 0;
+ const hrt_abstime mavlink_open_interval = 500000;
/* 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 = _offboard_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,187 +632,927 @@ Navigator::task_main()
perf_begin(_loop_perf);
- /* check vehicle status for changes to publication state */
- vehicle_status_poll();
+ if (_mavlink_fd < 0 && hrt_absolute_time() > mavlink_open_time) {
+ /* try to reopen the mavlink log device with specified interval */
+ mavlink_open_time = hrt_abstime() + mavlink_open_interval;
+ _mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
+ }
- /* only update parameters if they changed */
- if (fds[0].revents & POLLIN) {
- /* read from param to clear updated flag */
- struct parameter_update_s update;
- orb_copy(ORB_ID(parameter_update), _params_sub, &update);
+ /* vehicle status updated */
+ if (fds[6].revents & POLLIN) {
+ vehicle_status_update();
+ pub_control_mode = true;
+
+ /* Evaluate state machine from commander and set the navigator mode accordingly */
+ if (_vstatus.main_state == MAIN_STATE_AUTO &&
+ (_vstatus.arming_state == ARMING_STATE_ARMED || _vstatus.arming_state == ARMING_STATE_ARMED_ERROR)) {
+ bool stick_mode = false;
+ if (!_vstatus.rc_signal_lost) {
+ /* RC signal available, use control switches to set mode */
+ /* RETURN switch, overrides MISSION switch */
+ if (_vstatus.return_switch == RETURN_SWITCH_RETURN) {
+ if (myState != NAV_STATE_READY || _rtl_state != RTL_STATE_LAND) {
+ dispatch(EVENT_RTL_REQUESTED);
+ }
+ stick_mode = true;
+ } else {
+ /* MISSION switch */
+ if (_vstatus.mission_switch == MISSION_SWITCH_LOITER) {
+ dispatch(EVENT_LOITER_REQUESTED);
+ stick_mode = true;
+ } else if (_vstatus.mission_switch == MISSION_SWITCH_MISSION) {
+ /* switch to mission only if available */
+ if (_mission.current_mission_available()) {
+ dispatch(EVENT_MISSION_REQUESTED);
+ } else {
+ dispatch(EVENT_LOITER_REQUESTED);
+ }
+ stick_mode = true;
+ }
+ if (!stick_mode && _vstatus.return_switch == RETURN_SWITCH_NORMAL && myState == NAV_STATE_RTL) {
+ /* RETURN switch is in normal mode, no MISSION switch mapped, interrupt if in RTL state */
+ dispatch(EVENT_LOITER_REQUESTED);
+ stick_mode = true;
+ }
+ }
+ }
+
+ if (!stick_mode) {
+ if (_vstatus.set_nav_state_timestamp != _set_nav_state_timestamp) {
+ /* commander requested new navigation mode, try to set it */
+ _set_nav_state_timestamp = _vstatus.set_nav_state_timestamp;
+
+ switch (_vstatus.set_nav_state) {
+ case NAV_STATE_NONE:
+ /* nothing to do */
+ break;
+
+ case NAV_STATE_LOITER:
+ dispatch(EVENT_LOITER_REQUESTED);
+ break;
+
+ case NAV_STATE_MISSION:
+ if (_mission.current_mission_available()) {
+ dispatch(EVENT_MISSION_REQUESTED);
+ } else {
+ dispatch(EVENT_LOITER_REQUESTED);
+ }
+ break;
+
+ case NAV_STATE_RTL:
+ if (myState != NAV_STATE_READY || _rtl_state != RTL_STATE_LAND) {
+ dispatch(EVENT_RTL_REQUESTED);
+ }
+ break;
+
+ default:
+ warnx("ERROR: Requested navigation state not supported");
+ break;
+ }
+
+ } else {
+ /* on first switch to AUTO try mission by default, if none is available fallback to loiter */
+ if (myState == NAV_STATE_NONE) {
+ if (_mission.current_mission_available()) {
+ dispatch(EVENT_MISSION_REQUESTED);
+ } else {
+ dispatch(EVENT_LOITER_REQUESTED);
+ }
+ }
+ }
+ }
+
+ } else {
+ /* not in AUTO */
+ dispatch(EVENT_NONE_REQUESTED);
+ }
+ }
- /* update parameters from storage */
+ /* parameters updated */
+ if (fds[0].revents & POLLIN) {
parameters_update();
+ /* note that these new parameters won't be in effect until a mission triplet is published again */
+ }
+
+ /* navigation capabilities updated */
+ if (fds[3].revents & POLLIN) {
+ navigation_capabilities_update();
+ }
+
+ /* offboard mission updated */
+ if (fds[4].revents & POLLIN) {
+ offboard_mission_update(_vstatus.is_rotary_wing);
+ // XXX check if mission really changed
+ dispatch(EVENT_MISSION_CHANGED);
+ }
+
+ /* onboard mission updated */
+ if (fds[5].revents & POLLIN) {
+ onboard_mission_update();
+ // XXX check if mission really changed
+ dispatch(EVENT_MISSION_CHANGED);
+ }
+
+ /* home position updated */
+ if (fds[2].revents & POLLIN) {
+ home_position_update();
+ // XXX check if home position really changed
+ dispatch(EVENT_HOME_POSITION_CHANGED);
}
- /* only run controller if position changed */
+ /* global position updated */
if (fds[1].revents & POLLIN) {
+ global_position_update();
+ /* only check if waypoint has been reached in MISSION and RTL modes */
+ if (myState == NAV_STATE_MISSION || myState == NAV_STATE_RTL) {
+ if (check_mission_item_reached()) {
+ on_mission_item_reached();
+ }
+ }
+ /* Check geofence violation */
+ if(!_geofence.inside(&_global_pos)) {
+ //xxx: publish geofence violation here (or change local flag depending on which app handles the flight termination)
- static uint64_t last_run = 0;
- float deltaT = (hrt_absolute_time() - last_run) / 1000000.0f;
- last_run = hrt_absolute_time();
+ /* Issue a warning about the geofence violation once */
+ if (!_geofence_violation_warning_sent)
+ {
+ mavlink_log_critical(_mavlink_fd, "#audio: Geofence violation");
+ _geofence_violation_warning_sent = true;
+ }
+ } else {
+ /* Reset the _geofence_violation_warning_sent field */
+ _geofence_violation_warning_sent = false;
+ }
+ }
- /* guard against too large deltaT's */
- if (deltaT > 1.0f)
- deltaT = 0.01f;
+ /* notify user about state changes */
+ if (myState != prevState) {
+ mavlink_log_info(_mavlink_fd, "[navigator] nav state %d -> %d", prevState, myState);
+ prevState = myState;
+ pub_control_mode = true;
+ }
- /* load local copies */
- orb_copy(ORB_ID(vehicle_global_position), _global_pos_sub, &_global_pos);
+ /* publish control mode if updated */
+ if (pub_control_mode) {
+ publish_control_mode();
+ }
- vehicle_attitude_poll();
+ perf_end(_loop_perf);
+ }
- mission_poll();
+ warnx("exiting.");
- 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);
+ _navigator_task = -1;
+ _exit(0);
+}
- /* AUTONOMOUS FLIGHT */
+int
+Navigator::start()
+{
+ ASSERT(_navigator_task == -1);
- if (1 /* autonomous flight */) {
+ /* start the task */
+ _navigator_task = task_spawn_cmd("navigator",
+ SCHED_DEFAULT,
+ SCHED_PRIORITY_MAX - 5,
+ 2048,
+ (main_t)&Navigator::task_main_trampoline,
+ nullptr);
- /* execute navigation once we have a setpoint */
- if (_mission_valid) {
+ if (_navigator_task < 0) {
+ warn("task start failed");
+ return -errno;
+ }
- // Next waypoint
- math::Vector2f prev_wp;
+ return OK;
+}
- if (_global_triplet.previous_valid) {
- prev_wp.setX(_global_triplet.previous.lat / 1e7f);
- prev_wp.setY(_global_triplet.previous.lon / 1e7f);
+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 / 1e7d, _global_pos.lat / 1e7d);
+ 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 * M_RAD_TO_DEG_F));
+ }
+ 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 {
- /*
- * 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);
+ switch (myState) {
+ case NAV_STATE_NONE:
+ warnx("State: None");
+ break;
+ case NAV_STATE_LOITER:
+ warnx("State: Loiter");
+ break;
+ case NAV_STATE_MISSION:
+ warnx("State: Mission");
+ break;
+ case NAV_STATE_RTL:
+ warnx("State: RTL");
+ break;
+ default:
+ warnx("State: Unknown");
+ break;
+ }
+}
- }
+StateTable::Tran const Navigator::myTable[NAV_STATE_MAX][MAX_EVENT] = {
+ {
+ /* STATE_NONE */
+ /* EVENT_NONE_REQUESTED */ {NO_ACTION, NAV_STATE_NONE},
+ /* EVENT_READY_REQUESTED */ {ACTION(&Navigator::start_ready), NAV_STATE_READY},
+ /* EVENT_LOITER_REQUESTED */ {ACTION(&Navigator::start_loiter), NAV_STATE_LOITER},
+ /* EVENT_MISSION_REQUESTED */ {ACTION(&Navigator::start_mission), NAV_STATE_MISSION},
+ /* EVENT_RTL_REQUESTED */ {ACTION(&Navigator::start_rtl), NAV_STATE_RTL},
+ /* EVENT_MISSION_CHANGED */ {NO_ACTION, NAV_STATE_NONE},
+ /* EVENT_HOME_POSITION_CHANGED */ {NO_ACTION, NAV_STATE_NONE},
+ },
+ {
+ /* STATE_READY */
+ /* EVENT_NONE_REQUESTED */ {NO_ACTION, NAV_STATE_NONE},
+ /* EVENT_READY_REQUESTED */ {NO_ACTION, NAV_STATE_READY},
+ /* EVENT_LOITER_REQUESTED */ {NO_ACTION, NAV_STATE_READY},
+ /* EVENT_MISSION_REQUESTED */ {ACTION(&Navigator::start_mission), NAV_STATE_MISSION},
+ /* EVENT_RTL_REQUESTED */ {ACTION(&Navigator::start_rtl), NAV_STATE_RTL},
+ /* EVENT_MISSION_CHANGED */ {NO_ACTION, NAV_STATE_READY},
+ /* EVENT_HOME_POSITION_CHANGED */ {NO_ACTION, NAV_STATE_READY},
+ },
+ {
+ /* STATE_LOITER */
+ /* EVENT_NONE_REQUESTED */ {ACTION(&Navigator::start_none), NAV_STATE_NONE},
+ /* EVENT_READY_REQUESTED */ {NO_ACTION, NAV_STATE_LOITER},
+ /* EVENT_LOITER_REQUESTED */ {NO_ACTION, NAV_STATE_LOITER},
+ /* EVENT_MISSION_REQUESTED */ {ACTION(&Navigator::start_mission), NAV_STATE_MISSION},
+ /* EVENT_RTL_REQUESTED */ {ACTION(&Navigator::start_rtl), NAV_STATE_RTL},
+ /* EVENT_MISSION_CHANGED */ {NO_ACTION, NAV_STATE_LOITER},
+ /* EVENT_HOME_POSITION_CHANGED */ {NO_ACTION, NAV_STATE_LOITER},
+ },
+ {
+ /* STATE_MISSION */
+ /* EVENT_NONE_REQUESTED */ {ACTION(&Navigator::start_none), NAV_STATE_NONE},
+ /* EVENT_READY_REQUESTED */ {ACTION(&Navigator::start_ready), NAV_STATE_READY},
+ /* EVENT_LOITER_REQUESTED */ {ACTION(&Navigator::start_loiter), NAV_STATE_LOITER},
+ /* EVENT_MISSION_REQUESTED */ {NO_ACTION, NAV_STATE_MISSION},
+ /* EVENT_RTL_REQUESTED */ {ACTION(&Navigator::start_rtl), NAV_STATE_RTL},
+ /* EVENT_MISSION_CHANGED */ {ACTION(&Navigator::start_mission), NAV_STATE_MISSION},
+ /* EVENT_HOME_POSITION_CHANGED */ {NO_ACTION, NAV_STATE_MISSION},
+ },
+ {
+ /* STATE_RTL */
+ /* EVENT_NONE_REQUESTED */ {ACTION(&Navigator::start_none), NAV_STATE_NONE},
+ /* EVENT_READY_REQUESTED */ {ACTION(&Navigator::start_ready), NAV_STATE_READY},
+ /* EVENT_LOITER_REQUESTED */ {ACTION(&Navigator::start_loiter), NAV_STATE_LOITER},
+ /* EVENT_MISSION_REQUESTED */ {ACTION(&Navigator::start_mission), NAV_STATE_MISSION},
+ /* EVENT_RTL_REQUESTED */ {NO_ACTION, NAV_STATE_RTL},
+ /* EVENT_MISSION_CHANGED */ {NO_ACTION, NAV_STATE_RTL},
+ /* EVENT_HOME_POSITION_CHANGED */ {ACTION(&Navigator::start_rtl), NAV_STATE_RTL},
+ },
+};
+void
+Navigator::start_none()
+{
+ _mission_item_triplet.previous_valid = false;
+ _mission_item_triplet.current_valid = false;
+ _mission_item_triplet.next_valid = false;
+ _reset_loiter_pos = true;
+ _do_takeoff = false;
+ _rtl_state = RTL_STATE_NONE;
- /******** MAIN NAVIGATION STATE MACHINE ********/
+ publish_mission_item_triplet();
+}
- // XXX to be put in its own class
+void
+Navigator::start_ready()
+{
+ _mission_item_triplet.previous_valid = false;
+ _mission_item_triplet.current_valid = false;
+ _mission_item_triplet.next_valid = false;
- if (_global_triplet.current.nav_cmd == NAV_CMD_WAYPOINT) {
- /* waypoint is a plain navigation waypoint */
-
+ _reset_loiter_pos = true;
+ _do_takeoff = false;
- } 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) {
+ // TODO check
+ if (_rtl_state != RTL_STATE_LAND) {
+ _rtl_state = RTL_STATE_NONE;
+ }
- /* waypoint is a loiter waypoint */
-
- }
+ publish_mission_item_triplet();
+}
- // XXX at this point we always want no loiter hold if a
- // mission is active
- _loiter_hold = false;
+void
+Navigator::start_loiter()
+{
+ _do_takeoff = false;
- } else {
+ /* set loiter position if needed */
+ if (_reset_loiter_pos || !_mission_item_triplet.current_valid) {
+ _reset_loiter_pos = false;
- 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;
- }
+ _mission_item_triplet.current.lat = (double)_global_pos.lat / 1e7d;
+ _mission_item_triplet.current.lon = (double)_global_pos.lon / 1e7d;
+ _mission_item_triplet.current.yaw = NAN; // NAN means to use current yaw
+
+ _mission_item_triplet.current.altitude_is_relative = false;
+ float min_alt_amsl = _parameters.min_altitude + _home_pos.altitude;
+
+ /* use current altitude if above min altitude set by parameter */
+ if (_global_pos.alt < min_alt_amsl) {
+ _mission_item_triplet.current.altitude = min_alt_amsl;
+ mavlink_log_info(_mavlink_fd, "[navigator] loiter %.1fm higher", (double)(min_alt_amsl - _global_pos.alt));
+ } else {
+ _mission_item_triplet.current.altitude = _global_pos.alt;
+ mavlink_log_info(_mavlink_fd, "[navigator] loiter at current altitude");
+ }
+ }
+
+ _mission_item_triplet.previous_valid = false;
+ _mission_item_triplet.current_valid = true;
+ _mission_item_triplet.next_valid = false;
- //_parameters.loiter_hold_radius
+ get_loiter_item(&_mission_item_triplet.current);
+
+ publish_mission_item_triplet();
+}
+
+void
+Navigator::start_mission()
+{
+ _need_takeoff = true;
+
+ mavlink_log_info(_mavlink_fd, "[navigator] mission started");
+ advance_mission();
+}
+
+void
+Navigator::advance_mission()
+{
+ /* 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;
+
+ _reset_loiter_pos = true;
+ _do_takeoff = false;
+
+ int ret;
+ bool onboard;
+ unsigned index;
+
+ ret = _mission.get_current_mission_item(&_mission_item_triplet.current, &onboard, &index);
+
+ if (ret == OK) {
+ _mission_item_triplet.current_valid = true;
+ add_home_pos_to_rtl(&_mission_item_triplet.current);
+
+ if (_mission_item_triplet.current.nav_cmd != NAV_CMD_RETURN_TO_LAUNCH &&
+ _mission_item_triplet.current.nav_cmd != NAV_CMD_LOITER_TIME_LIMIT &&
+ _mission_item_triplet.current.nav_cmd != NAV_CMD_LOITER_TURN_COUNT &&
+ _mission_item_triplet.current.nav_cmd != NAV_CMD_LOITER_UNLIMITED) {
+ /* don't reset RTL state on RTL or LOITER items */
+ _rtl_state = RTL_STATE_NONE;
+ }
+
+ if (_vstatus.is_rotary_wing) {
+ if (_need_takeoff && (
+ _mission_item_triplet.current.nav_cmd == NAV_CMD_TAKEOFF ||
+ _mission_item_triplet.current.nav_cmd == NAV_CMD_WAYPOINT ||
+ _mission_item_triplet.current.nav_cmd == NAV_CMD_RETURN_TO_LAUNCH ||
+ _mission_item_triplet.current.nav_cmd == NAV_CMD_LOITER_TIME_LIMIT ||
+ _mission_item_triplet.current.nav_cmd == NAV_CMD_LOITER_TURN_COUNT ||
+ _mission_item_triplet.current.nav_cmd == NAV_CMD_LOITER_UNLIMITED
+ )) {
+ /* do special TAKEOFF handling for VTOL */
+ _need_takeoff = false;
+
+ /* calculate desired takeoff altitude AMSL */
+ float takeoff_alt_amsl = _mission_item_triplet.current.altitude;
+ if (_mission_item_triplet.current.altitude_is_relative)
+ takeoff_alt_amsl += _home_pos.altitude;
+
+ if (_vstatus.condition_landed) {
+ /* takeoff to at least NAV_TAKEOFF_ALT from ground if landed */
+ takeoff_alt_amsl = fmaxf(takeoff_alt_amsl, _global_pos.alt + _parameters.takeoff_alt);
}
- } else if (0/* seatbelt mode enabled */) {
+ /* check if we really need takeoff */
+ if (_vstatus.condition_landed || _global_pos.alt < takeoff_alt_amsl - _mission_item_triplet.current.acceptance_radius) {
+ /* force TAKEOFF if landed or waypoint altitude is more than current */
+ _do_takeoff = true;
- /** SEATBELT FLIGHT **/
- continue;
+ /* move current mission item to next */
+ memcpy(&_mission_item_triplet.next, &_mission_item_triplet.current, sizeof(mission_item_s));
+ _mission_item_triplet.next_valid = true;
- } else {
+ /* set current item to TAKEOFF */
+ get_takeoff_item(&_mission_item_triplet.current);
- /** MANUAL FLIGHT **/
+ _mission_item_triplet.current.lat = (double)_global_pos.lat / 1e7d;
+ _mission_item_triplet.current.lon = (double)_global_pos.lon / 1e7d;
+ _mission_item_triplet.current.altitude = takeoff_alt_amsl;
+ _mission_item_triplet.current.altitude_is_relative = false;
+ }
+ } else if (_mission_item_triplet.current.nav_cmd == NAV_CMD_LAND) {
+ /* will need takeoff after landing */
+ _need_takeoff = true;
+ }
+ }
- /* no flight mode applies, do not publish an attitude setpoint */
- continue;
+ if (_do_takeoff) {
+ mavlink_log_info(_mavlink_fd, "[navigator] takeoff to %.1fm", _mission_item_triplet.current.altitude);
+ } else {
+ if (onboard) {
+ mavlink_log_info(_mavlink_fd, "[navigator] heading to onboard WP %d", index);
+ } else {
+ mavlink_log_info(_mavlink_fd, "[navigator] heading to offboard WP %d", index);
}
+ }
+ } else {
+ /* since a mission is not advanced without WPs available, this is not supposed to happen */
+ _mission_item_triplet.current_valid = false;
+ warnx("ERROR: current WP can't be set");
+ }
- /******** MAIN NAVIGATION STATE MACHINE ********/
+ if (!_do_takeoff) {
+ ret = _mission.get_next_mission_item(&_mission_item_triplet.next);
- if (_global_triplet.current.nav_cmd == NAV_CMD_RETURN_TO_LAUNCH) {
- // XXX define launch position and return
+ if (ret == OK) {
+ add_home_pos_to_rtl(&_mission_item_triplet.next);
+ _mission_item_triplet.next_valid = true;
+ } else {
+ /* this will fail for the last WP */
+ _mission_item_triplet.next_valid = false;
+ }
+ }
+
+ publish_mission_item_triplet();
+}
- } else if (_global_triplet.current.nav_cmd == NAV_CMD_LAND) {
- // XXX flared descent on final approach
+void
+Navigator::start_rtl()
+{
+ _reset_loiter_pos = true;
+ _do_takeoff = false;
+ if (_rtl_state == RTL_STATE_NONE)
+ _rtl_state = RTL_STATE_CLIMB;
- } else if (_global_triplet.current.nav_cmd == NAV_CMD_TAKEOFF) {
+ mavlink_log_info(_mavlink_fd, "[navigator] RTL started");
+ set_rtl_item();
+}
- /* 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);
- }
+void
+Navigator::set_rtl_item()
+{
+ switch (_rtl_state) {
+ case RTL_STATE_CLIMB: {
+ memcpy(&_mission_item_triplet.previous, &_mission_item_triplet.current, sizeof(mission_item_s));
+ _mission_item_triplet.previous_valid = _mission_item_triplet.current_valid;
+
+ _mission_item_triplet.current_valid = true;
+ _mission_item_triplet.next_valid = false;
+
+ float climb_alt = _home_pos.altitude + _parameters.rtl_alt;
+ if (_vstatus.condition_landed)
+ climb_alt = fmaxf(climb_alt, _global_pos.alt + _parameters.rtl_alt);
+
+ _mission_item_triplet.current.altitude_is_relative = false;
+ _mission_item_triplet.current.lat = (double)_global_pos.lat / 1e7d;
+ _mission_item_triplet.current.lon = (double)_global_pos.lon / 1e7d;
+ _mission_item_triplet.current.altitude = climb_alt;
+ _mission_item_triplet.current.yaw = NAN;
+ _mission_item_triplet.current.loiter_radius = _parameters.loiter_radius;
+ _mission_item_triplet.current.loiter_direction = 1;
+ _mission_item_triplet.current.nav_cmd = NAV_CMD_TAKEOFF;
+ _mission_item_triplet.current.acceptance_radius = _parameters.acceptance_radius;
+ _mission_item_triplet.current.time_inside = 0.0f;
+ _mission_item_triplet.current.pitch_min = 0.0f;
+ _mission_item_triplet.current.autocontinue = true;
+ _mission_item_triplet.current.origin = ORIGIN_ONBOARD;
+ mavlink_log_info(_mavlink_fd, "[navigator] RTL: climb to %.1fm", climb_alt - _home_pos.altitude);
+ break;
+ }
+ case RTL_STATE_RETURN: {
+ memcpy(&_mission_item_triplet.previous, &_mission_item_triplet.current, sizeof(mission_item_s));
+ _mission_item_triplet.previous_valid = _mission_item_triplet.current_valid;
+
+ _mission_item_triplet.current_valid = true;
+ _mission_item_triplet.next_valid = false;
+
+ _mission_item_triplet.current.altitude_is_relative = false;
+ _mission_item_triplet.current.lat = _home_pos.lat;
+ _mission_item_triplet.current.lon = _home_pos.lon;
+ // don't change altitude setpoint
+ _mission_item_triplet.current.yaw = NAN;
+ _mission_item_triplet.current.loiter_radius = _parameters.loiter_radius;
+ _mission_item_triplet.current.loiter_direction = 1;
+ _mission_item_triplet.current.nav_cmd = NAV_CMD_WAYPOINT;
+ _mission_item_triplet.current.acceptance_radius = _parameters.acceptance_radius;
+ _mission_item_triplet.current.time_inside = 0.0f;
+ _mission_item_triplet.current.pitch_min = 0.0f;
+ _mission_item_triplet.current.autocontinue = true;
+ _mission_item_triplet.current.origin = ORIGIN_ONBOARD;
+ mavlink_log_info(_mavlink_fd, "[navigator] RTL: return");
+ break;
+ }
+ case RTL_STATE_DESCEND: {
+ memcpy(&_mission_item_triplet.previous, &_mission_item_triplet.current, sizeof(mission_item_s));
+ _mission_item_triplet.previous_valid = _mission_item_triplet.current_valid;
+
+ _mission_item_triplet.current_valid = true;
+ _mission_item_triplet.next_valid = false;
+
+ float descend_alt = _home_pos.altitude + _parameters.land_alt;
+
+ _mission_item_triplet.current.altitude_is_relative = false;
+ _mission_item_triplet.current.lat = _home_pos.lat;
+ _mission_item_triplet.current.lon = _home_pos.lon;
+ _mission_item_triplet.current.altitude = descend_alt;
+ _mission_item_triplet.current.yaw = NAN;
+ _mission_item_triplet.current.loiter_radius = _parameters.loiter_radius;
+ _mission_item_triplet.current.loiter_direction = 1;
+ _mission_item_triplet.current.nav_cmd = NAV_CMD_WAYPOINT;
+ _mission_item_triplet.current.acceptance_radius = _parameters.acceptance_radius;
+ _mission_item_triplet.current.time_inside = 0.0f;
+ _mission_item_triplet.current.pitch_min = 0.0f;
+ _mission_item_triplet.current.autocontinue = true;
+ _mission_item_triplet.current.origin = ORIGIN_ONBOARD;
+ mavlink_log_info(_mavlink_fd, "[navigator] RTL: descend to %.1fm", descend_alt - _home_pos.altitude);
+ break;
+ }
+ case RTL_STATE_LAND: {
+ memcpy(&_mission_item_triplet.previous, &_mission_item_triplet.current, sizeof(mission_item_s));
+ _mission_item_triplet.previous_valid = _mission_item_triplet.current_valid;
+
+ _mission_item_triplet.current_valid = true;
+ _mission_item_triplet.next_valid = false;
+
+ _mission_item_triplet.current.altitude_is_relative = false;
+ _mission_item_triplet.current.lat = _home_pos.lat;
+ _mission_item_triplet.current.lon = _home_pos.lon;
+ _mission_item_triplet.current.altitude = _home_pos.altitude;
+ _mission_item_triplet.current.yaw = NAN;
+ _mission_item_triplet.current.loiter_radius = _parameters.loiter_radius;
+ _mission_item_triplet.current.loiter_direction = 1;
+ _mission_item_triplet.current.nav_cmd = NAV_CMD_LAND;
+ _mission_item_triplet.current.acceptance_radius = _parameters.acceptance_radius;
+ _mission_item_triplet.current.time_inside = 0.0f;
+ _mission_item_triplet.current.pitch_min = 0.0f;
+ _mission_item_triplet.current.autocontinue = true;
+ _mission_item_triplet.current.origin = ORIGIN_ONBOARD;
+ mavlink_log_info(_mavlink_fd, "[navigator] RTL: land");
+ break;
+ }
+ default: {
+ mavlink_log_critical(_mavlink_fd, "[navigator] error: unknown RTL state: %d", _rtl_state);
+ start_loiter();
+ break;
+ }
+ }
+
+ publish_mission_item_triplet();
+}
+
+bool
+Navigator::check_mission_item_reached()
+{
+ /* only check if there is actually a mission item to check */
+ if (!_mission_item_triplet.current_valid) {
+ return false;
+ }
+
+ if (_mission_item_triplet.current.nav_cmd == NAV_CMD_LAND) {
+ return _vstatus.condition_landed;
+ }
+
+ /* XXX TODO count turns */
+ 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) {
+
+ return false;
+ }
+
+ uint64_t now = hrt_absolute_time();
+
+ if (!_waypoint_position_reached) {
+ float acceptance_radius;
+
+ if (_mission_item_triplet.current.nav_cmd == NAV_CMD_WAYPOINT && _mission_item_triplet.current.acceptance_radius > 0.01f) {
+ acceptance_radius = _mission_item_triplet.current.acceptance_radius;
+
+ } else {
+ acceptance_radius = _parameters.acceptance_radius;
+ }
+
+ float dist = -1.0f;
+ float dist_xy = -1.0f;
+ float dist_z = -1.0f;
+
+ /* current relative or AMSL altitude depending on mission item altitude_is_relative flag */
+ float wp_alt_amsl = _mission_item_triplet.current.altitude;
+ if (_mission_item_triplet.current.altitude_is_relative)
+ _mission_item_triplet.current.altitude += _home_pos.altitude;
+
+ dist = get_distance_to_point_global_wgs84(_mission_item_triplet.current.lat, _mission_item_triplet.current.lon, wp_alt_amsl,
+ (double)_global_pos.lat / 1e7d, (double)_global_pos.lon / 1e7d, _global_pos.alt,
+ &dist_xy, &dist_z);
+
+ if (_do_takeoff) {
+ if (_global_pos.alt > wp_alt_amsl - acceptance_radius) {
+ /* require only altitude for takeoff */
+ _waypoint_position_reached = true;
+ }
+ } else {
+ if (dist >= 0.0f && dist <= acceptance_radius) {
+ _waypoint_position_reached = true;
}
+ }
+ }
- /* 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);
+ if (!_waypoint_yaw_reached) {
+ if (_vstatus.is_rotary_wing && !_do_takeoff && isfinite(_mission_item_triplet.current.yaw)) {
+ /* check yaw if defined only for rotary wing except takeoff */
+ float yaw_err = _wrap_pi(_mission_item_triplet.current.yaw - _global_pos.yaw);
+ if (fabsf(yaw_err) < 0.05f) { /* XXX get rid of magic number */
+ _waypoint_yaw_reached = true;
+ }
+ } else {
+ _waypoint_yaw_reached = true;
+ }
+ }
- } else {
- /* advertise and publish */
- _triplet_pub = orb_advertise(ORB_ID(vehicle_global_position_set_triplet), &_global_triplet);
+ /* check if the current waypoint was reached */
+ if (_waypoint_position_reached && _waypoint_yaw_reached) {
+ if (_time_first_inside_orbit == 0) {
+ _time_first_inside_orbit = now;
+ if (_mission_item_triplet.current.time_inside > 0.01f) {
+ mavlink_log_info(_mavlink_fd, "[navigator] waypoint reached, wait for %.1fs", _mission_item_triplet.current.time_inside);
}
+ }
+
+ /* 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) {
+ _time_first_inside_orbit = 0;
+ _waypoint_yaw_reached = false;
+ _waypoint_position_reached = false;
+ return true;
+ }
+ }
+ return false;
+
+}
+void
+Navigator::on_mission_item_reached()
+{
+ if (myState == NAV_STATE_MISSION) {
+ if (_do_takeoff) {
+ /* takeoff completed */
+ _do_takeoff = false;
+ mavlink_log_info(_mavlink_fd, "[navigator] takeoff completed");
+ } else {
+ /* advance by one mission item */
+ _mission.move_to_next();
}
- perf_end(_loop_perf);
+ if (_mission.current_mission_available()) {
+ advance_mission();
+ } else {
+ /* if no more mission items available then finish mission */
+ /* loiter at last waypoint */
+ _reset_loiter_pos = false;
+ mavlink_log_info(_mavlink_fd, "[navigator] mission completed");
+ if (_vstatus.condition_landed) {
+ dispatch(EVENT_READY_REQUESTED);
+ } else {
+ dispatch(EVENT_LOITER_REQUESTED);
+ }
+ }
+ } else {
+ /* RTL finished */
+ if (_rtl_state == RTL_STATE_LAND) {
+ /* landed at home position */
+ mavlink_log_info(_mavlink_fd, "[navigator] RTL completed, landed");
+ dispatch(EVENT_READY_REQUESTED);
+ } else {
+ /* next RTL step */
+ _rtl_state = (RTLState)(_rtl_state + 1);
+ set_rtl_item();
+ }
}
+}
- warnx("exiting.\n");
+void
+Navigator::get_loiter_item(struct mission_item_s *item)
+{
+ //item->altitude_is_relative
+ //item->lat
+ //item->lon
+ //item->altitude
+ //item->yaw
+ item->loiter_radius = _parameters.loiter_radius;
+ item->loiter_direction = 1;
+ item->nav_cmd = NAV_CMD_LOITER_UNLIMITED;
+ item->acceptance_radius = _parameters.acceptance_radius;
+ item->time_inside = 0.0f;
+ item->pitch_min = 0.0f;
+ item->autocontinue = false;
+ item->origin = ORIGIN_ONBOARD;
- _navigator_task = -1;
- _exit(0);
}
-int
-Navigator::start()
+void
+Navigator::get_takeoff_item(mission_item_s *item)
{
- ASSERT(_navigator_task == -1);
+ //item->altitude_is_relative
+ //item->lat
+ //item->lon
+ //item->altitude
+ item->yaw = NAN;
+ item->loiter_radius = _parameters.loiter_radius;
+ item->loiter_direction = 1;
+ item->nav_cmd = NAV_CMD_TAKEOFF;
+ item->acceptance_radius = _parameters.acceptance_radius;
+ item->time_inside = 0.0f;
+ item->pitch_min = 0.0;
+ item->autocontinue = true;
+ item->origin = ORIGIN_ONBOARD;
+}
- /* start the task */
- _navigator_task = task_spawn_cmd("navigator",
- SCHED_DEFAULT,
- SCHED_PRIORITY_MAX - 5,
- 2048,
- (main_t)&Navigator::task_main_trampoline,
- nullptr);
+void
+Navigator::add_home_pos_to_rtl(struct mission_item_s *new_mission_item)
+{
+ if (new_mission_item->nav_cmd == NAV_CMD_RETURN_TO_LAUNCH) {
+ /* append the home position to RTL item */
+ new_mission_item->lat = _home_pos.lat;
+ new_mission_item->lon = _home_pos.lon;
+ new_mission_item->altitude = _home_pos.altitude + _parameters.rtl_alt;
+ new_mission_item->altitude_is_relative = false;
+ new_mission_item->loiter_radius = _parameters.loiter_radius;
+ new_mission_item->acceptance_radius = _parameters.acceptance_radius;
+ }
+}
- if (_navigator_task < 0) {
- warn("task start failed");
- return -errno;
+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);
}
+}
- return OK;
+void
+Navigator::publish_control_mode()
+{
+ /* update vehicle_control_mode topic*/
+ _control_mode.main_state = _vstatus.main_state;
+ _control_mode.nav_state = static_cast<nav_state_t>(myState);
+ _control_mode.flag_armed = _vstatus.arming_state == ARMING_STATE_ARMED || _vstatus.arming_state == ARMING_STATE_ARMED_ERROR;
+ _control_mode.flag_external_manual_override_ok = !_vstatus.is_rotary_wing;
+ _control_mode.flag_system_hil_enabled = _vstatus.hil_state == HIL_STATE_ON;
+
+ _control_mode.flag_control_offboard_enabled = false;
+ _control_mode.flag_control_flighttermination_enabled = false;
+
+ switch (_vstatus.main_state) {
+ case MAIN_STATE_MANUAL:
+ _control_mode.flag_control_manual_enabled = true;
+ _control_mode.flag_control_rates_enabled = _vstatus.is_rotary_wing;
+ _control_mode.flag_control_attitude_enabled = _vstatus.is_rotary_wing;
+ _control_mode.flag_control_altitude_enabled = false;
+ _control_mode.flag_control_climb_rate_enabled = false;
+ _control_mode.flag_control_position_enabled = false;
+ _control_mode.flag_control_velocity_enabled = false;
+ break;
+
+ case MAIN_STATE_SEATBELT:
+ _control_mode.flag_control_manual_enabled = true;
+ _control_mode.flag_control_rates_enabled = true;
+ _control_mode.flag_control_attitude_enabled = true;
+ _control_mode.flag_control_altitude_enabled = true;
+ _control_mode.flag_control_climb_rate_enabled = true;
+ _control_mode.flag_control_position_enabled = false;
+ _control_mode.flag_control_velocity_enabled = false;
+ break;
+
+ case MAIN_STATE_EASY:
+ _control_mode.flag_control_manual_enabled = true;
+ _control_mode.flag_control_rates_enabled = true;
+ _control_mode.flag_control_attitude_enabled = true;
+ _control_mode.flag_control_altitude_enabled = true;
+ _control_mode.flag_control_climb_rate_enabled = true;
+ _control_mode.flag_control_position_enabled = true;
+ _control_mode.flag_control_velocity_enabled = true;
+ break;
+
+ case MAIN_STATE_AUTO:
+ _control_mode.flag_control_manual_enabled = false;
+ if (myState == NAV_STATE_READY) {
+ /* disable all controllers, armed but idle */
+ _control_mode.flag_control_rates_enabled = false;
+ _control_mode.flag_control_attitude_enabled = false;
+ _control_mode.flag_control_position_enabled = false;
+ _control_mode.flag_control_velocity_enabled = false;
+ _control_mode.flag_control_altitude_enabled = false;
+ _control_mode.flag_control_climb_rate_enabled = false;
+ } else {
+ _control_mode.flag_control_rates_enabled = true;
+ _control_mode.flag_control_attitude_enabled = true;
+ _control_mode.flag_control_position_enabled = true;
+ _control_mode.flag_control_velocity_enabled = true;
+ _control_mode.flag_control_altitude_enabled = true;
+ _control_mode.flag_control_climb_rate_enabled = true;
+ }
+ break;
+
+ default:
+ break;
+ }
+
+ _control_mode.timestamp = hrt_absolute_time();
+
+ /* lazily publish the mission triplet only once available */
+ if (_control_mode_pub > 0) {
+ /* publish the mission triplet */
+ orb_publish(ORB_ID(vehicle_control_mode), _control_mode_pub, &_control_mode);
+
+ } else {
+ /* advertise and publish */
+ _control_mode_pub = orb_advertise(ORB_ID(vehicle_control_mode), &_control_mode);
+ }
+}
+
+bool Navigator::cmp_mission_item_equivalent(const struct mission_item_s a, const struct mission_item_s b) {
+ if (a.altitude_is_relative == b.altitude_is_relative &&
+ fabs(a.lat - b.lat) < FLT_EPSILON &&
+ fabs(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 &&
+ a.loiter_direction == b.loiter_direction &&
+ a.nav_cmd == b.nav_cmd &&
+ fabsf(a.acceptance_radius - b.acceptance_radius) < FLT_EPSILON &&
+ fabsf(a.time_inside - b.time_inside) < FLT_EPSILON &&
+ a.autocontinue == b.autocontinue) {
+ return true;
+ } else {
+ return false;
+ }
+}
+
+void Navigator::add_fence_point(int argc, char *argv[])
+{
+ _geofence.addPoint(argc, argv);
+}
+
+void Navigator::load_fence_from_file(const char *filename)
+{
+ _geofence.loadFromFile(filename);
+}
+
+
+static void usage()
+{
+ errx(1, "usage: navigator {start|stop|status|fence|fencefile}");
}
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 +1560,27 @@ 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->add_fence_point(argc - 2, argv + 2);
+ } else if (!strcmp(argv[1], "fencefile")) {
+ navigator::g_navigator->load_fence_from_file(GEOFENCE_FILENAME);
+
+ } else {
+ usage();
}
- warnx("unrecognized command");
- return 1;
+ return 0;
}
diff --git a/src/modules/navigator/navigator_mission.cpp b/src/modules/navigator/navigator_mission.cpp
new file mode 100644
index 000000000..6576aae70
--- /dev/null
+++ b/src/modules/navigator/navigator_mission.cpp
@@ -0,0 +1,257 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ * Author: @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
+ * 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_mission.cpp
+ * Helper class to access missions
+ */
+
+// #include <stdio.h>
+// #include <stdlib.h>
+// #include <string.h>
+// #include <unistd.h>
+
+#include <stdlib.h>
+#include <dataman/dataman.h>
+#include "navigator_mission.h"
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
+
+
+Mission::Mission() :
+
+ _offboard_dataman_id(-1),
+ _current_offboard_mission_index(0),
+ _current_onboard_mission_index(0),
+ _offboard_mission_item_count(0),
+ _onboard_mission_item_count(0),
+ _onboard_mission_allowed(false),
+ _current_mission_type(MISSION_TYPE_NONE)
+{}
+
+Mission::~Mission()
+{
+
+}
+
+void
+Mission::set_offboard_dataman_id(int new_id)
+{
+ _offboard_dataman_id = new_id;
+}
+
+void
+Mission::set_current_offboard_mission_index(int new_index)
+{
+ if (new_index != -1) {
+ _current_offboard_mission_index = (unsigned)new_index;
+ }
+}
+
+void
+Mission::set_current_onboard_mission_index(int new_index)
+{
+ if (new_index != -1) {
+ _current_onboard_mission_index = (unsigned)new_index;
+ }
+}
+
+void
+Mission::set_offboard_mission_count(unsigned new_count)
+{
+ _offboard_mission_item_count = new_count;
+}
+
+void
+Mission::set_onboard_mission_count(unsigned new_count)
+{
+ _onboard_mission_item_count = new_count;
+}
+
+void
+Mission::set_onboard_mission_allowed(bool allowed)
+{
+ _onboard_mission_allowed = allowed;
+}
+
+bool
+Mission::current_mission_available()
+{
+ return (current_onboard_mission_available() || current_offboard_mission_available());
+
+}
+
+bool
+Mission::next_mission_available()
+{
+ return (next_onboard_mission_available() || next_offboard_mission_available());
+}
+
+int
+Mission::get_current_mission_item(struct mission_item_s *new_mission_item, bool *onboard, unsigned *index)
+{
+ /* try onboard mission first */
+ if (current_onboard_mission_available()) {
+
+ const ssize_t len = sizeof(struct mission_item_s);
+ if (dm_read(DM_KEY_WAYPOINTS_ONBOARD, _current_onboard_mission_index, new_mission_item, len) != len) {
+ /* not supposed to happen unless the datamanager can't access the SD card, etc. */
+ return ERROR;
+ }
+ _current_mission_type = MISSION_TYPE_ONBOARD;
+ *onboard = true;
+ *index = _current_onboard_mission_index;
+
+ /* otherwise fallback to offboard */
+ } else if (current_offboard_mission_available()) {
+
+ dm_item_t dm_current;
+
+ if (_offboard_dataman_id == 0) {
+ dm_current = DM_KEY_WAYPOINTS_OFFBOARD_0;
+ } else {
+ dm_current = DM_KEY_WAYPOINTS_OFFBOARD_1;
+ }
+
+ const ssize_t len = sizeof(struct mission_item_s);
+ if (dm_read(dm_current, _current_offboard_mission_index, new_mission_item, len) != len) {
+ /* not supposed to happen unless the datamanager can't access the SD card, etc. */
+ _current_mission_type = MISSION_TYPE_NONE;
+ return ERROR;
+ }
+ _current_mission_type = MISSION_TYPE_OFFBOARD;
+ *onboard = false;
+ *index = _current_offboard_mission_index;
+
+ } else {
+ /* happens when no more mission items can be added as a next item */
+ _current_mission_type = MISSION_TYPE_NONE;
+ return ERROR;
+ }
+
+ return OK;
+}
+
+int
+Mission::get_next_mission_item(struct mission_item_s *new_mission_item)
+{
+ /* try onboard mission first */
+ if (next_onboard_mission_available()) {
+
+ const ssize_t len = sizeof(struct mission_item_s);
+ if (dm_read(DM_KEY_WAYPOINTS_ONBOARD, _current_onboard_mission_index + 1, new_mission_item, len) != len) {
+ /* not supposed to happen unless the datamanager can't access the SD card, etc. */
+ return ERROR;
+ }
+
+ /* otherwise fallback to offboard */
+ } else if (next_offboard_mission_available()) {
+
+ dm_item_t dm_current;
+
+ if (_offboard_dataman_id == 0) {
+ dm_current = DM_KEY_WAYPOINTS_OFFBOARD_0;
+ } else {
+ dm_current = DM_KEY_WAYPOINTS_OFFBOARD_1;
+ }
+
+ const ssize_t len = sizeof(struct mission_item_s);
+ if (dm_read(dm_current, _current_offboard_mission_index + 1, new_mission_item, len) != len) {
+ /* not supposed to happen unless the datamanager can't access the SD card, etc. */
+ return ERROR;
+ }
+
+ } else {
+ /* happens when no more mission items can be added as a next item */
+ return ERROR;
+ }
+
+ return OK;
+}
+
+
+bool
+Mission::current_onboard_mission_available()
+{
+ return _onboard_mission_item_count > _current_onboard_mission_index && _onboard_mission_allowed;
+}
+
+bool
+Mission::current_offboard_mission_available()
+{
+ return _offboard_mission_item_count > _current_offboard_mission_index;
+}
+
+bool
+Mission::next_onboard_mission_available()
+{
+ unsigned next = 0;
+
+ if (_current_mission_type != MISSION_TYPE_ONBOARD) {
+ next = 1;
+ }
+
+ return _onboard_mission_item_count > (_current_onboard_mission_index + next) && _onboard_mission_allowed;
+}
+
+bool
+Mission::next_offboard_mission_available()
+{
+ unsigned next = 0;
+
+ if (_current_mission_type != MISSION_TYPE_OFFBOARD) {
+ next = 1;
+ }
+
+ return _offboard_mission_item_count > (_current_offboard_mission_index + next);
+}
+
+void
+Mission::move_to_next()
+{
+ switch (_current_mission_type) {
+ case MISSION_TYPE_ONBOARD:
+ _current_onboard_mission_index++;
+ break;
+ case MISSION_TYPE_OFFBOARD:
+ _current_offboard_mission_index++;
+ break;
+ case MISSION_TYPE_NONE:
+ default:
+ break;
+ }
+} \ No newline at end of file
diff --git a/src/modules/navigator/navigator_mission.h b/src/modules/navigator/navigator_mission.h
new file mode 100644
index 000000000..15d4e86bf
--- /dev/null
+++ b/src/modules/navigator/navigator_mission.h
@@ -0,0 +1,97 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ * Author: @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
+ * 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_mission.h
+ * Helper class to access missions
+ */
+
+#ifndef NAVIGATOR_MISSION_H
+#define NAVIGATOR_MISSION_H
+
+#include <uORB/topics/mission.h>
+
+
+class __EXPORT Mission
+{
+public:
+ /**
+ * Constructor
+ */
+ Mission();
+
+ /**
+ * Destructor, also kills the sensors task.
+ */
+ ~Mission();
+
+ void set_offboard_dataman_id(int new_id);
+ void set_current_offboard_mission_index(int new_index);
+ void set_current_onboard_mission_index(int new_index);
+ void set_offboard_mission_count(unsigned new_count);
+ void set_onboard_mission_count(unsigned new_count);
+
+ void set_onboard_mission_allowed(bool allowed);
+
+ bool current_mission_available();
+ bool next_mission_available();
+
+ int get_current_mission_item(struct mission_item_s *mission_item, bool *onboard, unsigned *index);
+ int get_next_mission_item(struct mission_item_s *mission_item);
+
+ void move_to_next();
+
+ void add_home_pos(struct mission_item_s *new_mission_item);
+
+private:
+ bool current_onboard_mission_available();
+ bool current_offboard_mission_available();
+ bool next_onboard_mission_available();
+ bool next_offboard_mission_available();
+
+ int _offboard_dataman_id;
+ unsigned _current_offboard_mission_index;
+ unsigned _current_onboard_mission_index;
+ unsigned _offboard_mission_item_count; /** number of offboard mission items available */
+ unsigned _onboard_mission_item_count; /** number of onboard mission items available */
+
+ bool _onboard_mission_allowed;
+
+ enum {
+ MISSION_TYPE_NONE,
+ MISSION_TYPE_ONBOARD,
+ MISSION_TYPE_OFFBOARD,
+ } _current_mission_type;
+};
+
+#endif \ No newline at end of file
diff --git a/src/modules/navigator/navigator_params.c b/src/modules/navigator/navigator_params.c
index 06df9a452..8df47fc3b 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,10 @@
*
*/
-PARAM_DEFINE_FLOAT(NAV_DUMMY, 0.0f);
-
+PARAM_DEFINE_FLOAT(NAV_MIN_ALT, 50.0f);
+PARAM_DEFINE_FLOAT(NAV_ACCEPT_RAD, 10.0f);
+PARAM_DEFINE_FLOAT(NAV_LOITER_RAD, 100.0f);
+PARAM_DEFINE_INT32(NAV_ONB_MIS_EN, 0);
+PARAM_DEFINE_FLOAT(NAV_TAAKEOFF_ALT, 10.0f); // default TAKEOFF altitude
+PARAM_DEFINE_FLOAT(NAV_LAND_ALT, 5.0f); // slow descend from this altitude when landing
+PARAM_DEFINE_FLOAT(NAV_RTL_ALT, 30.0f); // min altitude for going home in RTL mode
diff --git a/src/modules/position_estimator_inav/position_estimator_inav_main.c b/src/modules/position_estimator_inav/position_estimator_inav_main.c
index 3084b6d92..5bf0fba30 100644
--- a/src/modules/position_estimator_inav/position_estimator_inav_main.c
+++ b/src/modules/position_estimator_inav/position_estimator_inav_main.c
@@ -614,8 +614,8 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
if (local_pos.xy_global) {
double est_lat, est_lon;
map_projection_reproject(local_pos.x, local_pos.y, &est_lat, &est_lon);
- global_pos.lat = (int32_t)(est_lat * 1e7);
- global_pos.lon = (int32_t)(est_lon * 1e7);
+ global_pos.lat = (int32_t)(est_lat * 1e7d);
+ global_pos.lon = (int32_t)(est_lon * 1e7d);
global_pos.time_gps_usec = gps.time_gps_usec;
}
diff --git a/src/modules/px4iofirmware/registers.c b/src/modules/px4iofirmware/registers.c
index ad4473073..0e704a360 100644
--- a/src/modules/px4iofirmware/registers.c
+++ b/src/modules/px4iofirmware/registers.c
@@ -601,7 +601,7 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
if (conf[PX4IO_P_RC_CONFIG_ASSIGNMENT] == UINT8_MAX) {
disabled = true;
- } else if ((int)(conf[PX4IO_P_RC_CONFIG_ASSIGNMENT]) < 0 || conf[PX4IO_P_RC_CONFIG_ASSIGNMENT] >= PX4IO_RC_MAPPED_CONTROL_CHANNELS) {
+ } else if (REG_TO_SIGNED(conf[PX4IO_P_RC_CONFIG_ASSIGNMENT]) < 0 || conf[PX4IO_P_RC_CONFIG_ASSIGNMENT] >= PX4IO_RC_MAPPED_CONTROL_CHANNELS) {
count++;
}
diff --git a/src/modules/px4iofirmware/safety.c b/src/modules/px4iofirmware/safety.c
index cdb54a80a..83bd3026e 100644
--- a/src/modules/px4iofirmware/safety.c
+++ b/src/modules/px4iofirmware/safety.c
@@ -45,7 +45,6 @@
#include "px4io.h"
static struct hrt_call arming_call;
-static struct hrt_call heartbeat_call;
static struct hrt_call failsafe_call;
/*
diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c
index 06b1eddaa..e16cadd29 100644
--- a/src/modules/sdlog2/sdlog2.c
+++ b/src/modules/sdlog2/sdlog2.c
@@ -62,6 +62,7 @@
#include <uORB/uORB.h>
#include <uORB/topics/vehicle_status.h>
+#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/sensor_combined.h>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_attitude_setpoint.h>
@@ -72,7 +73,7 @@
#include <uORB/topics/vehicle_local_position.h>
#include <uORB/topics/vehicle_local_position_setpoint.h>
#include <uORB/topics/vehicle_global_position.h>
-#include <uORB/topics/vehicle_global_position_setpoint.h>
+#include <uORB/topics/mission_item_triplet.h>
#include <uORB/topics/vehicle_gps_position.h>
#include <uORB/topics/vehicle_vicon_position.h>
#include <uORB/topics/vehicle_global_velocity_setpoint.h>
@@ -684,6 +685,7 @@ int sdlog2_thread_main(int argc, char *argv[])
/* warning! using union here to save memory, elements should be used separately! */
union {
struct vehicle_command_s cmd;
+ struct vehicle_control_mode_s control_mode;
struct sensor_combined_s sensor;
struct vehicle_attitude_s att;
struct vehicle_attitude_setpoint_s att_sp;
@@ -693,7 +695,7 @@ int sdlog2_thread_main(int argc, char *argv[])
struct vehicle_local_position_s local_pos;
struct vehicle_local_position_setpoint_s local_pos_sp;
struct vehicle_global_position_s global_pos;
- struct vehicle_global_position_setpoint_s global_pos_sp;
+ struct mission_item_triplet_s triplet;
struct vehicle_gps_position_s gps_pos;
struct vehicle_vicon_position_s vicon_pos;
struct optical_flow_s flow;
@@ -710,6 +712,7 @@ int sdlog2_thread_main(int argc, char *argv[])
struct {
int cmd_sub;
int status_sub;
+ int control_mode_sub;
int sensor_sub;
int att_sub;
int att_sp_sub;
@@ -719,7 +722,7 @@ int sdlog2_thread_main(int argc, char *argv[])
int local_pos_sub;
int local_pos_sp_sub;
int global_pos_sub;
- int global_pos_sp_sub;
+ int triplet_sub;
int gps_pos_sub;
int vicon_pos_sub;
int flow_sub;
@@ -782,6 +785,12 @@ int sdlog2_thread_main(int argc, char *argv[])
fds[fdsc_count].events = POLLIN;
fdsc_count++;
+ /* --- VEHICLE CONTROL MODE --- */
+ subs.control_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode));
+ fds[fdsc_count].fd = subs.control_mode_sub;
+ fds[fdsc_count].events = POLLIN;
+ fdsc_count++;
+
/* --- GPS POSITION --- */
subs.gps_pos_sub = orb_subscribe(ORB_ID(vehicle_gps_position));
fds[fdsc_count].fd = subs.gps_pos_sub;
@@ -843,8 +852,8 @@ int sdlog2_thread_main(int argc, char *argv[])
fdsc_count++;
/* --- GLOBAL POSITION SETPOINT--- */
- subs.global_pos_sp_sub = orb_subscribe(ORB_ID(vehicle_global_position_setpoint));
- fds[fdsc_count].fd = subs.global_pos_sp_sub;
+ subs.triplet_sub = orb_subscribe(ORB_ID(mission_item_triplet));
+ fds[fdsc_count].fd = subs.triplet_sub;
fds[fdsc_count].events = POLLIN;
fdsc_count++;
@@ -975,16 +984,21 @@ int sdlog2_thread_main(int argc, char *argv[])
/* --- VEHICLE STATUS --- */
if (fds[ifds++].revents & POLLIN) {
- // Don't orb_copy, it's already done few lines above
+ /* don't orb_copy, it's already done few lines above */
+ /* copy control mode here to construct STAT message */
+ if (fds[ifds].revents & POLLIN) {
+ orb_copy(ORB_ID(vehicle_control_mode), subs.control_mode_sub, &buf.control_mode);
+ }
log_msg.msg_type = LOG_STAT_MSG;
- log_msg.body.log_STAT.main_state = (uint8_t) buf_status.main_state;
- log_msg.body.log_STAT.navigation_state = (uint8_t) buf_status.navigation_state;
+ log_msg.body.log_STAT.main_state = (uint8_t) buf.control_mode.main_state;
+ log_msg.body.log_STAT.navigation_state = (uint8_t) buf.control_mode.nav_state;
log_msg.body.log_STAT.arming_state = (uint8_t) buf_status.arming_state;
log_msg.body.log_STAT.battery_remaining = buf_status.battery_remaining;
log_msg.body.log_STAT.battery_warning = (uint8_t) buf_status.battery_warning;
log_msg.body.log_STAT.landed = (uint8_t) buf_status.condition_landed;
LOGBUFFER_WRITE_AND_COUNT(STAT);
}
+ ifds++; // skip CONTROL MODE, already copied
/* --- GPS POSITION --- */
if (fds[ifds++].revents & POLLIN) {
@@ -1157,20 +1171,19 @@ int sdlog2_thread_main(int argc, char *argv[])
/* --- GLOBAL POSITION SETPOINT --- */
if (fds[ifds++].revents & POLLIN) {
- orb_copy(ORB_ID(vehicle_global_position_setpoint), subs.global_pos_sp_sub, &buf.global_pos_sp);
+ orb_copy(ORB_ID(mission_item_triplet), subs.triplet_sub, &buf.triplet);
log_msg.msg_type = LOG_GPSP_MSG;
- log_msg.body.log_GPSP.altitude_is_relative = buf.global_pos_sp.altitude_is_relative;
- log_msg.body.log_GPSP.lat = buf.global_pos_sp.lat;
- log_msg.body.log_GPSP.lon = buf.global_pos_sp.lon;
- log_msg.body.log_GPSP.altitude = buf.global_pos_sp.altitude;
- log_msg.body.log_GPSP.yaw = buf.global_pos_sp.yaw;
- log_msg.body.log_GPSP.loiter_radius = buf.global_pos_sp.loiter_radius;
- log_msg.body.log_GPSP.loiter_direction = buf.global_pos_sp.loiter_direction;
- log_msg.body.log_GPSP.nav_cmd = buf.global_pos_sp.nav_cmd;
- log_msg.body.log_GPSP.param1 = buf.global_pos_sp.param1;
- log_msg.body.log_GPSP.param2 = buf.global_pos_sp.param2;
- log_msg.body.log_GPSP.param3 = buf.global_pos_sp.param3;
- log_msg.body.log_GPSP.param4 = buf.global_pos_sp.param4;
+ log_msg.body.log_GPSP.altitude_is_relative = buf.triplet.current.altitude_is_relative;
+ log_msg.body.log_GPSP.lat = (int32_t)(buf.triplet.current.lat * 1e7d);
+ log_msg.body.log_GPSP.lon = (int32_t)(buf.triplet.current.lon * 1e7d);
+ log_msg.body.log_GPSP.altitude = buf.triplet.current.altitude;
+ log_msg.body.log_GPSP.yaw = buf.triplet.current.yaw;
+ log_msg.body.log_GPSP.nav_cmd = buf.triplet.current.nav_cmd;
+ log_msg.body.log_GPSP.loiter_radius = buf.triplet.current.loiter_radius;
+ log_msg.body.log_GPSP.loiter_direction = buf.triplet.current.loiter_direction;
+ log_msg.body.log_GPSP.acceptance_radius = buf.triplet.current.acceptance_radius;
+ log_msg.body.log_GPSP.time_inside = buf.triplet.current.time_inside;
+ log_msg.body.log_GPSP.pitch_min = buf.triplet.current.pitch_min;
LOGBUFFER_WRITE_AND_COUNT(GPSP);
}
diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h
index a784a1f30..d80027cbf 100644
--- a/src/modules/sdlog2/sdlog2_messages.h
+++ b/src/modules/sdlog2/sdlog2_messages.h
@@ -212,13 +212,12 @@ struct log_GPSP_s {
int32_t lon;
float altitude;
float yaw;
+ uint8_t nav_cmd;
float loiter_radius;
int8_t loiter_direction;
- uint8_t nav_cmd;
- float param1;
- float param2;
- float param3;
- float param4;
+ float acceptance_radius;
+ float time_inside;
+ float pitch_min;
};
/* --- ESC - ESC STATE --- */
@@ -295,7 +294,7 @@ static const struct log_format_s log_formats[] = {
LOG_FORMAT(ARSP, "fff", "RollRateSP,PitchRateSP,YawRateSP"),
LOG_FORMAT(FLOW, "hhfffBB", "RawX,RawY,CompX,CompY,Dist,Q,SensID"),
LOG_FORMAT(GPOS, "LLffff", "Lat,Lon,Alt,VelN,VelE,VelD"),
- LOG_FORMAT(GPSP, "BLLfffbBffff", "AltRel,Lat,Lon,Alt,Yaw,LoiterR,LoiterDir,NavCmd,P1,P2,P3,P4"),
+ LOG_FORMAT(GPSP, "BLLffBfbfff", "AltRel,Lat,Lon,Alt,Yaw,NavCmd,LoitR,LoitDir,AccR,TimeIn,PitMin"),
LOG_FORMAT(ESC, "HBBBHHHHHHfH", "Counter,NumESC,Conn,N,Ver,Adr,Volt,Amp,RPM,Temp,SetP,SetPRAW"),
LOG_FORMAT(GVSP, "fff", "VX,VY,VZ"),
LOG_FORMAT(BATT, "ffff", "V,VFilt,C,Discharged"),
diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp
index ff6c5882e..c78b9b361 100644
--- a/src/modules/sensors/sensors.cpp
+++ b/src/modules/sensors/sensors.cpp
@@ -1404,18 +1404,6 @@ Sensors::rc_poll()
manual_control.yaw *= _parameters.rc_scale_yaw;
}
- /* mode switch input */
- manual_control.mode_switch = limit_minus_one_to_one(_rc.chan[_rc.function[MODE]].scaled);
-
- /* land switch input */
- manual_control.return_switch = limit_minus_one_to_one(_rc.chan[_rc.function[RETURN]].scaled);
-
- /* assisted switch input */
- manual_control.assisted_switch = limit_minus_one_to_one(_rc.chan[_rc.function[ASSISTED]].scaled);
-
- /* mission switch input */
- manual_control.mission_switch = limit_minus_one_to_one(_rc.chan[_rc.function[MISSION]].scaled);
-
/* flaps */
if (_rc.function[FLAPS] >= 0) {
@@ -1426,14 +1414,26 @@ Sensors::rc_poll()
}
}
+ /* mode switch input */
if (_rc.function[MODE] >= 0) {
manual_control.mode_switch = limit_minus_one_to_one(_rc.chan[_rc.function[MODE]].scaled);
}
+ /* assisted switch input */
+ if (_rc.function[ASSISTED] >= 0) {
+ manual_control.assisted_switch = limit_minus_one_to_one(_rc.chan[_rc.function[ASSISTED]].scaled);
+ }
+
+ /* mission switch input */
if (_rc.function[MISSION] >= 0) {
manual_control.mission_switch = limit_minus_one_to_one(_rc.chan[_rc.function[MISSION]].scaled);
}
+ /* return switch input */
+ if (_rc.function[RETURN] >= 0) {
+ manual_control.return_switch = limit_minus_one_to_one(_rc.chan[_rc.function[RETURN]].scaled);
+ }
+
// if (_rc.function[OFFBOARD_MODE] >= 0) {
// manual_control.auto_offboard_input_switch = limit_minus_one_to_one(_rc.chan[_rc.function[OFFBOARD_MODE]].scaled);
// }
diff --git a/src/modules/systemlib/mixer/mixer.cpp b/src/modules/systemlib/mixer/mixer.cpp
index cce46bf5f..20b1f18ed 100644
--- a/src/modules/systemlib/mixer/mixer.cpp
+++ b/src/modules/systemlib/mixer/mixer.cpp
@@ -171,7 +171,6 @@ NullMixer *
NullMixer::from_text(const char *buf, unsigned &buflen)
{
NullMixer *nm = nullptr;
- const char *end = buf + buflen;
/* enforce that the mixer ends with space or a new line */
for (int i = buflen - 1; i >= 0; i--) {
diff --git a/src/modules/systemlib/state_table.h b/src/modules/systemlib/state_table.h
new file mode 100644
index 000000000..f2709d29f
--- /dev/null
+++ b/src/modules/systemlib/state_table.h
@@ -0,0 +1,75 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file state_table.h
+ *
+ * Finite-State-Machine helper class for state table
+ */
+
+#ifndef __SYSTEMLIB_STATE_TABLE_H
+#define __SYSTEMLIB_STATE_TABLE_H
+
+class StateTable
+{
+public:
+ typedef void (StateTable::*Action)();
+ struct Tran {
+ Action action;
+ unsigned nextState;
+ };
+
+ StateTable(Tran const *table, unsigned nStates, unsigned nSignals)
+ : myTable(table), myNsignals(nSignals), myNstates(nStates) {}
+
+ #define NO_ACTION &StateTable::doNothing
+ #define ACTION(_target) static_cast<StateTable::Action>(_target)
+
+ virtual ~StateTable() {}
+
+ void dispatch(unsigned const sig) {
+ register Tran const *t = myTable + myState*myNsignals + sig;
+ (this->*(t->action))();
+
+ myState = t->nextState;
+ }
+ void doNothing() {}
+protected:
+ unsigned myState;
+private:
+ Tran const *myTable;
+ unsigned myNsignals;
+ unsigned myNstates;
+};
+
+#endif \ No newline at end of file
diff --git a/src/modules/uORB/objects_common.cpp b/src/modules/uORB/objects_common.cpp
index c6a252b55..79a820c06 100644
--- a/src/modules/uORB/objects_common.cpp
+++ b/src/modules/uORB/objects_common.cpp
@@ -117,17 +117,21 @@ ORB_DEFINE(vehicle_local_position_setpoint, struct vehicle_local_position_setpoi
#include "topics/vehicle_bodyframe_speed_setpoint.h"
ORB_DEFINE(vehicle_bodyframe_speed_setpoint, struct vehicle_bodyframe_speed_setpoint_s);
-#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/vehicle_global_position_setpoint.h b/src/modules/uORB/topics/fence.h
index a56434d3b..6f16c51cf 100644
--- a/src/modules/uORB/topics/vehicle_global_position_setpoint.h
+++ b/src/modules/uORB/topics/fence.h
@@ -1,9 +1,7 @@
/****************************************************************************
*
* 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>
+ * 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
@@ -35,45 +33,41 @@
****************************************************************************/
/**
- * @file vehicle_global_position_setpoint.h
- * Definition of the global WGS84 position setpoint uORB topic.
+ * @file fence.h
+ * Definition of geofence.
*/
-#ifndef TOPIC_VEHICLE_GLOBAL_POSITION_SETPOINT_H_
-#define TOPIC_VEHICLE_GLOBAL_POSITION_SETPOINT_H_
+#ifndef TOPIC_FENCE_H_
+#define TOPIC_FENCE_H_
#include <stdint.h>
#include <stdbool.h>
#include "../uORB.h"
-#include "mission.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 */
+};
+
/**
- * Global position setpoint in WGS84 coordinates.
+ * This is the position of a geofence
*
- * This is the position the MAV is heading towards. If it of type loiter,
- * the MAV is circling around it with the given loiter radius in meters.
*/
-struct vehicle_global_position_setpoint_s
-{
- bool altitude_is_relative; /**< true if altitude is relative from start point */
- int32_t lat; /**< latitude in degrees * 1E7 */
- int32_t lon; /**< longitude in degrees * 1E7 */
- 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 */
- int8_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;
- float turn_distance_xy; /**< The distance on the plane which will mark this as reached */
- float turn_distance_z; /**< The distance in Z direction which will mark this as reached */
+struct fence_s {
+ unsigned count; /**< number of actual vertices */
+ struct fence_vertex_s vertices[GEOFENCE_MAX_VERTICES];
};
/**
@@ -81,6 +75,6 @@ struct vehicle_global_position_setpoint_s
*/
/* register this as object request broker structure */
-ORB_DECLARE(vehicle_global_position_setpoint);
+ORB_DECLARE(fence);
#endif
diff --git a/src/modules/uORB/topics/home_position.h b/src/modules/uORB/topics/home_position.h
index 7e1b82a0f..3e2fee84e 100644
--- a/src/modules/uORB/topics/home_position.h
+++ b/src/modules/uORB/topics/home_position.h
@@ -2,6 +2,7 @@
*
* Copyright (C) 2012-2013 PX4 Development Team. All rights reserved.
* Author: Lorenz Meier <lm@inf.ethz.ch>
+ * 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
@@ -34,9 +35,10 @@
/**
* @file home_position.h
- * Definition of the GPS home position uORB topic.
+ * Definition of the home position uORB topic.
*
* @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
*/
#ifndef TOPIC_HOME_POSITION_H_
@@ -55,16 +57,12 @@
*/
struct home_position_s
{
- uint64_t timestamp; /**< Timestamp (microseconds since system boot) */
- uint64_t time_gps_usec; /**< Timestamp (microseconds in GPS format), this is the timestamp from the gps module */
-
- int32_t lat; /**< Latitude in 1E7 degrees */
- int32_t lon; /**< Longitude in 1E7 degrees */
- int32_t alt; /**< Altitude in 1E3 meters (millimeters) above MSL */
- float eph_m; /**< GPS HDOP horizontal dilution of position in m */
- float epv_m; /**< GPS VDOP horizontal dilution of position in m */
- float s_variance_m_s; /**< speed accuracy estimate m/s */
- float p_variance_m; /**< position accuracy estimate m */
+ uint64_t timestamp; /**< Timestamp (microseconds since system boot) */
+
+ //bool altitude_is_relative; // TODO what means home relative altitude? we need clear definition of reference altitude then
+ double lat; /**< Latitude in degrees */
+ double lon; /**< Longitude in degrees */
+ float altitude; /**< Altitude in meters */
};
/**
diff --git a/src/modules/uORB/topics/mission.h b/src/modules/uORB/topics/mission.h
index 978a3383a..194e2ed0c 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,24 @@
#include <stdbool.h>
#include "../uORB.h"
+#define NUM_MISSIONS_SUPPORTED 256
+
+/* 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
+};
+
+enum ORIGIN {
+ ORIGIN_MAVLINK = 0,
+ ORIGIN_ONBOARD
};
/**
@@ -70,23 +80,25 @@ enum NAV_CMD {
struct mission_item_s
{
bool altitude_is_relative; /**< true if altitude is relative from start point */
- double lat; /**< latitude in degrees * 1E7 */
- double lon; /**< longitude in degrees * 1E7 */
+ double lat; /**< latitude in degrees */
+ double lon; /**< longitude in degrees */
float altitude; /**< altitude in meters */
- float yaw; /**< in radians NED -PI..+PI */
+ float yaw; /**< in radians NED -PI..+PI, NAN means don't change yaw */
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 acceptance_radius; /**< default 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 */
+ float pitch_min; /**< minimal pitch angle for fixed wing takeoff waypoints */
+ bool autocontinue; /**< true if next waypoint should follow after this one */
+ enum ORIGIN origin; /**< where the waypoint has been generated */
};
struct mission_s
{
- struct mission_item_s *items;
- unsigned count;
+ int dataman_id; /**< default -1, there are two offboard storage places in the dataman: 0 or 1 */
+ unsigned count; /**< count of the missions stored in the datamanager */
+ int current_index; /**< default -1, start at the one changed latest */
};
/**
@@ -95,5 +107,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/mavlink/missionlib.h b/src/modules/uORB/topics/mission_result.h
index c7d8f90c5..c99706b97 100644
--- a/src/modules/mavlink/missionlib.h
+++ b/src/modules/uORB/topics/mission_result.h
@@ -1,7 +1,9 @@
/****************************************************************************
*
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: @author Lorenz Meier <lm@inf.ethz.ch>
+ * 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
@@ -33,20 +35,33 @@
****************************************************************************/
/**
- * @file missionlib.h
- * MAVLink mission helper library
+ * @file mission_result.h
+ * Mission results that navigator needs to pass on to commander and mavlink.
*/
-#pragma once
+#ifndef TOPIC_MISSION_RESULT_H
+#define TOPIC_MISSION_RESULT_H
-#include "mavlink_bridge_header.h"
+#include <stdint.h>
+#include <stdbool.h>
+#include "../uORB.h"
-//extern void mavlink_wpm_send_message(mavlink_message_t *msg);
-//extern void mavlink_wpm_send_gcs_string(const char *string);
-//extern uint64_t mavlink_wpm_get_system_timestamp(void);
-extern int mavlink_missionlib_send_message(mavlink_message_t *msg);
-extern int mavlink_missionlib_send_gcs_string(const char *string);
-extern uint64_t mavlink_missionlib_get_system_timestamp(void);
-extern void mavlink_missionlib_current_waypoint_changed(uint16_t index, float param1,
- float param2, float param3, float param4, float param5_lat_x,
- float param6_lon_y, float param7_alt_z, uint8_t frame, uint16_t command);
+/**
+ * @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/navigation_capabilities.h b/src/modules/uORB/topics/navigation_capabilities.h
index 6a3e811e3..391756f99 100644
--- a/src/modules/uORB/topics/navigation_capabilities.h
+++ b/src/modules/uORB/topics/navigation_capabilities.h
@@ -53,6 +53,11 @@
*/
struct navigation_capabilities_s {
float turn_distance; /**< the optimal distance to a waypoint to switch to the next */
+
+ /* Landing parameters: see fw_pos_control_l1/landingslope.h */
+ float landing_horizontal_slope_displacement;
+ float landing_slope_angle_rad;
+ float landing_flare_length;
};
/**
diff --git a/src/modules/uORB/topics/vehicle_control_mode.h b/src/modules/uORB/topics/vehicle_control_mode.h
index 38fb74c9b..26dcbd985 100644
--- a/src/modules/uORB/topics/vehicle_control_mode.h
+++ b/src/modules/uORB/topics/vehicle_control_mode.h
@@ -48,6 +48,7 @@
#include <stdint.h>
#include <stdbool.h>
#include "../uORB.h"
+#include "vehicle_status.h"
/**
* @addtogroup topics @{
@@ -59,10 +60,23 @@
*
* Encodes the complete system state and is set by the commander app.
*/
+
+typedef enum {
+ NAV_STATE_NONE = 0,
+ NAV_STATE_READY,
+ NAV_STATE_LOITER,
+ NAV_STATE_MISSION,
+ NAV_STATE_RTL,
+ NAV_STATE_MAX
+} nav_state_t;
+
struct vehicle_control_mode_s
{
uint64_t timestamp; /**< in microseconds since system start, is set whenever the writing thread stores new data */
+ main_state_t main_state;
+ nav_state_t nav_state;
+
bool flag_armed;
bool flag_external_manual_override_ok; /**< external override non-fatal for system. Only true for fixed wing */
@@ -78,9 +92,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_auto_enabled; // TEMP
- uint8_t auto_state; // TEMP navigation state for AUTO modes
+ bool flag_control_flighttermination_enabled; /**< true if flighttermination is enabled */
};
/**
diff --git a/src/modules/uORB/topics/vehicle_status.h b/src/modules/uORB/topics/vehicle_status.h
index 1c184d3a7..1a9dec5f5 100644
--- a/src/modules/uORB/topics/vehicle_status.h
+++ b/src/modules/uORB/topics/vehicle_status.h
@@ -66,20 +66,6 @@ typedef enum {
MAIN_STATE_AUTO,
} main_state_t;
-/* navigation state machine */
-typedef enum {
- NAVIGATION_STATE_DIRECT = 0, // true manual control, no any stabilization
- NAVIGATION_STATE_STABILIZE, // attitude stabilization
- NAVIGATION_STATE_ALTHOLD, // attitude + altitude stabilization
- NAVIGATION_STATE_VECTOR, // attitude + altitude + position stabilization
- NAVIGATION_STATE_AUTO_READY, // AUTO, landed, reeady for takeoff
- NAVIGATION_STATE_AUTO_TAKEOFF, // detect takeoff using land detector and switch to desired AUTO mode
- NAVIGATION_STATE_AUTO_LOITER, // pause mission
- NAVIGATION_STATE_AUTO_MISSION, // fly mission
- NAVIGATION_STATE_AUTO_RTL, // Return To Launch, when home position switch to LAND
- NAVIGATION_STATE_AUTO_LAND // land and switch to AUTO_READY when landed (detect using land detector)
-} navigation_state_t;
-
typedef enum {
ARMING_STATE_INIT = 0,
ARMING_STATE_STANDBY,
@@ -96,6 +82,11 @@ typedef enum {
} hil_state_t;
typedef enum {
+ FLIGHTTERMINATION_STATE_OFF = 0,
+ FLIGHTTERMINATION_STATE_ON
+} flighttermination_state_t;
+
+typedef enum {
MODE_SWITCH_MANUAL = 0,
MODE_SWITCH_ASSISTED,
MODE_SWITCH_AUTO
@@ -108,11 +99,13 @@ typedef enum {
typedef enum {
RETURN_SWITCH_NONE = 0,
+ RETURN_SWITCH_NORMAL,
RETURN_SWITCH_RETURN
} return_switch_pos_t;
typedef enum {
MISSION_SWITCH_NONE = 0,
+ MISSION_SWITCH_LOITER,
MISSION_SWITCH_MISSION
} mission_switch_pos_t;
@@ -176,7 +169,8 @@ struct vehicle_status_s
uint64_t timestamp; /**< in microseconds since system start, is set whenever the writing thread stores new data */
main_state_t main_state; /**< main state machine */
- navigation_state_t navigation_state; /**< navigation state machine */
+ unsigned int set_nav_state; /**< set navigation state machine to specified value */
+ uint64_t set_nav_state_timestamp; /**< timestamp of latest change of set_nav_state */
arming_state_t arming_state; /**< current arming state */
hil_state_t hil_state; /**< current hil state */
@@ -229,6 +223,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/preflight_check/preflight_check.c b/src/systemcmds/preflight_check/preflight_check.c
index 982b03782..86e4ff545 100644
--- a/src/systemcmds/preflight_check/preflight_check.c
+++ b/src/systemcmds/preflight_check/preflight_check.c
@@ -44,6 +44,7 @@
#include <string.h>
#include <fcntl.h>
#include <errno.h>
+#include <math.h>
#include <systemlib/err.h>
#include <systemlib/param/param.h>
@@ -87,9 +88,7 @@ int preflight_check_main(int argc, char *argv[])
/* give the system some time to sample the sensors in the background */
usleep(150000);
-
/* ---- MAG ---- */
- close(fd);
fd = open(MAG_DEVICE_PATH, 0);
if (fd < 0) {
warn("failed to open magnetometer - start with 'hmc5883 start' or 'lsm303d start'");
diff --git a/src/systemcmds/tests/test_dataman.c b/src/systemcmds/tests/test_dataman.c
new file mode 100644
index 000000000..5b121e34e
--- /dev/null
+++ b/src/systemcmds/tests/test_dataman.c
@@ -0,0 +1,182 @@
+/****************************************************************************
+ * 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 < NUM_MISSIONS_SUPPORTED; i++) {
+ memset(buffer, my_id, sizeof(buffer));
+ buffer[1] = i;
+ unsigned hash = i ^ my_id;
+ unsigned len = (hash & 63) + 2;
+
+ int ret = dm_write(DM_KEY_WAYPOINTS_OFFBOARD, hash, DM_PERSIST_IN_FLIGHT_RESET, buffer, len);
+ warnx("ret: %d", ret);
+ if (ret != 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 < NUM_MISSIONS_SUPPORTED; i++) {
+ unsigned hash = i ^ my_id;
+ unsigned len2, len = (hash & 63) + 2;
+ if ((len2 = dm_read(DM_KEY_WAYPOINTS_OFFBOARD, 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) / NUM_MISSIONS_SUPPORTED / 1000, (wend - wstart) / NUM_MISSIONS_SUPPORTED / 1000);
+ 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 < NUM_MISSIONS_SUPPORTED; i++) {
+ if (dm_read(DM_KEY_WAYPOINTS_OFFBOARD, i, buffer, sizeof(buffer)) != 0)
+ break;
+ }
+ if (i >= NUM_MISSIONS_SUPPORTED) {
+ warnx("Restart in-flight failed");
+ return -1;
+
+ }
+ dm_restart(DM_INIT_REASON_POWER_ON);
+ for (i = 0; i < NUM_MISSIONS_SUPPORTED; i++) {
+ if (dm_read(DM_KEY_WAYPOINTS_OFFBOARD, i, buffer, sizeof(buffer)) != 0) {
+ warnx("Restart power-on failed");
+ return -1;
+ }
+ }
+ return 0;
+}