aboutsummaryrefslogtreecommitdiff
path: root/src
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2014-03-27 18:19:57 +0100
committerThomas Gubler <thomasgubler@gmail.com>2014-03-27 18:19:57 +0100
commitfa336e4a9716f58d78938157696691e4536a3f99 (patch)
treed2be239af8652b75f59d1a2994f7bcdcafd36c2d /src
parent2af4e521ade7ecc29335b4442e958b6c815d01f2 (diff)
parent9b1de5004c673ebe8bdf68f1b518565cccd6b05b (diff)
downloadpx4-firmware-fa336e4a9716f58d78938157696691e4536a3f99.tar.gz
px4-firmware-fa336e4a9716f58d78938157696691e4536a3f99.tar.bz2
px4-firmware-fa336e4a9716f58d78938157696691e4536a3f99.zip
Merge remote-tracking branch 'upstream/master' into paul_mtecs
Diffstat (limited to 'src')
-rw-r--r--src/modules/commander/commander.cpp11
-rw-r--r--src/modules/mavlink/mavlink_messages.cpp93
2 files changed, 73 insertions, 31 deletions
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index d114a2e5c..cf7ba757e 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -119,6 +119,7 @@ extern struct system_load_s system_load;
#define POSITION_TIMEOUT 1000000 /**< consider the local or global position estimate invalid after 1s */
#define RC_TIMEOUT 100000
+#define RC_TIMEOUT_HIL 500000
#define DIFFPRESS_TIMEOUT 2000000
#define PRINT_INTERVAL 5000000
@@ -1108,8 +1109,16 @@ 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;
diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp
index 96852bb0e..4ca3840d4 100644
--- a/src/modules/mavlink/mavlink_messages.cpp
+++ b/src/modules/mavlink/mavlink_messages.cpp
@@ -71,6 +71,7 @@
#include <uORB/topics/battery_status.h>
#include <uORB/topics/navigation_capabilities.h>
#include <drivers/drv_rc_input.h>
+#include <drivers/drv_pwm_output.h>
#include "mavlink_messages.h"
@@ -788,47 +789,79 @@ protected:
uint32_t mavlink_custom_mode;
get_mavlink_mode_state(status, pos_sp_triplet, &mavlink_state, &mavlink_base_mode, &mavlink_custom_mode);
- /* set number of valid outputs depending on vehicle type */
- unsigned n;
+ if (mavlink_system.type == MAV_TYPE_QUADROTOR ||
+ mavlink_system.type == MAV_TYPE_HEXAROTOR ||
+ mavlink_system.type == MAV_TYPE_OCTOROTOR) {
+ /* set number of valid outputs depending on vehicle type */
+ unsigned n;
- switch (mavlink_system.type) {
- case MAV_TYPE_QUADROTOR:
- n = 4;
- break;
+ switch (mavlink_system.type) {
+ case MAV_TYPE_QUADROTOR:
+ n = 4;
+ break;
- case MAV_TYPE_HEXAROTOR:
- n = 6;
- break;
+ case MAV_TYPE_HEXAROTOR:
+ n = 6;
+ break;
- default:
- n = 8;
- break;
- }
+ default:
+ n = 8;
+ break;
+ }
- /* scale / assign outputs depending on system type */
- float out[8];
+ /* scale / assign outputs depending on system type */
+ float out[8];
- for (unsigned i = 0; i < 8; i++) {
- if (i < n) {
- if (mavlink_base_mode & MAV_MODE_FLAG_SAFETY_ARMED) {
- /* scale fake PWM out 900..2100 us to -1..1*/
- out[i] = (act->output[i] - 1500.0f) / 600.0f;
+ for (unsigned i = 0; i < 8; i++) {
+ if (i < n) {
+ if (mavlink_base_mode & MAV_MODE_FLAG_SAFETY_ARMED) {
+ /* scale fake PWM out 900..2100 us to 0..1 for normal multirotors */
+ out[i] = (act->output[i] - PWM_LOWEST_MIN) / (PWM_HIGHEST_MAX - PWM_LOWEST_MIN);
+
+ } else {
+ /* send 0 when disarmed */
+ out[i] = 0.0f;
+ }
} else {
- /* send 0 when disarmed */
- out[i] = 0.0f;
+ out[i] = -1.0f;
+ }
+ }
+
+ mavlink_msg_hil_controls_send(_channel,
+ hrt_absolute_time(),
+ out[0], out[1], out[2], out[3], out[4], out[5], out[6], out[7],
+ mavlink_base_mode,
+ 0);
+ } else {
+
+ /* fixed wing: scale all channels except throttle -1 .. 1
+ * because we know that we set the mixers up this way
+ */
+
+ float out[8];
+
+ const float pwm_center = (PWM_HIGHEST_MAX + PWM_LOWEST_MIN) / 2;
+
+ for (unsigned i = 0; i < 8; i++) {
+ if (i != 3) {
+ /* scale fake PWM out 900..2100 us to -1..+1 for normal channels */
+ out[i] = (act->output[i] - pwm_center) / ((PWM_HIGHEST_MAX - PWM_LOWEST_MIN) / 2);
+
+ } else {
+
+ /* scale fake PWM out 900..2100 us to 0..1 for throttle */
+ out[i] = (act->output[i] - PWM_LOWEST_MIN) / (PWM_HIGHEST_MAX - PWM_LOWEST_MIN);
}
- } else {
- out[i] = -1.0f;
}
- }
- mavlink_msg_hil_controls_send(_channel,
- hrt_absolute_time(),
- out[0], out[1], out[2], out[3], out[4], out[5], out[6], out[7],
- mavlink_base_mode,
- 0);
+ mavlink_msg_hil_controls_send(_channel,
+ hrt_absolute_time(),
+ out[0], out[1], out[2], out[3], out[4], out[5], out[6], out[7],
+ mavlink_base_mode,
+ 0);
+ }
}
}
};