aboutsummaryrefslogtreecommitdiff
path: root/src
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2013-08-17 20:30:52 +0200
committerLorenz Meier <lm@inf.ethz.ch>2013-08-17 20:30:52 +0200
commit061be7f7fed430d1c235809f1e1dce61e8b7aa01 (patch)
tree5964318a7902c4eeaa67f185698e6cafc25fbf08 /src
parent628e806df5b05ea8a44d46f29606db03fee1fce9 (diff)
parentb08ca02410cc02f75bbfe154963edcea6767972e (diff)
downloadpx4-firmware-061be7f7fed430d1c235809f1e1dce61e8b7aa01.tar.gz
px4-firmware-061be7f7fed430d1c235809f1e1dce61e8b7aa01.tar.bz2
px4-firmware-061be7f7fed430d1c235809f1e1dce61e8b7aa01.zip
Merged master
Diffstat (limited to 'src')
-rw-r--r--src/drivers/px4io/px4io.cpp143
-rw-r--r--src/modules/px4iofirmware/dsm.c408
-rw-r--r--src/modules/px4iofirmware/px4io.h2
3 files changed, 329 insertions, 224 deletions
diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp
index ed98ff0a5..cebe33996 100644
--- a/src/drivers/px4io/px4io.cpp
+++ b/src/drivers/px4io/px4io.cpp
@@ -92,21 +92,62 @@ extern device::Device *PX4IO_serial_interface() weak_function;
#define PX4IO_SET_DEBUG _IOC(0xff00, 0)
#define PX4IO_INAIR_RESTART_ENABLE _IOC(0xff00, 1)
+/**
+ * The PX4IO class.
+ *
+ * Encapsulates PX4FMU to PX4IO communications modeled as file operations.
+ */
class PX4IO : public device::CDev
{
public:
+ /**
+ * Constructor.
+ *
+ * Initialize all class variables.
+ */
PX4IO(device::Device *interface);
+
+ /**
+ * Destructor.
+ *
+ * Wait for worker thread to terminate.
+ */
virtual ~PX4IO();
+ /**
+ * Initialize the PX4IO class.
+ *
+ * Initialize the physical I2C interface to PX4IO. Retrieve relevant initial system parameters. Initialize PX4IO registers.
+ */
virtual int init();
+ /**
+ * IO Control handler.
+ *
+ * Handle all IOCTL calls to the PX4IO file descriptor.
+ *
+ * @param[in] filp file handle (not used). This function is always called directly through object reference
+ * @param[in] cmd the IOCTL command
+ * @param[in] the IOCTL command parameter (optional)
+ */
virtual int ioctl(file *filp, int cmd, unsigned long arg);
+
+ /**
+ * write handler.
+ *
+ * Handle writes to the PX4IO file descriptor.
+ *
+ * @param[in] filp file handle (not used). This function is always called directly through object reference
+ * @param[in] buffer pointer to the data buffer to be written
+ * @param[in] len size in bytes to be written
+ * @return number of bytes written
+ */
virtual ssize_t write(file *filp, const char *buffer, size_t len);
/**
* Set the update rate for actuator outputs from FMU to IO.
*
- * @param rate The rate in Hz actuator outpus are sent to IO.
+ * @param[in] rate The rate in Hz actuator outpus are sent to IO.
* Min 10 Hz, max 400 Hz
*/
int set_update_rate(int rate);
@@ -114,29 +155,41 @@ public:
/**
* Set the battery current scaling and bias
*
- * @param amp_per_volt
- * @param amp_bias
+ * @param[in] amp_per_volt
+ * @param[in] amp_bias
*/
void set_battery_current_scaling(float amp_per_volt, float amp_bias);
/**
* Push failsafe values to IO.
*
- * @param vals Failsafe control inputs: in us PPM (900 for zero, 1500 for centered, 2100 for full)
- * @param len Number of channels, could up to 8
+ * @param[in] vals Failsafe control inputs: in us PPM (900 for zero, 1500 for centered, 2100 for full)
+ * @param[in] len Number of channels, could up to 8
*/
int set_failsafe_values(const uint16_t *vals, unsigned len);
/**
- * Print the current status of IO
+ * Print IO status.
+ *
+ * Print all relevant IO status information
*/
void print_status();
+ /**
+ * Set the DSM VCC is controlled by relay one flag
+ *
+ * @param[in] enable true=DSM satellite VCC is controlled by relay1, false=DSM satellite VCC not controlled
+ */
inline void set_dsm_vcc_ctl(bool enable)
{
_dsm_vcc_ctl = enable;
};
+ /**
+ * Get the DSM VCC is controlled by relay one flag
+ *
+ * @return true=DSM satellite VCC is controlled by relay1, false=DSM satellite VCC not controlled
+ */
inline bool get_dsm_vcc_ctl()
{
return _dsm_vcc_ctl;
@@ -146,59 +199,49 @@ private:
device::Device *_interface;
// XXX
- unsigned _hardware;
- unsigned _max_actuators;
- unsigned _max_controls;
- unsigned _max_rc_input;
- unsigned _max_relays;
- unsigned _max_transfer;
+ unsigned _hardware; ///< Hardware revision
+ unsigned _max_actuators; ///<Maximum # of actuators supported by PX4IO
+ unsigned _max_controls; ///<Maximum # of controls supported by PX4IO
+ unsigned _max_rc_input; ///<Maximum receiver channels supported by PX4IO
+ unsigned _max_relays; ///<Maximum relays supported by PX4IO
+ unsigned _max_transfer; ///<Maximum number of I2C transfers supported by PX4IO
- unsigned _update_interval; ///< subscription interval limiting send rate
+ unsigned _update_interval; ///<Subscription interval limiting send rate
- volatile int _task; ///< worker task
- volatile bool _task_should_exit;
+ volatile int _task; ///<worker task id
+ volatile bool _task_should_exit; ///<worker terminate flag
- int _mavlink_fd;
+ int _mavlink_fd; ///<mavlink file descriptor
- perf_counter_t _perf_update;
+ perf_counter_t _perf_update; ///<local performance counter
/* cached IO state */
- uint16_t _status;
- uint16_t _alarms;
+ uint16_t _status; ///<Various IO status flags
+ uint16_t _alarms; ///<Various IO alarms
/* subscribed topics */
- int _t_actuators; ///< actuator controls topic
- int _t_armed; ///< system armed control topic
- int _t_vstatus; ///< system / vehicle status
- int _t_param; ///< parameter update topic
+ int _t_actuators; ///<actuator controls topic
+ int _t_armed; ///<system armed control topic
+ int _t_vstatus; ///<system / vehicle status
+ int _t_param; ///<parameter update topic
/* advertised topics */
- orb_advert_t _to_input_rc; ///< rc inputs from io
- orb_advert_t _to_actuators_effective; ///< effective actuator controls topic
- orb_advert_t _to_outputs; ///< mixed servo outputs topic
- orb_advert_t _to_battery; ///< battery status / voltage
-
- actuator_outputs_s _outputs; ///< mixed outputs
- actuator_controls_effective_s _controls_effective; ///< effective controls
+ orb_advert_t _to_input_rc; ///<rc inputs from IO topic
+ orb_advert_t _to_actuators_effective; ///<effective actuator controls topic
+ orb_advert_t _to_outputs; ///<mixed servo outputs topic
+ orb_advert_t _to_battery; ///<battery status / voltage topic
- bool _primary_pwm_device; ///< true if we are the default PWM output
+ actuator_outputs_s _outputs; ///<mixed outputs
+ actuator_controls_effective_s _controls_effective; ///<effective controls
- float _battery_amp_per_volt;
- float _battery_amp_bias;
- float _battery_mamphour_total;
- uint64_t _battery_last_timestamp;
+ bool _primary_pwm_device; ///<true if we are the default PWM output
- /**
- * Relay1 is dedicated to controlling DSM receiver power
- */
-
- bool _dsm_vcc_ctl;
-
- /**
- * System armed
- */
+ float _battery_amp_per_volt; ///<current sensor amps/volt
+ float _battery_amp_bias; ///<current sensor bias
+ float _battery_mamphour_total;///<amp hours consumed so far
+ uint64_t _battery_last_timestamp;///<last amp hour calculation timestamp
- bool _system_armed;
+ bool _dsm_vcc_ctl; ///<true if relay 1 controls DSM satellite RX power
/**
* Trampoline to the worker task
@@ -369,8 +412,7 @@ PX4IO::PX4IO(device::Device *interface) :
_battery_amp_bias(0),
_battery_mamphour_total(0),
_battery_last_timestamp(0),
- _dsm_vcc_ctl(false),
- _system_armed(false)
+ _dsm_vcc_ctl(false)
{
/* we need this potentially before it could be set in task_main */
g_dev = this;
@@ -705,7 +747,7 @@ PX4IO::task_main()
// See if bind parameter has been set, and reset it to 0
param_get(dsm_bind_param = param_find("RC_DSM_BIND"), &dsm_bind_val);
if (dsm_bind_val) {
- if (!_system_armed) {
+ if (!(_status & PX4IO_P_STATUS_FLAGS_ARMED)) {
if ((dsm_bind_val == 1) || (dsm_bind_val == 2)) {
mavlink_log_info(mavlink_fd, "[IO] binding dsm%c rx", dsm_bind_val == 1 ? '2' : 'x');
ioctl(nullptr, DSM_BIND_START, dsm_bind_val == 1 ? 3 : 7);
@@ -784,8 +826,6 @@ PX4IO::io_set_arming_state()
uint16_t set = 0;
uint16_t clear = 0;
- _system_armed = vstatus.flag_system_armed;
-
if (armed.armed && !armed.lockdown) {
set |= PX4IO_P_SETUP_ARMING_FMU_ARMED;
} else {
@@ -1635,7 +1675,8 @@ PX4IO::ioctl(file * /*filep*/, int cmd, unsigned long arg)
}
ssize_t
-PX4IO::write(file *filp, const char *buffer, size_t len)
+PX4IO::write(file * /*filp*/, const char *buffer, size_t len)
+/* Make it obvious that file * isn't used here */
{
unsigned count = len / 2;
diff --git a/src/modules/px4iofirmware/dsm.c b/src/modules/px4iofirmware/dsm.c
index 4925ced54..206e27db5 100644
--- a/src/modules/px4iofirmware/dsm.c
+++ b/src/modules/px4iofirmware/dsm.c
@@ -48,161 +48,44 @@
#include <drivers/drv_hrt.h>
-#define DEBUG
-
#include "px4io.h"
-#define DSM_FRAME_SIZE 16
-#define DSM_FRAME_CHANNELS 7
-
-static int dsm_fd = -1;
-
-static hrt_abstime last_rx_time;
-static hrt_abstime last_frame_time;
-
-static uint8_t frame[DSM_FRAME_SIZE];
-
-static unsigned partial_frame_count;
-static unsigned channel_shift;
-
-unsigned dsm_frame_drops;
-
-static bool dsm_decode_channel(uint16_t raw, unsigned shift, unsigned *channel, unsigned *value);
-static void dsm_guess_format(bool reset);
-static bool dsm_decode(hrt_abstime now, uint16_t *values, uint16_t *num_values);
-
-int
-dsm_init(const char *device)
-{
- if (dsm_fd < 0)
- dsm_fd = open(device, O_RDONLY | O_NONBLOCK);
-
- if (dsm_fd >= 0) {
- struct termios t;
-
- /* 115200bps, no parity, one stop bit */
- tcgetattr(dsm_fd, &t);
- cfsetspeed(&t, 115200);
- t.c_cflag &= ~(CSTOPB | PARENB);
- tcsetattr(dsm_fd, TCSANOW, &t);
-
- /* initialise the decoder */
- partial_frame_count = 0;
- last_rx_time = hrt_absolute_time();
-
- /* reset the format detector */
- dsm_guess_format(true);
-
- debug("DSM: ready");
-
- } else {
- debug("DSM: open failed");
- }
-
- return dsm_fd;
-}
-
-void
-dsm_bind(uint16_t cmd, int pulses)
-{
- const uint32_t usart1RxAsOutp = GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN10;
-
- if (dsm_fd < 0)
- return;
-
-#ifdef CONFIG_ARCH_BOARD_PX4IO_V2
- // XXX implement
- #warning DSM BIND NOT IMPLEMENTED ON PX4IO V2
-#else
- switch (cmd) {
- case dsm_bind_power_down:
- // power down DSM satellite
- POWER_RELAY1(0);
- break;
- case dsm_bind_power_up:
- POWER_RELAY1(1);
- dsm_guess_format(true);
- break;
- case dsm_bind_set_rx_out:
- stm32_configgpio(usart1RxAsOutp);
- break;
- case dsm_bind_send_pulses:
- for (int i = 0; i < pulses; i++) {
- stm32_gpiowrite(usart1RxAsOutp, false);
- up_udelay(25);
- stm32_gpiowrite(usart1RxAsOutp, true);
- up_udelay(25);
- }
- break;
- case dsm_bind_reinit_uart:
- // Restore USART rx pin
- stm32_configgpio(GPIO_USART1_RX);
- break;
- }
-#endif
-}
-
-bool
-dsm_input(uint16_t *values, uint16_t *num_values)
-{
- ssize_t ret;
- hrt_abstime now;
-
- /*
- * The DSM* protocol doesn't provide any explicit framing,
- * so we detect frame boundaries by the inter-frame delay.
- *
- * The minimum frame spacing is 11ms; with 16 bytes at 115200bps
- * frame transmission time is ~1.4ms.
- *
- * We expect to only be called when bytes arrive for processing,
- * and if an interval of more than 5ms passes between calls,
- * the first byte we read will be the first byte of a frame.
- *
- * In the case where byte(s) are dropped from a frame, this also
- * provides a degree of protection. Of course, it would be better
- * if we didn't drop bytes...
- */
- now = hrt_absolute_time();
-
- if ((now - last_rx_time) > 5000) {
- if (partial_frame_count > 0) {
- dsm_frame_drops++;
- partial_frame_count = 0;
- }
- }
+#define DSM_FRAME_SIZE 16 /**<DSM frame size in bytes*/
+#define DSM_FRAME_CHANNELS 7 /**<Max supported DSM channels*/
- /*
- * Fetch bytes, but no more than we would need to complete
- * the current frame.
- */
- ret = read(dsm_fd, &frame[partial_frame_count], DSM_FRAME_SIZE - partial_frame_count);
-
- /* if the read failed for any reason, just give up here */
- if (ret < 1)
- return false;
-
- last_rx_time = now;
-
- /*
- * Add bytes to the current frame
- */
- partial_frame_count += ret;
-
- /*
- * If we don't have a full frame, return
- */
- if (partial_frame_count < DSM_FRAME_SIZE)
- return false;
-
- /*
- * Great, it looks like we might have a frame. Go ahead and
- * decode it.
- */
- partial_frame_count = 0;
- return dsm_decode(now, values, num_values);
-}
+static int dsm_fd = -1; /**< File handle to the DSM UART */
+static hrt_abstime dsm_last_rx_time; /**< Timestamp when we last received */
+static hrt_abstime dsm_last_frame_time; /**< Timestamp for start of last dsm frame */
+static uint8_t dsm_frame[DSM_FRAME_SIZE]; /**< DSM dsm frame receive buffer */
+static unsigned dsm_partial_frame_count; /**< Count of bytes received for current dsm frame */
+static unsigned dsm_channel_shift; /**< Channel resolution, 0=unknown, 1=10 bit, 2=11 bit */
+static unsigned dsm_frame_drops; /**< Count of incomplete DSM frames */
+/**
+ * Attempt to decode a single channel raw channel datum
+ *
+ * The DSM* protocol doesn't provide any explicit framing,
+ * so we detect dsm frame boundaries by the inter-dsm frame delay.
+ *
+ * The minimum dsm frame spacing is 11ms; with 16 bytes at 115200bps
+ * dsm frame transmission time is ~1.4ms.
+ *
+ * We expect to only be called when bytes arrive for processing,
+ * and if an interval of more than 5ms passes between calls,
+ * the first byte we read will be the first byte of a dsm frame.
+ *
+ * In the case where byte(s) are dropped from a dsm frame, this also
+ * provides a degree of protection. Of course, it would be better
+ * if we didn't drop bytes...
+ *
+ * Upon receiving a full dsm frame we attempt to decode it
+ *
+ * @param[in] raw 16 bit raw channel value from dsm frame
+ * @param[in] shift position of channel number in raw data
+ * @param[out] channel pointer to returned channel number
+ * @param[out] value pointer to returned channel value
+ * @return true=raw value successfully decoded
+ */
static bool
dsm_decode_channel(uint16_t raw, unsigned shift, unsigned *channel, unsigned *value)
{
@@ -220,6 +103,11 @@ dsm_decode_channel(uint16_t raw, unsigned shift, unsigned *channel, unsigned *va
return true;
}
+/**
+ * Attempt to guess if receiving 10 or 11 bit channel values
+ *
+ * @param[in] reset true=reset the 10/11 bit state to unknown
+ */
static void
dsm_guess_format(bool reset)
{
@@ -232,14 +120,14 @@ dsm_guess_format(bool reset)
cs10 = 0;
cs11 = 0;
samples = 0;
- channel_shift = 0;
+ dsm_channel_shift = 0;
return;
}
- /* scan the channels in the current frame in both 10- and 11-bit mode */
+ /* scan the channels in the current dsm_frame in both 10- and 11-bit mode */
for (unsigned i = 0; i < DSM_FRAME_CHANNELS; i++) {
- uint8_t *dp = &frame[2 + (2 * i)];
+ uint8_t *dp = &dsm_frame[2 + (2 * i)];
uint16_t raw = (dp[0] << 8) | dp[1];
unsigned channel, value;
@@ -250,10 +138,10 @@ dsm_guess_format(bool reset)
if (dsm_decode_channel(raw, 11, &channel, &value) && (channel < 31))
cs11 |= (1 << channel);
- /* XXX if we cared, we could look for the phase bit here to decide 1 vs. 2-frame format */
+ /* XXX if we cared, we could look for the phase bit here to decide 1 vs. 2-dsm_frame format */
}
- /* wait until we have seen plenty of frames - 2 should normally be enough */
+ /* wait until we have seen plenty of frames - 5 should normally be enough */
if (samples++ < 5)
return;
@@ -289,13 +177,13 @@ dsm_guess_format(bool reset)
}
if ((votes11 == 1) && (votes10 == 0)) {
- channel_shift = 11;
+ dsm_channel_shift = 11;
debug("DSM: 11-bit format");
return;
}
if ((votes10 == 1) && (votes11 == 0)) {
- channel_shift = 10;
+ dsm_channel_shift = 10;
debug("DSM: 10-bit format");
return;
}
@@ -305,27 +193,136 @@ dsm_guess_format(bool reset)
dsm_guess_format(true);
}
+/**
+ * Initialize the DSM receive functionality
+ *
+ * Open the UART for receiving DSM frames and configure it appropriately
+ *
+ * @param[in] device Device name of DSM UART
+ */
+int
+dsm_init(const char *device)
+{
+ if (dsm_fd < 0)
+ dsm_fd = open(device, O_RDONLY | O_NONBLOCK);
+
+ if (dsm_fd >= 0) {
+
+ struct termios t;
+
+ /* 115200bps, no parity, one stop bit */
+ tcgetattr(dsm_fd, &t);
+ cfsetspeed(&t, 115200);
+ t.c_cflag &= ~(CSTOPB | PARENB);
+ tcsetattr(dsm_fd, TCSANOW, &t);
+
+ /* initialise the decoder */
+ dsm_partial_frame_count = 0;
+ dsm_last_rx_time = hrt_absolute_time();
+
+ /* reset the format detector */
+ dsm_guess_format(true);
+
+ debug("DSM: ready");
+
+ } else {
+
+ debug("DSM: open failed");
+
+ }
+
+ return dsm_fd;
+}
+
+/**
+ * Handle DSM satellite receiver bind mode handler
+ *
+ * @param[in] cmd commands - dsm_bind_power_down, dsm_bind_power_up, dsm_bind_set_rx_out, dsm_bind_send_pulses, dsm_bind_reinit_uart
+ * @param[in] pulses Number of pulses for dsm_bind_send_pulses command
+ */
+void
+dsm_bind(uint16_t cmd, int pulses)
+{
+ const uint32_t usart1RxAsOutp =
+ GPIO_OUTPUT | GPIO_CNF_OUTPP | GPIO_MODE_50MHz | GPIO_OUTPUT_SET | GPIO_PORTA | GPIO_PIN10;
+
+ if (dsm_fd < 0)
+ return;
+
+#ifdef CONFIG_ARCH_BOARD_PX4IO_V2
+ // XXX implement
+ #warning DSM BIND NOT IMPLEMENTED ON PX4IO V2
+#else
+ switch (cmd) {
+
+ case dsm_bind_power_down:
+
+ /*power down DSM satellite*/
+ POWER_RELAY1(0);
+ break;
+
+ case dsm_bind_power_up:
+
+ /*power up DSM satellite*/
+ POWER_RELAY1(1);
+ dsm_guess_format(true);
+ break;
+
+ case dsm_bind_set_rx_out:
+
+ /*Set UART RX pin to active output mode*/
+ stm32_configgpio(usart1RxAsOutp);
+ break;
+
+ case dsm_bind_send_pulses:
+
+ /*Pulse RX pin a number of times*/
+ for (int i = 0; i < pulses; i++) {
+ stm32_gpiowrite(usart1RxAsOutp, false);
+ up_udelay(25);
+ stm32_gpiowrite(usart1RxAsOutp, true);
+ up_udelay(25);
+ }
+ break;
+
+ case dsm_bind_reinit_uart:
+
+ /*Restore USART RX pin to RS232 receive mode*/
+ stm32_configgpio(GPIO_USART1_RX);
+ break;
+
+ }
+#endif
+}
+
+/**
+ * Decode the entire dsm frame (all contained channels)
+ *
+ * @param[in] frame_time timestamp when this dsm frame was received. Used to detect RX loss in order to reset 10/11 bit guess.
+ * @param[out] values pointer to per channel array of decoded values
+ * @param[out] num_values pointer to number of raw channel values returned
+ * @return true=DSM frame successfully decoded, false=no update
+ */
static bool
dsm_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values)
{
-
/*
- debug("DSM frame %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x",
- frame[0], frame[1], frame[2], frame[3], frame[4], frame[5], frame[6], frame[7],
- frame[8], frame[9], frame[10], frame[11], frame[12], frame[13], frame[14], frame[15]);
+ debug("DSM dsm_frame %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x",
+ dsm_frame[0], dsm_frame[1], dsm_frame[2], dsm_frame[3], dsm_frame[4], dsm_frame[5], dsm_frame[6], dsm_frame[7],
+ dsm_frame[8], dsm_frame[9], dsm_frame[10], dsm_frame[11], dsm_frame[12], dsm_frame[13], dsm_frame[14], dsm_frame[15]);
*/
/*
* If we have lost signal for at least a second, reset the
* format guessing heuristic.
*/
- if (((frame_time - last_frame_time) > 1000000) && (channel_shift != 0))
+ if (((frame_time - dsm_last_frame_time) > 1000000) && (dsm_channel_shift != 0))
dsm_guess_format(true);
- /* we have received something we think is a frame */
- last_frame_time = frame_time;
+ /* we have received something we think is a dsm_frame */
+ dsm_last_frame_time = frame_time;
- /* if we don't know the frame format, update the guessing state machine */
- if (channel_shift == 0) {
+ /* if we don't know the dsm_frame format, update the guessing state machine */
+ if (dsm_channel_shift == 0) {
dsm_guess_format(false);
return false;
}
@@ -337,17 +334,17 @@ dsm_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values)
* Each channel is a 16-bit unsigned value containing either a 10-
* or 11-bit channel value and a 4-bit channel number, shifted
* either 10 or 11 bits. The MSB may also be set to indicate the
- * second frame in variants of the protocol where more than
+ * second dsm_frame in variants of the protocol where more than
* seven channels are being transmitted.
*/
for (unsigned i = 0; i < DSM_FRAME_CHANNELS; i++) {
- uint8_t *dp = &frame[2 + (2 * i)];
+ uint8_t *dp = &dsm_frame[2 + (2 * i)];
uint16_t raw = (dp[0] << 8) | dp[1];
unsigned channel, value;
- if (!dsm_decode_channel(raw, channel_shift, &channel, &value))
+ if (!dsm_decode_channel(raw, dsm_channel_shift, &channel, &value))
continue;
/* ignore channels out of range */
@@ -359,7 +356,7 @@ dsm_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values)
*num_values = channel + 1;
/* convert 0-1024 / 0-2048 values to 1000-2000 ppm encoding in a very sloppy fashion */
- if (channel_shift == 11)
+ if (dsm_channel_shift == 11)
value /= 2;
value += 998;
@@ -390,7 +387,7 @@ dsm_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values)
values[channel] = value;
}
- if (channel_shift == 11)
+ if (dsm_channel_shift == 11)
*num_values |= 0x8000;
/*
@@ -398,3 +395,70 @@ dsm_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values)
*/
return true;
}
+
+/**
+ * Called periodically to check for input data from the DSM UART
+ *
+ * The DSM* protocol doesn't provide any explicit framing,
+ * so we detect dsm frame boundaries by the inter-dsm frame delay.
+ * The minimum dsm frame spacing is 11ms; with 16 bytes at 115200bps
+ * dsm frame transmission time is ~1.4ms.
+ * We expect to only be called when bytes arrive for processing,
+ * and if an interval of more than 5ms passes between calls,
+ * the first byte we read will be the first byte of a dsm frame.
+ * In the case where byte(s) are dropped from a dsm frame, this also
+ * provides a degree of protection. Of course, it would be better
+ * if we didn't drop bytes...
+ * Upon receiving a full dsm frame we attempt to decode it.
+ *
+ * @param[out] values pointer to per channel array of decoded values
+ * @param[out] num_values pointer to number of raw channel values returned
+ * @return true=decoded raw channel values updated, false=no update
+ */
+bool
+dsm_input(uint16_t *values, uint16_t *num_values)
+{
+ ssize_t ret;
+ hrt_abstime now;
+
+ /*
+ */
+ now = hrt_absolute_time();
+
+ if ((now - dsm_last_rx_time) > 5000) {
+ if (dsm_partial_frame_count > 0) {
+ dsm_frame_drops++;
+ dsm_partial_frame_count = 0;
+ }
+ }
+
+ /*
+ * Fetch bytes, but no more than we would need to complete
+ * the current dsm frame.
+ */
+ ret = read(dsm_fd, &dsm_frame[dsm_partial_frame_count], DSM_FRAME_SIZE - dsm_partial_frame_count);
+
+ /* if the read failed for any reason, just give up here */
+ if (ret < 1)
+ return false;
+
+ dsm_last_rx_time = now;
+
+ /*
+ * Add bytes to the current dsm frame
+ */
+ dsm_partial_frame_count += ret;
+
+ /*
+ * If we don't have a full dsm frame, return
+ */
+ if (dsm_partial_frame_count < DSM_FRAME_SIZE)
+ return false;
+
+ /*
+ * Great, it looks like we might have a dsm frame. Go ahead and
+ * decode it.
+ */
+ dsm_partial_frame_count = 0;
+ return dsm_decode(now, values, num_values);
+}
diff --git a/src/modules/px4iofirmware/px4io.h b/src/modules/px4iofirmware/px4io.h
index 9eb092a63..b30d155bc 100644
--- a/src/modules/px4iofirmware/px4io.h
+++ b/src/modules/px4iofirmware/px4io.h
@@ -195,7 +195,7 @@ extern void controls_init(void);
extern void controls_tick(void);
extern int dsm_init(const char *device);
extern bool dsm_input(uint16_t *values, uint16_t *num_values);
-extern void dsm_bind(uint16_t cmd, int pulses);
+extern void dsm_bind(uint16_t cmd, int pulses);
extern int sbus_init(const char *device);
extern bool sbus_input(uint16_t *values, uint16_t *num_values);