diff --git a/esc-control.cpp b/esc-control.cpp index 8d08a31..06f3c4e 100644 --- a/esc-control.cpp +++ b/esc-control.cpp @@ -18,9 +18,9 @@ const char* dummy_data = ("qwertyuiopasdfghjklzxcvbnmmmmmm,./1234567890-=" void ppm_decode(void){ - SerialUSB.println("Decoding DIY Drones PPM encoder on pin D15"); + SerialUSB.println("Decoding DIY Drones PPM encoder on pin D27"); - int pin = 15; + int pin = 27; uint8 prev_state; int time_elapsed = 0; int time_start = 0; diff --git a/main.cpp b/main.cpp index 60599d7..11f22d7 100644 --- a/main.cpp +++ b/main.cpp @@ -4,7 +4,7 @@ #include "wirish.h" #include "utils.h" #include "esc-control.h" -//#include "ppm-decode.h" +#include "ppm-decode.h" // ASCII escape character @@ -66,6 +66,13 @@ int main(void) { break; case '?': + SerialUSB.println("no help available"); + break; + + case 'd': + ppm_decode_interrupt_dma(); + break; + case 'h': cmd_print_help(); break; diff --git a/ppm-decode.cpp b/ppm-decode.cpp index 55be8ff..ce500ca 100644 --- a/ppm-decode.cpp +++ b/ppm-decode.cpp @@ -4,10 +4,10 @@ ///********************************************************************** // Various Maple tests.. including timer capture to memory via dma =) // */ -//#include "wirish.h" -//#include "usb.h" -//#include "timer.h" -//#include "dma.h" +#include "wirish.h" +#include "usb.h" +#include "timer.h" +#include "dma.h" // // ///********************************************************************** @@ -84,8 +84,8 @@ // return output; //} // -//HardwareTimer timer2 = HardwareTimer(2); -//HardwareTimer timer1 = HardwareTimer(1); +HardwareTimer timer2 = HardwareTimer(2); +HardwareTimer timer1 = HardwareTimer(1); //void timingTest(){ // SerialUSB.println("Starting Timing test"); // SerialUSB.print(" Prescale: "); @@ -121,253 +121,169 @@ ///****************************************************************************** // DMA from Timer Capture to array test.. // */ -// -////number of captures to do.. -//#define TIMERS 512 -//volatile int exit=0; //set to 1 when dma complete. -//volatile uint16 data[TIMERS]; //place to put the data via dma -// -////dump routine to show content of captured data. -//void printData(){ -// SerialUSB.print("DATA: "); -// for(int i=0; i "); -// SerialUSB.println(" eg. e 128 200 for a prescale of 128 and wait of 200"); -//done: -// break; -// } -// case 'f':{ -// timer_dev *t = TIMER1; -// -// timer1.pause(); -// timer1.setPrescaleFactor(128); -// timer1.setOverflow(65535); -// timer1.setCount(0); -// timer1.refresh(); -// -// timer_reg_map r = t->regs; -// -// //using timer1, channel1, maps to pin d6 -// //according to maple master pin map. -// pinMode(6,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, -// //and interrupt, or dma req can be sent if they are enabled. -// -// //if cap occurs while flag is already high CCxOF (overcapture) flag is set.. -// -// //CCIX can be cleared by writing 0, or by reading the capped data from TIMx_CCRx -// //CCxOF is cleared by writing 0 to it. -// -// //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 D6, according to maple master pin map) -// //CC1S bits are bits 0,1 -// bitSet(r.adv->CCMR1, 0); -// bitClear(r.adv->CCMR1, 1); -// -// -// //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) -// //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); -// -// //sort out the input capture prescaler.. -// //00 no prescaler.. capture is done as soon as edge is detected -// bitClear(r.adv->CCMR1, 3); -// bitClear(r.adv->CCMR1, 2); -// -// //select the edge for the transition on TI1 channel using CC1P in CCER -// //CC1P is bit 1 of CCER (page 339) -// // 0 = falling -// // 1 = rising -// bitClear(r.adv->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); -// -// //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); -// -// 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_SIZE_16BITS, //peripheral size -// data, //memory address -// DMA_SIZE_16BITS, //memory transfer size -// (0 -// //| DMA_FROM_MEM //set if going from memory, don't set if going to memory. -// | DMA_MINC_MODE //auto inc where the data does in memory (uses size_16bits to know how much) -// | DMA_TRNS_ERR //tell me if it's fubar -// //| DMA_HALF_TRNS //tell me half way (actually, don't as I spend so long there, I dont see 'complete') -// | DMA_TRNS_CMPLT //tell me at the end -// ) -// ); -// -// 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.. -// -// SerialUSB.println("Starting timer.. falling edge of D6 (hopefully)"); -// //start the timer counting. -// timer1.resume(); -// //the timer is now counting up, and any falling edges on D6 -// //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); -// -// SerialUSB.println("Waiting for exit flag from dma..."); -// //busy wait on the exit flag -// //we could do real work here if wanted.. -// while(!exit); -// //dump the data -// printData(); -// -// -// //turn off the timer & tidy up before we leave this cmd. -// timer1.pause(); -// dma_disable(DMA1, DMA_CH2); -// dma_detach_interrupt(DMA1, DMA_CH2); -// -// break; -// } -// } -//} -// -// -// -// + +//number of captures to do.. +#define TIMERS 512 +volatile int exit=0; //set to 1 when dma complete. +volatile uint16 data[TIMERS]; //place to put the data via dma + +//dump routine to show content of captured data. +void printData(){ + SerialUSB.print("DATA: "); + for(int i=0; iregs; + + //using timer1, channel1, maps to pin d27 (maple mini) //d6 (maple?) + //according to maple master pin map. + pinMode(27,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, + //and interrupt, or dma req can be sent if they are enabled. + + //if cap occurs while flag is already high CCxOF (overcapture) flag is set.. + + //CCIX can be cleared by writing 0, or by reading the capped data from TIMx_CCRx + //CCxOF is cleared by writing 0 to it. + + //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 D6, according to maple master pin map) + //CC1S bits are bits 0,1 + bitSet(r.adv->CCMR1, 0); + bitClear(r.adv->CCMR1, 1); + + + //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) + //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); + + //sort out the input capture prescaler.. + //00 no prescaler.. capture is done as soon as edge is detected + bitClear(r.adv->CCMR1, 3); + bitClear(r.adv->CCMR1, 2); + + //select the edge for the transition on TI1 channel using CC1P in CCER + //CC1P is bit 1 of CCER (page 339) + // 0 = rising (non-inverted. capture is done on a rising edge of IC1) + // 1 = falling (inverted. capture is donw on a falling edge of IC1) + bitClear(r.adv->CCER,0); + + //set the CC1E bit to enable capture from the counter. + //CCE1 is bit 0 of CCER (page 339) + bitSet(r.adv->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); + + 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_SIZE_16BITS, //peripheral size + data, //memory address + DMA_SIZE_16BITS, //memory transfer size + (0 + //| DMA_FROM_MEM //set if going from memory, don't set if going to memory. + | DMA_MINC_MODE //auto inc where the data does in memory (uses size_16bits to know how much) + | DMA_TRNS_ERR //tell me if it's fubar + //| DMA_HALF_TRNS //tell me half way (actually, don't as I spend so long there, I dont see 'complete') + | DMA_TRNS_CMPLT //tell me at the end + ) + ); + + 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.. + + SerialUSB.println("Starting timer.. rising edge of D27 (hopefully)"); + //start the timer counting. + timer1.resume(); + //the timer is now counting up, and any falling edges on D6 + //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); + + SerialUSB.println("Waiting for exit flag from dma..."); + //busy wait on the exit flag + //we could do real work here if wanted.. + while(!exit); + //dump the data + printData(); + + + //turn off the timer & tidy up before we leave this cmd. + timer1.pause(); + dma_disable(DMA1, DMA_CH2); + dma_detach_interrupt(DMA1, DMA_CH2); + + exit=0; +} + diff --git a/ppm-decode.h b/ppm-decode.h index e69de29..4078aa2 100644 --- a/ppm-decode.h +++ b/ppm-decode.h @@ -0,0 +1,4 @@ +void printData(); +void dma_isr(); +void ppm_decode_interrupt_dma(); +