aboutsummaryrefslogtreecommitdiff
path: root/src/modules/commander
diff options
context:
space:
mode:
authorJulian Oes <julian@oes.ch>2014-04-07 21:45:45 +0200
committerJulian Oes <julian@oes.ch>2014-04-07 21:45:45 +0200
commitfc2bfb828f0f2ba681da1b33addd03698db4b679 (patch)
treea133e82429f186e8b7b727092944777f4d0b6d42 /src/modules/commander
parent38c3e68976c8dc167b4d1e5d24792401fc7cc7d3 (diff)
parente4628fbed641496704011b0c488a36ed05b45d5f (diff)
downloadpx4-firmware-fc2bfb828f0f2ba681da1b33addd03698db4b679.tar.gz
px4-firmware-fc2bfb828f0f2ba681da1b33addd03698db4b679.tar.bz2
px4-firmware-fc2bfb828f0f2ba681da1b33addd03698db4b679.zip
Merge remote-tracking branch 'px4/master' into mavlink_broadcast
Diffstat (limited to 'src/modules/commander')
-rw-r--r--src/modules/commander/airspeed_calibration.cpp14
-rw-r--r--src/modules/commander/commander.cpp13
2 files changed, 10 insertions, 17 deletions
diff --git a/src/modules/commander/airspeed_calibration.cpp b/src/modules/commander/airspeed_calibration.cpp
index 6039d92a7..c8c7a42e7 100644
--- a/src/modules/commander/airspeed_calibration.cpp
+++ b/src/modules/commander/airspeed_calibration.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2013, 2014 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
@@ -64,9 +64,9 @@ int do_airspeed_calibration(int mavlink_fd)
{
/* give directions */
mavlink_log_info(mavlink_fd, CAL_STARTED_MSG, sensor_name);
- mavlink_log_info(mavlink_fd, "don't move system");
+ mavlink_log_info(mavlink_fd, "ensure airspeed sensor is not registering wind");
- const int calibration_count = 2500;
+ const int calibration_count = 2000;
int diff_pres_sub = orb_subscribe(ORB_ID(differential_pressure));
struct differential_pressure_s diff_pres;
@@ -85,13 +85,15 @@ int do_airspeed_calibration(int mavlink_fd)
if (fd > 0) {
if (OK == ioctl(fd, AIRSPEEDIOCSSCALE, (long unsigned int)&airscale)) {
paramreset_successful = true;
+ } else {
+ mavlink_log_critical(mavlink_fd, "airspeed offset zero failed");
}
close(fd);
}
if (!paramreset_successful) {
- warn("WARNING: failed to set scale / offsets for airspeed sensor");
- mavlink_log_critical(mavlink_fd, "could not reset dpress sensor");
+ warn("FAILED to set scale / offsets for airspeed");
+ mavlink_log_critical(mavlink_fd, "dpress reset failed");
mavlink_log_info(mavlink_fd, CAL_FAILED_MSG, sensor_name);
return ERROR;
}
@@ -107,7 +109,7 @@ int do_airspeed_calibration(int mavlink_fd)
if (poll_ret) {
orb_copy(ORB_ID(differential_pressure), diff_pres_sub, &diff_pres);
- diff_pres_offset += diff_pres.differential_pressure_pa;
+ diff_pres_offset += diff_pres.differential_pressure_raw_pa;
calibration_counter++;
if (calibration_counter % (calibration_count / 20) == 0)
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index 06f7ae6cc..69a45a02f 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -118,8 +118,7 @@ extern struct system_load_s system_load;
#define STICK_ON_OFF_COUNTER_LIMIT (STICK_ON_OFF_HYSTERESIS_TIME_MS*COMMANDER_MONITORING_LOOPSPERMSEC)
#define POSITION_TIMEOUT 1000000 /**< consider the local or global position estimate invalid after 1s */
-#define RC_TIMEOUT 100000
-#define RC_TIMEOUT_HIL 500000
+#define RC_TIMEOUT 500000
#define DIFFPRESS_TIMEOUT 2000000
#define PRINT_INTERVAL 5000000
@@ -1109,16 +1108,8 @@ int commander_thread_main(int argc, char *argv[])
}
}
-
- /*
- * XXX workaround:
- * Prevent RC loss in HIL when sensors.cpp is only publishing sp_man at a low rate (e.g. 30Hz)
- * which can trigger RC loss if the computer/simulator lags.
- */
- uint64_t rc_timeout = status.hil_state == HIL_STATE_ON ? RC_TIMEOUT_HIL : RC_TIMEOUT;
-
/* start RC input check */
- if (!status.rc_input_blocked && sp_man.timestamp != 0 && hrt_absolute_time() < sp_man.timestamp + rc_timeout) {
+ if (!status.rc_input_blocked && sp_man.timestamp != 0 && hrt_absolute_time() < sp_man.timestamp + RC_TIMEOUT) {
/* handle the case where RC signal was regained */
if (!status.rc_signal_found_once) {
status.rc_signal_found_once = true;