aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorJulian Oes <julian@oes.ch>2014-02-23 12:28:11 +0100
committerJulian Oes <julian@oes.ch>2014-02-23 12:28:11 +0100
commit1a6c53301bca6c085ca4cd977c12475ae95ff0a4 (patch)
tree8bbbeb278447dbd58d5eed69d53ab97c7bc116af
parentb17cdb12b013a99a924b02ccef718c0ea0f776aa (diff)
parentc659e0240b5db87b2b117bc950f4d7d50838d241 (diff)
downloadpx4-firmware-1a6c53301bca6c085ca4cd977c12475ae95ff0a4.tar.gz
px4-firmware-1a6c53301bca6c085ca4cd977c12475ae95ff0a4.tar.bz2
px4-firmware-1a6c53301bca6c085ca4cd977c12475ae95ff0a4.zip
Merge remote-tracking branch 'px4/beta' into beta_mavlink
-rw-r--r--src/drivers/drv_pwm_output.h2
-rw-r--r--src/drivers/px4io/px4io.cpp57
-rw-r--r--src/modules/px4iofirmware/dsm.c34
-rw-r--r--src/modules/px4iofirmware/registers.c2
4 files changed, 63 insertions, 32 deletions
diff --git a/src/drivers/drv_pwm_output.h b/src/drivers/drv_pwm_output.h
index c3eea310f..7a93e513e 100644
--- a/src/drivers/drv_pwm_output.h
+++ b/src/drivers/drv_pwm_output.h
@@ -160,7 +160,7 @@ ORB_DECLARE(output_pwm);
#define DSM2_BIND_PULSES 3 /* DSM_BIND_START ioctl parameter, pulses required to start dsm2 pairing */
#define DSMX_BIND_PULSES 7 /* DSM_BIND_START ioctl parameter, pulses required to start dsmx pairing */
-#define DSMX8_BIND_PULSES 10 /* DSM_BIND_START ioctl parameter, pulses required to start 8 or more channel dsmx pairing */
+#define DSMX8_BIND_PULSES 10 /* DSM_BIND_START ioctl parameter, pulses required to start 8 or more channel dsmx pairing */
/** power up DSM receiver */
#define DSM_BIND_POWER_UP _IOC(_PWM_SERVO_BASE, 11)
diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp
index efcf4d12b..7c7b3dcb7 100644
--- a/src/drivers/px4io/px4io.cpp
+++ b/src/drivers/px4io/px4io.cpp
@@ -244,8 +244,7 @@ private:
volatile int _task; ///< worker task id
volatile bool _task_should_exit; ///< worker terminate flag
- int _mavlink_fd; ///< mavlink file descriptor. This is opened by class instantiation and Doesn't appear to be usable in main thread.
- int _thread_mavlink_fd; ///< mavlink file descriptor for thread.
+ int _mavlink_fd; ///< mavlink file descriptor.
perf_counter_t _perf_update; ///<local performance counter for status updates
perf_counter_t _perf_write; ///<local performance counter for PWM control writes
@@ -474,7 +473,6 @@ PX4IO::PX4IO(device::Device *interface) :
_task(-1),
_task_should_exit(false),
_mavlink_fd(-1),
- _thread_mavlink_fd(-1),
_perf_update(perf_alloc(PC_ELAPSED, "io update")),
_perf_write(perf_alloc(PC_ELAPSED, "io write")),
_perf_chan_count(perf_alloc(PC_COUNT, "io rc #")),
@@ -507,9 +505,6 @@ PX4IO::PX4IO(device::Device *interface) :
/* we need this potentially before it could be set in task_main */
g_dev = this;
- /* open MAVLink text channel */
- _mavlink_fd = ::open(MAVLINK_LOG_DEVICE, 0);
-
_debug_enabled = false;
_servorail_status.rssi_v = 0;
}
@@ -785,7 +780,7 @@ PX4IO::task_main()
hrt_abstime poll_last = 0;
hrt_abstime orb_check_last = 0;
- _thread_mavlink_fd = ::open(MAVLINK_LOG_DEVICE, 0);
+ _mavlink_fd = ::open(MAVLINK_LOG_DEVICE, 0);
/*
* Subscribe to the appropriate PWM output topic based on whether we are the
@@ -880,6 +875,10 @@ PX4IO::task_main()
/* run at 5Hz */
orb_check_last = now;
+ /* try to claim the MAVLink log FD */
+ if (_mavlink_fd < 0)
+ _mavlink_fd = ::open(MAVLINK_LOG_DEVICE, 0);
+
/* check updates on uORB topics and handle it */
bool updated = false;
@@ -1275,16 +1274,14 @@ void
PX4IO::dsm_bind_ioctl(int dsmMode)
{
if (!(_status & PX4IO_P_STATUS_FLAGS_SAFETY_OFF)) {
- /* 0: dsm2, 1:dsmx */
- if ((dsmMode == 0) || (dsmMode == 1)) {
- mavlink_log_info(_thread_mavlink_fd, "[IO] binding dsm%s rx", (dsmMode == 0) ? "2" : ((dsmMode == 1) ? "x" : "x8"));
- ioctl(nullptr, DSM_BIND_START, (dsmMode == 0) ? DSM2_BIND_PULSES : ((dsmMode == 1) ? DSMX_BIND_PULSES : DSMX8_BIND_PULSES));
- } else {
- mavlink_log_info(_thread_mavlink_fd, "[IO] invalid dsm bind mode, bind request rejected");
- }
+ mavlink_log_info(_mavlink_fd, "[IO] binding DSM%s RX", (dsmMode == 0) ? "2" : ((dsmMode == 1) ? "-X" : "-X8"));
+ int ret = ioctl(nullptr, DSM_BIND_START, (dsmMode == 0) ? DSM2_BIND_PULSES : ((dsmMode == 1) ? DSMX_BIND_PULSES : DSMX8_BIND_PULSES));
+
+ if (ret)
+ mavlink_log_critical(_mavlink_fd, "binding failed.");
} else {
- mavlink_log_info(_thread_mavlink_fd, "[IO] system armed, bind request rejected");
+ mavlink_log_info(_mavlink_fd, "[IO] system armed, bind request rejected");
}
}
@@ -2115,14 +2112,24 @@ PX4IO::ioctl(file * /*filep*/, int cmd, unsigned long arg)
break;
case DSM_BIND_START:
- io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_power_down);
- usleep(500000);
- io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_set_rx_out);
- io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_power_up);
- usleep(72000);
- io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_send_pulses | (arg << 4));
- usleep(50000);
- io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_reinit_uart);
+
+ /* only allow DSM2, DSM-X and DSM-X with more than 7 channels */
+ if (arg == DSM2_BIND_PULSES ||
+ arg == DSMX_BIND_PULSES ||
+ arg == DSMX8_BIND_PULSES) {
+ io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_power_down);
+ usleep(500000);
+ io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_set_rx_out);
+ io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_power_up);
+ usleep(72000);
+ io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_send_pulses | (arg << 4));
+ usleep(50000);
+ io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_reinit_uart);
+
+ ret = OK;
+ } else {
+ ret = -EINVAL;
+ }
break;
case DSM_BIND_POWER_UP:
@@ -2615,7 +2622,7 @@ bind(int argc, char *argv[])
#endif
if (argc < 3)
- errx(0, "needs argument, use dsm2 or dsmx");
+ errx(0, "needs argument, use dsm2, dsmx or dsmx8");
if (!strcmp(argv[2], "dsm2"))
pulses = DSM2_BIND_PULSES;
@@ -2624,7 +2631,7 @@ bind(int argc, char *argv[])
else if (!strcmp(argv[2], "dsmx8"))
pulses = DSMX8_BIND_PULSES;
else
- errx(1, "unknown parameter %s, use dsm2 or dsmx", argv[2]);
+ errx(1, "unknown parameter %s, use dsm2, dsmx or dsmx8", argv[2]);
// Test for custom pulse parameter
if (argc > 3)
pulses = atoi(argv[3]);
diff --git a/src/modules/px4iofirmware/dsm.c b/src/modules/px4iofirmware/dsm.c
index 60eda2319..d3f365822 100644
--- a/src/modules/px4iofirmware/dsm.c
+++ b/src/modules/px4iofirmware/dsm.c
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2012-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
@@ -162,6 +162,7 @@ dsm_guess_format(bool reset)
0xff, /* 8 channels (DX8) */
0x1ff, /* 9 channels (DX9, etc.) */
0x3ff, /* 10 channels (DX10) */
+ 0x1fff, /* 13 channels (DX10t) */
0x3fff /* 18 channels (DX10) */
};
unsigned votes10 = 0;
@@ -368,11 +369,25 @@ dsm_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values)
if (channel >= *num_values)
*num_values = channel + 1;
- /* convert 0-1024 / 0-2048 values to 1000-2000 ppm encoding in a very sloppy fashion */
- if (dsm_channel_shift == 11)
- value /= 2;
+ /* convert 0-1024 / 0-2048 values to 1000-2000 ppm encoding. */
+ if (dsm_channel_shift == 10)
+ value *= 2;
- value += 998;
+ /*
+ * Spektrum scaling is special. There are these basic considerations
+ *
+ * * Midpoint is 1520 us
+ * * 100% travel channels are +- 400 us
+ *
+ * We obey the original Spektrum scaling (so a default setup will scale from
+ * 1100 - 1900 us), but we do not obey the weird 1520 us center point
+ * and instead (correctly) center the center around 1500 us. This is in order
+ * to get something useful without requiring the user to calibrate on a digital
+ * link for no reason.
+ */
+
+ /* scaled integer for decent accuracy while staying efficient */
+ value = ((((int)value - 1024) * 1000) / 1700) + 1500;
/*
* Store the decoded channel into the R/C input buffer, taking into
@@ -400,6 +415,15 @@ dsm_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values)
values[channel] = value;
}
+ /*
+ * Spektrum likes to send junk in higher channel numbers to fill
+ * their packets. We don't know about a 13 channel model in their TX
+ * lines, so if we get a channel count of 13, we'll return 12 (the last
+ * data index that is stable).
+ */
+ if (*num_values == 13)
+ *num_values = 12;
+
if (dsm_channel_shift == 11) {
/* Set the 11-bit data indicator */
*num_values |= 0x8000;
diff --git a/src/modules/px4iofirmware/registers.c b/src/modules/px4iofirmware/registers.c
index 1335f52e1..97d25bbfa 100644
--- a/src/modules/px4iofirmware/registers.c
+++ b/src/modules/px4iofirmware/registers.c
@@ -566,7 +566,7 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
break;
case PX4IO_P_SETUP_DSM:
- dsm_bind(value & 0x0f, (value >> 4) & 7);
+ dsm_bind(value & 0x0f, (value >> 4) & 0xF);
break;
default: