aboutsummaryrefslogtreecommitdiff
path: root/src
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2013-11-03 18:38:34 +0100
committerThomas Gubler <thomasgubler@gmail.com>2013-11-03 18:38:34 +0100
commitfa4533e3592d055bbd298d81ad3760e19dedec95 (patch)
tree6e0bf72ca6d08671b54266696404471a2db6fddd /src
parent1aef7c502cc50b724a3eb47c05dcdb5bec6de4a3 (diff)
parent791695ccd008859f6abe1a12d86b7be2ba811fec (diff)
downloadpx4-firmware-fa4533e3592d055bbd298d81ad3760e19dedec95.tar.gz
px4-firmware-fa4533e3592d055bbd298d81ad3760e19dedec95.tar.bz2
px4-firmware-fa4533e3592d055bbd298d81ad3760e19dedec95.zip
Merge remote-tracking branch 'upstream/master' into fw_autoland_att_tecs
Diffstat (limited to 'src')
-rw-r--r--src/lib/external_lgpl/tecs/tecs.h4
-rw-r--r--src/lib/mathlib/math/arm/Matrix.hpp6
-rw-r--r--src/lib/mathlib/math/arm/Vector.hpp6
-rw-r--r--src/modules/commander/mag_calibration.cpp29
-rw-r--r--src/modules/uORB/uORB.cpp4
-rw-r--r--src/systemcmds/preflight_check/preflight_check.c28
6 files changed, 57 insertions, 20 deletions
diff --git a/src/lib/external_lgpl/tecs/tecs.h b/src/lib/external_lgpl/tecs/tecs.h
index d07bd00dd..06e1c8ad3 100644
--- a/src/lib/external_lgpl/tecs/tecs.h
+++ b/src/lib/external_lgpl/tecs/tecs.h
@@ -54,7 +54,9 @@ public:
_SPE_est(0.0f),
_SKE_est(0.0f),
_SPEdot(0.0f),
- _SKEdot(0.0f) {
+ _SKEdot(0.0f),
+ _vel_dot(0.0f),
+ _STEdotErrLast(0.0f) {
}
diff --git a/src/lib/mathlib/math/arm/Matrix.hpp b/src/lib/mathlib/math/arm/Matrix.hpp
index 715fd3a5e..1945bb02d 100644
--- a/src/lib/mathlib/math/arm/Matrix.hpp
+++ b/src/lib/mathlib/math/arm/Matrix.hpp
@@ -121,10 +121,10 @@ public:
for (size_t i = 0; i < getRows(); i++) {
for (size_t j = 0; j < getCols(); j++) {
float sig;
- int exp;
+ int exponent;
float num = (*this)(i, j);
- float2SigExp(num, sig, exp);
- printf("%6.3fe%03.3d,", (double)sig, exp);
+ float2SigExp(num, sig, exponent);
+ printf("%6.3fe%03d ", (double)sig, exponent);
}
printf("\n");
diff --git a/src/lib/mathlib/math/arm/Vector.hpp b/src/lib/mathlib/math/arm/Vector.hpp
index 4155800e8..52220fc15 100644
--- a/src/lib/mathlib/math/arm/Vector.hpp
+++ b/src/lib/mathlib/math/arm/Vector.hpp
@@ -109,10 +109,10 @@ public:
inline void print() const {
for (size_t i = 0; i < getRows(); i++) {
float sig;
- int exp;
+ int exponent;
float num = (*this)(i);
- float2SigExp(num, sig, exp);
- printf("%6.3fe%03.3d,", (double)sig, exp);
+ float2SigExp(num, sig, exponent);
+ printf("%6.3fe%03d ", (double)sig, exponent);
}
printf("\n");
diff --git a/src/modules/commander/mag_calibration.cpp b/src/modules/commander/mag_calibration.cpp
index 09f4104f8..4ebf266f4 100644
--- a/src/modules/commander/mag_calibration.cpp
+++ b/src/modules/commander/mag_calibration.cpp
@@ -73,7 +73,7 @@ int do_mag_calibration(int mavlink_fd)
/* maximum 500 values */
const unsigned int calibration_maxcount = 500;
- unsigned int calibration_counter = 0;
+ unsigned int calibration_counter;
struct mag_scale mscale_null = {
0.0f,
@@ -99,28 +99,34 @@ int do_mag_calibration(int mavlink_fd)
res = ioctl(fd, MAGIOCCALIBRATE, fd);
if (res != OK) {
- mavlink_log_critical(mavlink_fd, "ERROR: failed to calibrate scale");
+ mavlink_log_critical(mavlink_fd, "Skipped scale calibration");
+ /* this is non-fatal - mark it accordingly */
+ res = OK;
}
}
close(fd);
- float *x;
- float *y;
- float *z;
+ float *x = NULL;
+ float *y = NULL;
+ float *z = NULL;
if (res == OK) {
/* allocate memory */
mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, 20);
- x = (float *)malloc(sizeof(float) * calibration_maxcount);
- y = (float *)malloc(sizeof(float) * calibration_maxcount);
- z = (float *)malloc(sizeof(float) * calibration_maxcount);
+ x = reinterpret_cast<float *>(malloc(sizeof(float) * calibration_maxcount));
+ y = reinterpret_cast<float *>(malloc(sizeof(float) * calibration_maxcount));
+ z = reinterpret_cast<float *>(malloc(sizeof(float) * calibration_maxcount));
if (x == NULL || y == NULL || z == NULL) {
mavlink_log_critical(mavlink_fd, "ERROR: out of memory");
res = ERROR;
+ return res;
}
+ } else {
+ /* exit */
+ return ERROR;
}
if (res == OK) {
@@ -136,6 +142,8 @@ int do_mag_calibration(int mavlink_fd)
mavlink_log_info(mavlink_fd, "rotate in a figure 8 around all axis");
+ calibration_counter = 0;
+
while (hrt_absolute_time() < calibration_deadline &&
calibration_counter < calibration_maxcount) {
@@ -178,6 +186,7 @@ int do_mag_calibration(int mavlink_fd)
float sphere_radius;
if (res == OK) {
+
/* sphere fit */
mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, 70);
sphere_fit_least_squares(x, y, z, calibration_counter, 100, 0.0f, &sphere_x, &sphere_y, &sphere_z, &sphere_radius);
@@ -270,7 +279,7 @@ int do_mag_calibration(int mavlink_fd)
} else {
mavlink_log_info(mavlink_fd, CAL_FAILED_MSG, sensor_name);
}
-
- return res;
}
+
+ return res;
}
diff --git a/src/modules/uORB/uORB.cpp b/src/modules/uORB/uORB.cpp
index 7abbf42ae..149b8f6d2 100644
--- a/src/modules/uORB/uORB.cpp
+++ b/src/modules/uORB/uORB.cpp
@@ -249,8 +249,10 @@ ORBDevNode::close(struct file *filp)
} else {
SubscriberData *sd = filp_to_sd(filp);
- if (sd != nullptr)
+ if (sd != nullptr) {
+ hrt_cancel(&sd->update_call);
delete sd;
+ }
}
return CDev::close(filp);
diff --git a/src/systemcmds/preflight_check/preflight_check.c b/src/systemcmds/preflight_check/preflight_check.c
index 1c58a2db6..07581459b 100644
--- a/src/systemcmds/preflight_check/preflight_check.c
+++ b/src/systemcmds/preflight_check/preflight_check.c
@@ -109,7 +109,7 @@ int preflight_check_main(int argc, char *argv[])
/* ---- ACCEL ---- */
close(fd);
- fd = open(ACCEL_DEVICE_PATH, 0);
+ fd = open(ACCEL_DEVICE_PATH, O_RDONLY);
ret = ioctl(fd, ACCELIOCSELFTEST, 0);
if (ret != OK) {
@@ -119,6 +119,29 @@ int preflight_check_main(int argc, char *argv[])
goto system_eval;
}
+ /* check measurement result range */
+ struct accel_report acc;
+ ret = read(fd, &acc, sizeof(acc));
+
+ if (ret == sizeof(acc)) {
+ /* evaluate values */
+ if (sqrtf(acc.x * acc.x + acc.y * acc.y + acc.z * acc.z) > 30.0f /* m/s^2 */) {
+ warnx("accel with spurious values");
+ mavlink_log_critical(mavlink_fd, "SENSOR FAIL: |ACCEL| > 30 m/s^2");
+ /* this is frickin' fatal */
+ fail_on_error = true;
+ system_ok = false;
+ goto system_eval;
+ }
+ } else {
+ warnx("accel read failed");
+ mavlink_log_critical(mavlink_fd, "SENSOR FAIL: ACCEL READ");
+ /* this is frickin' fatal */
+ fail_on_error = true;
+ system_ok = false;
+ goto system_eval;
+ }
+
/* ---- GYRO ---- */
close(fd);
@@ -193,9 +216,10 @@ system_eval:
/* stop alarm */
ioctl(buzzer, TONE_SET_ALARM, TONE_STOP_TUNE);
- /* switch on leds */
+ /* switch off leds */
led_on(leds, LED_BLUE);
led_on(leds, LED_AMBER);
+ close(leds);
if (fail_on_error) {
/* exit with error message */