Defines refactoring
This commit is contained in:
5
.vscode/arduino.json
vendored
5
.vscode/arduino.json
vendored
@@ -1,6 +1,7 @@
|
|||||||
{
|
{
|
||||||
"board": "bsfrance:avr:lora32u4",
|
"board": "arduino:avr:pro",
|
||||||
"sketch": "crossbow.ino",
|
"sketch": "crossbow.ino",
|
||||||
"port": "COM23",
|
"port": "COM23",
|
||||||
"output": "./build"
|
"output": "./build",
|
||||||
|
"configuration": "cpu=16MHzatmega328"
|
||||||
}
|
}
|
||||||
31
crossbow.ino
31
crossbow.ino
@@ -4,8 +4,8 @@
|
|||||||
// #define LORA_HARDWARE_SERIAL
|
// #define LORA_HARDWARE_SERIAL
|
||||||
#define LORA_HARDWARE_SPI
|
#define LORA_HARDWARE_SPI
|
||||||
|
|
||||||
#define DEVICE_MODE_TX
|
// #define DEVICE_MODE_TX
|
||||||
// #define DEVICE_MODE_RX
|
#define DEVICE_MODE_RX
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* Main defines for device working in TX mode
|
* Main defines for device working in TX mode
|
||||||
@@ -13,11 +13,8 @@
|
|||||||
#ifdef DEVICE_MODE_TX
|
#ifdef DEVICE_MODE_TX
|
||||||
|
|
||||||
#include <PPMReader.h>
|
#include <PPMReader.h>
|
||||||
|
|
||||||
#define PPM_INPUT_PIN 2
|
|
||||||
#define PPM_INPUT_INTERRUPT 1 //For Pro Micro 1, For Pro Mini 0
|
|
||||||
|
|
||||||
PPMReader ppmReader(PPM_INPUT_PIN, PPM_INPUT_INTERRUPT);
|
PPMReader ppmReader(PPM_INPUT_PIN, PPM_INPUT_INTERRUPT);
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/*
|
/*
|
||||||
@@ -296,12 +293,12 @@ void setup(void) {
|
|||||||
display.display();
|
display.display();
|
||||||
|
|
||||||
//initiallize default ppm values
|
//initiallize default ppm values
|
||||||
for(int i=0; i<CHANNEL_NUMBER; i++){
|
for(int i=0; i<PPM_CHANNEL_COUNT; i++){
|
||||||
ppm[i]= CHANNEL_DEFAULT_VALUE;
|
ppm[i]= PPM_CHANNEL_DEFAULT_VALUE;
|
||||||
}
|
}
|
||||||
|
|
||||||
pinMode(sigPin, OUTPUT);
|
pinMode(PPM_OUTPUT_PIN, OUTPUT);
|
||||||
digitalWrite(sigPin, !onState); //set the PPM signal pin to the default state (off)
|
digitalWrite(PPM_OUTPUT_PIN, !PPM_SIGNAL_POSITIVE_STATE); //set the PPM signal pin to the default state (off)
|
||||||
|
|
||||||
cli();
|
cli();
|
||||||
TCCR1A = 0; // set entire TCCR1 register to 0
|
TCCR1A = 0; // set entire TCCR1 register to 0
|
||||||
@@ -366,24 +363,24 @@ ISR(TIMER1_COMPA_vect){ //leave this alone
|
|||||||
TCNT1 = 0;
|
TCNT1 = 0;
|
||||||
|
|
||||||
if (state) { //start pulse
|
if (state) { //start pulse
|
||||||
digitalWrite(sigPin, onState);
|
digitalWrite(PPM_OUTPUT_PIN, PPM_SIGNAL_POSITIVE_STATE);
|
||||||
OCR1A = PULSE_LENGTH * 2;
|
OCR1A = PPM_PULSE_LENGTH * 2;
|
||||||
state = false;
|
state = false;
|
||||||
} else{ //end pulse and calculate when to start the next pulse
|
} else{ //end pulse and calculate when to start the next pulse
|
||||||
static byte cur_chan_numb;
|
static byte cur_chan_numb;
|
||||||
static unsigned int calc_rest;
|
static unsigned int calc_rest;
|
||||||
|
|
||||||
digitalWrite(sigPin, !onState);
|
digitalWrite(PPM_OUTPUT_PIN, !PPM_SIGNAL_POSITIVE_STATE);
|
||||||
state = true;
|
state = true;
|
||||||
|
|
||||||
if(cur_chan_numb >= CHANNEL_NUMBER){
|
if(cur_chan_numb >= PPM_CHANNEL_COUNT){
|
||||||
cur_chan_numb = 0;
|
cur_chan_numb = 0;
|
||||||
calc_rest = calc_rest + PULSE_LENGTH;//
|
calc_rest = calc_rest + PPM_PULSE_LENGTH;//
|
||||||
OCR1A = (FRAME_LENGTH - calc_rest) * 2;
|
OCR1A = (PPM_FRAME_LENGTH - calc_rest) * 2;
|
||||||
calc_rest = 0;
|
calc_rest = 0;
|
||||||
}
|
}
|
||||||
else{
|
else{
|
||||||
OCR1A = (ppm[cur_chan_numb] - PULSE_LENGTH) * 2;
|
OCR1A = (ppm[cur_chan_numb] - PPM_PULSE_LENGTH) * 2;
|
||||||
calc_rest = calc_rest + ppm[cur_chan_numb];
|
calc_rest = calc_rest + ppm[cur_chan_numb];
|
||||||
cur_chan_numb++;
|
cur_chan_numb++;
|
||||||
}
|
}
|
||||||
|
|||||||
13
variables.h
13
variables.h
@@ -27,10 +27,11 @@ enum dataStates {
|
|||||||
CRC_RECEIVED
|
CRC_RECEIVED
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#define PPM_INPUT_PIN 2
|
||||||
|
#define PPM_INPUT_INTERRUPT 1 //For Pro Micro 1, For Pro Mini 0
|
||||||
|
|
||||||
#define CHANNEL_NUMBER 12 //set the number of chanels
|
#define PPM_CHANNEL_DEFAULT_VALUE 1500 //set the default servo value
|
||||||
#define 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 FRAME_LENGTH 22500 //set the PPM frame length in microseconds (1ms = 1000µs)
|
#define PPM_PULSE_LENGTH 300 //set the pulse length
|
||||||
#define PULSE_LENGTH 300 //set the pulse length
|
#define PPM_SIGNAL_POSITIVE_STATE 1 //set polarity of the pulses: 1 is positive, 0 is negative
|
||||||
#define onState 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
|
||||||
#define sigPin 10 //set PPM signal output pin on the arduino
|
|
||||||
|
|||||||
Reference in New Issue
Block a user