aboutsummaryrefslogtreecommitdiff
path: root/src/lib
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2014-03-06 21:53:51 +0100
committerThomas Gubler <thomasgubler@gmail.com>2014-03-06 21:53:51 +0100
commitb086bdf21ef593331da8c48cc21468ff823cdc01 (patch)
tree85bf8eb5d3c2c62a2252f5d6a4ebe7bf982daaf5 /src/lib
parentf2b46389ee8c8e9dd73ad9ac1fc8170c759e8b1c (diff)
parent320745003783c6306996a1e6339ec91bfefcc7d0 (diff)
downloadpx4-firmware-b086bdf21ef593331da8c48cc21468ff823cdc01.tar.gz
px4-firmware-b086bdf21ef593331da8c48cc21468ff823cdc01.tar.bz2
px4-firmware-b086bdf21ef593331da8c48cc21468ff823cdc01.zip
Merge remote-tracking branch 'upstream/master' into launchdetector
Conflicts: src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
Diffstat (limited to 'src/lib')
-rw-r--r--src/lib/ecl/ecl.h3
-rw-r--r--src/lib/ecl/l1/ecl_l1_pos_controller.cpp13
-rw-r--r--src/lib/external_lgpl/tecs/tecs.cpp5
-rw-r--r--src/lib/external_lgpl/tecs/tecs.h27
4 files changed, 26 insertions, 22 deletions
diff --git a/src/lib/ecl/ecl.h b/src/lib/ecl/ecl.h
index e0f207696..aa3c5000a 100644
--- a/src/lib/ecl/ecl.h
+++ b/src/lib/ecl/ecl.h
@@ -38,7 +38,6 @@
*/
#include <drivers/drv_hrt.h>
-#include <geo/geo.h>
#define ecl_absolute_time hrt_absolute_time
-#define ecl_elapsed_time hrt_elapsed_time \ No newline at end of file
+#define ecl_elapsed_time hrt_elapsed_time
diff --git a/src/lib/ecl/l1/ecl_l1_pos_controller.cpp b/src/lib/ecl/l1/ecl_l1_pos_controller.cpp
index 3b68a0a4e..d1c864d78 100644
--- a/src/lib/ecl/l1/ecl_l1_pos_controller.cpp
+++ b/src/lib/ecl/l1/ecl_l1_pos_controller.cpp
@@ -38,6 +38,8 @@
*
*/
+#include <float.h>
+
#include "ecl_l1_pos_controller.h"
float ECL_L1_Pos_Controller::nav_roll()
@@ -231,8 +233,15 @@ void ECL_L1_Pos_Controller::navigate_loiter(const math::Vector<2> &vector_A, con
/* calculate the vector from waypoint A to current position */
math::Vector<2> vector_A_to_airplane = get_local_planar_vector(vector_A, vector_curr_position);
- /* store the normalized vector from waypoint A to current position */
- math::Vector<2> vector_A_to_airplane_unit = (vector_A_to_airplane).normalized();
+ math::Vector<2> vector_A_to_airplane_unit;
+
+ /* prevent NaN when normalizing */
+ if (vector_A_to_airplane.length() > FLT_EPSILON) {
+ /* store the normalized vector from waypoint A to current position */
+ vector_A_to_airplane_unit = vector_A_to_airplane.normalized();
+ } else {
+ vector_A_to_airplane_unit = vector_A_to_airplane;
+ }
/* calculate eta angle towards the loiter center */
diff --git a/src/lib/external_lgpl/tecs/tecs.cpp b/src/lib/external_lgpl/tecs/tecs.cpp
index 0f28bccad..3730b1920 100644
--- a/src/lib/external_lgpl/tecs/tecs.cpp
+++ b/src/lib/external_lgpl/tecs/tecs.cpp
@@ -3,13 +3,10 @@
#include "tecs.h"
#include <ecl/ecl.h>
#include <systemlib/err.h>
+#include <geo/geo.h>
using namespace math;
-#ifndef CONSTANTS_ONE_G
-#define CONSTANTS_ONE_G GRAVITY
-#endif
-
/**
* @file tecs.cpp
*
diff --git a/src/lib/external_lgpl/tecs/tecs.h b/src/lib/external_lgpl/tecs/tecs.h
index d1ebacda1..5cafb1c79 100644
--- a/src/lib/external_lgpl/tecs/tecs.h
+++ b/src/lib/external_lgpl/tecs/tecs.h
@@ -28,16 +28,7 @@ class __EXPORT TECS
{
public:
TECS() :
-
- _airspeed_enabled(false),
- _throttle_slewrate(0.0f),
- _climbOutDem(false),
- _hgt_dem_prev(0.0f),
- _hgt_dem_adj_last(0.0f),
- _hgt_dem_in_old(0.0f),
- _TAS_dem_last(0.0f),
- _TAS_dem_adj(0.0f),
- _TAS_dem(0.0f),
+ _pitch_dem(0.0f),
_integ1_state(0.0f),
_integ2_state(0.0f),
_integ3_state(0.0f),
@@ -45,8 +36,16 @@ public:
_integ5_state(0.0f),
_integ6_state(0.0f),
_integ7_state(0.0f),
- _pitch_dem(0.0f),
_last_pitch_dem(0.0f),
+ _vel_dot(0.0f),
+ _TAS_dem(0.0f),
+ _TAS_dem_last(0.0f),
+ _hgt_dem_in_old(0.0f),
+ _hgt_dem_adj_last(0.0f),
+ _hgt_dem_prev(0.0f),
+ _TAS_dem_adj(0.0f),
+ _STEdotErrLast(0.0f),
+ _climbOutDem(false),
_SPE_dem(0.0f),
_SKE_dem(0.0f),
_SPEdot_dem(0.0f),
@@ -55,9 +54,9 @@ public:
_SKE_est(0.0f),
_SPEdot(0.0f),
_SKEdot(0.0f),
- _vel_dot(0.0f),
- _STEdotErrLast(0.0f) {
-
+ _airspeed_enabled(false),
+ _throttle_slewrate(0.0f)
+ {
}
bool airspeed_sensor_enabled() {