aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2014-10-07 10:02:01 +0200
committerThomas Gubler <thomasgubler@gmail.com>2014-10-07 10:02:01 +0200
commitb64e675d5354c32d746a61399e2c9bcb573f2f4b (patch)
treec5597929745c8ba03e4fefbb70949f066ad887c3
parentebc84b9f44dd3d26bc8d26b18f8c059f900e5e1a (diff)
parent5d52978bc780707d63c1422369842629d26fb1e2 (diff)
downloadpx4-firmware-b64e675d5354c32d746a61399e2c9bcb573f2f4b.tar.gz
px4-firmware-b64e675d5354c32d746a61399e2c9bcb573f2f4b.tar.bz2
px4-firmware-b64e675d5354c32d746a61399e2c9bcb573f2f4b.zip
Merge remote-tracking branch 'upstream/master' into swissfang
-rw-r--r--ROMFS/px4fmu_test/init.d/rcS30
-rw-r--r--makefiles/config_px4fmu-v2_test.mk1
-rw-r--r--src/modules/commander/commander_tests/commander_tests.cpp4
-rw-r--r--src/modules/commander/commander_tests/state_machine_helper_test.cpp13
-rw-r--r--src/modules/commander/commander_tests/state_machine_helper_test.h2
-rw-r--r--src/modules/dataman/module.mk2
-rw-r--r--src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp2
-rw-r--r--src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp132
-rw-r--r--src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c26
-rw-r--r--src/modules/mavlink/mavlink_ftp.cpp278
-rw-r--r--src/modules/mavlink/mavlink_ftp.h14
-rw-r--r--src/modules/mavlink/mavlink_tests/mavlink_ftp_test.cpp20
-rw-r--r--src/modules/mavlink/mavlink_tests/mavlink_ftp_test.h9
-rw-r--r--src/modules/mavlink/mavlink_tests/mavlink_tests.cpp7
-rw-r--r--src/modules/mavlink/mavlink_tests/module.mk2
-rw-r--r--src/modules/mc_pos_control/mc_pos_control_main.cpp248
-rw-r--r--src/modules/navigator/mission.cpp97
-rw-r--r--src/modules/navigator/mission.h17
-rw-r--r--src/modules/navigator/module.mk2
-rw-r--r--src/modules/unit_test/unit_test.cpp24
-rw-r--r--src/modules/unit_test/unit_test.h125
21 files changed, 769 insertions, 286 deletions
diff --git a/ROMFS/px4fmu_test/init.d/rcS b/ROMFS/px4fmu_test/init.d/rcS
index 56482d140..bc248ac04 100644
--- a/ROMFS/px4fmu_test/init.d/rcS
+++ b/ROMFS/px4fmu_test/init.d/rcS
@@ -75,3 +75,33 @@ if [ -f /fs/microsd/mount_test_cmds.txt ]
then
tests mount
fi
+
+#
+# Run unit tests at board boot, reporting failure as needed.
+# Add new unit tests using the same pattern as below.
+#
+
+set unit_test_failure 0
+
+if mavlink_tests
+then
+else
+ set unit_test_failure 1
+ set unit_test_failure_list "${unit_test_failure_list} mavlink_tests"
+fi
+
+if commander_tests
+then
+else
+ set unit_test_failure 1
+ set unit_test_failure_list "${unit_test_failure_list} commander_tests"
+fi
+
+if [ $unit_test_failure == 0 ]
+then
+ echo
+ echo "All Unit Tests PASSED"
+else
+ echo
+ echo "Some Unit Tests FAILED:${unit_test_failure_list}"
+fi \ No newline at end of file
diff --git a/makefiles/config_px4fmu-v2_test.mk b/makefiles/config_px4fmu-v2_test.mk
index a41670a77..2f4d9d6a4 100644
--- a/makefiles/config_px4fmu-v2_test.mk
+++ b/makefiles/config_px4fmu-v2_test.mk
@@ -56,6 +56,7 @@ LIBRARIES += lib/mathlib/CMSIS
MODULES += modules/unit_test
MODULES += modules/mavlink/mavlink_tests
+MODULES += modules/commander/commander_tests
#
# Transitional support - add commands from the NuttX export archive.
diff --git a/src/modules/commander/commander_tests/commander_tests.cpp b/src/modules/commander/commander_tests/commander_tests.cpp
index 0abb84a82..2bfa5d0bb 100644
--- a/src/modules/commander/commander_tests/commander_tests.cpp
+++ b/src/modules/commander/commander_tests/commander_tests.cpp
@@ -48,7 +48,5 @@ extern "C" __EXPORT int commander_tests_main(int argc, char *argv[]);
int commander_tests_main(int argc, char *argv[])
{
- stateMachineHelperTest();
-
- return 0;
+ return stateMachineHelperTest() ? 0 : -1;
}
diff --git a/src/modules/commander/commander_tests/state_machine_helper_test.cpp b/src/modules/commander/commander_tests/state_machine_helper_test.cpp
index 08dda2fab..874090e93 100644
--- a/src/modules/commander/commander_tests/state_machine_helper_test.cpp
+++ b/src/modules/commander/commander_tests/state_machine_helper_test.cpp
@@ -49,7 +49,7 @@ public:
StateMachineHelperTest();
virtual ~StateMachineHelperTest();
- virtual void runTests(void);
+ virtual bool run_tests(void);
private:
bool armingStateTransitionTest();
@@ -488,16 +488,13 @@ bool StateMachineHelperTest::isSafeTest(void)
return true;
}
-void StateMachineHelperTest::runTests(void)
+bool StateMachineHelperTest::run_tests(void)
{
ut_run_test(armingStateTransitionTest);
ut_run_test(mainStateTransitionTest);
ut_run_test(isSafeTest);
+
+ return (_tests_failed == 0);
}
-void stateMachineHelperTest(void)
-{
- StateMachineHelperTest* test = new StateMachineHelperTest();
- test->runTests();
- test->printResults();
-}
+ut_declare_test(stateMachineHelperTest, StateMachineHelperTest) \ No newline at end of file
diff --git a/src/modules/commander/commander_tests/state_machine_helper_test.h b/src/modules/commander/commander_tests/state_machine_helper_test.h
index bbf66255e..cf6719095 100644
--- a/src/modules/commander/commander_tests/state_machine_helper_test.h
+++ b/src/modules/commander/commander_tests/state_machine_helper_test.h
@@ -39,6 +39,6 @@
#ifndef STATE_MACHINE_HELPER_TEST_H_
#define STATE_MACHINE_HELPER_TEST_
-void stateMachineHelperTest(void);
+bool stateMachineHelperTest(void);
#endif /* STATE_MACHINE_HELPER_TEST_H_ */
diff --git a/src/modules/dataman/module.mk b/src/modules/dataman/module.mk
index 234607b3d..7ebe09fb7 100644
--- a/src/modules/dataman/module.mk
+++ b/src/modules/dataman/module.mk
@@ -40,3 +40,5 @@ MODULE_COMMAND = dataman
SRCS = dataman.c
MODULE_STACKSIZE = 1200
+
+MAXOPTIMIZATION = -Os
diff --git a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp
index 97abb76a9..2c50e5c75 100644
--- a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp
+++ b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp
@@ -1369,7 +1369,7 @@ FixedwingEstimator::task_main()
if (newRangeData) {
_ekf->fuseRngData = true;
_ekf->useRangeFinder = true;
- _ekf->RecallStates(_ekf->statesAtRngTime, (IMUmsec - 500.0f));
+ _ekf->RecallStates(_ekf->statesAtRngTime, (IMUmsec - 100.0f));
_ekf->GroundEKF();
}
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 00b12fffa..6017369aa 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
@@ -88,7 +88,6 @@
#include <launchdetection/LaunchDetector.h>
#include <ecl/l1/ecl_l1_pos_controller.h>
#include <external_lgpl/tecs/tecs.h>
-#include <drivers/drv_range_finder.h>
#include "landingslope.h"
#include "mtecs/mTecs.h"
@@ -146,7 +145,6 @@ private:
int _params_sub; /**< notification of parameter updates */
int _manual_control_sub; /**< notification of manual control updates */
int _sensor_combined_sub; /**< for body frame accelerations */
- int _range_finder_sub; /**< range finder subscription */
orb_advert_t _attitude_sp_pub; /**< attitude setpoint */
orb_advert_t _tecs_status_pub; /**< TECS status publication */
@@ -162,17 +160,16 @@ private:
struct vehicle_global_position_s _global_pos; /**< global vehicle position */
struct position_setpoint_triplet_s _pos_sp_triplet; /**< triplet of mission items */
struct sensor_combined_s _sensor_combined; /**< for body frame accelerations */
- struct range_finder_report _range_finder; /**< range finder report */
perf_counter_t _loop_perf; /**< loop performance counter */
/* land states */
- /* not in non-abort mode for landing yet */
bool land_noreturn_horizontal;
bool land_noreturn_vertical;
bool land_stayonground;
bool land_motor_lim;
bool land_onslope;
+ bool land_useterrain;
/* takeoff/launch states */
LaunchDetectionResult launch_detection_state;
@@ -243,7 +240,9 @@ private:
float land_flare_alt_relative;
float land_thrust_lim_alt_relative;
float land_heading_hold_horizontal_distance;
- float range_finder_rel_alt;
+ float land_flare_pitch_min_deg;
+ float land_flare_pitch_max_deg;
+ int land_use_terrain_estimate;
} _parameters; /**< local copies of interesting parameters */
@@ -289,7 +288,9 @@ private:
param_t land_flare_alt_relative;
param_t land_thrust_lim_alt_relative;
param_t land_heading_hold_horizontal_distance;
- param_t range_finder_rel_alt;
+ param_t land_flare_pitch_min_deg;
+ param_t land_flare_pitch_max_deg;
+ param_t land_use_terrain_estimate;
} _parameter_handles; /**< handles for interesting parameters */
@@ -321,12 +322,6 @@ private:
bool vehicle_airspeed_poll();
/**
- * Check for range finder updates.
- */
- bool range_finder_poll();
-
-
- /**
* Check for position updates.
*/
void vehicle_attitude_poll();
@@ -347,9 +342,9 @@ private:
void navigation_capabilities_publish();
/**
- * Get the relative alt either from the difference between estimate and waypoint or from the laser range finder
+ * Return the terrain estimate during landing: uses the wp altitude value or the terrain estimate if available
*/
- float get_relative_landingalt(float land_setpoint_alt, float current_alt, const struct range_finder_report &range_finder, float range_finder_use_relative_alt);
+ float get_terrain_altitude_landing(float land_setpoint_alt, const struct vehicle_global_position_s &global_pos);
/**
* Control position.
@@ -423,7 +418,6 @@ FixedwingPositionControl::FixedwingPositionControl() :
_params_sub(-1),
_manual_control_sub(-1),
_sensor_combined_sub(-1),
- _range_finder_sub(-1),
/* publications */
_attitude_sp_pub(-1),
@@ -441,7 +435,6 @@ FixedwingPositionControl::FixedwingPositionControl() :
_global_pos(),
_pos_sp_triplet(),
_sensor_combined(),
- _range_finder(),
/* performance counters */
_loop_perf(perf_alloc(PC_ELAPSED, "fw l1 control")),
@@ -451,6 +444,7 @@ FixedwingPositionControl::FixedwingPositionControl() :
land_stayonground(false),
land_motor_lim(false),
land_onslope(false),
+ land_useterrain(false),
launch_detection_state(LAUNCHDETECTION_RES_NONE),
last_manual(false),
landingslope(),
@@ -489,7 +483,9 @@ FixedwingPositionControl::FixedwingPositionControl() :
_parameter_handles.land_flare_alt_relative = param_find("FW_LND_FLALT");
_parameter_handles.land_thrust_lim_alt_relative = param_find("FW_LND_TLALT");
_parameter_handles.land_heading_hold_horizontal_distance = param_find("FW_LND_HHDIST");
- _parameter_handles.range_finder_rel_alt = param_find("FW_LND_RFRALT");
+ _parameter_handles.land_flare_pitch_min_deg = param_find("FW_FLARE_PMIN");
+ _parameter_handles.land_flare_pitch_max_deg = param_find("FW_FLARE_PMAX");
+ _parameter_handles.land_use_terrain_estimate= param_find("FW_LND_USETER");
_parameter_handles.time_const = param_find("FW_T_TIME_CONST");
_parameter_handles.time_const_throt = param_find("FW_T_THRO_CONST");
@@ -590,8 +586,9 @@ FixedwingPositionControl::parameters_update()
}
param_get(_parameter_handles.land_heading_hold_horizontal_distance, &(_parameters.land_heading_hold_horizontal_distance));
-
- param_get(_parameter_handles.range_finder_rel_alt, &(_parameters.range_finder_rel_alt));
+ param_get(_parameter_handles.land_flare_pitch_min_deg, &(_parameters.land_flare_pitch_min_deg));
+ param_get(_parameter_handles.land_flare_pitch_max_deg, &(_parameters.land_flare_pitch_max_deg));
+ param_get(_parameter_handles.land_use_terrain_estimate, &(_parameters.land_use_terrain_estimate));
_l1_control.set_l1_damping(_parameters.l1_damping);
_l1_control.set_l1_period(_parameters.l1_period);
@@ -695,20 +692,6 @@ FixedwingPositionControl::vehicle_airspeed_poll()
return airspeed_updated;
}
-bool
-FixedwingPositionControl::range_finder_poll()
-{
- /* check if there is a range finder measurement */
- bool range_finder_updated;
- orb_check(_range_finder_sub, &range_finder_updated);
-
- if (range_finder_updated) {
- orb_copy(ORB_ID(sensor_range_finder), _range_finder_sub, &_range_finder);
- }
-
- return range_finder_updated;
-}
-
void
FixedwingPositionControl::vehicle_attitude_poll()
{
@@ -846,21 +829,23 @@ void FixedwingPositionControl::navigation_capabilities_publish()
}
}
-float FixedwingPositionControl::get_relative_landingalt(float land_setpoint_alt, float current_alt, const struct range_finder_report &range_finder, float range_finder_use_relative_alt)
+float FixedwingPositionControl::get_terrain_altitude_landing(float land_setpoint_alt, const struct vehicle_global_position_s &global_pos)
{
- float rel_alt_estimated = current_alt - land_setpoint_alt;
-
- /* only use range finder if:
- * parameter (range_finder_use_relative_alt) > 0
- * the measurement is valid
- * the estimated relative altitude (from global altitude estimate and landing waypoint) <= range_finder_use_relative_alt
- */
- if (range_finder_use_relative_alt < 0 || !range_finder.valid || range_finder.distance > range_finder_use_relative_alt ) {
- return rel_alt_estimated;
+ if (!isfinite(global_pos.terrain_alt)) {
+ return land_setpoint_alt;
}
- return range_finder.distance;
-
+ /* Decide if the terrain estimation can be used, once we switched to using the terrain we stick with it
+ * for the whole landing */
+ if (_parameters.land_use_terrain_estimate && (global_pos.terrain_alt_valid || land_useterrain)) {
+ if(!land_useterrain) {
+ mavlink_log_info(_mavlink_fd, "#audio: Landing, using terrain estimate");
+ land_useterrain = true;
+ }
+ return global_pos.terrain_alt;
+ } else {
+ return land_setpoint_alt;
+ }
}
bool
@@ -965,10 +950,17 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
} else if (pos_sp_triplet.current.type == SETPOINT_TYPE_LAND) {
float bearing_lastwp_currwp = get_bearing_to_next_waypoint(prev_wp(0), prev_wp(1), curr_wp(0), curr_wp(1));
+ float bearing_airplane_currwp = get_bearing_to_next_waypoint(current_position(0), current_position(1), curr_wp(0), curr_wp(1));
/* 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(0), current_position(1), curr_wp(0), curr_wp(1));
+ /* calculate a waypoint distance value which is 0 when the aircraft is behind the waypoint */
+ float wp_distance_save = wp_distance;
+ if (fabsf(bearing_airplane_currwp - bearing_lastwp_currwp) >= math::radians(90.0f)) {
+ wp_distance_save = 0.0f;
+ }
+
//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) {
@@ -1004,29 +996,30 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
/* Vertical landing control */
//xxx: using the tecs altitude controller for slope control for now
-
-// /* do not go down too early */
-// if (wp_distance > 50.0f) {
-// altitude_error = (_global_triplet.current.alt + 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
- float flare_pitch_angle_rad = -math::radians(5.0f);//math::radians(pos_sp_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;
+ /* Get an estimate of the terrain altitude if available, otherwise terrain_alt will be
+ * equal to _pos_sp_triplet.current.alt */
+ float terrain_alt = get_terrain_altitude_landing(_pos_sp_triplet.current.alt, _global_pos);
+
/* Calculate distance (to landing waypoint) and altitude of last ordinary waypoint L */
- float L_altitude_rel = _pos_sp_triplet.previous.valid ? _pos_sp_triplet.previous.alt - _pos_sp_triplet.current.alt : 0.0f;
+ float L_altitude_rel = _pos_sp_triplet.previous.valid ?
+ _pos_sp_triplet.previous.alt - terrain_alt : 0.0f;
- float bearing_airplane_currwp = get_bearing_to_next_waypoint(current_position(0), current_position(1), curr_wp(0), curr_wp(1));
float landing_slope_alt_rel_desired = landingslope.getLandingSlopeRelativeAltitudeSave(wp_distance, bearing_lastwp_currwp, bearing_airplane_currwp);
- float relative_alt = get_relative_landingalt(_pos_sp_triplet.current.alt, _global_pos.alt, _range_finder, _parameters.range_finder_rel_alt);
-
- if ( (relative_alt < landingslope.flare_relative_alt()) || land_noreturn_vertical) { //checking for land_noreturn to avoid unwanted climb out
-
+ /* Check if we should start flaring with a vertical and a
+ * horizontal limit (with some tolerance)
+ * The horizontal limit is only applied when we are in front of the wp
+ */
+ if (((_global_pos.alt < terrain_alt + landingslope.flare_relative_alt()) &&
+ (wp_distance_save < landingslope.flare_length() + 5.0f)) ||
+ land_noreturn_vertical) { //checking for land_noreturn to avoid unwanted climb out
/* land with minimal speed */
// /* force TECS to only control speed with pitch, altitude is only implicitely controlled now */
@@ -1035,7 +1028,7 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
/* kill the throttle if param requests it */
throttle_max = _parameters.throttle_max;
- if (relative_alt < landingslope.motor_lim_relative_alt() || land_motor_lim) {
+ if (_global_pos.alt < terrain_alt + landingslope.motor_lim_relative_alt() || land_motor_lim) {
throttle_max = math::min(throttle_max, _parameters.throttle_land_max);
if (!land_motor_lim) {
land_motor_lim = true;
@@ -1053,12 +1046,13 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
land_stayonground = true;
}
- tecs_update_pitch_throttle(_pos_sp_triplet.current.alt + flare_curve_alt_rel,
+ tecs_update_pitch_throttle(terrain_alt + flare_curve_alt_rel,
calculate_target_airspeed(airspeed_land), eas2tas,
- flare_pitch_angle_rad, math::radians(15.0f),
+ math::radians(_parameters.land_flare_pitch_min_deg),
+ math::radians(_parameters.land_flare_pitch_max_deg),
0.0f, throttle_max, throttle_land,
- false, flare_pitch_angle_rad,
- _pos_sp_triplet.current.alt + relative_alt, ground_speed,
+ false, land_motor_lim ? math::radians(_parameters.land_flare_pitch_min_deg) : math::radians(_parameters.pitch_limit_min),
+ _global_pos.alt, ground_speed,
land_motor_lim ? TECS_MODE_LAND_THROTTLELIM : TECS_MODE_LAND);
if (!land_noreturn_vertical) {
@@ -1079,8 +1073,8 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
* if current position is below the slope continue at previous wp altitude
* until the intersection with slope
* */
- float altitude_desired_rel = relative_alt;
- if (relative_alt > landing_slope_alt_rel_desired || land_onslope) {
+ float altitude_desired_rel;
+ if (_global_pos.alt > terrain_alt + landing_slope_alt_rel_desired || land_onslope) {
/* stay on slope */
altitude_desired_rel = landing_slope_alt_rel_desired;
if (!land_onslope) {
@@ -1089,10 +1083,11 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
}
} else {
/* continue horizontally */
- altitude_desired_rel = _pos_sp_triplet.previous.valid ? L_altitude_rel : relative_alt;
+ altitude_desired_rel = _pos_sp_triplet.previous.valid ? L_altitude_rel :
+ _global_pos.alt - terrain_alt;
}
- tecs_update_pitch_throttle(_pos_sp_triplet.current.alt + altitude_desired_rel,
+ tecs_update_pitch_throttle(terrain_alt + altitude_desired_rel,
calculate_target_airspeed(airspeed_approach), eas2tas,
math::radians(_parameters.pitch_limit_min),
math::radians(_parameters.pitch_limit_max),
@@ -1101,7 +1096,7 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
_parameters.throttle_cruise,
false,
math::radians(_parameters.pitch_limit_min),
- _pos_sp_triplet.current.alt + relative_alt,
+ _global_pos.alt,
ground_speed);
}
@@ -1277,7 +1272,6 @@ FixedwingPositionControl::task_main()
_airspeed_sub = orb_subscribe(ORB_ID(airspeed));
_params_sub = orb_subscribe(ORB_ID(parameter_update));
_manual_control_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
- _range_finder_sub = orb_subscribe(ORB_ID(sensor_range_finder));
/* rate limit control mode updates to 5Hz */
orb_set_interval(_control_mode_sub, 200);
@@ -1356,7 +1350,6 @@ FixedwingPositionControl::task_main()
vehicle_setpoint_poll();
vehicle_sensor_combined_poll();
vehicle_airspeed_poll();
- range_finder_poll();
// vehicle_baro_poll();
math::Vector<3> ground_speed(_global_pos.vel_n, _global_pos.vel_e, _global_pos.vel_d);
@@ -1420,6 +1413,7 @@ void FixedwingPositionControl::reset_landing_state()
land_stayonground = false;
land_motor_lim = false;
land_onslope = false;
+ land_useterrain = false;
}
void FixedwingPositionControl::tecs_update_pitch_throttle(float alt_sp, float v_sp, float eas2tas,
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 847ecbb5c..c00d82232 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
@@ -412,12 +412,28 @@ PARAM_DEFINE_FLOAT(FW_LND_TLALT, -1.0f);
PARAM_DEFINE_FLOAT(FW_LND_HHDIST, 15.0f);
/**
- * Relative altitude threshold for range finder measurements for use during landing
+ * Enable or disable usage of terrain estimate during landing
*
- * range finder measurements will only be used if the estimated relative altitude (gobal_pos.alt - landing_waypoint.alt) is < FW_LND_RFRALT
- * set to < 0 to disable
- * the correct value of this parameter depends on your range measuring device as well as on the terrain at the landing location
+ * 0: disabled, 1: enabled
*
* @group L1 Control
*/
-PARAM_DEFINE_FLOAT(FW_LND_RFRALT, -1.0f);
+PARAM_DEFINE_INT32(FW_LND_USETER, 0);
+
+/**
+ * Flare, minimum pitch
+ *
+ * Minimum pitch during flare, a positive sign means nose up
+ * Applied once FW_LND_TLALT is reached
+ *
+ */
+PARAM_DEFINE_FLOAT(FW_FLARE_PMIN, 2.5f);
+
+/**
+ * Flare, maximum pitch
+ *
+ * Maximum pitch during flare, a positive sign means nose up
+ * Applied once FW_LND_TLALT is reached
+ *
+ */
+PARAM_DEFINE_FLOAT(FW_FLARE_PMAX, 15.0f);
diff --git a/src/modules/mavlink/mavlink_ftp.cpp b/src/modules/mavlink/mavlink_ftp.cpp
index 2a85c3702..f17497aa8 100644
--- a/src/modules/mavlink/mavlink_ftp.cpp
+++ b/src/modules/mavlink/mavlink_ftp.cpp
@@ -34,6 +34,7 @@
/// @file mavlink_ftp.cpp
/// @author px4dev, Don Gagne <don@thegagnes.com>
+#include <crc32.h>
#include <unistd.h>
#include <stdio.h>
#include <fcntl.h>
@@ -180,12 +181,16 @@ MavlinkFTP::_process_request(Request *req)
errorCode = _workList(payload);
break;
- case kCmdOpenFile:
- errorCode = _workOpen(payload, false);
+ case kCmdOpenFileRO:
+ errorCode = _workOpen(payload, O_RDONLY);
break;
case kCmdCreateFile:
- errorCode = _workOpen(payload, true);
+ errorCode = _workOpen(payload, O_CREAT | O_EXCL | O_WRONLY);
+ break;
+
+ case kCmdOpenFileWO:
+ errorCode = _workOpen(payload, O_CREAT | O_WRONLY);
break;
case kCmdReadFile:
@@ -200,6 +205,14 @@ MavlinkFTP::_process_request(Request *req)
errorCode = _workRemoveFile(payload);
break;
+ case kCmdRename:
+ errorCode = _workRename(payload);
+ break;
+
+ case kCmdTruncateFile:
+ errorCode = _workTruncateFile(payload);
+ break;
+
case kCmdCreateDirectory:
errorCode = _workCreateDirectory(payload);
break;
@@ -208,6 +221,11 @@ MavlinkFTP::_process_request(Request *req)
errorCode = _workRemoveDirectory(payload);
break;
+
+ case kCmdCalcFileCRC32:
+ errorCode = _workCalcFileCRC32(payload);
+ break;
+
default:
errorCode = kErrUnknownCommand;
break;
@@ -222,6 +240,7 @@ out:
warnx("FTP: ack\n");
#endif
} else {
+ int r_errno = errno;
warnx("FTP: nak %u", errorCode);
payload->req_opcode = payload->opcode;
payload->opcode = kRspNak;
@@ -229,7 +248,7 @@ out:
payload->data[0] = errorCode;
if (errorCode == kErrFailErrno) {
payload->size = 2;
- payload->data[1] = errno;
+ payload->data[1] = r_errno;
}
}
@@ -396,27 +415,27 @@ MavlinkFTP::_workList(PayloadHeader* payload)
/// @brief Responds to an Open command
MavlinkFTP::ErrorCode
-MavlinkFTP::_workOpen(PayloadHeader* payload, bool create)
+MavlinkFTP::_workOpen(PayloadHeader* payload, int oflag)
{
int session_index = _find_unused_session();
if (session_index < 0) {
warnx("FTP: Open failed - out of sessions\n");
return kErrNoSessionsAvailable;
}
-
+
char *filename = _data_as_cstring(payload);
-
+
uint32_t fileSize = 0;
- if (!create) {
- struct stat st;
- if (stat(filename, &st) != 0) {
+ struct stat st;
+ if (stat(filename, &st) != 0) {
+ // fail only if requested open for read
+ if (oflag & O_RDONLY)
return kErrFailErrno;
- }
- fileSize = st.st_size;
+ else
+ st.st_size = 0;
}
+ fileSize = st.st_size;
- int oflag = create ? (O_CREAT | O_EXCL | O_APPEND) : O_RDONLY;
-
int fd = ::open(filename, oflag);
if (fd < 0) {
return kErrFailErrno;
@@ -424,12 +443,8 @@ MavlinkFTP::_workOpen(PayloadHeader* payload, bool create)
_session_fds[session_index] = fd;
payload->session = session_index;
- if (create) {
- payload->size = 0;
- } else {
- payload->size = sizeof(uint32_t);
- *((uint32_t*)payload->data) = fileSize;
- }
+ payload->size = sizeof(uint32_t);
+ *((uint32_t*)payload->data) = fileSize;
return kErrNone;
}
@@ -470,29 +485,33 @@ MavlinkFTP::_workRead(PayloadHeader* payload)
MavlinkFTP::ErrorCode
MavlinkFTP::_workWrite(PayloadHeader* payload)
{
-#if 0
- // NYI: Coming soon
- auto hdr = req->header();
+ int session_index = payload->session;
- // look up session
- auto session = getSession(hdr->session);
- if (session == nullptr) {
- return kErrNoSession;
+ if (!_valid_session(session_index)) {
+ return kErrInvalidSession;
}
- // append to file
- int result = session->append(hdr->offset, &hdr->data[0], hdr->size);
+ // Seek to the specified position
+#ifdef MAVLINK_FTP_DEBUG
+ warnx("seek %d", payload->offset);
+#endif
+ if (lseek(_session_fds[session_index], payload->offset, SEEK_SET) < 0) {
+ // Unable to see to the specified location
+ warnx("seek fail");
+ return kErrFailErrno;
+ }
- if (result < 0) {
- // XXX might also be no space, I/O, etc.
- return kErrNotAppend;
+ int bytes_written = ::write(_session_fds[session_index], &payload->data[0], payload->size);
+ if (bytes_written < 0) {
+ // Negative return indicates error other than eof
+ warnx("write fail %d", bytes_written);
+ return kErrFailErrno;
}
- hdr->size = result;
+ payload->size = sizeof(uint32_t);
+ *((uint32_t*)payload->data) = bytes_written;
+
return kErrNone;
-#else
- return kErrUnknownCommand;
-#endif
}
/// @brief Responds to a RemoveFile command
@@ -510,6 +529,81 @@ MavlinkFTP::_workRemoveFile(PayloadHeader* payload)
}
}
+/// @brief Responds to a TruncateFile command
+MavlinkFTP::ErrorCode
+MavlinkFTP::_workTruncateFile(PayloadHeader* payload)
+{
+ char file[kMaxDataLength];
+ const char temp_file[] = "/fs/microsd/.trunc.tmp";
+ strncpy(file, _data_as_cstring(payload), kMaxDataLength);
+ payload->size = 0;
+
+ // emulate truncate(file, payload->offset) by
+ // copying to temp and overwrite with O_TRUNC flag.
+
+ struct stat st;
+ if (stat(file, &st) != 0) {
+ return kErrFailErrno;
+ }
+
+ if (!S_ISREG(st.st_mode)) {
+ errno = EISDIR;
+ return kErrFailErrno;
+ }
+
+ // check perms allow us to write (not romfs)
+ if (!(st.st_mode & (S_IWUSR | S_IWGRP | S_IWOTH))) {
+ errno = EROFS;
+ return kErrFailErrno;
+ }
+
+ if (payload->offset == (unsigned)st.st_size) {
+ // nothing to do
+ return kErrNone;
+ }
+ else if (payload->offset == 0) {
+ // 1: truncate all data
+ int fd = ::open(file, O_TRUNC | O_WRONLY);
+ if (fd < 0) {
+ return kErrFailErrno;
+ }
+
+ ::close(fd);
+ return kErrNone;
+ }
+ else if (payload->offset > (unsigned)st.st_size) {
+ // 2: extend file
+ int fd = ::open(file, O_WRONLY);
+ if (fd < 0) {
+ return kErrFailErrno;
+ }
+
+ if (lseek(fd, payload->offset - 1, SEEK_SET) < 0) {
+ ::close(fd);
+ return kErrFailErrno;
+ }
+
+ bool ok = 1 == ::write(fd, "", 1);
+ ::close(fd);
+
+ return (ok)? kErrNone : kErrFailErrno;
+ }
+ else {
+ // 3: truncate
+ if (_copy_file(file, temp_file, payload->offset) != 0) {
+ return kErrFailErrno;
+ }
+ if (_copy_file(temp_file, file, payload->offset) != 0) {
+ return kErrFailErrno;
+ }
+ if (::unlink(temp_file) != 0) {
+ return kErrFailErrno;
+ }
+
+ return kErrNone;
+ }
+}
+
/// @brief Responds to a Terminate command
MavlinkFTP::ErrorCode
MavlinkFTP::_workTerminate(PayloadHeader* payload)
@@ -542,6 +636,33 @@ MavlinkFTP::_workReset(PayloadHeader* payload)
return kErrNone;
}
+/// @brief Responds to a Rename command
+MavlinkFTP::ErrorCode
+MavlinkFTP::_workRename(PayloadHeader* payload)
+{
+ char oldpath[kMaxDataLength];
+ char newpath[kMaxDataLength];
+
+ char *ptr = _data_as_cstring(payload);
+ size_t oldpath_sz = strlen(ptr);
+
+ if (oldpath_sz == payload->size) {
+ // no newpath
+ errno = EINVAL;
+ return kErrFailErrno;
+ }
+
+ strncpy(oldpath, ptr, kMaxDataLength);
+ strncpy(newpath, ptr + oldpath_sz + 1, kMaxDataLength);
+
+ if (rename(oldpath, newpath) == 0) {
+ payload->size = 0;
+ return kErrNone;
+ } else {
+ return kErrFailErrno;
+ }
+}
+
/// @brief Responds to a RemoveDirectory command
MavlinkFTP::ErrorCode
MavlinkFTP::_workRemoveDirectory(PayloadHeader* payload)
@@ -572,6 +693,39 @@ MavlinkFTP::_workCreateDirectory(PayloadHeader* payload)
}
}
+/// @brief Responds to a CalcFileCRC32 command
+MavlinkFTP::ErrorCode
+MavlinkFTP::_workCalcFileCRC32(PayloadHeader* payload)
+{
+ char file_buf[256];
+ uint32_t checksum = 0;
+ ssize_t bytes_read;
+ strncpy(file_buf, _data_as_cstring(payload), kMaxDataLength);
+
+ int fd = ::open(file_buf, O_RDONLY);
+ if (fd < 0) {
+ return kErrFailErrno;
+ }
+
+ do {
+ bytes_read = ::read(fd, file_buf, sizeof(file_buf));
+ if (bytes_read < 0) {
+ int r_errno = errno;
+ ::close(fd);
+ errno = r_errno;
+ return kErrFailErrno;
+ }
+
+ checksum = crc32part((uint8_t*)file_buf, bytes_read, checksum);
+ } while (bytes_read == sizeof(file_buf));
+
+ ::close(fd);
+
+ payload->size = sizeof(uint32_t);
+ *((uint32_t*)payload->data) = checksum;
+ return kErrNone;
+}
+
/// @brief Returns true if the specified session is a valid open session
bool
MavlinkFTP::_valid_session(unsigned index)
@@ -645,3 +799,55 @@ MavlinkFTP::_return_request(Request *req)
_unlock_request_queue();
}
+/// @brief Copy file (with limited space)
+int
+MavlinkFTP::_copy_file(const char *src_path, const char *dst_path, ssize_t length)
+{
+ char buff[512];
+ int src_fd = -1, dst_fd = -1;
+ int op_errno = 0;
+
+ src_fd = ::open(src_path, O_RDONLY);
+ if (src_fd < 0) {
+ return -1;
+ }
+
+ dst_fd = ::open(dst_path, O_CREAT | O_TRUNC | O_WRONLY);
+ if (dst_fd < 0) {
+ op_errno = errno;
+ ::close(src_fd);
+ errno = op_errno;
+ return -1;
+ }
+
+ while (length > 0) {
+ ssize_t bytes_read, bytes_written;
+ size_t blen = (length > sizeof(buff))? sizeof(buff) : length;
+
+ bytes_read = ::read(src_fd, buff, blen);
+ if (bytes_read == 0) {
+ // EOF
+ break;
+ }
+ else if (bytes_read < 0) {
+ warnx("cp: read");
+ op_errno = errno;
+ break;
+ }
+
+ bytes_written = ::write(dst_fd, buff, bytes_read);
+ if (bytes_written != bytes_read) {
+ warnx("cp: short write");
+ op_errno = errno;
+ break;
+ }
+
+ length -= bytes_written;
+ }
+
+ ::close(src_fd);
+ ::close(dst_fd);
+
+ errno = op_errno;
+ return (length > 0)? -1 : 0;
+}
diff --git a/src/modules/mavlink/mavlink_ftp.h b/src/modules/mavlink/mavlink_ftp.h
index 657e2f855..bef6775a9 100644
--- a/src/modules/mavlink/mavlink_ftp.h
+++ b/src/modules/mavlink/mavlink_ftp.h
@@ -89,13 +89,17 @@ public:
kCmdTerminateSession, ///< Terminates open Read session
kCmdResetSessions, ///< Terminates all open Read sessions
kCmdListDirectory, ///< List files in <path> from <offset>
- kCmdOpenFile, ///< Opens file at <path> for reading, returns <session>
+ kCmdOpenFileRO, ///< Opens file at <path> for reading, returns <session>
kCmdReadFile, ///< Reads <size> bytes from <offset> in <session>
kCmdCreateFile, ///< Creates file at <path> for writing, returns <session>
- kCmdWriteFile, ///< Appends <size> bytes to file in <session>
+ kCmdWriteFile, ///< Writes <size> bytes to <offset> in <session>
kCmdRemoveFile, ///< Remove file at <path>
kCmdCreateDirectory, ///< Creates directory at <path>
kCmdRemoveDirectory, ///< Removes Directory at <path>, must be empty
+ kCmdOpenFileWO, ///< Opens file at <path> for writing, returns <session>
+ kCmdTruncateFile, ///< Truncate file at <path> to <offset> length
+ kCmdRename, ///< Rename <path1> to <path2>
+ kCmdCalcFileCRC32, ///< Calculate CRC32 for file at <path>
kRspAck = 128, ///< Ack response
kRspNak ///< Nak response
@@ -138,9 +142,10 @@ private:
static void _worker_trampoline(void *arg);
void _process_request(Request *req);
void _reply(Request *req);
+ int _copy_file(const char *src_path, const char *dst_path, ssize_t length);
ErrorCode _workList(PayloadHeader *payload);
- ErrorCode _workOpen(PayloadHeader *payload, bool create);
+ ErrorCode _workOpen(PayloadHeader *payload, int oflag);
ErrorCode _workRead(PayloadHeader *payload);
ErrorCode _workWrite(PayloadHeader *payload);
ErrorCode _workTerminate(PayloadHeader *payload);
@@ -148,6 +153,9 @@ private:
ErrorCode _workRemoveDirectory(PayloadHeader *payload);
ErrorCode _workCreateDirectory(PayloadHeader *payload);
ErrorCode _workRemoveFile(PayloadHeader *payload);
+ ErrorCode _workTruncateFile(PayloadHeader *payload);
+ ErrorCode _workRename(PayloadHeader *payload);
+ ErrorCode _workCalcFileCRC32(PayloadHeader *payload);
static const unsigned kRequestQueueSize = 2; ///< Max number of queued requests
Request _request_bufs[kRequestQueueSize]; ///< Request buffers which hold work
diff --git a/src/modules/mavlink/mavlink_tests/mavlink_ftp_test.cpp b/src/modules/mavlink/mavlink_tests/mavlink_ftp_test.cpp
index 022041c74..4caa820b6 100644
--- a/src/modules/mavlink/mavlink_tests/mavlink_ftp_test.cpp
+++ b/src/modules/mavlink/mavlink_tests/mavlink_ftp_test.cpp
@@ -65,7 +65,7 @@ MavlinkFtpTest::~MavlinkFtpTest()
}
/// @brief Called before every test to initialize the FTP Server.
-void MavlinkFtpTest::init(void)
+void MavlinkFtpTest::_init(void)
{
_ftp_server = new MavlinkFTP;;
_ftp_server->set_unittest_worker(MavlinkFtpTest::receive_message, this);
@@ -74,7 +74,7 @@ void MavlinkFtpTest::init(void)
}
/// @brief Called after every test to take down the FTP Server.
-void MavlinkFtpTest::cleanup(void)
+void MavlinkFtpTest::_cleanup(void)
{
delete _ftp_server;
@@ -265,7 +265,7 @@ bool MavlinkFtpTest::_open_badfile_test(void)
MavlinkFTP::PayloadHeader *reply;
const char *dir = "/foo"; // non-existent file
- payload.opcode = MavlinkFTP::kCmdOpenFile;
+ payload.opcode = MavlinkFTP::kCmdOpenFileRO;
payload.offset = 0;
bool success = _send_receive_msg(&payload, // FTP payload header
@@ -295,7 +295,7 @@ bool MavlinkFtpTest::_open_terminate_test(void)
struct stat st;
const ReadTestCase *test = &_rgReadTestCases[i];
- payload.opcode = MavlinkFTP::kCmdOpenFile;
+ payload.opcode = MavlinkFTP::kCmdOpenFileRO;
payload.offset = 0;
bool success = _send_receive_msg(&payload, // FTP payload header
@@ -342,7 +342,7 @@ bool MavlinkFtpTest::_terminate_badsession_test(void)
MavlinkFTP::PayloadHeader *reply;
const char *file = _rgReadTestCases[0].file;
- payload.opcode = MavlinkFTP::kCmdOpenFile;
+ payload.opcode = MavlinkFTP::kCmdOpenFileRO;
payload.offset = 0;
bool success = _send_receive_msg(&payload, // FTP payload header
@@ -400,7 +400,7 @@ bool MavlinkFtpTest::_read_test(void)
// Test case data files are created for specific boundary conditions
ut_compare("Test case data files are out of date", test->length, st.st_size);
- payload.opcode = MavlinkFTP::kCmdOpenFile;
+ payload.opcode = MavlinkFTP::kCmdOpenFileRO;
payload.offset = 0;
bool success = _send_receive_msg(&payload, // FTP payload header
@@ -463,7 +463,7 @@ bool MavlinkFtpTest::_read_badsession_test(void)
MavlinkFTP::PayloadHeader *reply;
const char *file = _rgReadTestCases[0].file;
- payload.opcode = MavlinkFTP::kCmdOpenFile;
+ payload.opcode = MavlinkFTP::kCmdOpenFileRO;
payload.offset = 0;
bool success = _send_receive_msg(&payload, // FTP payload header
@@ -738,7 +738,7 @@ void MavlinkFtpTest::_cleanup_microsd(void)
}
/// @brief Runs all the unit tests
-void MavlinkFtpTest::runTests(void)
+bool MavlinkFtpTest::run_tests(void)
{
ut_run_test(_ack_test);
ut_run_test(_bad_opcode_test);
@@ -753,5 +753,9 @@ void MavlinkFtpTest::runTests(void)
ut_run_test(_removedirectory_test);
ut_run_test(_createdirectory_test);
ut_run_test(_removefile_test);
+
+ return (_tests_failed == 0);
+
}
+ut_declare_test(mavlink_ftp_test, MavlinkFtpTest)
diff --git a/src/modules/mavlink/mavlink_tests/mavlink_ftp_test.h b/src/modules/mavlink/mavlink_tests/mavlink_ftp_test.h
index babd909da..2696192cc 100644
--- a/src/modules/mavlink/mavlink_tests/mavlink_ftp_test.h
+++ b/src/modules/mavlink/mavlink_tests/mavlink_ftp_test.h
@@ -46,10 +46,7 @@ public:
MavlinkFtpTest();
virtual ~MavlinkFtpTest();
- virtual void init(void);
- virtual void cleanup(void);
-
- virtual void runTests(void);
+ virtual bool run_tests(void);
static void receive_message(const mavlink_message_t *msg, MavlinkFtpTest* ftpTest);
@@ -65,6 +62,9 @@ public:
MavlinkFtpTest& operator=(const MavlinkFtpTest&);
private:
+ virtual void _init(void);
+ virtual void _cleanup(void);
+
bool _ack_test(void);
bool _bad_opcode_test(void);
bool _bad_datasize_test(void);
@@ -105,3 +105,4 @@ private:
static const char _unittest_microsd_file[];
};
+bool mavlink_ftp_test(void);
diff --git a/src/modules/mavlink/mavlink_tests/mavlink_tests.cpp b/src/modules/mavlink/mavlink_tests/mavlink_tests.cpp
index d9c1e413a..10cbcb0ec 100644
--- a/src/modules/mavlink/mavlink_tests/mavlink_tests.cpp
+++ b/src/modules/mavlink/mavlink_tests/mavlink_tests.cpp
@@ -43,10 +43,5 @@ extern "C" __EXPORT int mavlink_tests_main(int argc, char *argv[]);
int mavlink_tests_main(int argc, char *argv[])
{
- MavlinkFtpTest* test = new MavlinkFtpTest;
-
- test->runTests();
- test->printResults();
-
- return 0;
+ return mavlink_ftp_test() ? 0 : -1;
}
diff --git a/src/modules/mavlink/mavlink_tests/module.mk b/src/modules/mavlink/mavlink_tests/module.mk
index 07cfce1dc..1cc28cce1 100644
--- a/src/modules/mavlink/mavlink_tests/module.mk
+++ b/src/modules/mavlink/mavlink_tests/module.mk
@@ -45,4 +45,6 @@ INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink
MODULE_STACKSIZE = 5000
+MAXOPTIMIZATION = -Os
+
EXTRACXXFLAGS = -Weffc++ -DMAVLINK_FTP_UNIT_TEST
diff --git a/src/modules/mc_pos_control/mc_pos_control_main.cpp b/src/modules/mc_pos_control/mc_pos_control_main.cpp
index ecc40428d..ec7b2a78f 100644
--- a/src/modules/mc_pos_control/mc_pos_control_main.cpp
+++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp
@@ -76,6 +76,7 @@
#define TILT_COS_MAX 0.7f
#define SIGMA 0.000001f
+#define MIN_DIST 0.01f
/**
* Multicopter position control app start / stop handling function
@@ -179,6 +180,7 @@ private:
bool _reset_pos_sp;
bool _reset_alt_sp;
+ bool _mode_auto;
math::Vector<3> _pos;
math::Vector<3> _pos_sp;
@@ -220,6 +222,11 @@ private:
void reset_alt_sp();
/**
+ * Check if position setpoint is too far from current position and adjust it if needed.
+ */
+ void limit_pos_sp_offset();
+
+ /**
* Set position setpoint using manual control
*/
void control_manual(float dt);
@@ -229,6 +236,14 @@ private:
*/
void control_offboard(float dt);
+ bool cross_sphere_line(const math::Vector<3>& sphere_c, float sphere_r,
+ const math::Vector<3> line_a, const math::Vector<3> line_b, math::Vector<3>& res);
+
+ /**
+ * Set position setpoint for AUTO
+ */
+ void control_auto(float dt);
+
/**
* Select between barometric and global (AMSL) altitudes
*/
@@ -283,7 +298,8 @@ MulticopterPositionControl::MulticopterPositionControl() :
_ref_timestamp(0),
_reset_pos_sp(true),
- _reset_alt_sp(true)
+ _reset_alt_sp(true),
+ _mode_auto(false)
{
memset(&_att, 0, sizeof(_att));
memset(&_att_sp, 0, sizeof(_att_sp));
@@ -534,6 +550,29 @@ MulticopterPositionControl::reset_alt_sp()
}
void
+MulticopterPositionControl::limit_pos_sp_offset()
+{
+ math::Vector<3> pos_sp_offs;
+ pos_sp_offs.zero();
+
+ if (_control_mode.flag_control_position_enabled) {
+ pos_sp_offs(0) = (_pos_sp(0) - _pos(0)) / _params.sp_offs_max(0);
+ pos_sp_offs(1) = (_pos_sp(1) - _pos(1)) / _params.sp_offs_max(1);
+ }
+
+ if (_control_mode.flag_control_altitude_enabled) {
+ pos_sp_offs(2) = (_pos_sp(2) - _pos(2)) / _params.sp_offs_max(2);
+ }
+
+ float pos_sp_offs_norm = pos_sp_offs.length();
+
+ if (pos_sp_offs_norm > 1.0f) {
+ pos_sp_offs /= pos_sp_offs_norm;
+ _pos_sp = _pos + pos_sp_offs.emult(_params.sp_offs_max);
+ }
+}
+
+void
MulticopterPositionControl::control_manual(float dt)
{
_sp_move_rate.zero();
@@ -647,6 +686,170 @@ MulticopterPositionControl::control_offboard(float dt)
}
}
+bool
+MulticopterPositionControl::cross_sphere_line(const math::Vector<3>& sphere_c, float sphere_r,
+ const math::Vector<3> line_a, const math::Vector<3> line_b, math::Vector<3>& res)
+{
+ /* project center of sphere on line */
+ /* normalized AB */
+ math::Vector<3> ab_norm = line_b - line_a;
+ ab_norm.normalize();
+ math::Vector<3> d = line_a + ab_norm * ((sphere_c - line_a) * ab_norm);
+ float cd_len = (sphere_c - d).length();
+
+ /* we have triangle CDX with known CD and CX = R, find DX */
+ if (sphere_r > cd_len) {
+ /* have two roots, select one in A->B direction from D */
+ float dx_len = sqrtf(sphere_r * sphere_r - cd_len * cd_len);
+ res = d + ab_norm * dx_len;
+ return true;
+
+ } else {
+ /* have no roots, return D */
+ res = d;
+ return false;
+ }
+}
+
+void
+MulticopterPositionControl::control_auto(float dt)
+{
+ if (!_mode_auto) {
+ _mode_auto = true;
+ /* reset position setpoint on AUTO mode activation */
+ reset_pos_sp();
+ reset_alt_sp();
+ }
+
+ bool updated;
+ orb_check(_pos_sp_triplet_sub, &updated);
+
+ if (updated) {
+ orb_copy(ORB_ID(position_setpoint_triplet), _pos_sp_triplet_sub, &_pos_sp_triplet);
+ }
+
+ if (_pos_sp_triplet.current.valid) {
+ /* in case of interrupted mission don't go to waypoint but stay at current position */
+ _reset_pos_sp = true;
+ _reset_alt_sp = true;
+
+ /* project setpoint to local frame */
+ math::Vector<3> curr_sp;
+ map_projection_project(&_ref_pos,
+ _pos_sp_triplet.current.lat, _pos_sp_triplet.current.lon,
+ &curr_sp.data[0], &curr_sp.data[1]);
+ curr_sp(2) = -(_pos_sp_triplet.current.alt - _ref_alt);
+
+ /* scaled space: 1 == position error resulting max allowed speed, L1 = 1 in this space */
+ math::Vector<3> scale = _params.pos_p.edivide(_params.vel_max); // TODO add mult param here
+
+ /* convert current setpoint to scaled space */
+ math::Vector<3> curr_sp_s = curr_sp.emult(scale);
+
+ /* by default use current setpoint as is */
+ math::Vector<3> pos_sp_s = curr_sp_s;
+
+ if (_pos_sp_triplet.current.type == SETPOINT_TYPE_POSITION && _pos_sp_triplet.previous.valid) {
+ /* follow "previous - current" line */
+ math::Vector<3> prev_sp;
+ map_projection_project(&_ref_pos,
+ _pos_sp_triplet.previous.lat, _pos_sp_triplet.previous.lon,
+ &prev_sp.data[0], &prev_sp.data[1]);
+ prev_sp(2) = -(_pos_sp_triplet.previous.alt - _ref_alt);
+
+ if ((curr_sp - prev_sp).length() > MIN_DIST) {
+
+ /* find X - cross point of L1 sphere and trajectory */
+ math::Vector<3> pos_s = _pos.emult(scale);
+ math::Vector<3> prev_sp_s = prev_sp.emult(scale);
+ math::Vector<3> prev_curr_s = curr_sp_s - prev_sp_s;
+ math::Vector<3> curr_pos_s = pos_s - curr_sp_s;
+ float curr_pos_s_len = curr_pos_s.length();
+ if (curr_pos_s_len < 1.0f) {
+ /* copter is closer to waypoint than L1 radius */
+ /* check next waypoint and use it to avoid slowing down when passing via waypoint */
+ if (_pos_sp_triplet.next.valid) {
+ math::Vector<3> next_sp;
+ map_projection_project(&_ref_pos,
+ _pos_sp_triplet.next.lat, _pos_sp_triplet.next.lon,
+ &next_sp.data[0], &next_sp.data[1]);
+ next_sp(2) = -(_pos_sp_triplet.next.alt - _ref_alt);
+
+ if ((next_sp - curr_sp).length() > MIN_DIST) {
+ math::Vector<3> next_sp_s = next_sp.emult(scale);
+
+ /* calculate angle prev - curr - next */
+ math::Vector<3> curr_next_s = next_sp_s - curr_sp_s;
+ math::Vector<3> prev_curr_s_norm = prev_curr_s.normalized();
+
+ /* cos(a) * curr_next, a = angle between current and next trajectory segments */
+ float cos_a_curr_next = prev_curr_s_norm * curr_next_s;
+
+ /* cos(b), b = angle pos - curr_sp - prev_sp */
+ float cos_b = -curr_pos_s * prev_curr_s_norm / curr_pos_s_len;
+
+ if (cos_a_curr_next > 0.0f && cos_b > 0.0f) {
+ float curr_next_s_len = curr_next_s.length();
+ /* if curr - next distance is larger than L1 radius, limit it */
+ if (curr_next_s_len > 1.0f) {
+ cos_a_curr_next /= curr_next_s_len;
+ }
+
+ /* feed forward position setpoint offset */
+ math::Vector<3> pos_ff = prev_curr_s_norm *
+ cos_a_curr_next * cos_b * cos_b * (1.0f - curr_pos_s_len) *
+ (1.0f - expf(-curr_pos_s_len * curr_pos_s_len * 20.0f));
+ pos_sp_s += pos_ff;
+ }
+ }
+ }
+
+ } else {
+ bool near = cross_sphere_line(pos_s, 1.0f, prev_sp_s, curr_sp_s, pos_sp_s);
+ if (near) {
+ /* L1 sphere crosses trajectory */
+
+ } else {
+ /* copter is too far from trajectory */
+ /* if copter is behind prev waypoint, go directly to prev waypoint */
+ if ((pos_sp_s - prev_sp_s) * prev_curr_s < 0.0f) {
+ pos_sp_s = prev_sp_s;
+ }
+
+ /* if copter is in front of curr waypoint, go directly to curr waypoint */
+ if ((pos_sp_s - curr_sp_s) * prev_curr_s > 0.0f) {
+ pos_sp_s = curr_sp_s;
+ }
+
+ pos_sp_s = pos_s + (pos_sp_s - pos_s).normalized();
+ }
+ }
+ }
+ }
+
+ /* move setpoint not faster than max allowed speed */
+ math::Vector<3> pos_sp_old_s = _pos_sp.emult(scale);
+
+ /* difference between current and desired position setpoints, 1 = max speed */
+ math::Vector<3> d_pos_m = (pos_sp_s - pos_sp_old_s).edivide(_params.pos_p);
+ float d_pos_m_len = d_pos_m.length();
+ if (d_pos_m_len > dt) {
+ pos_sp_s = pos_sp_old_s + (d_pos_m / d_pos_m_len * dt).emult(_params.pos_p);
+ }
+
+ /* scale result back to normal space */
+ _pos_sp = pos_sp_s.edivide(scale);
+
+ /* update yaw setpoint if needed */
+ if (isfinite(_pos_sp_triplet.current.yaw)) {
+ _att_sp.yaw_body = _pos_sp_triplet.current.yaw;
+ }
+
+ } else {
+ /* no waypoint, do nothing, setpoint was already reset */
+ }
+}
+
void
MulticopterPositionControl::task_main()
{
@@ -750,41 +953,16 @@ MulticopterPositionControl::task_main()
if (_control_mode.flag_control_manual_enabled) {
/* manual control */
control_manual(dt);
+ _mode_auto = false;
} else if (_control_mode.flag_control_offboard_enabled) {
/* offboard control */
control_offboard(dt);
+ _mode_auto = false;
} else {
/* AUTO */
- bool updated;
- orb_check(_pos_sp_triplet_sub, &updated);
-
- if (updated) {
- orb_copy(ORB_ID(position_setpoint_triplet), _pos_sp_triplet_sub, &_pos_sp_triplet);
- }
-
- if (_pos_sp_triplet.current.valid) {
- /* in case of interrupted mission don't go to waypoint but stay at current position */
- _reset_pos_sp = true;
- _reset_alt_sp = true;
-
- /* project setpoint to local frame */
- map_projection_project(&_ref_pos,
- _pos_sp_triplet.current.lat, _pos_sp_triplet.current.lon,
- &_pos_sp.data[0], &_pos_sp.data[1]);
- _pos_sp(2) = -(_pos_sp_triplet.current.alt - _ref_alt);
-
- /* update yaw setpoint if needed */
- if (isfinite(_pos_sp_triplet.current.yaw)) {
- _att_sp.yaw_body = _pos_sp_triplet.current.yaw;
- }
-
- } else {
- /* no waypoint, loiter, reset position setpoint if needed */
- reset_pos_sp();
- reset_alt_sp();
- }
+ control_auto(dt);
}
/* fill local position setpoint */
@@ -846,16 +1024,6 @@ MulticopterPositionControl::task_main()
_vel_sp(2) = _params.land_speed;
}
-
- if (!_control_mode.flag_control_manual_enabled) {
- /* limit 3D speed only in non-manual modes */
- float vel_sp_norm = _vel_sp.edivide(_params.vel_max).length();
-
- if (vel_sp_norm > 1.0f) {
- _vel_sp /= vel_sp_norm;
- }
- }
-
_global_vel_sp.vx = _vel_sp(0);
_global_vel_sp.vy = _vel_sp(1);
_global_vel_sp.vz = _vel_sp(2);
@@ -1132,9 +1300,9 @@ MulticopterPositionControl::task_main()
/* position controller disabled, reset setpoints */
_reset_alt_sp = true;
_reset_pos_sp = true;
+ _mode_auto = false;
reset_int_z = true;
reset_int_xy = true;
-
}
/* reset altitude controller integral (hovering throttle) to manual throttle after manual throttle control */
diff --git a/src/modules/navigator/mission.cpp b/src/modules/navigator/mission.cpp
index e9e03a44e..7fac69a61 100644
--- a/src/modules/navigator/mission.cpp
+++ b/src/modules/navigator/mission.cpp
@@ -37,6 +37,7 @@
*
* @author Julian Oes <julian@oes.ch>
* @author Thomas Gubler <thomasgubler@gmail.com>
+ * @author Anton Babushkin <anton.babushkin@me.com>
*/
#include <sys/types.h>
@@ -113,6 +114,7 @@ Mission::on_inactive()
update_offboard_mission();
}
+ /* require takeoff after non-loiter or landing */
if (!_navigator->get_can_loiter_at_sp() || _navigator->get_vstatus()->condition_landed) {
_need_takeoff = true;
}
@@ -147,8 +149,19 @@ Mission::on_active()
/* lets check if we reached the current mission item */
if (_mission_type != MISSION_TYPE_NONE && is_mission_item_reached()) {
- advance_mission();
- set_mission_items();
+ if (_mission_item.autocontinue) {
+ /* switch to next waypoint if 'autocontinue' flag set */
+ advance_mission();
+ set_mission_items();
+
+ } else {
+ /* else just report that item reached */
+ if (_mission_type == MISSION_TYPE_OFFBOARD) {
+ if (!(_navigator->get_mission_result()->seq_reached == _current_offboard_mission_index && _navigator->get_mission_result()->reached)) {
+ set_mission_item_reached();
+ }
+ }
+ }
} else if (_mission_type != MISSION_TYPE_NONE &&_param_altmode.get() == MISSION_ALTMODE_FOH) {
altitude_sp_foh_update();
@@ -221,7 +234,7 @@ Mission::update_offboard_mission()
_current_offboard_mission_index = 0;
}
- report_current_offboard_mission_item();
+ set_current_offboard_mission_item();
}
@@ -359,6 +372,10 @@ Mission::set_mission_items()
/* no mission available or mission finished, switch to loiter */
if (_mission_type != MISSION_TYPE_NONE) {
mavlink_log_critical(_navigator->get_mavlink_fd(), "mission finished, loitering");
+
+ /* use last setpoint for loiter */
+ _navigator->set_can_loiter_at_sp(true);
+
} else if (!user_feedback_done) {
/* only tell users that we got no mission if there has not been any
* better, more specific feedback yet
@@ -375,10 +392,11 @@ Mission::set_mission_items()
mission_item_to_position_setpoint(&_mission_item, &pos_sp_triplet->current);
pos_sp_triplet->next.valid = false;
+ /* reuse setpoint for LOITER only if it's not IDLE */
_navigator->set_can_loiter_at_sp(pos_sp_triplet->current.type == SETPOINT_TYPE_LOITER);
reset_mission_item_reached();
- report_mission_finished();
+ set_mission_finished();
_navigator->set_position_setpoint_triplet_updated();
return;
@@ -415,7 +433,7 @@ Mission::set_mission_items()
takeoff_alt += _navigator->get_home_position()->alt;
}
- /* perform takeoff at least to NAV_TAKEOFF_ALT above home/ground, even if first waypoint is lower */
+ /* takeoff to at least NAV_TAKEOFF_ALT above home/ground, even if first waypoint is lower */
if (_navigator->get_vstatus()->condition_landed) {
takeoff_alt = fmaxf(takeoff_alt, _navigator->get_global_position()->alt + _param_takeoff_alt.get());
@@ -423,32 +441,46 @@ Mission::set_mission_items()
takeoff_alt = fmaxf(takeoff_alt, _navigator->get_home_position()->alt + _param_takeoff_alt.get());
}
- mavlink_log_critical(_navigator->get_mavlink_fd(), "takeoff to %.1f meters above home", (double)(takeoff_alt - _navigator->get_home_position()->alt));
+ /* check if we already above takeoff altitude */
+ if (_navigator->get_global_position()->alt < takeoff_alt - _navigator->get_acceptance_radius()) {
+ mavlink_log_critical(_navigator->get_mavlink_fd(), "takeoff to %.1f meters above home", (double)(takeoff_alt - _navigator->get_home_position()->alt));
- _mission_item.lat = _navigator->get_global_position()->lat;
- _mission_item.lon = _navigator->get_global_position()->lon;
- _mission_item.altitude = takeoff_alt;
- _mission_item.altitude_is_relative = false;
+ _mission_item.nav_cmd = NAV_CMD_TAKEOFF;
+ _mission_item.lat = _navigator->get_global_position()->lat;
+ _mission_item.lon = _navigator->get_global_position()->lon;
+ _mission_item.altitude = takeoff_alt;
+ _mission_item.altitude_is_relative = false;
+ _mission_item.autocontinue = true;
+ _mission_item.time_inside = 0;
- mission_item_to_position_setpoint(&_mission_item, &pos_sp_triplet->current);
+ mission_item_to_position_setpoint(&_mission_item, &pos_sp_triplet->current);
- } else {
- /* set current position setpoint from mission item */
- mission_item_to_position_setpoint(&_mission_item, &pos_sp_triplet->current);
+ _navigator->set_position_setpoint_triplet_updated();
+ return;
- /* require takeoff after landing or idle */
- if (pos_sp_triplet->current.type == SETPOINT_TYPE_LAND || pos_sp_triplet->current.type == SETPOINT_TYPE_IDLE) {
- _need_takeoff = true;
+ } else {
+ /* skip takeoff */
+ _takeoff = false;
}
+ }
- _navigator->set_can_loiter_at_sp(false);
- reset_mission_item_reached();
+ /* set current position setpoint from mission item */
+ mission_item_to_position_setpoint(&_mission_item, &pos_sp_triplet->current);
- if (_mission_type == MISSION_TYPE_OFFBOARD) {
- report_current_offboard_mission_item();
- }
- // TODO: report onboard mission item somehow
+ /* require takeoff after landing or idle */
+ if (pos_sp_triplet->current.type == SETPOINT_TYPE_LAND || pos_sp_triplet->current.type == SETPOINT_TYPE_IDLE) {
+ _need_takeoff = true;
+ }
+
+ _navigator->set_can_loiter_at_sp(false);
+ reset_mission_item_reached();
+
+ if (_mission_type == MISSION_TYPE_OFFBOARD) {
+ set_current_offboard_mission_item();
+ }
+ // TODO: report onboard mission item somehow
+ if (_mission_item.autocontinue && _mission_item.time_inside <= 0.001f) {
/* try to read next mission item */
struct mission_item_s mission_item_next;
@@ -460,6 +492,10 @@ Mission::set_mission_items()
/* next mission item is not available */
pos_sp_triplet->next.valid = false;
}
+
+ } else {
+ /* vehicle will be paused on current waypoint, don't set next item */
+ pos_sp_triplet->next.valid = false;
}
/* Save the distance between the current sp and the previous one */
@@ -666,19 +702,19 @@ Mission::save_offboard_mission_state()
}
void
-Mission::report_mission_item_reached()
+Mission::set_mission_item_reached()
{
- if (_mission_type == MISSION_TYPE_OFFBOARD) {
- _navigator->get_mission_result()->reached = true;
- _navigator->get_mission_result()->seq_reached = _current_offboard_mission_index;
- }
+ _navigator->get_mission_result()->reached = true;
+ _navigator->get_mission_result()->seq_reached = _current_offboard_mission_index;
_navigator->publish_mission_result();
}
void
-Mission::report_current_offboard_mission_item()
+Mission::set_current_offboard_mission_item()
{
warnx("current offboard mission index: %d", _current_offboard_mission_index);
+ _navigator->get_mission_result()->reached = false;
+ _navigator->get_mission_result()->finished = false;
_navigator->get_mission_result()->seq_current = _current_offboard_mission_index;
_navigator->publish_mission_result();
@@ -686,9 +722,8 @@ Mission::report_current_offboard_mission_item()
}
void
-Mission::report_mission_finished()
+Mission::set_mission_finished()
{
_navigator->get_mission_result()->finished = true;
_navigator->publish_mission_result();
}
-
diff --git a/src/modules/navigator/mission.h b/src/modules/navigator/mission.h
index 176529209..ea7cc0927 100644
--- a/src/modules/navigator/mission.h
+++ b/src/modules/navigator/mission.h
@@ -37,6 +37,7 @@
*
* @author Julian Oes <julian@oes.ch>
* @author Thomas Gubler <thomasgubler@gmail.com>
+ * @author Anton Babushkin <anton.babushkin@me.com>
*/
#ifndef NAVIGATOR_MISSION_H
@@ -130,19 +131,19 @@ private:
void save_offboard_mission_state();
/**
- * Report that a mission item has been reached
+ * Set a mission item as reached
*/
- void report_mission_item_reached();
+ void set_mission_item_reached();
/**
- * Rport the current mission item
+ * Set the current offboard mission item
*/
- void report_current_offboard_mission_item();
+ void set_current_offboard_mission_item();
/**
- * Report that the mission is finished if one exists or that none exists
+ * Set that the mission is finished if one exists or that none exists
*/
- void report_mission_finished();
+ void set_mission_finished();
control::BlockParamInt _param_onboard_enabled;
control::BlockParamFloat _param_takeoff_alt;
@@ -154,8 +155,8 @@ private:
int _current_onboard_mission_index;
int _current_offboard_mission_index;
- bool _need_takeoff;
- bool _takeoff;
+ bool _need_takeoff; /**< if true, then takeoff must be performed before going to the first waypoint (if needed) */
+ bool _takeoff; /**< takeoff state flag */
enum {
MISSION_TYPE_NONE,
diff --git a/src/modules/navigator/module.mk b/src/modules/navigator/module.mk
index c075903b7..fb8d07901 100644
--- a/src/modules/navigator/module.mk
+++ b/src/modules/navigator/module.mk
@@ -63,3 +63,5 @@ INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink
MODULE_STACKSIZE = 1200
EXTRACXXFLAGS = -Weffc++
+
+MAXOPTIMIZATION = -Os
diff --git a/src/modules/unit_test/unit_test.cpp b/src/modules/unit_test/unit_test.cpp
index be3b9461a..b7568ce3a 100644
--- a/src/modules/unit_test/unit_test.cpp
+++ b/src/modules/unit_test/unit_test.cpp
@@ -36,7 +36,11 @@
#include <systemlib/err.h>
-UnitTest::UnitTest()
+UnitTest::UnitTest() :
+ _tests_run(0),
+ _tests_failed(0),
+ _tests_passed(0),
+ _assertions(0)
{
}
@@ -44,20 +48,22 @@ UnitTest::~UnitTest()
{
}
-void UnitTest::printResults(void)
+void UnitTest::print_results(void)
{
- warnx(mu_tests_failed() ? "SOME TESTS FAILED" : "ALL TESTS PASSED");
- warnx(" Tests passed : %d", mu_tests_passed());
- warnx(" Tests failed : %d", mu_tests_failed());
- warnx(" Assertions : %d", mu_assertion());
+ warnx(_tests_failed ? "SOME TESTS FAILED" : "ALL TESTS PASSED");
+ warnx(" Tests passed : %d", _tests_passed);
+ warnx(" Tests failed : %d", _tests_failed);
+ warnx(" Assertions : %d", _assertions);
}
-void UnitTest::printAssert(const char* msg, const char* test, const char* file, int line)
+/// @brief Used internally to the ut_assert macro to print assert failures.
+void UnitTest::_print_assert(const char* msg, const char* test, const char* file, int line)
{
- warnx("Assertion failed: %s - %s (%s:%d)", msg, test, file, line);
+ warnx("Assertion failed: %s - %s (%s:%d)", msg, test, file, line);
}
-void UnitTest::printCompare(const char* msg, const char *v1_text, int v1, const char *v2_text, int v2, const char* file, int line)
+/// @brief Used internally to the ut_compare macro to print assert failures.
+void UnitTest::_print_compare(const char* msg, const char *v1_text, int v1, const char *v2_text, int v2, const char* file, int line)
{
warnx("Compare failed: %s - (%s:%d) (%s:%d) (%s:%d)", msg, v1_text, v1, v2_text, v2, file, line);
}
diff --git a/src/modules/unit_test/unit_test.h b/src/modules/unit_test/unit_test.h
index 1a5489709..8ed4efadf 100644
--- a/src/modules/unit_test/unit_test.h
+++ b/src/modules/unit_test/unit_test.h
@@ -37,68 +37,85 @@
#include <systemlib/err.h>
+/// @brief Base class to be used for unit tests.
class __EXPORT UnitTest
{
-
public:
-#define INLINE_GLOBAL(type,func) inline type& func() { static type x; return x; }
-
-INLINE_GLOBAL(int, mu_tests_run)
-INLINE_GLOBAL(int, mu_tests_failed)
-INLINE_GLOBAL(int, mu_tests_passed)
-INLINE_GLOBAL(int, mu_assertion)
-INLINE_GLOBAL(int, mu_line)
-INLINE_GLOBAL(const char*, mu_last_test)
UnitTest();
- virtual ~UnitTest();
+ virtual ~UnitTest();
- virtual void init(void) { };
- virtual void cleanup(void) { };
-
- virtual void runTests(void) = 0;
- void printResults(void);
-
- void printAssert(const char* msg, const char* test, const char* file, int line);
- void printCompare(const char* msg, const char *v1_text, int v1, const char *v2_text, int v2, const char* file, int line);
-
-#define ut_assert(message, test) \
- do { \
- if (!(test)) { \
- printAssert(message, #test, __FILE__, __LINE__); \
- return false; \
- } else { \
- mu_assertion()++; \
- } \
- } while (0)
-
-#define ut_compare(message, v1, v2) \
- do { \
- int _v1 = v1; \
- int _v2 = v2; \
- if (_v1 != _v2) { \
- printCompare(message, #v1, _v1, #v2, _v2, __FILE__, __LINE__); \
- return false; \
- } else { \
- mu_assertion()++; \
- } \
+ /// @brief Override to run your unit tests. Unit tests should be called using ut_run_test macro.
+ /// @return true: all unit tests succeeded, false: one or more unit tests failed
+ virtual bool run_tests(void) = 0;
+
+ /// @brief Prints results from running of unit tests.
+ void print_results(void);
+
+/// @brief Macro to create a function which will run a unit test class and print results.
+#define ut_declare_test(test_function, test_class) \
+ bool test_function(void) \
+ { \
+ test_class* test = new test_class(); \
+ bool success = test->run_tests(); \
+ test->print_results(); \
+ return success; \
+ }
+
+protected:
+
+/// @brief Runs a single unit test. Unit tests must have the function signature of bool test(void). The unit
+/// test should return true if it succeeded, false for fail.
+#define ut_run_test(test) \
+ do { \
+ warnx("RUNNING TEST: %s", #test); \
+ _tests_run++; \
+ _init(); \
+ if (!test()) { \
+ warnx("TEST FAILED: %s", #test); \
+ _tests_failed++; \
+ } else { \
+ warnx("TEST PASSED: %s", #test); \
+ _tests_passed++; \
+ } \
+ _cleanup(); \
} while (0)
-
-#define ut_run_test(test) \
- do { \
- warnx("RUNNING TEST: %s", #test); \
- mu_tests_run()++; \
- init(); \
- if (!test()) { \
- warnx("TEST FAILED: %s", #test); \
- mu_tests_failed()++; \
- } else { \
- warnx("TEST PASSED: %s", #test); \
- mu_tests_passed()++; \
- } \
- cleanup(); \
- } while (0)
+
+/// @brief Used to assert a value within a unit test.
+#define ut_assert(message, test) \
+ do { \
+ if (!(test)) { \
+ _print_assert(message, #test, __FILE__, __LINE__); \
+ return false; \
+ } else { \
+ _assertions++; \
+ } \
+ } while (0)
+
+/// @brief Used to compare two integer values within a unit test. If possible use ut_compare instead of ut_assert
+/// since it will give you better error reporting of the actual values being compared.
+#define ut_compare(message, v1, v2) \
+ do { \
+ int _v1 = v1; \
+ int _v2 = v2; \
+ if (_v1 != _v2) { \
+ _print_compare(message, #v1, _v1, #v2, _v2, __FILE__, __LINE__); \
+ return false; \
+ } else { \
+ _assertions++; \
+ } \
+ } while (0)
+
+ virtual void _init(void) { }; ///< Run before each unit test. Override to provide custom behavior.
+ virtual void _cleanup(void) { }; ///< Run after each unit test. Override to provide custom behavior.
+
+ void _print_assert(const char* msg, const char* test, const char* file, int line);
+ void _print_compare(const char* msg, const char *v1_text, int v1, const char *v2_text, int v2, const char* file, int line);
+ int _tests_run; ///< The number of individual unit tests run
+ int _tests_failed; ///< The number of unit tests which failed
+ int _tests_passed; ///< The number of unit tests which passed
+ int _assertions; ///< Total number of assertions tested by all unit tests
};
#endif /* UNIT_TEST_H_ */