lis-epfl / MAVRIC_Library

Software library to build drone autopilots
http://lis-epfl.github.io/MAVRIC_Library/
BSD 3-Clause "New" or "Revised" License
12 stars 21 forks source link

Enable more than 7 channels on DSM receivers #36

Closed jlecoeur closed 9 years ago

jlecoeur commented 9 years ago

We are currently limited to 7 channels for spektrum satellites. Implementing the DSMX protocol should fix this

jlecoeur commented 9 years ago

Here is what PX4 is using

/****************************************************************************
 *
 *   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
 * are met:
 *
 * 1. Redistributions of source code must retain the above copyright
 *    notice, this list of conditions and the following disclaimer.
 * 2. Redistributions in binary form must reproduce the above copyright
 *    notice, this list of conditions and the following disclaimer in
 *    the documentation and/or other materials provided with the
 *    distribution.
 * 3. Neither the name PX4 nor the names of its contributors may be
 *    used to endorse or promote products derived from this software
 *    without specific prior written permission.
 *
 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
 * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
 * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
 * POSSIBILITY OF SUCH DAMAGE.
 *
 ****************************************************************************/

/**
 * @file dsm.c
 *
 * Serial protocol decoder for the Spektrum DSM* family of protocols.
 *
 * Decodes into the global PPM buffer and updates accordingly.
 */

#include <nuttx/config.h>
#include <nuttx/arch.h>

#include <fcntl.h>
#include <unistd.h>
#include <termios.h>

#include <drivers/drv_hrt.h>

#include "px4io.h"

#define DSM_FRAME_SIZE      16      /**<DSM frame size in bytes*/
#define DSM_FRAME_CHANNELS  7       /**<Max supported DSM channels*/

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)
{

    if (raw == 0xffff)
        return false;

    *channel = (raw >> shift) & 0xf;

    uint16_t data_mask = (1 << shift) - 1;
    *value = raw & data_mask;

    //debug("DSM: %d 0x%04x -> %d %d", shift, raw, *channel, *value);

    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)
{
    static uint32_t cs10;
    static uint32_t cs11;
    static unsigned samples;

    /* reset the 10/11 bit sniffed channel masks */
    if (reset) {
        cs10 = 0;
        cs11 = 0;
        samples = 0;
        dsm_channel_shift = 0;
        return;
    }

    /* 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 = &dsm_frame[2 + (2 * i)];
        uint16_t raw = (dp[0] << 8) | dp[1];
        unsigned channel, value;

        /* if the channel decodes, remember the assigned number */
        if (dsm_decode_channel(raw, 10, &channel, &value) && (channel < 31))
            cs10 |= (1 << channel);

        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-dsm_frame format */
    }

    /* wait until we have seen plenty of frames - 5 should normally be enough */
    if (samples++ < 5)
        return;

    /*
     * Iterate the set of sensible sniffed channel sets and see whether
     * decoding in 10 or 11-bit mode has yielded anything we recognize.
     *
     * XXX Note that due to what seem to be bugs in the DSM2 high-resolution
     *     stream, we may want to sniff for longer in some cases when we think we
     *     are talking to a DSM2 receiver in high-resolution mode (so that we can
     *     reject it, ideally).
     *     See e.g. http://git.openpilot.org/cru/OPReview-116 for a discussion
     *     of this issue.
     */
    static uint32_t masks[] = {
        0x3f,   /* 6 channels (DX6) */
        0x7f,   /* 7 channels (DX7) */
        0xff,   /* 8 channels (DX8) */
        0x1ff,  /* 9 channels (DX9, etc.) */
        0x3ff,  /* 10 channels (DX10) */
        0x1fff, /* 13 channels (DX10t) */
        0x3fff  /* 18 channels (DX10) */
    };
    unsigned votes10 = 0;
    unsigned votes11 = 0;

    for (unsigned i = 0; i < (sizeof(masks) / sizeof(masks[0])); i++) {

        if (cs10 == masks[i])
            votes10++;

        if (cs11 == masks[i])
            votes11++;
    }

    if ((votes11 == 1) && (votes10 == 0)) {
        dsm_channel_shift = 11;
        debug("DSM: 11-bit format");
        return;
    }

    if ((votes10 == 1) && (votes11 == 0)) {
        dsm_channel_shift = 10;
        debug("DSM: 10-bit format");
        return;
    }

    /* call ourselves to reset our state ... we have to try again */
    debug("DSM: format detect fail, 10: 0x%08x %d 11: 0x%08x %d", cs10, votes10, cs11, votes11);
    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)
{

#ifdef CONFIG_ARCH_BOARD_PX4IO_V2
    // enable power on DSM connector
    POWER_SPEKTRUM(true);
#endif

    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)
{
#if !defined(CONFIG_ARCH_BOARD_PX4IO_V1) && !defined(CONFIG_ARCH_BOARD_PX4IO_V2)
    #warning DSM BIND NOT IMPLEMENTED ON UNKNOWN PLATFORM
#else
    const uint32_t usart1RxAsOutp =
        GPIO_OUTPUT | GPIO_CNF_OUTPP | GPIO_MODE_50MHz | GPIO_OUTPUT_SET | GPIO_PORTA | GPIO_PIN10;

    if (dsm_fd < 0)
        return;

    switch (cmd) {

    case dsm_bind_power_down:

        /*power down DSM satellite*/
#ifdef CONFIG_ARCH_BOARD_PX4IO_V1
        POWER_RELAY1(0);
#else /* CONFIG_ARCH_BOARD_PX4IO_V2 */
        POWER_SPEKTRUM(0);
#endif
        break;

    case dsm_bind_power_up:

        /*power up DSM satellite*/
#ifdef CONFIG_ARCH_BOARD_PX4IO_V1
        POWER_RELAY1(1);
#else /* CONFIG_ARCH_BOARD_PX4IO_V2 */
        POWER_SPEKTRUM(1);
#endif
        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++) {
            up_udelay(25);
            stm32_gpiowrite(usart1RxAsOutp, false);
            up_udelay(25);
            stm32_gpiowrite(usart1RxAsOutp, true);
        }
        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 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 - dsm_last_frame_time) > 1000000) && (dsm_channel_shift != 0))
        dsm_guess_format(true);

    /* we have received something we think is a dsm_frame */
    dsm_last_frame_time = frame_time;

    /* 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;
    }

    /*
     * The encoding of the first two bytes is uncertain, so we're
     * going to ignore them for now.
     *
     * 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 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 = &dsm_frame[2 + (2 * i)];
        uint16_t raw = (dp[0] << 8) | dp[1];
        unsigned channel, value;

        if (!dsm_decode_channel(raw, dsm_channel_shift, &channel, &value))
            continue;

        /* ignore channels out of range */
        if (channel >= PX4IO_RC_INPUT_CHANNELS)
            continue;

        /* update the decoded channel count */
        if (channel >= *num_values)
            *num_values = channel + 1;

        /* convert 0-1024 / 0-2048 values to 1000-2000 ppm encoding. */
        if (dsm_channel_shift == 10)
            value *= 2;

        /*
         * 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
         * account the different ideas about channel assignement that we have.
         *
         * Specifically, the first four channels in rc_channel_data are roll, pitch, thrust, yaw,
         * but the first four channels from the DSM receiver are thrust, roll, pitch, yaw.
         */
        switch (channel) {
        case 0:
            channel = 2;
            break;

        case 1:
            channel = 0;
            break;

        case 2:
            channel = 1;

        default:
            break;
        }

        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;
    }

    /*
     * XXX Note that we may be in failsafe here; we need to work out how to detect that.
     */
    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, high order bit 0:10 bit data, 1:11 bit data
 * @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);
}
jlecoeur commented 9 years ago

And here is what they are doing in paparazzi

/*
 * Copyright (C) 2010 Eric Parsonage <eric@eparsonage.com>
 *
 * This file is part of paparazzi.
 *
 * paparazzi is free software; you can redistribute it and/or modify
 * it under the terms of the GNU General Public License as published by
 * the Free Software Foundation; either version 2, or (at your option)
 * any later version.
 *
 * paparazzi is distributed in the hope that it will be useful,
 * but WITHOUT ANY WARRANTY; without even the implied warranty of
 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
 * GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with paparazzi; see the file COPYING.  If not, write to
 * the Free Software Foundation, 59 Temple Place - Suite 330,
 * Boston, MA 02111-1307, USA.
 */

#include <stdint.h>
#include <libopencm3/stm32/gpio.h>
#include <libopencm3/stm32/rcc.h>
#include <libopencm3/stm32/timer.h>
#include <libopencm3/stm32/usart.h>
#include <libopencm3/cm3/nvic.h>

#include "subsystems/radio_control.h"
#include "subsystems/radio_control/spektrum_arch.h"
#include "mcu_periph/uart.h"
#include "mcu_periph/gpio.h"
#include "mcu_periph/sys_time.h"

// for timer_get_frequency
#include "mcu_arch.h"

#include BOARD_CONFIG

#define SPEKTRUM_CHANNELS_PER_FRAME 7
#define MAX_SPEKTRUM_FRAMES 2
#define MAX_SPEKTRUM_CHANNELS 16

#define ONE_MHZ 1000000

/* Number of low pulses sent to satellite receivers */
#define MASTER_RECEIVER_PULSES 5
#define SLAVE_RECEIVER_PULSES 6

#define TIM_TICS_FOR_100us 100
#define MIN_FRAME_SPACE  70  // 7ms
#define MAX_BYTE_SPACE  3   // .3ms

#ifndef NVIC_TIM6_IRQ_PRIO
#define NVIC_TIM6_IRQ_PRIO 2
#endif

#ifndef NVIC_TIM6_DAC_IRQ_PRIO
#define NVIC_TIM6_DAC_IRQ_PRIO 2
#endif

#ifdef NVIC_UART_IRQ_PRIO
#define NVIC_PRIMARY_UART_PRIO NVIC_UART_IRQ_PRIO
#else
#define NVIC_PRIMARY_UART_PRIO 2
#endif

/*
 * in the makefile we set RADIO_CONTROL_SPEKTRUM_PRIMARY_PORT to be UARTx
 * but in uart_hw.c the initialisation functions are
 * defined as uartx these macros give us the glue
 * that allows static calls at compile time
 */

#define __PrimaryUart(dev, _x) dev##_x
#define _PrimaryUart(dev, _x)  __PrimaryUart(dev, _x)
#define PrimaryUart(_x) _PrimaryUart(RADIO_CONTROL_SPEKTRUM_PRIMARY_PORT, _x)

#define __SecondaryUart(dev, _x) dev##_x
#define _SecondaryUart(dev, _x)  __SecondaryUart(dev, _x)
#define SecondaryUart(_x) _SecondaryUart(RADIO_CONTROL_SPEKTRUM_SECONDARY_PORT, _x)

struct SpektrumStateStruct {
    uint8_t ReSync;
    uint8_t SpektrumTimer;
    uint8_t Sync;
    uint8_t ChannelCnt;
    uint8_t FrameCnt;
    uint8_t HighByte;
    uint8_t SecondFrame;
    uint16_t LostFrameCnt;
    uint8_t RcAvailable;
    int16_t values[SPEKTRUM_CHANNELS_PER_FRAME*MAX_SPEKTRUM_FRAMES];
};

typedef struct SpektrumStateStruct SpektrumStateType;

SpektrumStateType PrimarySpektrumState = {1,0,0,0,0,0,0,0,0,{0}};
PRINT_CONFIG_VAR(RADIO_CONTROL_SPEKTRUM_PRIMARY_PORT)

#ifdef RADIO_CONTROL_SPEKTRUM_SECONDARY_PORT
PRINT_CONFIG_MSG("Using secondary spektrum receiver.")
PRINT_CONFIG_VAR(RADIO_CONTROL_SPEKTRUM_SECONDARY_PORT)
SpektrumStateType SecondarySpektrumState = {1,0,0,0,0,0,0,0,0,{0}};
#else
PRINT_CONFIG_MSG("NOT using secondary spektrum receiver.")
#endif

int16_t SpektrumBuf[SPEKTRUM_CHANNELS_PER_FRAME*MAX_SPEKTRUM_FRAMES];
/* the order of the channels on a spektrum is always as follows :
 *
 * Throttle   0
 * Aileron    1
 * Elevator   2
 * Rudder     3
 * Gear       4
 * Flap/Aux1  5
 * Aux2       6
 * Aux3       7
 * Aux4       8
 * Aux5       9
 * Aux6      10
 * Aux7      11
 */

/* reverse some channels to suit Paparazzi conventions          */
/* the maximum number of channels a Spektrum can transmit is 12 */
int8_t SpektrumSigns[] = RADIO_CONTROL_SPEKTRUM_SIGNS;

/* Parser state variables */
static uint8_t EncodingType = 0;
static uint8_t ExpectedFrames = 0;
/* initialise the uarts used by the parser */
void SpektrumUartInit(void);
/* initialise the timer used by the parser to ensure sync */
void SpektrumTimerInit(void);

void tim6_irq_handler(void);

/** Set polarity using RC_POLARITY_GPIO.
 * SBUS signal has a reversed polarity compared to normal UART
 * this allows to using hardware UART peripheral by changing
 * the input signal polarity.
 * Setting this gpio ouput high inverts the signal,
 * output low sets it to normal polarity.
 * So for spektrum this is set to normal polarity.
 */
#ifndef RC_SET_POLARITY
#define RC_SET_POLARITY gpio_clear
#endif

 /*****************************************************************************
 *
 * Initialise the timer an uarts used by the Spektrum receiver subsystem
 *
 *****************************************************************************/
void radio_control_impl_init(void) {

  PrimarySpektrumState.ReSync = 1;

#ifdef RADIO_CONTROL_SPEKTRUM_SECONDARY_PORT
  SecondarySpektrumState.ReSync = 1;
#endif

  // Set polarity to normal on boards that can change this
#ifdef RC_POLARITY_GPIO_PORT
  gpio_setup_output(RC_POLARITY_GPIO_PORT, RC_POLARITY_GPIO_PIN);
  RC_SET_POLARITY(RC_POLARITY_GPIO_PORT, RC_POLARITY_GPIO_PIN);
#endif

  SpektrumTimerInit();
  SpektrumUartInit();
}

/*****************************************************************************
 * The bind function means that the satellite receivers believe they are
 * connected to a 9 channel JR-R921 24 receiver thus during the bind process
 * they try to get the transmitter to transmit at the highest resolution that
 * it can manage. The data is contained in 16 byte packets transmitted at
 * 115200 baud. Depending on the transmitter either 1 or 2 frames are required
 * to contain the data for all channels. These frames are either 11ms or 22ms
 * apart.
 *
 * The format of each frame for the main receiver is as follows
 *
 *  byte1:  frame loss data
 *  byte2:  transmitter information
 *  byte3:  and byte4:  channel data
 *  byte5:  and byte6:  channel data
 *  byte7:  and byte8:  channel data
 *  byte9:  and byte10: channel data
 *  byte11: and byte12: channel data
 *  byte13: and byte14: channel data
 *  byte15: and byte16: channel data
 *
 *
 * The format of each frame for the secondary receiver is as follows
 *
 *  byte1:  frame loss data
 *  byte2:  frame loss data
 *  byte3:  and byte4:  channel data
 *  byte5:  and byte6:  channel data
 *  byte7:  and byte8:  channel data
 *  byte9:  and byte10: channel data
 *  byte11: and byte12: channel data
 *  byte13: and byte14: channel data
 *  byte15: and byte16: channel data
 *
 * The frame loss data bytes starts out containing 0 as long as the
 * transmitter is switched on before the receivers. It then increments
 * whenever frames are dropped.
 *
 * Three values for the transmitter information byte have been seen thus far
 *
 * 0x01 From a Spektrum DX7eu which transmits a single frame containing all
 * channel data every 22ms with 10bit resolution.
 *
 * 0x02 From a Spektrum DM9 module which transmits two frames to carry the
 * data for all channels 11ms apart with 10bit resolution.
 *
 * 0x12 From a Spektrum DX7se which transmits two frames to carry the
 * data for all channels 11ms apart with 11bit resolution.
 *
 * 0x12 From a JR X9503 which transmits two frames to carry the
 * data for all channels 11ms apart with 11bit resolution.
 *
 * 0x01 From a Spektrum DX7 which transmits a single frame containing all
 * channel data every 22ms with 10bit resolution.
 *
 * 0x12 From a JR DSX12 which transmits two frames to carry the
 * data for all channels 11ms apart with 11bit resolution.
 *
 * 0x1 From a Spektru DX5e which transmits a single frame containing all
 * channel data every 22ms with 10bit resolution.
 *
 * 0x01 From a Spektrum DX6i which transmits a single frame containing all
 * channel data every 22ms with 10bit resolution.
 *
 * Currently the assumption is that the data has the form :
 *
 * [0 0 0 R 0 0 N1 N0]
 *
 * where :
 *
 * 0 means a '0' bit
 * R: 0 for 10 bit resolution 1 for 11 bit resolution channel data
 * N1 to N0 is the number of frames required to receive all channel
 * data.
 *
 * Channels can have either 10bit or 11bit resolution. Data from a tranmitter
 * with 10 bit resolution has the form:
 *
 * [F 0 C3 C2 C1 C0 D9 D8 D7 D6 D5 D4 D3 D2 D1 D0]
 *
 * Data from a tranmitter with 11 bit resolution has the form
 *
 * [F C3 C2 C1 C0 D10 D9 D8 D7 D6 D5 D4 D3 D2 D1 D0]
 *
 * where :
 *
 * 0 means a '0' bit
 * F: Normally 0 but set to 1 for the first channel of the 2nd frame if a
 * second frame is transmitted.
 *
 * C3 to C0 is the channel number, 4 bit, matching the numbers allocated in
 * the transmitter.
 *
 * D9 to D0 is the channel data (10 bit) 0xaa..0x200..0x356 for
 * 100% transmitter-travel
 *
 *
 * D10 to D0 is the channel data (11 bit) 0x154..0x400..0x6AC for
 * 100% transmitter-travel
 *****************************************************************************/

 /*****************************************************************************
 *
 * Spektrum Parser captures frame data by using time between frames to sync on
 *
 *****************************************************************************/

static inline void SpektrumParser(uint8_t _c, SpektrumStateType* spektrum_state, bool_t secondary_receiver)  {

  uint16_t ChannelData;
  uint8_t TimedOut;
  static uint8_t TmpEncType = 0;        /* 0 = 10bit, 1 = 11 bit        */
  static uint8_t TmpExpFrames = 0;      /* # of frames for channel data */

   TimedOut = (!spektrum_state->SpektrumTimer) ? 1 : 0;

  /* If we have just started the resync process or */
  /* if we have recieved a character before our    */
  /* 7ms wait has finished                         */
  if ((spektrum_state->ReSync == 1) ||
      ((spektrum_state->Sync == 0) && (!TimedOut))) {

    spektrum_state->ReSync = 0;
    spektrum_state->SpektrumTimer = MIN_FRAME_SPACE;
    spektrum_state->Sync = 0;
    spektrum_state->ChannelCnt = 0;
    spektrum_state->FrameCnt = 0;
    spektrum_state->SecondFrame = 0;
    return;
  }

  /* the first byte of a new frame. It was received */
  /* more than 7ms after the last received byte.    */
  /* It represents the number of lost frames so far.*/
  if (spektrum_state->Sync == 0) {
      spektrum_state->LostFrameCnt = _c;
      if(secondary_receiver) /* secondary receiver */
        spektrum_state->LostFrameCnt = spektrum_state->LostFrameCnt << 8;
      spektrum_state->Sync = 1;
      spektrum_state->SpektrumTimer = MAX_BYTE_SPACE;
      return;
  }

  /* all other bytes should be recieved within     */
  /* MAX_BYTE_SPACE time of the last byte received */
  /* otherwise something went wrong resynchronise  */
  if(TimedOut) {
    spektrum_state->ReSync = 1;
    /* next frame not expected sooner than 7ms     */
    spektrum_state->SpektrumTimer = MIN_FRAME_SPACE;
    return;
  }

  /* second character determines resolution and frame rate for main */
  /* receiver or low byte of LostFrameCount for secondary receiver  */
  if(spektrum_state->Sync == 1) {
    if(secondary_receiver) {
      spektrum_state->LostFrameCnt +=_c;
      TmpExpFrames = ExpectedFrames;
    } else {
      /** @todo collect more data. I suspect that there is a low res       */
      /* protocol that is still 10 bit but without using the full range.    */
      TmpEncType =(_c & 0x10)>>4;      /* 0 = 10bit, 1 = 11 bit             */
      TmpExpFrames = _c & 0x03;        /* 1 = 1 frame contains all channels */
                                       /* 2 = 2 channel data in 2 frames    */
    }
    spektrum_state->Sync = 2;
    spektrum_state->SpektrumTimer = MAX_BYTE_SPACE;
    return;
  }

  /* high byte of channel data if this is the first byte */
  /* of channel data and the most significant bit is set */
  /* then this is the second frame of channel data.      */
  if(spektrum_state->Sync == 2) {
    spektrum_state->HighByte = _c;
    if (spektrum_state->ChannelCnt == 0) {
      spektrum_state->SecondFrame = (spektrum_state->HighByte & 0x80) ? 1 : 0;
    }
    spektrum_state->Sync = 3;
    spektrum_state->SpektrumTimer = MAX_BYTE_SPACE;
    return;
  }

  /* low byte of channel data */
  if(spektrum_state->Sync == 3) {
    spektrum_state->Sync = 2;
    spektrum_state->SpektrumTimer = MAX_BYTE_SPACE;
    /* we overwrite the buffer now so rc data is not available now */
    spektrum_state->RcAvailable = 0;
    ChannelData = ((uint16_t)spektrum_state->HighByte << 8) | _c;
    spektrum_state->values[spektrum_state->ChannelCnt
                          + (spektrum_state->SecondFrame * 7)] = ChannelData;
    spektrum_state->ChannelCnt ++;
  }

  /* If we have a whole frame */
  if(spektrum_state->ChannelCnt >= SPEKTRUM_CHANNELS_PER_FRAME) {
    /* how many frames did we expect ? */
    ++spektrum_state->FrameCnt;
    if (spektrum_state->FrameCnt == TmpExpFrames)
    {
      /* set the rc_available_flag */
      spektrum_state->RcAvailable = 1;
      spektrum_state->FrameCnt = 0;
    }
    if(!secondary_receiver) { /* main receiver */
      EncodingType = TmpEncType;         /* only update on a good */
      ExpectedFrames = TmpExpFrames;     /* main receiver frame   */
    }
    spektrum_state->Sync = 0;
    spektrum_state->ChannelCnt = 0;
    spektrum_state->SecondFrame = 0;
    spektrum_state->SpektrumTimer = MIN_FRAME_SPACE;
  }
}

/*****************************************************************************
 *
 * RadioControlEventImp decodes channel data stored by uart irq handlers
 * and calls callback funtion
 *
 *****************************************************************************/

void RadioControlEventImp(void (*frame_handler)(void)) {
  uint8_t ChannelCnt;
  uint8_t ChannelNum;
  uint16_t ChannelData;
  uint8_t MaxChannelNum = 0;

#ifdef RADIO_CONTROL_SPEKTRUM_SECONDARY_PORT
  /* If we have two receivers and at least one of them has new data */
  uint8_t BestReceiver;
  if ((PrimarySpektrumState.RcAvailable) ||
      (SecondarySpektrumState.RcAvailable)) {
    /* if both receivers have new data select the one  */
    /* that has had the least number of frames lost    */
    if ((PrimarySpektrumState.RcAvailable) &&
        (SecondarySpektrumState.RcAvailable)) {
      BestReceiver  = (PrimarySpektrumState.LostFrameCnt
                       <= SecondarySpektrumState.LostFrameCnt) ? 0 : 1;
    } else {
      /* if only one of the receivers have new data use it */
      BestReceiver  = (PrimarySpektrumState.RcAvailable) ? 0 : 1;
    }
    /* clear the data ready flags */
    PrimarySpektrumState.RcAvailable = 0;
    SecondarySpektrumState.RcAvailable = 0;

#else
  /* if we have one receiver and it has new data */
  if(PrimarySpektrumState.RcAvailable) {
    PrimarySpektrumState.RcAvailable = 0;
#endif
    ChannelCnt = 0;
    /* for every piece of channel data we have received */
    for(int i = 0; (i < SPEKTRUM_CHANNELS_PER_FRAME * ExpectedFrames); i++) {
#ifndef RADIO_CONTROL_SPEKTRUM_SECONDARY_PORT
      ChannelData = PrimarySpektrumState.values[i];
#else
      ChannelData = (!BestReceiver) ? PrimarySpektrumState.values[i] :
                                 SecondarySpektrumState.values[i];
#endif
      /* find out the channel number and its value by  */
      /* using the EncodingType which is only received */
      /* from the main receiver                        */
      switch(EncodingType) {
        case(0) : /* 10 bit */
          ChannelNum = (ChannelData >> 10) & 0x0f;
          /* don't bother decoding unused channels */
          if (ChannelNum < RADIO_CONTROL_NB_CHANNEL) {
           SpektrumBuf[ChannelNum] = ChannelData & 0x3ff;
           SpektrumBuf[ChannelNum] -= 0x200;
           SpektrumBuf[ChannelNum] *= MAX_PPRZ/0x156;
           ChannelCnt++;
          }
          break;

        case(1) : /* 11 bit */
          ChannelNum = (ChannelData >> 11) & 0x0f;
          /* don't bother decoding unused channels */
          if (ChannelNum < RADIO_CONTROL_NB_CHANNEL) {
            SpektrumBuf[ChannelNum] = ChannelData & 0x7ff;
            SpektrumBuf[ChannelNum] -= 0x400;
            SpektrumBuf[ChannelNum] *= MAX_PPRZ/0x2AC;
            ChannelCnt++;
          }
          break;

        default : ChannelNum = 0x0F; break;  /* never going to get here */
      }
      /* store the value of the highest valid channel */
      if ((ChannelNum != 0x0F) && (ChannelNum > MaxChannelNum))
        MaxChannelNum = ChannelNum;

    }

    /* if we have a valid frame the pass it to the frame handler */
    if (ChannelCnt >= (MaxChannelNum + 1)) {
      radio_control.frame_cpt++;
      radio_control.time_since_last_frame = 0;
      radio_control.status = RC_OK;
      for (int i = 0; i < (MaxChannelNum + 1); i++) {
        radio_control.values[i] = SpektrumBuf[i];
        if (i == RADIO_THROTTLE ) {
          radio_control.values[i] += MAX_PPRZ;
          radio_control.values[i] /= 2;
        }
        radio_control.values[i] *= SpektrumSigns[i];
      }
      (*frame_handler)();
    }
  }
}

/*****************************************************************************
 *
 * Initialise TIM6 to fire an interrupt every 100 microseconds to provide
 * timebase for SpektrumParser
 *
 *****************************************************************************/
void SpektrumTimerInit( void ) {

  /* enable TIM6 clock */
  rcc_periph_clock_enable(RCC_TIM6);

  /* TIM6 configuration, always counts up */
  timer_set_mode(TIM6, TIM_CR1_CKD_CK_INT, 0, 0);
  /* 100 microseconds ie 0.1 millisecond */
  timer_set_period(TIM6, TIM_TICS_FOR_100us-1);
  uint32_t tim6_clk = timer_get_frequency(TIM6);
  /* timer ticks with 1us */
  timer_set_prescaler(TIM6, ((tim6_clk / ONE_MHZ) - 1));

  /* Enable TIM6 interrupts */
#ifdef STM32F1
  nvic_set_priority(NVIC_TIM6_IRQ, NVIC_TIM6_IRQ_PRIO);
  nvic_enable_irq(NVIC_TIM6_IRQ);
#elif defined STM32F4
  /* the define says DAC IRQ, but it is also the global TIM6 IRQ*/
  nvic_set_priority(NVIC_TIM6_DAC_IRQ, NVIC_TIM6_DAC_IRQ_PRIO);
  nvic_enable_irq(NVIC_TIM6_DAC_IRQ);
#endif

  /* Enable TIM6 Update interrupt */
  timer_enable_irq(TIM6, TIM_DIER_UIE);
  timer_clear_flag(TIM6, TIM_SR_UIF);

  /* TIM6 enable counter */
  timer_enable_counter(TIM6);
}

/*****************************************************************************
 *
 * TIM6 interrupt request handler updates times used by SpektrumParser
 *
 *****************************************************************************/
#ifdef STM32F1
void tim6_isr( void ) {
#elif defined STM32F4
void tim6_dac_isr( void ) {
#endif

  timer_clear_flag(TIM6, TIM_SR_UIF);

  if (PrimarySpektrumState.SpektrumTimer)
    --PrimarySpektrumState.SpektrumTimer;
#ifdef RADIO_CONTROL_SPEKTRUM_SECONDARY_PORT
  if (SecondarySpektrumState.SpektrumTimer)
    --SecondarySpektrumState.SpektrumTimer;
#endif
}

/*****************************************************************************
 *
 * Initialise the uarts for the spektrum satellite receivers
 *
 *****************************************************************************/
void SpektrumUartInit(void) {
  /* init RCC */
  gpio_enable_clock(PrimaryUart(_BANK));
  rcc_periph_clock_enable(PrimaryUart(_RCC));

  /* Enable USART interrupts */
  nvic_set_priority(PrimaryUart(_IRQ), NVIC_PRIMARY_UART_PRIO);
  nvic_enable_irq(PrimaryUart(_IRQ));

  /* Init GPIOS */
  /* Primary UART Rx pin as floating input */
  gpio_setup_pin_af(PrimaryUart(_BANK), PrimaryUart(_PIN), PrimaryUart(_AF), FALSE);

  /* Configure Primary UART */
  usart_set_baudrate(PrimaryUart(_DEV), 115200);
  usart_set_databits(PrimaryUart(_DEV), 8);
  usart_set_stopbits(PrimaryUart(_DEV), USART_STOPBITS_1);
  usart_set_parity(PrimaryUart(_DEV), USART_PARITY_NONE);
  usart_set_flow_control(PrimaryUart(_DEV), USART_FLOWCONTROL_NONE);
  usart_set_mode(PrimaryUart(_DEV), USART_MODE_RX);

  /* Enable Primary UART Receive interrupts */
  USART_CR1(PrimaryUart(_DEV)) |= USART_CR1_RXNEIE;

  /* Enable the Primary UART */
  usart_enable(PrimaryUart(_DEV));

#ifdef RADIO_CONTROL_SPEKTRUM_SECONDARY_PORT
  /* init RCC */
  gpio_enable_clock(SecondaryUart(_BANK));
  rcc_periph_clock_enable(SecondaryUart(_RCC));

  /* Enable USART interrupts */
  nvic_set_priority(SecondaryUart(_IRQ), NVIC_PRIMARY_UART_PRIO+1);
  nvic_enable_irq(SecondaryUart(_IRQ));

  /* Init GPIOS */;
  /* Secondary UART Rx pin as floating input */
  gpio_setup_pin_af(SecondaryUart(_BANK), SecondaryUart(_PIN), SecondaryUart(_AF), FALSE);

  /* Configure secondary UART */
  usart_set_baudrate(SecondaryUart(_DEV), 115200);
  usart_set_databits(SecondaryUart(_DEV), 8);
  usart_set_stopbits(SecondaryUart(_DEV), USART_STOPBITS_1);
  usart_set_parity(SecondaryUart(_DEV), USART_PARITY_NONE);
  usart_set_flow_control(SecondaryUart(_DEV), USART_FLOWCONTROL_NONE);
  usart_set_mode(SecondaryUart(_DEV), USART_MODE_RX);

  /* Enable Secondary UART Receive interrupts */
  USART_CR1(SecondaryUart(_DEV)) |= USART_CR1_RXNEIE;

  /* Enable the Primary UART */
  usart_enable(SecondaryUart(_DEV));
#endif

}

/*****************************************************************************
 *
 * The primary receiver UART interrupt request handler which passes the
 * received character to Spektrum Parser.
 *
 *****************************************************************************/
void PrimaryUart(_ISR)(void) {

  if (((USART_CR1(PrimaryUart(_DEV)) & USART_CR1_TXEIE) != 0) &&
      ((USART_SR(PrimaryUart(_DEV)) & USART_SR_TXE) != 0)) {
    USART_CR1(PrimaryUart(_DEV)) &= ~USART_CR1_TXEIE;
  }

  if (((USART_CR1(PrimaryUart(_DEV)) & USART_CR1_RXNEIE) != 0) &&
      ((USART_SR(PrimaryUart(_DEV)) & USART_SR_RXNE) != 0)) {
    uint8_t b = usart_recv(PrimaryUart(_DEV));
    SpektrumParser(b, &PrimarySpektrumState, FALSE);
  }

}

/*****************************************************************************
 *
 * The secondary receiver UART interrupt request handler which passes the
 * received character to Spektrum Parser.
 *
 *****************************************************************************/
#ifdef RADIO_CONTROL_SPEKTRUM_SECONDARY_PORT
void SecondaryUart(_ISR)(void) {

  if (((USART_CR1(SecondaryUart(_DEV)) & USART_CR1_TXEIE) != 0) &&
      ((USART_SR(SecondaryUart(_DEV)) & USART_SR_TXE) != 0)) {
    USART_CR1(SecondaryUart(_DEV)) &= ~USART_CR1_TXEIE;
  }

  if (((USART_CR1(SecondaryUart(_DEV)) & USART_CR1_RXNEIE) != 0) &&
      ((USART_SR(SecondaryUart(_DEV)) & USART_SR_RXNE) != 0)) {
    uint8_t b = usart_recv(SecondaryUart(_DEV));
    SpektrumParser(b, &SecondarySpektrumState, TRUE);
  }

}
#endif

/*****************************************************************************
 *
 * The following functions provide functionality to allow binding of
 * spektrum satellite receivers. The pulse train sent to them means
 * that AP is emulating a 9 channel JR-R921 24.
 * By default, the same pin is used for pulse train and uart rx, but
 * they can be different if needed
 *
 *****************************************************************************/
#ifndef SPEKTRUM_PRIMARY_BIND_CONF_PORT
#define SPEKTRUM_PRIMARY_BIND_CONF_PORT PrimaryUart(_BANK)
#endif
#ifndef SPEKTRUM_PRIMARY_BIND_CONF_PIN
#define SPEKTRUM_PRIMARY_BIND_CONF_PIN PrimaryUart(_PIN)
#endif
#ifndef SPEKTRUM_SECONDARY_BIND_CONF_PORT
#define SPEKTRUM_SECONDARY_BIND_CONF_PORT SecondaryUart(_BANK)
#endif
#ifndef SPEKTRUM_SECONDARY_BIND_CONF_PIN
#define SPEKTRUM_SECONDARY_BIND_CONF_PIN SecondaryUart(_PIN)
#endif

/*****************************************************************************
 *
 * radio_control_spektrum_try_bind(void) must called on powerup as spektrum
 * satellites can only bind immediately after power up also it must be called
 * before the call to SpektrumUartInit as we leave them with their Rx pins set
 * as outputs.
 *
 *****************************************************************************/
void radio_control_spektrum_try_bind(void) {

  /* Init GPIO for the bind pin */
  gpio_setup_input(SPEKTRUM_BIND_PIN_PORT, SPEKTRUM_BIND_PIN);

  /* exit if the BIND_PIN is high, it needs to
     be pulled low at startup to initiate bind */
#ifdef SPEKTRUM_BIND_PIN_HIGH
  if (gpio_get(SPEKTRUM_BIND_PIN_PORT, SPEKTRUM_BIND_PIN) == 0)
    return;
#else
  if (gpio_get(SPEKTRUM_BIND_PIN_PORT, SPEKTRUM_BIND_PIN) != 0)
    return;
#endif

  /* Master receiver Rx push-pull */
  gpio_setup_output(SPEKTRUM_PRIMARY_BIND_CONF_PORT, SPEKTRUM_PRIMARY_BIND_CONF_PIN);

  /* Master receiver RX line, drive high */
  gpio_set(SPEKTRUM_PRIMARY_BIND_CONF_PORT, SPEKTRUM_PRIMARY_BIND_CONF_PIN);

#ifdef RADIO_CONTROL_SPEKTRUM_SECONDARY_PORT
  /* Slave receiver Rx push-pull */
  gpio_setup_output(SPEKTRUM_SECONDARY_BIND_CONF_PORT, SPEKTRUM_SECONDARY_BIND_CONF_PIN);

  /* Slave receiver RX line, drive high */
  gpio_set(SPEKTRUM_SECONDARY_BIND_CONF_PORT, SPEKTRUM_SECONDARY_BIND_CONF_PIN);
#endif

  /* We have no idea how long the window for allowing binding after
     power up is. This works for the moment but will need revisiting */
  sys_time_usleep(61000);

  for (int i = 0; i < MASTER_RECEIVER_PULSES ; i++)
  {
    gpio_clear(SPEKTRUM_PRIMARY_BIND_CONF_PORT, SPEKTRUM_PRIMARY_BIND_CONF_PIN);
    sys_time_usleep(118);
    gpio_set(SPEKTRUM_PRIMARY_BIND_CONF_PORT, SPEKTRUM_PRIMARY_BIND_CONF_PIN);
    sys_time_usleep(122);
  }

#ifdef RADIO_CONTROL_SPEKTRUM_SECONDARY_PORT
  for (int i = 0; i < SLAVE_RECEIVER_PULSES; i++)
  {
    gpio_clear(SPEKTRUM_SECONDARY_BIND_CONF_PORT, SPEKTRUM_SECONDARY_BIND_CONF_PIN);
    sys_time_usleep(120);
    gpio_set(SPEKTRUM_SECONDARY_BIND_CONF_PORT, SPEKTRUM_SECONDARY_BIND_CONF_PIN);
    sys_time_usleep(120);
  }
#endif /* RADIO_CONTROL_SPEKTRUM_SECONDARY_PORT */

  /* Set conf pin as input in case it is different from RX pin */
  gpio_setup_input(SPEKTRUM_PRIMARY_BIND_CONF_PORT, SPEKTRUM_PRIMARY_BIND_CONF_PIN);
#ifdef RADIO_CONTROL_SPEKTRUM_SECONDARY_PORT
  gpio_setup_input(SPEKTRUM_SECONDARY_BIND_CONF_PORT, SPEKTRUM_SECONDARY_BIND_CONF_PIN);
#endif
}
jlecoeur commented 9 years ago

@GregoireH you looked motivated :-)

GregoireH commented 9 years ago

PX4 also has this limitation... ?

from their code

define DSM_FRAMECHANNELS 7 /*<Max supported DSM channels_/

jlecoeur commented 9 years ago

I think this means 7 channels per frame, they seem to handle up to 18 channels.

GregoireH commented 9 years ago

I tried to change pulse number to be able to bind in different mode.

I figured out that we can that way set in

There is an issue in reading the encoding type. As c2 = 0xB2 in our case, using channel_encoding = (c2 & 0x10) >> 4; always gives 1 which corresponds to 10bits. But manually changing the channel_encoding to 0, I could check that 11bits encoding type is properly parsed.

Besides, as c2 = 0xB2, it does not match paparazzi guessing format, Thus the frame number to transmit all channels is not so clear

Finally, I did not manage to set in DSMX mode so far.

jlecoeur commented 9 years ago

Hi,

Thanks for looking into it,

I found this about binding pulses

http://wiki.openpilot.org/plugins/servlet/mobile#content/view/12386876

It might help

GregoireH commented 9 years ago

Sure I was already trying this.

Turnigy LED sequence None = 3 pulses, DMS2 10bits 1/sec = 5 pulses, DSM2 11bits 2/sec = 7 pulses, DSMX 10bits 3/sec = 9 pulses, DSMX 11bits

Setting 7 or 9 pulses for the binding process with the turnigy always end-up in a DSM2 11bits resolution according to our turnigy LED (blinking once per sec). But the result of those bind are not similar to 5 pulses, as I cannot decode packet after binding with 7 or 9 pulses.

I was also trying to bind using the Spektrum DX8 from the openspace without any success, even though I tried all possible pulses combinations (3, 5, 7 or 9)

GregoireH commented 9 years ago

I now have an other orange module, DSM2, 9CH, I will bind a satellite with this guy and see whether I can read more than 7 channels in the end. I ll let you know.

GregoireH commented 9 years ago

Binding with the rx satellite receiver to a DSM2 rx orange module, enable the possibility to use 14 channels !!! For this, go in setup of your remote and set the number of channels to 14. Unfortunately the 9XR turnigy does not support 16 channels, even though it has the setting for. I will try to see how many pulses are sent, by this orange module, to better understand why our bind procedure doesn't give the same result. Best

GregoireH commented 9 years ago

Done in pull request 64 All the Best