Last active
January 25, 2018 21:50
-
-
Save FLYBYME/48562a78d420d236f0e7e87bb8b7fc79 to your computer and use it in GitHub Desktop.
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
//////////////////////CONFIGURATION/////////////////////////////// | |
#define chanel_number 8 //set the number of chanels | |
#define default_servo_value 1500 //set the default servo value | |
#define PPM_FrLen 22500 //set the PPM frame length in microseconds (1ms = 1000µs) | |
#define PPM_PulseLen 300 //set the pulse length | |
#define onState 1 //set polarity of the pulses: 1 is positive, 0 is negative | |
#define sigPin 10 //set PPM signal output pin on the arduino | |
////////////////////////////////////////////////////////////////// | |
#define DSM_FRAME_SIZE 16 /**<DSM frame size in bytes*/ | |
#define DSM_FRAME_CHANNELS 7 /**<Max supported DSM channels*/ | |
#define LED_PIN 8 | |
//#define LED_PIN 13 | |
#define MIN_NUM_CHANNELS 5 | |
unsigned long dsm_last_frame_time = millis(); /**< Timestamp for start of last dsm frame */ | |
static unsigned dsm_channel_shift; /**< Channel resolution, 0=unknown, 1=10 bit, 2=11 bit */ | |
bool LEDState = false; | |
uint8_t dsmstr[DSM_FRAME_SIZE]; | |
int rxBufPos = 0; | |
bool synced = false; | |
int ppm[chanel_number]; | |
void setup() { | |
Serial.begin(115000); | |
pinMode(LED_PIN, OUTPUT); | |
for (int i = 0; i < chanel_number; i++) { | |
ppm[i] = default_servo_value; | |
} | |
pinMode(sigPin, OUTPUT); | |
digitalWrite(sigPin, !onState); //set the PPM signal pin to the default state (off) | |
cli(); | |
TCCR1A = 0; // set entire TCCR1 register to 0 | |
TCCR1B = 0; | |
OCR1A = 100; // compare match register, change this | |
TCCR1B |= (1 << WGM12); // turn on CTC mode | |
TCCR1B |= (1 << CS11); // 8 prescaler: 0,5 microseconds at 16mhz | |
TIMSK1 |= (1 << OCIE1A); // enable timer compare interrupt | |
sei(); | |
} | |
void loop() { | |
// put your main code here, to run repeatedly: | |
unsigned long frame_time = millis(); | |
/* | |
If we have lost signal for at least a second, reset the | |
format guessing heuristic. | |
*/ | |
if (((frame_time - dsm_last_frame_time) > 1000)) { | |
dsm_last_frame_time = frame_time; | |
synced = false; | |
ppm[0] = 900; | |
ppm[1] = 1500; | |
ppm[2] = 1500; | |
ppm[3] = 1500; | |
digitalWrite(LED_PIN, LEDState = !LEDState); | |
} | |
while (Serial.available()) { | |
uint8_t val = Serial.read(); | |
frame_time = millis(); | |
if (frame_time - dsm_last_frame_time > 10) { | |
digitalWrite(LED_PIN, LEDState = !LEDState); | |
dsm_last_frame_time = frame_time; | |
rxBufPos = 0; | |
synced = true; | |
} | |
if (synced) { | |
dsmstr[rxBufPos++] = val; | |
if (rxBufPos >= DSM_FRAME_SIZE) { | |
synced = false; | |
int values[8]; | |
uint16_t num_values = 0; | |
if (dsm_decode(dsmstr, values, &num_values, 8) && num_values >= MIN_NUM_CHANNELS) { | |
for (int i = 0; i < num_values; i++) { | |
ppm[i] = (int)values[i]; | |
} | |
} | |
memset(dsmstr, 0, DSM_FRAME_SIZE); | |
} | |
} | |
} | |
} | |
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, const uint8_t dsm_frame[16]) { | |
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++) { | |
const 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) { | |
Serial.println("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); i++) { | |
if (cs10 == masks[i]) | |
votes10++; | |
if (cs11 == masks[i]) | |
votes11++; | |
} | |
if ((votes11 == 1) && (votes10 == 0)) { | |
dsm_channel_shift = 11; | |
Serial.println("DSM: 11-bit format"); | |
return; | |
} | |
if ((votes10 == 1) && (votes11 == 0)) { | |
dsm_channel_shift = 10; | |
Serial.println("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, dsm_frame); | |
} | |
/** | |
Decode the entire dsm frame (all contained channels) | |
*/ | |
bool dsm_decode(const uint8_t dsm_frame[16], uint16_t *values, uint16_t *num_values, uint16_t max_values) { | |
/* if we don't know the dsm_frame format, update the guessing state machine */ | |
if (dsm_channel_shift == 0) { | |
dsm_guess_format(false, dsm_frame); | |
//Serial.println("dsm_channel_shift == 0"); | |
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++) { | |
const 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 >= max_values) { | |
continue; | |
} | |
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; | |
//value = (((value - 1024) * 1000) / 1700) + 1500; | |
value = map(value, 0, 2048, 1000, 2000); | |
values[channel] = value; | |
} | |
if (*num_values == 13) | |
*num_values = 12; | |
/* | |
XXX Note that we may be in failsafe here; we need to work out how to detect that. | |
*/ | |
return true; | |
} | |
ISR(TIMER1_COMPA_vect) { //leave this alone | |
static boolean state = true; | |
TCNT1 = 0; | |
if (state) { //start pulse | |
digitalWrite(sigPin, onState); | |
OCR1A = PPM_PulseLen * 2; | |
state = false; | |
} | |
else { //end pulse and calculate when to start the next pulse | |
static byte cur_chan_numb; | |
static unsigned int calc_rest; | |
digitalWrite(sigPin, !onState); | |
state = true; | |
if (cur_chan_numb >= chanel_number) { | |
cur_chan_numb = 0; | |
calc_rest = calc_rest + PPM_PulseLen;// | |
OCR1A = (PPM_FrLen - calc_rest) * 2; | |
calc_rest = 0; | |
} | |
else { | |
OCR1A = (ppm[cur_chan_numb] - PPM_PulseLen) * 2; | |
calc_rest = calc_rest + ppm[cur_chan_numb]; | |
cur_chan_numb++; | |
} | |
} | |
} |
Sign up for free
to join this conversation on GitHub.
Already have an account?
Sign in to comment