Fixed missing constrain
This commit is contained in:
26
crossbow.ino
26
crossbow.ino
@@ -1,8 +1,8 @@
|
||||
// #define LORA_HARDWARE_SERIAL
|
||||
#define LORA_HARDWARE_SPI
|
||||
|
||||
#define DEVICE_MODE_TX
|
||||
// #define DEVICE_MODE_RX
|
||||
// #define DEVICE_MODE_TX
|
||||
#define DEVICE_MODE_RX
|
||||
|
||||
#define DEBUG_SERIAL
|
||||
// #define DEBUG_PING_PONG
|
||||
@@ -19,7 +19,7 @@
|
||||
#define LORA32U4_RST_PIN 4
|
||||
#define LORA32U4_DI0_PIN 7
|
||||
|
||||
int ppm[PPM_CHANNEL_COUNT] = {0};
|
||||
int ppm[PPM_OUTPUT_CHANNEL_COUNT] = {0};
|
||||
|
||||
/*
|
||||
* Main defines for device working in TX mode
|
||||
@@ -207,7 +207,7 @@ void setup(void)
|
||||
// display.display();
|
||||
|
||||
//initiallize default ppm values
|
||||
for (int i = 0; i < PPM_CHANNEL_COUNT; i++)
|
||||
for (int i = 0; i < PPM_OUTPUT_CHANNEL_COUNT; i++)
|
||||
{
|
||||
ppm[i] = PPM_CHANNEL_DEFAULT_VALUE;
|
||||
}
|
||||
@@ -267,7 +267,7 @@ ISR(TIMER1_COMPA_vect) { //leave this alone
|
||||
if (state)
|
||||
{ //start pulse
|
||||
writePpmOutput(PPM_SIGNAL_POSITIVE_STATE);
|
||||
OCR1A = PPM_PULSE_LENGTH * 2;
|
||||
OCR1A = PPM_PULSE_LENGTH * PPM_OUTPUT_MULTIPLIER;
|
||||
state = false;
|
||||
}
|
||||
else
|
||||
@@ -278,16 +278,16 @@ ISR(TIMER1_COMPA_vect) { //leave this alone
|
||||
writePpmOutput(!PPM_SIGNAL_POSITIVE_STATE);
|
||||
state = true;
|
||||
|
||||
if (cur_chan_numb >= PPM_CHANNEL_COUNT)
|
||||
if (cur_chan_numb >= PPM_OUTPUT_CHANNEL_COUNT)
|
||||
{
|
||||
cur_chan_numb = 0;
|
||||
calc_rest = calc_rest + PPM_PULSE_LENGTH; //
|
||||
OCR1A = (PPM_FRAME_LENGTH - calc_rest) * 2;
|
||||
OCR1A = (PPM_FRAME_LENGTH - calc_rest) * PPM_OUTPUT_MULTIPLIER;
|
||||
calc_rest = 0;
|
||||
}
|
||||
else
|
||||
{
|
||||
OCR1A = (ppm[cur_chan_numb] - PPM_PULSE_LENGTH) * 2;
|
||||
OCR1A = (ppm[cur_chan_numb] - PPM_PULSE_LENGTH) * PPM_OUTPUT_MULTIPLIER;
|
||||
calc_rest = calc_rest + ppm[cur_chan_numb];
|
||||
cur_chan_numb++;
|
||||
}
|
||||
@@ -361,10 +361,18 @@ void loop(void)
|
||||
qsp.protocolState == QSP_STATE_IDLE
|
||||
)
|
||||
{
|
||||
// int count;
|
||||
// while(ppmReader.get(count) != 0){ //print out the servo values
|
||||
// Serial.print(ppmReader.get(count));
|
||||
// Serial.print(" ");
|
||||
// count++;
|
||||
// }
|
||||
// Serial.println("");
|
||||
|
||||
qsp.lastFrameTransmitedAt[QSP_FRAME_RC_DATA] = currentMillis;
|
||||
|
||||
qspClearPayload(&qsp);
|
||||
encodeRcDataPayload(&qsp, &ppmReader, PPM_CHANNEL_COUNT);
|
||||
encodeRcDataPayload(&qsp, &ppmReader, PPM_INPUT_CHANNEL_COUNT);
|
||||
qsp.frameToSend = QSP_FRAME_RC_DATA;
|
||||
|
||||
transmitPayload = true;
|
||||
|
||||
12
qsp.cpp
12
qsp.cpp
@@ -3,7 +3,7 @@
|
||||
#include <PPMReader.h>
|
||||
|
||||
void qspDecodeRcDataFrame(QspConfiguration_t *qsp, int output[]) {
|
||||
int temporaryPpmOutput[PPM_CHANNEL_COUNT] = {0};
|
||||
int temporaryPpmOutput[PPM_OUTPUT_CHANNEL_COUNT] = {0};
|
||||
//TODO fix it, baby :)
|
||||
|
||||
temporaryPpmOutput[0] = (uint16_t) (((uint16_t) qsp->payload[0] << 2) & 0x3fc) | ((qsp->payload[1] >> 6) & 0x03);
|
||||
@@ -36,7 +36,7 @@ void qspDecodeRcDataFrame(QspConfiguration_t *qsp, int output[]) {
|
||||
/*
|
||||
* Copy tremporary to real output
|
||||
*/
|
||||
for (uint8_t i = 0; i < PPM_CHANNEL_COUNT; i++) {
|
||||
for (uint8_t i = 0; i < PPM_OUTPUT_CHANNEL_COUNT; i++) {
|
||||
output[i] = temporaryPpmOutput[i];
|
||||
}
|
||||
}
|
||||
@@ -81,9 +81,11 @@ void encodeRcDataPayload(QspConfiguration_t *qsp, PPMReader *ppmSource, uint8_t
|
||||
{
|
||||
for (uint8_t i = 0; i < noOfChannels; i++)
|
||||
{
|
||||
uint16_t channelValue10 = map(ppmSource->get(i), 1000, 2000, 0, 1000) & 0x03ff;
|
||||
uint8_t channelValue8 = map(ppmSource->get(i), 1000, 2000, 0, 255) & 0xff;
|
||||
uint8_t channelValue4 = map(ppmSource->get(i), 1000, 2000, 0, 15) & 0x0f;
|
||||
int cV = constrain(ppmSource->get(i), 1000, 2000);
|
||||
|
||||
uint16_t channelValue10 = map(cV, 1000, 2000, 0, 1000) & 0x03ff;
|
||||
uint8_t channelValue8 = map(cV, 1000, 2000, 0, 255) & 0xff;
|
||||
uint8_t channelValue4 = map(cV, 1000, 2000, 0, 15) & 0x0f;
|
||||
|
||||
if (i < 4)
|
||||
{
|
||||
|
||||
10
variables.h
10
variables.h
@@ -4,10 +4,8 @@
|
||||
#define UART_SPEED 57600
|
||||
#define E45_TTL_100_UART_DOWNTIME 30
|
||||
|
||||
#define PPM_CHANNEL_COUNT 10
|
||||
|
||||
#define RX_RX_HEALTH_FRAME_RATE 2000
|
||||
#define TX_RC_FRAME_RATE 50 //ms
|
||||
#define TX_RC_FRAME_RATE 1000 //ms
|
||||
#define RX_FAILSAFE_DELAY (TX_RC_FRAME_RATE * 4)
|
||||
|
||||
#define TX_PING_RATE 2000
|
||||
@@ -54,9 +52,13 @@ enum debugConfigFlags {
|
||||
#define PPM_INPUT_PIN 0 // Has to be one of Interrupt pins
|
||||
#define PPM_INPUT_INTERRUPT 2 // For Pro Micro 1, For Pro Mini 0
|
||||
|
||||
#define PPM_INPUT_CHANNEL_COUNT 10
|
||||
#define PPM_OUTPUT_CHANNEL_COUNT 10
|
||||
|
||||
#define PPM_CHANNEL_DEFAULT_VALUE 1500 //set the default servo value
|
||||
#define PPM_FRAME_LENGTH 22500 //set the PPM frame length in microseconds (1ms = 1000µs)
|
||||
#define PPM_FRAME_LENGTH 30500 //set the PPM frame length in microseconds (1ms = 1000µs)
|
||||
#define PPM_PULSE_LENGTH 300 //set the pulse length
|
||||
#define PPM_OUTPUT_MULTIPLIER 1 //1 for 8MHz RX, 2 for 16MHz RX
|
||||
#define PPM_SIGNAL_POSITIVE_STATE 1 //set polarity of the pulses: 1 is positive, 0 is negative
|
||||
#define PPM_OUTPUT_PIN 10 //set PPM signal output pin on the arduino
|
||||
|
||||
|
||||
Reference in New Issue
Block a user