Skip to content

Commit

Permalink
Moved PPM interface to pin D16 (timer4/channel1)
Browse files Browse the repository at this point in the history
  • Loading branch information
0xjairo committed Dec 29, 2011
1 parent 5c12b06 commit 63dea57
Show file tree
Hide file tree
Showing 4 changed files with 81 additions and 70 deletions.
2 changes: 1 addition & 1 deletion esc-control.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ const char* dummy_data = ("qwertyuiopasdfghjklzxcvbnmmmmmm,./1234567890-="
void ppm_decode(void){
SerialUSB.println("Decoding DIY Drones PPM encoder on pin D27");

int pin = 27;
int pin = 16;
uint8 prev_state;
int time_elapsed = 0;
int time_start = 0;
Expand Down
12 changes: 8 additions & 4 deletions main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,20 +12,24 @@
#define ESC ((uint8)27)

// Globals
HardwareTimer timer4(4);
HardwareTimer timer1(1);

// -- setup() and loop() ------------------------------------------------------

void setup() {
// Set up the LED to blink
pinMode(BOARD_LED_PIN, OUTPUT);

// Setup timer4 for PWM
timer4.setMode(TIMER_CH1, TIMER_PWM);
timer4.setPrescaleFactor(21);
// Setup timer1 for PWM
timer1.setMode(TIMER_CH1, TIMER_PWM);
timer1.setPrescaleFactor(21);
pinMode(ROTOR1_PIN, PWM);
pinMode(ROTOR2_PIN, PWM);
pinMode(ROTOR3_PIN, PWM);
//using timer4, channel1, maps to pin d16 (maple mini) according to maple master pin map.
pinMode(PPM_PIN, INPUT_PULLUP);



// ppm decode setup
// init timer1 and dma
Expand Down
15 changes: 8 additions & 7 deletions main.h
Original file line number Diff line number Diff line change
Expand Up @@ -11,11 +11,12 @@
*
*/

/* Timer 4, Ch 1 */
#define ROTOR1_PIN 16
/* Timer 4, Ch 2 */
#define ROTOR2_PIN 15
/* Timer 4, Ch 3 */
#define ROTOR3_PIN 32
/* Timer 1, Ch 1 */
#define ROTOR1_PIN 27
/* Timer 1, Ch 2 */
#define ROTOR2_PIN 26
/* Timer 1, Ch 3 */
#define ROTOR3_PIN 25

#define PPM_PIN 27
/* Timer 4, Ch 1 */
#define PPM_PIN 16
122 changes: 64 additions & 58 deletions ppm-decode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
// TIMER_PRESCALE*(1/72 MHz) =
#define TICK_PERIOD ( TIMER_PRESCALE*0.0000138888889f )

HardwareTimer timer1 = HardwareTimer(1);
HardwareTimer timer4 = HardwareTimer(4);
volatile int dma_data_captured=0; //set to 1 when dma complete.
volatile uint16 data[TIMERS]; //place to put the data via dma
uint16 delta=0;
Expand Down Expand Up @@ -59,12 +59,12 @@ void printData(){
//invoked as configured by the DMA mode flags.
void dma_isr()
{
dma_irq_cause cause = dma_get_irq_cause(DMA1, DMA_CH2);
dma_irq_cause cause = dma_get_irq_cause(DMA1, DMA_CH1);
//using serialusb to print messages here is nice, but
//it takes so long, we may never exit this isr invocation
//before the next one comes in.. (dma is fast.. m'kay)

timer1.setCount(0); // clear counter
timer4.setCount(0); // clear counter
if(ppm_timeout) ppm_timeout=0;
if(!do_print) do_print=1;
switch(cause)
Expand Down Expand Up @@ -108,28 +108,24 @@ void ppm_timeout_isr()
void init_timer_input_capture_dma()
{

timer_dev *t = TIMER1;
timer_dev *t = TIMER4;

timer1.pause();
timer1.setPrescaleFactor(TIMER_PRESCALE);
timer1.setOverflow(65535);
timer1.setCount(0);
timer4.pause();
timer4.setPrescaleFactor(TIMER_PRESCALE);
timer4.setOverflow(65535);
timer4.setCount(0);

// use channel 2 to detect when we stop receiving
// a ppm signal from the encoder.
timer1.setMode(TIMER_CH2, TIMER_OUTPUT_COMPARE);
timer1.setCompare(TIMER_CH2, 65535);
timer1.attachCompare2Interrupt(ppm_timeout_isr);
timer4.setMode(TIMER_CH2, TIMER_OUTPUT_COMPARE);
timer4.setCompare(TIMER_CH2, 65535);
timer4.attachCompare2Interrupt(ppm_timeout_isr);


timer1.refresh();
timer4.refresh();

timer_reg_map r = t->regs;

//using timer1, channel1, maps to pin d27 (maple mini) //d6 (maple?)
//according to maple master pin map.
pinMode(PPM_PIN,INPUT_PULLUP);

//capture compare regs TIMx_CCRx used to hold val after a transition on corresponding ICx

//when cap occurs, flag CCXIF (TIMx_SR register) is set,
Expand All @@ -140,50 +136,56 @@ void init_timer_input_capture_dma()
//CCIX can be cleared by writing 0, or by reading the capped data from TIMx_CCRx
//CCxOF is cleared by writing 0 to it.

//Clear the CC1E bit to disable capture from the counter as we set it up.
//CC1S bits aren't writeable when CC1E is set.
//CC1E is bit 0 of CCER (page 401)
bitClear(r.gen->CCER,0);


//Capture/Compare 1 Selection
// set CC1S bits to 01 in the capture compare mode register.
// 01 selects TI1 as the input to use. (page 336 stm32 reference)
// (assuming here that TI1 is D27, according to maple master pin map)
//CC1S bits are bits 0,1
bitClear(r.adv->CCMR1, 1);
bitSet(r.adv->CCMR1, 0);
// set CC1S bits to 01 in the capture compare mode register 1.
// 01 selects TI1 as the input to use. (page 399 stm32 reference)
// (assuming here that TI1 is D16, according to maple master pin map)
//CC1S bits are bits 1,0
bitClear(r.gen->CCMR1, 1);
bitSet(r.gen->CCMR1, 0);


//Input Capture 1 Filter.
// need to set IC1F bits according to a table saying how long
// we should wait for a signal to be 'stable' to validate a transition
// on the input.
// (page 336 stm32 reference)
// (page 401 stm32 reference)
//IC1F bits are bits 7,6,5,4
bitClear(r.adv->CCMR1, 7);
bitClear(r.adv->CCMR1, 6);
bitSet(r.adv->CCMR1, 5);
bitSet(r.adv->CCMR1, 4);
bitClear(r.gen->CCMR1, 7);
bitClear(r.gen->CCMR1, 6);
bitSet(r.gen->CCMR1, 5);
bitSet(r.gen->CCMR1, 4);

//sort out the input capture prescaler..
//sort out the input capture prescaler IC1PSC..
//00 no prescaler.. capture is done at every edge detected
bitClear(r.adv->CCMR1, 3);
bitClear(r.adv->CCMR1, 2);
bitClear(r.gen->CCMR1, 3);
bitClear(r.gen->CCMR1, 2);

//select the edge for the transition on TI1 channel using CC1P in CCER
//CC1P is bit 1 of CCER (page 339)
//CC1P is bit 1 of CCER (page 401)
// 0 = rising (non-inverted. capture is done on a rising edge of IC1)
// 1 = falling (inverted. capture is done on a falling edge of IC1)
bitClear(r.adv->CCER,1);
bitClear(r.gen->CCER,1);

//set the CC1E bit to enable capture from the counter.
//CCE1 is bit 0 of CCER (page 339)
bitSet(r.adv->CCER,0);
//CC1E is bit 0 of CCER (page 401)
bitSet(r.gen->CCER,0);

//enable dma for this timer..
//sets the Capture/Compare 1 DMA request enable bit on the DMA/interrupt enable register.
//bit 9 is CC1DE as defined on page 329.
bitSet(r.adv->DIER,9);
//bit 9 is CC1DE as defined on page 393.
bitSet(r.gen->DIER,9);

dma_init(DMA1);
dma_setup_transfer( DMA1, //dma device, dma1 here because that's the only one we have
DMA_CH2, //dma channel, channel2, because it looks after tim1_ch1 (timer1, channel1)
&(r.adv->CCR1), //peripheral address
DMA_CH1, //dma channel, channel1, because it looks after tim4_ch1 (timer4, channel1)
&(r.gen->CCR1), //peripheral address
DMA_SIZE_16BITS, //peripheral size
data, //memory address
DMA_SIZE_16BITS, //memory transfer size
Expand All @@ -197,50 +199,54 @@ void init_timer_input_capture_dma()
)
);

dma_attach_interrupt(DMA1, DMA_CH2, dma_isr); //hook up an isr for the dma chan to tell us if things happen.
dma_set_num_transfers(DMA1, DMA_CH2, TIMERS); //only allow it to transfer TIMERS number of times.
dma_enable(DMA1, DMA_CH2); //enable it..
dma_attach_interrupt(DMA1, DMA_CH1, dma_isr); //hook up an isr for the dma chan to tell us if things happen.
dma_set_num_transfers(DMA1, DMA_CH1, TIMERS); //only allow it to transfer TIMERS number of times.
dma_enable(DMA1, DMA_CH1); //enable it..


}

void ppm_decode_interrupt_dma()
{
timer_dev *t = TIMER4;
timer_reg_map r = t->regs;

SerialUSB.println("Starting timer.. rising edge of D27 (hopefully)");

// wait 2 seconds
delay(2000);
SerialUSB.println("...go!");
SerialUSB.print("Starting timer.. rising edge of D");
SerialUSB.print(PPM_PIN);

//start the timer counting.
timer1.resume();
//the timer is now counting up, and any falling edges on D6
timer4.resume();
//the timer is now counting up, and any rising edges on D16
//will trigger a DMA request to clone the timercapture to the array

//If we weren't using DMA, we could busy wait on the CC1IF bit in SR
//
//when the timer captures, the CC1IF bit will be set on the timer SR register.
//CC1IF bit is bit 1 (page 332)
//while(!bitRead(r.adv->SR, 1)){
//}
//SerialUSB.println("Timer triggered : ");
//SerialUSB.println(r.adv->CCR1);
// //If we weren't using DMA, we could busy wait on the CC1IF bit in SR
// //
// //when the timer captures, the CC1IF bit will be set on the timer SR register.
// //CC1IF bit is bit 1 (page 332)
// for(int i=0;i<10;i++){
//
// while(!bitRead(r.gen->SR, 1));
// SerialUSB.print("tt:");
// SerialUSB.print(r.gen->CCR1);
// SerialUSB.print(" OF:");
// SerialUSB.println(bitRead(r.gen->SR, 9)); // over capture flag
// }

//SerialUSB.println("Waiting for dma_data_captured flag from dma...");
//busy wait on the dma_data_captured flag
//we could do real work here if wanted..
while(!dma_data_captured);
while(!dma_data_captured && !SerialUSB.available());

while(!SerialUSB.available() && do_print==1)
while(!SerialUSB.available() && do_print==1)
{
//dump the data
printData();
delay(100);
}

//turn off the timer & tidy up before we leave this cmd.
timer1.pause();
timer4.pause();

// dma_disable(DMA1, DMA_CH2);
// dma_detach_interrupt(DMA1, DMA_CH2);
Expand Down

0 comments on commit 63dea57

Please sign in to comment.