Merge branch 'master' of https://github.com/stevstrong/Arduino_STM32 into stevstrong-master
This commit is contained in:
commit
ffea9588ea
|
@ -211,6 +211,12 @@ genericSTM32F103C.menu.upload_method.BMPMethod.upload.protocol=gdb_bmp
|
|||
genericSTM32F103C.menu.upload_method.BMPMethod.upload.tool=bmp_upload
|
||||
genericSTM32F103C.menu.upload_method.BMPMethod.build.upload_flags=-DCONFIG_MAPLE_MINI_NO_DISABLE_DEBUG
|
||||
|
||||
|
||||
genericSTM32F103C.menu.upload_method.jlinkMethod=JLink
|
||||
genericSTM32F103C.menu.upload_method.jlinkMethod.upload.protocol=jlink
|
||||
genericSTM32F103C.menu.upload_method.jlinkMethod.upload.tool=jlink_upload
|
||||
genericSTM32F103C.menu.upload_method.jlinkMethod.build.upload_flags=-DCONFIG_MAPLE_MINI_NO_DISABLE_DEBUG=1 -DSERIAL_USB -DGENERIC_BOOTLOADER
|
||||
|
||||
########################### Generic STM32F103R ###########################
|
||||
|
||||
genericSTM32F103R.name=Generic STM32F103R series
|
||||
|
@ -519,4 +525,4 @@ genericGD32F103C.menu.cpu_speed.speed_96mhz=96Mhz (Stable)
|
|||
genericGD32F103C.menu.cpu_speed.speed_96mhz.build.f_cpu=96000000L
|
||||
|
||||
genericGD32F103C.menu.cpu_speed.speed_72mhz=72Mhz (compatibility)
|
||||
genericGD32F103C.menu.cpu_speed.speed_72mhz.build.f_cpu=72000000L
|
||||
genericGD32F103C.menu.cpu_speed.speed_72mhz.build.f_cpu=72000000L
|
||||
|
|
|
@ -142,6 +142,28 @@ void HardwareTimer::refresh(void) {
|
|||
timer_generate_update(this->dev);
|
||||
}
|
||||
|
||||
/* CARLOS Changes to add encoder mode.*/
|
||||
|
||||
//direction of movement. (to be better described).
|
||||
uint8 HardwareTimer::getDirection(){
|
||||
return get_direction(this->dev);
|
||||
}
|
||||
|
||||
//set if the encoder will count edges on one, which or both channels.
|
||||
void HardwareTimer::setEdgeCounting(uint32 counting) {
|
||||
(dev->regs).gen->SMCR = counting;//TIMER_SMCR_SMS_ENCODER3; //choose encoder 3, counting on
|
||||
|
||||
}
|
||||
|
||||
uint8 HardwareTimer::getEdgeCounting() {
|
||||
return (dev->regs).gen->SMCR;
|
||||
}
|
||||
|
||||
|
||||
|
||||
//set the polarity of counting... not sure how interesting this is..
|
||||
void HardwareTimer::setPolarity(){}
|
||||
|
||||
/* -- Deprecated predefined instances -------------------------------------- */
|
||||
|
||||
HardwareTimer Timer1(1);
|
||||
|
|
|
@ -38,6 +38,10 @@
|
|||
/** Timer mode. */
|
||||
typedef timer_mode TimerMode;
|
||||
|
||||
//CARLOS
|
||||
//defines for the ENCODER mode.
|
||||
|
||||
|
||||
/**
|
||||
* @brief Interface to one of the 16-bit timer peripherals.
|
||||
*/
|
||||
|
@ -205,6 +209,23 @@ public:
|
|||
*/
|
||||
void refresh(void);
|
||||
|
||||
//CARLOS.
|
||||
/*
|
||||
added these functions to make sense for the encoder mode.
|
||||
*/
|
||||
//direction of movement. (to be better described).
|
||||
uint8 getDirection();
|
||||
|
||||
//set if the encoder will count edges on one, which or both channels.
|
||||
void setEdgeCounting(uint32 counting);
|
||||
uint8 getEdgeCounting(); //not sure if needed.
|
||||
|
||||
//set the polarity of counting... not sure how interesting this is..
|
||||
void setPolarity();
|
||||
|
||||
//add the filtering definition for the input channel.
|
||||
|
||||
|
||||
/* Escape hatch */
|
||||
|
||||
/**
|
||||
|
|
|
@ -44,7 +44,7 @@
|
|||
*
|
||||
* @param dev ADC peripheral to initialize
|
||||
*/
|
||||
void adc_init(const adc_dev *dev) {
|
||||
void adc_init(adc_dev *dev) {
|
||||
rcc_clk_enable(dev->clk_id);
|
||||
rcc_reset_dev(dev->clk_id);
|
||||
}
|
||||
|
@ -55,7 +55,7 @@ void adc_init(const adc_dev *dev) {
|
|||
* @param event Event used to trigger the start of conversion.
|
||||
* @see adc_extsel_event
|
||||
*/
|
||||
void adc_set_extsel(const adc_dev *dev, adc_extsel_event event) {
|
||||
void adc_set_extsel(adc_dev *dev, adc_extsel_event event) {
|
||||
uint32 cr2 = dev->regs->CR2;
|
||||
cr2 &= ~ADC_CR2_EXTSEL;
|
||||
cr2 |= event;
|
||||
|
@ -71,7 +71,7 @@ void adc_set_extsel(const adc_dev *dev, adc_extsel_event event) {
|
|||
* @param smp_rate sample rate to set
|
||||
* @see adc_smp_rate
|
||||
*/
|
||||
void adc_set_sample_rate(const adc_dev *dev, adc_smp_rate smp_rate) {
|
||||
void adc_set_sample_rate(adc_dev *dev, adc_smp_rate smp_rate) {
|
||||
uint32 adc_smpr1_val = 0, adc_smpr2_val = 0;
|
||||
int i;
|
||||
|
||||
|
@ -95,7 +95,7 @@ void adc_set_sample_rate(const adc_dev *dev, adc_smp_rate smp_rate) {
|
|||
* @param channel channel to convert
|
||||
* @return conversion result
|
||||
*/
|
||||
uint16 adc_read(const adc_dev *dev, uint8 channel) {
|
||||
uint16 adc_read(adc_dev *dev, uint8 channel) {
|
||||
adc_reg_map *regs = dev->regs;
|
||||
|
||||
adc_set_reg_seqlen(dev, 1);
|
||||
|
|
|
@ -34,6 +34,7 @@
|
|||
|
||||
#include <libmaple/adc.h>
|
||||
#include <libmaple/gpio.h>
|
||||
#include <libmaple/nvic.h>//Added by bubulindo.
|
||||
|
||||
/*
|
||||
* Devices
|
||||
|
@ -42,26 +43,126 @@
|
|||
adc_dev adc1 = {
|
||||
.regs = ADC1_BASE,
|
||||
.clk_id = RCC_ADC1,
|
||||
.handlers = {[3]=0}, //added by bubulindo. EOC, JEOC, AWD
|
||||
.irq_num = NVIC_ADC_1_2,
|
||||
};
|
||||
/** ADC1 device. */
|
||||
const adc_dev *ADC1 = &adc1;
|
||||
adc_dev *ADC1 = &adc1;
|
||||
|
||||
adc_dev adc2 = {
|
||||
.regs = ADC2_BASE,
|
||||
.clk_id = RCC_ADC2,
|
||||
};
|
||||
/** ADC2 device. */
|
||||
const adc_dev *ADC2 = &adc2;
|
||||
adc_dev *ADC2 = &adc2;
|
||||
|
||||
#if defined(STM32_HIGH_DENSITY) || defined(STM32_XL_DENSITY)
|
||||
adc_dev adc3 = {
|
||||
.regs = ADC3_BASE,
|
||||
.clk_id = RCC_ADC3,
|
||||
.handlers = {[3]=0}, //added by bubulindo. EOC, JEOC, AWD
|
||||
.irq_num = NVIC_ADC3,//added by bubulindo.
|
||||
};
|
||||
/** ADC3 device. */
|
||||
const adc_dev *ADC3 = &adc3;
|
||||
adc_dev *ADC3 = &adc3;
|
||||
#endif
|
||||
|
||||
|
||||
/*
|
||||
adc irq routine.
|
||||
Added by bubulindo.
|
||||
*/
|
||||
void __irq_adc() {
|
||||
//get status
|
||||
uint32 adc_sr = ADC1->regs->SR;
|
||||
//End Of Conversion
|
||||
if (adc_sr & (1U << ADC_SR_EOC_BIT)) {
|
||||
ADC1->regs->SR &= ~(1<<ADC_SR_EOC_BIT);
|
||||
void (*handler)(void) = ADC1->handlers[ADC_EOC];
|
||||
if (handler) {
|
||||
handler();
|
||||
}
|
||||
}
|
||||
//Injected End Of Conversion
|
||||
if (adc_sr & (1U << ADC_SR_JEOC_BIT)) {
|
||||
ADC1->regs->SR &= ~(1<<ADC_SR_JEOC_BIT);
|
||||
void (*handler)(void) = ADC1->handlers[ADC_JEOC];
|
||||
if (handler) {
|
||||
handler();
|
||||
}
|
||||
}
|
||||
//Analog Watchdog
|
||||
if (adc_sr & (1U << ADC_SR_AWD_BIT)) {
|
||||
ADC1->regs->SR &= ~(1<<ADC_SR_AWD_BIT);
|
||||
void (*handler)(void) = ADC1->handlers[ADC_AWD];
|
||||
if (handler) {
|
||||
handler();
|
||||
}
|
||||
}
|
||||
};//end of adc irq
|
||||
|
||||
|
||||
/*
|
||||
ADC3 IRQ handler.
|
||||
added by bubulindo
|
||||
*/
|
||||
#if defined(STM32_HIGH_DENSITY) || defined(STM32_XL_DENSITY)
|
||||
void __irq_adc3() {
|
||||
//get status
|
||||
uint32 adc_sr = ADC3->regs->SR;
|
||||
//End Of Conversion
|
||||
if (adc_sr & (1U << ADC_SR_EOC_BIT)) {
|
||||
ADC3->regs->SR &= ~(1<<ADC_SR_EOC_BIT);
|
||||
void (*handler)(void) = ADC3->handlers[ADC_EOC];
|
||||
if (handler) {
|
||||
handler();
|
||||
}
|
||||
}
|
||||
//Injected End Of Conversion
|
||||
if (adc_sr & (1U << ADC_SR_JEOC_BIT)) {
|
||||
ADC3->regs->SR &= ~(1<<ADC_SR_JEOC_BIT);
|
||||
void (*handler)(void) = ADC3->handlers[ADC_JEOC];
|
||||
if (handler) {
|
||||
handler();
|
||||
}
|
||||
}
|
||||
//Analog Watchdog
|
||||
if (adc_sr & (1U << ADC_SR_AWD_BIT)) {
|
||||
ADC3->regs->SR &= ~(1<<ADC_SR_AWD_BIT);
|
||||
void (*handler)(void) = ADC3->handlers[ADC_AWD];
|
||||
if (handler) {
|
||||
handler();
|
||||
}
|
||||
}
|
||||
};//end of ADC3 irq
|
||||
#endif
|
||||
|
||||
/*
|
||||
enable interrupts on the ADC:
|
||||
use ADC_EOC, ADC_JEOC, ADC_AWD
|
||||
This will set up the interrupt bit in the ADC as well as in the NVIC.
|
||||
added by bubulindo
|
||||
*/
|
||||
void adc_enable_irq(adc_dev* dev, uint8 interrupt) {//ADC1 for now.
|
||||
dev->regs->CR1 |= (1U<<(interrupt +ADC_CR1_EOCIE_BIT));
|
||||
nvic_irq_enable(dev->irq_num);
|
||||
}
|
||||
|
||||
/*
|
||||
attach interrupt functionality for ADC
|
||||
use ADC_EOC, ADC_JEOC, ADC_AWD
|
||||
added by bubulindo
|
||||
*/
|
||||
|
||||
void adc_attach_interrupt(adc_dev *dev,
|
||||
uint8 interrupt,
|
||||
voidFuncPtr handler) {
|
||||
dev->handlers[interrupt] = handler;
|
||||
adc_enable_irq(dev, interrupt);
|
||||
//enable_irq(dev, interrupt); //I need to create this function. to enable NVIC
|
||||
// nvic_irq_enable()
|
||||
}
|
||||
|
||||
/*
|
||||
* STM32F1 routines
|
||||
*/
|
||||
|
@ -73,7 +174,7 @@ const adc_dev *ADC3 = &adc3;
|
|||
*
|
||||
* @param dev adc device
|
||||
*/
|
||||
void adc_calibrate(const adc_dev *dev) {
|
||||
void adc_calibrate(adc_dev *dev) {
|
||||
__io uint32 *rstcal_bit = bb_perip(&(dev->regs->CR2), 3);
|
||||
__io uint32 *cal_bit = bb_perip(&(dev->regs->CR2), 2);
|
||||
|
||||
|
@ -94,7 +195,7 @@ void adc_set_prescaler(adc_prescaler pre) {
|
|||
rcc_set_prescaler(RCC_PRESCALER_ADC, (uint32)pre);
|
||||
}
|
||||
|
||||
void adc_foreach(void (*fn)(const adc_dev*)) {
|
||||
void adc_foreach(void (*fn)(adc_dev*)) {
|
||||
fn(ADC1);
|
||||
fn(ADC2);
|
||||
#if defined(STM32_HIGH_DENSITY) || defined(STM32_XL_DENSITY)
|
||||
|
@ -102,11 +203,11 @@ void adc_foreach(void (*fn)(const adc_dev*)) {
|
|||
#endif
|
||||
}
|
||||
|
||||
void adc_config_gpio(const adc_dev *ignored, gpio_dev *gdev, uint8 bit) {
|
||||
void adc_config_gpio(adc_dev *ignored, gpio_dev *gdev, uint8 bit) {
|
||||
gpio_set_mode(gdev, bit, GPIO_INPUT_ANALOG);
|
||||
}
|
||||
|
||||
void adc_enable_single_swstart(const adc_dev *dev) {
|
||||
void adc_enable_single_swstart(adc_dev *dev) {
|
||||
adc_init(dev);
|
||||
adc_set_extsel(dev, ADC_SWSTART);
|
||||
adc_set_exttrig(dev, 1);
|
||||
|
|
|
@ -38,6 +38,8 @@
|
|||
static void disable_channel(timer_dev *dev, uint8 channel);
|
||||
static void pwm_mode(timer_dev *dev, uint8 channel);
|
||||
static void output_compare_mode(timer_dev *dev, uint8 channel);
|
||||
static void encoder_mode(timer_dev *dev, uint8 channel) ;//CARLOS
|
||||
|
||||
|
||||
static inline void enable_irq(timer_dev *dev, timer_interrupt_id iid);
|
||||
|
||||
|
@ -230,6 +232,10 @@ void timer_set_mode(timer_dev *dev, uint8 channel, timer_mode mode) {
|
|||
case TIMER_OUTPUT_COMPARE:
|
||||
output_compare_mode(dev, channel);
|
||||
break;
|
||||
//added by CARLOS.
|
||||
case TIMER_ENCODER:
|
||||
encoder_mode(dev, channel); //find a way to pass all the needed stuff on the 8bit var
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -293,6 +299,13 @@ void timer_detach_interrupt(timer_dev *dev, uint8 interrupt) {
|
|||
dev->handlers[interrupt] = NULL;
|
||||
}
|
||||
|
||||
//CARLOS
|
||||
uint8 get_direction(timer_dev *dev){
|
||||
return *bb_perip(&(dev->regs).gen->CR1, TIMER_CR1_DIR_BIT);
|
||||
}
|
||||
|
||||
|
||||
|
||||
/*
|
||||
* Utilities
|
||||
*/
|
||||
|
@ -313,6 +326,31 @@ static void output_compare_mode(timer_dev *dev, uint8 channel) {
|
|||
timer_cc_enable(dev, channel);
|
||||
}
|
||||
|
||||
//added by CARLOS.
|
||||
static void encoder_mode(timer_dev *dev, uint8 channel) {
|
||||
|
||||
//prescaler.
|
||||
//(dev->regs).gen->PSC = 1;
|
||||
|
||||
//map inputs.
|
||||
(dev->regs).gen->CCMR1 = TIMER_CCMR1_CC1S_INPUT_TI1 | TIMER_CCMR1_CC2S_INPUT_TI2 | TIMER_CCMR1_IC2F | TIMER_CCMR1_IC1F ;
|
||||
|
||||
(dev->regs).gen->SMCR = TIMER_SMCR_SMS_ENCODER3; //choose encoder 3, counting on both edges.
|
||||
|
||||
//polarity
|
||||
//(dev->regs).gen->CCER = TIMER_CCER_CC1P; //to invert the counting, only one of the inputs should be inverted.
|
||||
|
||||
//set the interval used by the encoder.
|
||||
//timer_set_reload(dev, 1000);
|
||||
|
||||
// (dev->regs).gen->CR1 |=TIMER_CR1_UDIS_BIT;
|
||||
|
||||
//run timer
|
||||
timer_resume(dev);
|
||||
}
|
||||
|
||||
|
||||
|
||||
static void enable_adv_irq(timer_dev *dev, timer_interrupt_id id);
|
||||
static void enable_bas_gen_irq(timer_dev *dev);
|
||||
|
||||
|
|
|
@ -449,7 +449,7 @@ uint32 usb_cdcacm_rx(uint8* buf, uint32 len) {
|
|||
|
||||
/* If all bytes have been read, re-enable the RX endpoint, which
|
||||
* was set to NAK when the current batch of bytes was received. */
|
||||
if (n_unread_bytes <=0) {
|
||||
if (n_unread_bytes == 0) {
|
||||
usb_set_ep_rx_count(USB_CDCACM_RX_ENDP, USB_CDCACM_RX_EPSIZE);
|
||||
usb_set_ep_rx_stat(USB_CDCACM_RX_ENDP, USB_EP_STAT_RX_VALID);
|
||||
}
|
||||
|
@ -565,7 +565,7 @@ static void vcomDataRxCb(void) {
|
|||
|
||||
n_unread_bytes += ep_rx_size;
|
||||
|
||||
if ( n_unread_bytes<=0 ) {
|
||||
if ( n_unread_bytes == 0 ) {
|
||||
usb_set_ep_rx_count(USB_CDCACM_RX_ENDP, USB_CDCACM_RX_EPSIZE);
|
||||
usb_set_ep_rx_stat(USB_CDCACM_RX_ENDP, USB_EP_STAT_RX_VALID);
|
||||
}
|
||||
|
|
|
@ -31,9 +31,6 @@
|
|||
#define USB_StatusIn() Send0LengthData()
|
||||
#define USB_StatusOut() vSetEPRxStatus(EP_RX_VALID)
|
||||
|
||||
#define StatusInfo0 StatusInfo.bw.bb1 /* Reverse bb0 & bb1 */
|
||||
#define StatusInfo1 StatusInfo.bw.bb0
|
||||
|
||||
/* Private macro -------------------------------------------------------------*/
|
||||
/* Private variables ---------------------------------------------------------*/
|
||||
u16_u8 StatusInfo;
|
||||
|
@ -857,11 +854,11 @@ u8 Setup0_Process(void)
|
|||
pInformation->USBbmRequestType = *pBuf.b++; /* bmRequestType */
|
||||
pInformation->USBbRequest = *pBuf.b++; /* bRequest */
|
||||
pBuf.w++; /* word not accessed because of 32 bits addressing */
|
||||
pInformation->USBwValue = ByteSwap(*pBuf.w++); /* wValue */
|
||||
pInformation->USBwValue = *pBuf.w++; /* wValue in Little Endian */
|
||||
pBuf.w++; /* word not accessed because of 32 bits addressing */
|
||||
pInformation->USBwIndex = ByteSwap(*pBuf.w++); /* wIndex */
|
||||
pInformation->USBwIndex = *pBuf.w++; /* wIndex in Little Endian */
|
||||
pBuf.w++; /* word not accessed because of 32 bits addressing */
|
||||
pInformation->USBwLength = *pBuf.w; /* wLength */
|
||||
pInformation->USBwLength = *pBuf.w; /* wLength in Little Endian */
|
||||
}
|
||||
|
||||
pInformation->ControlState = SETTING_UP;
|
||||
|
|
|
@ -38,7 +38,7 @@
|
|||
* to INPUT_ANALOG. That's faster, but it does require some extra work
|
||||
* on the user's part. Not too much, we think ;). */
|
||||
uint16 analogRead(uint8 pin) {
|
||||
const adc_dev *dev = PIN_MAP[pin].adc_device;
|
||||
adc_dev *dev = PIN_MAP[pin].adc_device;
|
||||
if (dev == NULL) {
|
||||
return 0;
|
||||
}
|
||||
|
|
|
@ -51,7 +51,7 @@
|
|||
typedef struct stm32_pin_info {
|
||||
gpio_dev *gpio_device; /**< Maple pin's GPIO device */
|
||||
timer_dev *timer_device; /**< Pin's timer device, if any. */
|
||||
const adc_dev *adc_device; /**< ADC device, if any. */
|
||||
adc_dev *adc_device; /**< ADC device, if any. */
|
||||
uint8 gpio_bit; /**< Pin's GPIO port bit. */
|
||||
uint8 timer_channel; /**< Timer channel, or 0 if none. */
|
||||
uint8 adc_channel; /**< Pin ADC channel, or ADCx if none. */
|
||||
|
|
|
@ -0,0 +1,73 @@
|
|||
/*
|
||||
This example shows how to use the ADC library to continuously sample
|
||||
several channels/pins.
|
||||
The acquisition of the channels is done using DMA in circular mode.
|
||||
|
||||
*/
|
||||
#include <STM32ADC.h>
|
||||
|
||||
|
||||
STM32ADC myADC(ADC1);
|
||||
|
||||
#define BOARD_LED D33 //this is for Maple Mini
|
||||
|
||||
//Channels to be acquired.
|
||||
uint8 pins[] = {11,10,9,8,7,6,5,4};
|
||||
|
||||
|
||||
const int maxSamples = 8; // 8 channels
|
||||
|
||||
// Array for the ADC data
|
||||
uint16_t dataPoints[maxSamples];
|
||||
|
||||
void setup() {
|
||||
Serial.begin(19200);
|
||||
pinMode(BOARD_LED, OUTPUT);
|
||||
pinMode(D32, INPUT);
|
||||
//startup blink... good idea from Pig-O-Scope
|
||||
digitalWrite(BOARD_LED, HIGH);
|
||||
delay(1000);
|
||||
digitalWrite(BOARD_LED, LOW);
|
||||
delay(1000);
|
||||
|
||||
//calibrate ADC
|
||||
myADC.calibrate();
|
||||
|
||||
// Set up our analog pin(s)
|
||||
for (unsigned int j = 0; j <8; j++)
|
||||
pinMode(pins[j], INPUT_ANALOG);
|
||||
|
||||
myADC.setSampleRate(ADC_SMPR_1_5);//set the Sample Rate
|
||||
myADC.setScanMode(); //set the ADC in Scan mode.
|
||||
myADC.setPins(pins, 8); //set how many and which pins to convert.
|
||||
myADC.setContinuous(); //set the ADC in continuous mode.
|
||||
|
||||
//set the DMA transfer for the ADC.
|
||||
//in this case we want to increment the memory side and run it in circular mode
|
||||
//By doing this, we can read the last value sampled from the channels by reading the dataPoints array
|
||||
myADC.setDMA(dataPoints, 8, (DMA_MINC_MODE | DMA_CIRC_MODE), NULL);
|
||||
|
||||
//start the conversion.
|
||||
//because the ADC is set as continuous mode and in circular fashion, this can be done
|
||||
//on setup().
|
||||
myADC.startConversion();
|
||||
|
||||
|
||||
}
|
||||
|
||||
void loop(){
|
||||
//send the latest data acquired when the button is pushed.
|
||||
if(digitalRead(D32) == 1 ) {
|
||||
Serial.println("begin");
|
||||
// Take our samples
|
||||
|
||||
for(unsigned int i = 0; i < maxSamples; i ++) {
|
||||
Serial.print("sample[");
|
||||
Serial.print(i);
|
||||
Serial.print("] = ");
|
||||
Serial.println(dataPoints[i]);
|
||||
}
|
||||
while(digitalRead(D32) == 1); //stay here.
|
||||
}
|
||||
}; //end loop
|
||||
|
|
@ -0,0 +1,66 @@
|
|||
/*
|
||||
This example shows how to use the ADC library to sample several
|
||||
channels/pins in one go.
|
||||
This example attaches an interrupt to the DMA completion to notify the user.
|
||||
The DMA must be set together with the start conversion, so both setDMA and startConversion
|
||||
Must be called.
|
||||
|
||||
*/
|
||||
#include <STM32ADC.h>
|
||||
|
||||
#define BOARD_LED D33 //PB0
|
||||
|
||||
uint8 pins[] = {11,10,9,8,7,6,5,4};
|
||||
|
||||
const int maxSamples = 8; // 8 channels
|
||||
|
||||
// Array for the ADC data
|
||||
uint16 dataPoints[maxSamples];
|
||||
|
||||
volatile static bool dma1_ch1_Active; //flag for interrupt
|
||||
|
||||
STM32ADC myADC(ADC1);
|
||||
|
||||
void setup() {
|
||||
//start Serial
|
||||
Serial.begin(19200);
|
||||
//Start up blink from Pig-O-Scope
|
||||
pinMode(BOARD_LED, OUTPUT);
|
||||
pinMode(D32, INPUT);
|
||||
digitalWrite(BOARD_LED, HIGH);
|
||||
delay(1000);
|
||||
digitalWrite(BOARD_LED, LOW);
|
||||
delay(1000);
|
||||
//calibrate ADC.
|
||||
myADC.calibrate();
|
||||
|
||||
myADC.setSampleRate(ADC_SMPR_1_5); //sample ratio
|
||||
myADC.setPins(pins, maxSamples); //pins to be converted
|
||||
myADC.setScanMode(); //Set the ADC in Scan Mode
|
||||
}
|
||||
|
||||
void loop(){
|
||||
//start acquisition on button push.
|
||||
if(digitalRead(D32) == 1 ) {
|
||||
Serial.println("begin");
|
||||
dma1_ch1_Active = 1;
|
||||
myADC.setDMA(dataPoints, 8, (DMA_MINC_MODE | DMA_TRNS_CMPLT), DMA1_CH1_Event);
|
||||
myADC.startConversion();
|
||||
while (dma1_ch1_Active == 1); //wait for DMA to complete.
|
||||
|
||||
for(unsigned int i = 0; i < maxSamples; i ++) {
|
||||
Serial.print("sample[");
|
||||
Serial.print(i);
|
||||
Serial.print("] = ");
|
||||
Serial.println(dataPoints[i]);
|
||||
}
|
||||
while(digitalRead(D32) == 1); //stay here. Another button push is required.
|
||||
}
|
||||
}; //end loop
|
||||
|
||||
/*
|
||||
Interrupt handler. eh eh
|
||||
*/
|
||||
static void DMA1_CH1_Event() {
|
||||
dma1_ch1_Active = 0;
|
||||
}
|
|
@ -0,0 +1,17 @@
|
|||
/*
|
||||
This example shows how to use the ADC library to continuously sample
|
||||
one channel/pin.
|
||||
|
||||
*/
|
||||
#include <STM32ADC.h>
|
||||
|
||||
ADC myAdc(ADC1);
|
||||
|
||||
void setup() {
|
||||
Serial.begin(19200);
|
||||
|
||||
}
|
||||
|
||||
void loop(){
|
||||
|
||||
}; //end loop
|
|
@ -0,0 +1,25 @@
|
|||
/*
|
||||
This example shows how to use the ADC library sample
|
||||
one channels/pin at a time.
|
||||
A bit like analogRead, but with the possibility of having an interrupt.
|
||||
*/
|
||||
#include <STM32ADC.h>
|
||||
|
||||
ADC myAdc(ADC1);
|
||||
uint8 pin[] = {D11};
|
||||
|
||||
|
||||
void int_func() {
|
||||
Serial.println(adc_result);
|
||||
};
|
||||
|
||||
void setup() {
|
||||
Serial.begin(19200);
|
||||
myADC.setTrigger(ADC_EXT_EV_SWSTART);//start on SWStart bit
|
||||
myADC.setChannels(pin, 1); //this is actually the pin you want to measure
|
||||
myADC.attachADCInterrupt(int_func);
|
||||
}; //end setup
|
||||
|
||||
void loop(){
|
||||
|
||||
}; //end loop
|
|
@ -0,0 +1,50 @@
|
|||
#include <STM32ADC.h>
|
||||
|
||||
STM32ADC myADC(ADC1);
|
||||
|
||||
uint8 pin = D7;
|
||||
|
||||
#define BOARD_LED D33 //this is for Maple Mini
|
||||
volatile static bool triggered = 0;
|
||||
uint32 dado_adc = 0;
|
||||
|
||||
|
||||
void int_func() {
|
||||
|
||||
triggered = 1;
|
||||
dado_adc = myADC.getData();
|
||||
}
|
||||
|
||||
|
||||
|
||||
void setup() {
|
||||
Serial.begin(19200);
|
||||
pinMode(BOARD_LED, OUTPUT);
|
||||
pinMode(D32, INPUT);
|
||||
pinMode(D11, INPUT_ANALOG);//AD pin.
|
||||
//startup blink... good idea from Pig-O-Scope
|
||||
digitalWrite(BOARD_LED, HIGH);
|
||||
delay(1000);
|
||||
digitalWrite(BOARD_LED, LOW);
|
||||
delay(1000);
|
||||
myADC.calibrate();
|
||||
myADC.setSampleRate(ADC_SMPR_1_5);
|
||||
myADC.attachInterrupt(int_func, ADC_EOC);
|
||||
myADC.setPins(&pin, 1);
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
||||
void loop() {
|
||||
if(digitalRead(D32) == 1 ) {
|
||||
Serial.println("begin");
|
||||
// Take our samples
|
||||
myADC.startConversion();
|
||||
while (triggered == 0); //wait here...
|
||||
|
||||
Serial.print("Readin: ");
|
||||
Serial.println(dado_adc);
|
||||
}
|
||||
|
||||
}
|
|
@ -0,0 +1,42 @@
|
|||
#######################################
|
||||
# Syntax Coloring Map RTClock
|
||||
#######################################
|
||||
|
||||
#######################################
|
||||
# Datatypes (KEYWORD1)
|
||||
#######################################
|
||||
Encoder KEYWORD1
|
||||
|
||||
|
||||
start KEYWORD2
|
||||
stop KEYWORD2
|
||||
|
||||
resetCounts KEYWORD2
|
||||
value KEYWORD2
|
||||
getTurns KEYWORD2
|
||||
reset KEYWORD2
|
||||
getAngle KEYWORD2
|
||||
getDirection KEYWORD2
|
||||
Polarity KEYWORD2
|
||||
setPrescaler KEYWORD2
|
||||
getPrescaler KEYWORD2
|
||||
setPPR KEYWORD2
|
||||
getPPR KEYWORD2
|
||||
attachInterrupt KEYWORD2
|
||||
detachInterrupt KEYWORD2
|
||||
setFilter KEYWORD2
|
||||
|
||||
#######################################
|
||||
# Constants (LITERAL1)
|
||||
#######################################
|
||||
|
||||
COUNT_CH2 LITERAL1
|
||||
COUNT_CH1 LITERAL1
|
||||
COUNT_BOTH_CHANNELS LITERAL1
|
||||
RADIANS LITERAL1
|
||||
GRADES LITERAL1
|
||||
DEGREES LITERAL1
|
||||
NORMAL LITERAL1
|
||||
INVERTED LITERAL1
|
||||
POSITIVE LITERAL1
|
||||
NEGATIVE LITERAL1
|
|
@ -0,0 +1,10 @@
|
|||
name=STM32ADC
|
||||
version=1.0
|
||||
author=Cardoso
|
||||
email=
|
||||
sentence=Analog to Digital Converter Driver
|
||||
paragraph=ADC for STM32F1
|
||||
url=
|
||||
architectures=STM32F1
|
||||
maintainer=
|
||||
category=Timing
|
|
@ -0,0 +1,232 @@
|
|||
#include "STM32ADC.h"
|
||||
#include "boards.h"
|
||||
|
||||
|
||||
/*
|
||||
Constructor
|
||||
Choose which ADC to use.
|
||||
Start it up...
|
||||
*/
|
||||
STM32ADC::STM32ADC (adc_dev * dev){
|
||||
_dev = dev;
|
||||
//adc_calibrate(_dev);//get this out of the way.
|
||||
|
||||
}
|
||||
|
||||
uint32 STM32ADC::getData() {
|
||||
return _dev->regs->DR;
|
||||
};
|
||||
|
||||
|
||||
/*
|
||||
Set the ADC Sampling Rate.
|
||||
ADC_SMPR_1_5, < 1.5 ADC cycles
|
||||
ADC_SMPR_7_5, < 7.5 ADC cycles
|
||||
ADC_SMPR_13_5, < 13.5 ADC cycles
|
||||
ADC_SMPR_28_5, < 28.5 ADC cycles
|
||||
ADC_SMPR_41_5, < 41.5 ADC cycles
|
||||
ADC_SMPR_55_5, < 55.5 ADC cycles
|
||||
ADC_SMPR_71_5, < 71.5 ADC cycles
|
||||
ADC_SMPR_239_5, < 239.5 ADC cycles
|
||||
*/
|
||||
void STM32ADC::setSampleRate(adc_smp_rate SampleRate){
|
||||
adc_set_sample_rate(_dev, SampleRate);
|
||||
}
|
||||
|
||||
/*
|
||||
Attach an interrupt to the ADC completion.
|
||||
*/
|
||||
void STM32ADC::attachInterrupt(voidFuncPtr func, uint8 interrupt){
|
||||
adc_attach_interrupt(_dev,interrupt, func);
|
||||
}
|
||||
|
||||
/*
|
||||
This will enable the internal readings. Vcc and Temperature
|
||||
*/
|
||||
void STM32ADC::enableInternalReading(){
|
||||
enable_internal_reading(_dev);
|
||||
}
|
||||
|
||||
/*
|
||||
This will read the Vcc and return something useful.
|
||||
Polling is being used.
|
||||
*/
|
||||
float STM32ADC::readVcc(){
|
||||
unsigned int result = 0;
|
||||
float vcc = 0.0;
|
||||
result = adc_read(_dev, 17);
|
||||
|
||||
vcc = (float)result * 1.1; //to be done later...
|
||||
return vcc;
|
||||
}
|
||||
|
||||
/*
|
||||
This will read the Temperature and return something useful.
|
||||
Polling is being used.
|
||||
*/
|
||||
float STM32ADC::readTemp(){
|
||||
unsigned int result = 0;
|
||||
float temperature = 0.0;
|
||||
result = adc_read(_dev, 16);
|
||||
temperature = (float)((_V25-result)/_AverageSlope)+ 25.0;
|
||||
return temperature;
|
||||
}
|
||||
|
||||
/*
|
||||
This function will set the number of Pins to sample and which PINS to convert.
|
||||
This uses the Maple Pin numbers and not the ADC channel numbers. Do not confuse.
|
||||
*/
|
||||
void STM32ADC::setPins(uint8 *pins, uint8 length){
|
||||
//convert pins to channels.
|
||||
uint8 channels[length];
|
||||
unsigned int records[3] = {0,0,0};
|
||||
unsigned char i = 0, j = 0;
|
||||
|
||||
for (unsigned char i = 0; i < length; i++) { //convert the channels from pins to ch.
|
||||
channels[i] = PIN_MAP[pins[i]].adc_channel;
|
||||
}
|
||||
|
||||
//run away protection
|
||||
if (length > 16) length = 16;
|
||||
|
||||
//write the length
|
||||
records[2] |= (length - 1) << 20;
|
||||
|
||||
//i goes through records, j goes through variables.
|
||||
for (i = 0, j = 0; i < length; i++) {//go through the channel list.
|
||||
if (i!=0 && i%6 == 0) j++;//next variable, please!!
|
||||
records[j] |= (channels[i] << ((i%6)*5));
|
||||
}
|
||||
//update the registers inside with the scan sequence.
|
||||
_dev->regs->SQR1 = records[2];
|
||||
_dev->regs->SQR2 = records[1];
|
||||
_dev->regs->SQR3 = records[0];
|
||||
}
|
||||
|
||||
/*
|
||||
This function will set the number of channels to convert
|
||||
And which channels.
|
||||
This is the ADC channels and not the Maple Pins!!! Important!!
|
||||
Also, this will allow you to sample the AD and Vref channels.
|
||||
*/
|
||||
void STM32ADC::setChannels(uint8 *channels, uint8 length){
|
||||
adc_set_reg_seq_channel(_dev, channels, length);
|
||||
}
|
||||
|
||||
/*
|
||||
This function will set the trigger to start the conversion
|
||||
Timer, SWStart, etc...
|
||||
*/
|
||||
void STM32ADC::setTrigger(adc_extsel_event trigger){
|
||||
adc_set_extsel(_dev, trigger);
|
||||
}
|
||||
|
||||
/*
|
||||
this function will set the continuous conversion bit.
|
||||
*/
|
||||
void STM32ADC::setContinuous(){
|
||||
_dev->regs->CR2 |= ADC_CR2_CONT;
|
||||
};
|
||||
|
||||
/*
|
||||
this function will reset the continuous bit.
|
||||
*/
|
||||
void STM32ADC::resetContinuous(){
|
||||
_dev->regs->CR2 &= ~ADC_CR2_CONT;
|
||||
};
|
||||
|
||||
/*
|
||||
This will be used to start conversions
|
||||
*/
|
||||
void STM32ADC::startConversion(){
|
||||
_dev->regs->CR2 |= ADC_CR2_SWSTART;
|
||||
}
|
||||
|
||||
/*
|
||||
This will set the Scan Mode on.
|
||||
This will use DMA.
|
||||
*/
|
||||
void STM32ADC::setScanMode(){
|
||||
_dev->regs->CR1 |= ADC_CR1_SCAN;
|
||||
}
|
||||
|
||||
void STM32ADC::calibrate() {
|
||||
adc_calibrate(_dev);
|
||||
}
|
||||
|
||||
/*
|
||||
This function is used to setup DMA with the ADC.
|
||||
It will be independent of the mode used. It will either be used in continuous or scan mode
|
||||
or even both... go figure. :)
|
||||
|
||||
The reason why this is a uint16 is that I am not ready for dual mode.
|
||||
*/
|
||||
|
||||
void STM32ADC::setDMA(uint16 * Buf, uint16 BufLen, uint32 dmaFlags, voidFuncPtr func) {
|
||||
//initialize DMA
|
||||
dma_init(DMA1);
|
||||
//if there is an int handler to be called...
|
||||
if (func != NULL)
|
||||
dma_attach_interrupt(DMA1, DMA_CH1, func);
|
||||
//enable ADC DMA transfer
|
||||
//adc_dma_enable(ADC1);
|
||||
_dev->regs->CR2 |= ADC_CR2_DMA;
|
||||
//set it up...
|
||||
dma_setup_transfer(DMA1, DMA_CH1, &ADC1->regs->DR, DMA_SIZE_16BITS, Buf, DMA_SIZE_16BITS, dmaFlags);// Receive buffer DMA
|
||||
//how many are we making??
|
||||
dma_set_num_transfers(DMA1, DMA_CH1, BufLen);
|
||||
//enable dma.
|
||||
dma_enable(DMA1, DMA_CH1); // Enable the channel and start the transfer.
|
||||
}
|
||||
|
||||
/*
|
||||
This function is used to setup DMA with the ADC.
|
||||
It will be independent of the mode used. It will either be used in continuous or scan mode
|
||||
or even both...
|
||||
This function is to be used with Dual ADC (the difference is to use 32bit buffers).
|
||||
*/
|
||||
void STM32ADC::setDualDMA(uint32 * Buf, uint16 BufLen, uint32 Flags){
|
||||
dma_init(DMA1);
|
||||
adc_dma_enable(_dev);
|
||||
dma_setup_transfer(DMA1, DMA_CH1, &_dev->regs->DR, DMA_SIZE_32BITS,//(DMA_MINC_MODE | DMA_CIRC_MODE)
|
||||
Buf, DMA_SIZE_32BITS, Flags);// Receive buffer DMA
|
||||
dma_set_num_transfers(DMA1, DMA_CH1, BufLen);
|
||||
dma_enable(DMA1, DMA_CH1); // Enable the channel and start the transfer.
|
||||
}
|
||||
|
||||
/*
|
||||
This will set the Scan Mode on.
|
||||
This will use DMA.
|
||||
*/
|
||||
void STM32ADC::attachDMAInterrupt(voidFuncPtr func){
|
||||
_DMA_int = func;
|
||||
dma_attach_interrupt(DMA1, DMA_CH1, func);
|
||||
}
|
||||
|
||||
/*
|
||||
This will set an Analog Watchdog on a channel.
|
||||
It must be used with a channel that is being converted.
|
||||
*/
|
||||
void STM32ADC::setAnalogWatchdog(uint8 channel, uint32 HighLimit, uint32 LowLimit){
|
||||
set_awd_low_limit(_dev, LowLimit);
|
||||
set_awd_high_limit(_dev, HighLimit);
|
||||
set_awd_channel(_dev, channel);
|
||||
}
|
||||
|
||||
/*
|
||||
check analog watchdog
|
||||
Poll the status on the watchdog. This will return and reset the bit.
|
||||
*/
|
||||
uint8 STM32ADC::getAnalogWatchdog(){
|
||||
return 1;
|
||||
}
|
||||
|
||||
/*
|
||||
Attach an interrupt to the Watchdog...
|
||||
This can possibly be set together in one function and determine which peripheral
|
||||
it relates to.
|
||||
*/
|
||||
void STM32ADC::attachAnalogWatchdogInterrupt(voidFuncPtr func){
|
||||
_AWD_int = func;
|
||||
|
||||
}
|
|
@ -0,0 +1,158 @@
|
|||
#include "utility/util_adc.h"
|
||||
#include "libmaple/dma.h"
|
||||
|
||||
|
||||
class STM32ADC{
|
||||
|
||||
public:
|
||||
|
||||
/*
|
||||
Constructor
|
||||
Choose which ADC to use.
|
||||
Start it up...
|
||||
*/
|
||||
STM32ADC (adc_dev * dev);
|
||||
|
||||
/*
|
||||
Set the ADC Sampling Rate.
|
||||
*/
|
||||
void setSampleRate(adc_smp_rate SampleRate);
|
||||
|
||||
/*
|
||||
Attach an interrupt to the ADC completion.
|
||||
*/
|
||||
void attachInterrupt(voidFuncPtr func, uint8 interrupt);
|
||||
|
||||
void calibrate();
|
||||
|
||||
/*
|
||||
This function is used to setup DMA with the ADC.
|
||||
It will be independent of the mode used. It will either be used in continuous or scan mode
|
||||
or even both... go figure. :)
|
||||
|
||||
The reason why this is a uint16 is that I am not ready for dual mode.
|
||||
*/
|
||||
void setDMA(uint16 * Buf, uint16 BufLen, uint32 dmaFlags, voidFuncPtr func);
|
||||
|
||||
/*
|
||||
This function is used to setup DMA with the ADC.
|
||||
It will be independent of the mode used. It will either be used in continuous or scan mode
|
||||
or even both...
|
||||
This function is to be used with Dual ADC (the difference is to use 32bit buffers).
|
||||
*/
|
||||
void setDualDMA(uint32 * Buf, uint16 BufLen, uint32 Flags);
|
||||
|
||||
/*
|
||||
This will enable the internal readings. Vcc and Temperature
|
||||
*/
|
||||
void enableInternalReading();
|
||||
|
||||
/*
|
||||
This will read the Vcc and return something useful.
|
||||
Polling is being used.
|
||||
*/
|
||||
float readVcc();
|
||||
|
||||
/*
|
||||
This will read the Temperature and return something useful.
|
||||
Polling is being used.
|
||||
*/
|
||||
float readTemp();
|
||||
|
||||
/*
|
||||
This function will set the number of channels to convert
|
||||
And which channels.
|
||||
For pin numbers, see setPins below
|
||||
*/
|
||||
void setChannels(uint8 *pins, uint8 length);
|
||||
|
||||
/*
|
||||
This function will set the number of pins to convert
|
||||
And which pins.
|
||||
*/
|
||||
void setPins(uint8 *pins, uint8 length);
|
||||
|
||||
/*
|
||||
This function will set the trigger to start the conversion
|
||||
Timer, SWStart, etc...
|
||||
Possible triggers:
|
||||
|
||||
ADC_EXT_EV_TIM1_CC1
|
||||
ADC_EXT_EV_TIM1_CC2
|
||||
ADC_EXT_EV_TIM2_CC2
|
||||
ADC_EXT_EV_TIM3_TRGO
|
||||
ADC_EXT_EV_TIM4_CC4
|
||||
ADC_EXT_EV_EXTI11
|
||||
ADC_EXT_EV_TIM1_CC3
|
||||
ADC_EXT_EV_SWSTART
|
||||
ADC_EXT_EV_TIM3_CC1
|
||||
ADC_EXT_EV_TIM2_CC3
|
||||
ADC_EXT_EV_TIM8_CC1
|
||||
ADC_EXT_EV_ADC3_TIM8_TRGO
|
||||
ADC_EXT_EV_TIM5_CC1
|
||||
ADC_EXT_EV_ADC12_TIM8_TRGO
|
||||
ADC_EXT_EV_TIM5_CC3
|
||||
*/
|
||||
void setTrigger(adc_extsel_event trigger);
|
||||
|
||||
/*
|
||||
this function will set the continuous conversion bit.
|
||||
*/
|
||||
void setContinuous();
|
||||
|
||||
/*
|
||||
this function will reset the continuous bit.
|
||||
*/
|
||||
void resetContinuous();
|
||||
|
||||
/*
|
||||
This will be used to start conversions
|
||||
*/
|
||||
void startConversion();
|
||||
|
||||
/*
|
||||
This will set the Scan Mode on.
|
||||
This will use DMA.
|
||||
*/
|
||||
void setScanMode();
|
||||
|
||||
/*
|
||||
This will set the Scan Mode on.
|
||||
This will use DMA.
|
||||
*/
|
||||
void attachDMAInterrupt(voidFuncPtr func);
|
||||
|
||||
/*
|
||||
This will set an Analog Watchdog on a channel.
|
||||
It must be used with a channel that is being converted.
|
||||
*/
|
||||
void setAnalogWatchdog(uint8 channel, uint32 HighLimit, uint32 LowLimit);
|
||||
|
||||
/*
|
||||
check analog watchdog
|
||||
Poll the status on the watchdog. This will return and reset the bit.
|
||||
*/
|
||||
uint8 getAnalogWatchdog();
|
||||
|
||||
/*
|
||||
Attach an interrupt to the Watchdog...
|
||||
This can possibly be set together in one function and determine which peripheral
|
||||
it relates to.
|
||||
*/
|
||||
void attachAnalogWatchdogInterrupt(voidFuncPtr func);
|
||||
|
||||
/*
|
||||
Retrieve the contents of the DR register.
|
||||
*/
|
||||
uint32 getData();
|
||||
|
||||
private:
|
||||
|
||||
adc_dev * _dev;
|
||||
voidFuncPtr _DMA_int;
|
||||
voidFuncPtr _ADC_int;
|
||||
voidFuncPtr _AWD_int;
|
||||
static const float _AverageSlope = 4.3; // mV/oC //4.0 to 4.6
|
||||
static const float _V25 = 1.43; //Volts //1.34 - 1.52
|
||||
|
||||
};
|
|
@ -0,0 +1,205 @@
|
|||
#include "util_adc.h"
|
||||
#include<libmaple/nvic.h>
|
||||
//#include "boards.h"
|
||||
#include <libmaple/dma.h>
|
||||
|
||||
/*
|
||||
Interrupt function.
|
||||
This handles Analog watchdog and ADC1 and 2.
|
||||
*/
|
||||
extern volatile unsigned int adc_result = 0;
|
||||
|
||||
/*
|
||||
Starts a single conversion in one channel previously defined.
|
||||
Results must be read through interrupt or polled outside this function.
|
||||
*/
|
||||
void start_single_convert(adc_dev* dev, uint8 channel) {
|
||||
// int pinMapADCin = PIN_MAP[analogInPin].adc_channel;
|
||||
adc_set_reg_seqlen(dev, 1);
|
||||
dev->regs->SQR3 = channel;//use channels next time.
|
||||
dev->regs->CR2 |= ADC_CR2_SWSTART;
|
||||
}
|
||||
|
||||
/*
|
||||
Starts the continuous mode on one channel of the AD.
|
||||
Results must be read through interrupt or polled outside this function.
|
||||
*/
|
||||
void start_continuous_convert(adc_dev* dev, uint8 channel){
|
||||
// int pinMapADCin = PIN_MAP[analogInPin].adc_channel;
|
||||
adc_set_reg_seqlen(dev, 1);
|
||||
dev->regs->SQR3 = channel;
|
||||
dev->regs->CR2 |= ADC_CR2_CONT;
|
||||
dev->regs->CR2 |= ADC_CR2_SWSTART;
|
||||
}
|
||||
|
||||
/*
|
||||
Enable end of conversion interrupt on the ADC.
|
||||
This is for regular conversion, not injected.
|
||||
*/
|
||||
void enable_adc_irq(adc_dev* dev) {//ADC1 for now.
|
||||
dev->regs->CR1 |= (1U<<ADC_CR1_EOCIE_BIT);
|
||||
nvic_irq_enable(NVIC_ADC_1_2 );
|
||||
}
|
||||
|
||||
/*
|
||||
Enable the reading of the internal variables (Temperature and Vref).
|
||||
*/
|
||||
void enable_internal_reading(adc_dev *dev) {
|
||||
dev->regs->CR2 |= ADC_CR2_TSEREFE;
|
||||
}
|
||||
|
||||
/*
|
||||
Read internal variables.
|
||||
Channels are:
|
||||
16 - Temperature
|
||||
17 - VrefInt
|
||||
Results must be read through interrupt or polled outside this function.
|
||||
*/
|
||||
void internalRead(adc_dev *dev, uint8 channel) {
|
||||
adc_reg_map *regs = dev->regs;
|
||||
adc_set_reg_seqlen(dev, 1);
|
||||
regs->SQR3 = channel;
|
||||
regs->CR2 |= ADC_CR2_SWSTART;
|
||||
}
|
||||
|
||||
/*
|
||||
Enable the Analog Watchdog interrupt
|
||||
*/
|
||||
void enable_awd_irq(adc_dev * dev){
|
||||
dev->regs->CR1 |= (1U<<ADC_CR1_AWDIE_BIT);
|
||||
nvic_irq_enable(NVIC_ADC_1_2 );
|
||||
}
|
||||
|
||||
/*
|
||||
Set Analog Watchdog Low Limit.
|
||||
Results must be read through interrupt or polled outside this function.
|
||||
*/
|
||||
void set_awd_low_limit(adc_dev * dev, uint32 limit) {
|
||||
dev->regs->LTR = limit;
|
||||
}
|
||||
|
||||
/*
|
||||
Set Analog Watchdog High Limit.
|
||||
Results must be read through interrupt or polled outside this function.
|
||||
*/
|
||||
void set_awd_high_limit(adc_dev * dev, uint32 limit) {
|
||||
dev->regs->HTR = limit;
|
||||
}
|
||||
|
||||
/*
|
||||
Enable the Watchdog function on the ADC.
|
||||
*/
|
||||
void set_awd_channel(adc_dev * dev, uint8 awd_channel){
|
||||
dev->regs->CR1 |= (awd_channel & ADC_CR1_AWDCH);
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
Enable the Watchdog function on the ADC.
|
||||
*/
|
||||
void enable_awd(adc_dev * dev){
|
||||
dev->regs->CR1 |= ADC_CR1_AWDEN;
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
Used to configure the sequence and length of the scan mode.
|
||||
Can be used instead of adc_set_reg_seqlen() as it sets both information
|
||||
The channels are not the pin numbers, but ADC channels.
|
||||
*/
|
||||
void adc_set_reg_seq_channel(adc_dev * dev, unsigned char *channels, unsigned char len){
|
||||
|
||||
unsigned int records[3] = {0,0,0};
|
||||
unsigned char i = 0, j = 0;
|
||||
//run away protection
|
||||
if (len > 16) len = 16;
|
||||
|
||||
//write the length
|
||||
records[2] |= (len - 1) << 20;
|
||||
|
||||
//i goes through records, j goes through variables.
|
||||
for (i = 0, j = 0; i < len; i++) {//go through the channel list.
|
||||
if (i!=0 && i%6 == 0) j++;//next variable, please!!
|
||||
records[j] |= (channels[i] << ((i%6)*5));
|
||||
}
|
||||
//update the registers inside with the scan sequence.
|
||||
dev->regs->SQR1 = records[2];
|
||||
dev->regs->SQR2 = records[1];
|
||||
dev->regs->SQR3 = records[0];
|
||||
};
|
||||
|
||||
void adc_dma_disable(adc_dev * dev) {
|
||||
bb_peri_set_bit(&dev->regs->CR2, ADC_CR2_DMA_BIT, 0);
|
||||
}
|
||||
|
||||
|
||||
void adc_dma_enable(adc_dev * dev) {
|
||||
bb_peri_set_bit(&dev->regs->CR2, ADC_CR2_DMA_BIT, 1);
|
||||
}
|
||||
|
||||
uint8 poll_adc_convert(adc_dev *dev) {
|
||||
return bb_peri_get_bit(dev->regs->SR, ADC_SR_EOC_BIT);
|
||||
}
|
||||
|
||||
|
||||
|
||||
//uint8 maxSamples = 32;
|
||||
//uint32_t dataPoints32[maxSamples / 2];
|
||||
//uint16_t *dataPoints = (uint16_t *)&dataPoints32;
|
||||
|
||||
/*
|
||||
//fast interleaved mode
|
||||
void setADCs (uint8 analogInPin)
|
||||
{
|
||||
// const adc_dev *dev = PIN_MAP[analogInPin].adc_device;
|
||||
int pinMapADCin = PIN_MAP[analogInPin].adc_channel;
|
||||
adc_set_sample_rate(ADC1, ADC_SMPR_1_5); //=0,58uS/sample. ADC_SMPR_13_5 = 1.08uS - use this one if Rin>10Kohm,
|
||||
adc_set_sample_rate(ADC2, ADC_SMPR_1_5); // if not may get some sporadic noise. see datasheet.
|
||||
|
||||
// adc_reg_map *regs = dev->regs;
|
||||
adc_set_reg_seqlen(ADC1, 1);
|
||||
ADC1->regs->SQR3 = pinMapADCin;
|
||||
ADC1->regs->CR2 |= ADC_CR2_CONT; // | ADC_CR2_DMA; // Set continuous mode and DMA
|
||||
ADC1->regs->CR1 |= ADC_CR1_FASTINT; // Interleaved mode
|
||||
ADC1->regs->CR2 |= ADC_CR2_SWSTART;
|
||||
|
||||
ADC2->regs->CR2 |= ADC_CR2_CONT; // ADC 2 continuos
|
||||
ADC2->regs->SQR3 = pinMapADCin;
|
||||
}
|
||||
*/
|
||||
|
||||
/*
|
||||
This is run inside the loop() function.
|
||||
It stays active and polls for the end of the transfer.
|
||||
|
||||
*/
|
||||
|
||||
|
||||
/*
|
||||
void takeSamples ()
|
||||
{
|
||||
// This loop uses dual interleaved mode to get the best performance out of the ADCs
|
||||
//
|
||||
unsigned long samplingTime=0;
|
||||
dma_init(DMA1);
|
||||
dma_attach_interrupt(DMA1, DMA_CH1, DMA1_CH1_Event);
|
||||
|
||||
adc_dma_enable(ADC1);
|
||||
dma_setup_transfer(DMA1, DMA_CH1, &ADC1->regs->DR, DMA_SIZE_32BITS,
|
||||
dataPoints32, DMA_SIZE_32BITS, (DMA_MINC_MODE | DMA_TRNS_CMPLT));// Receive buffer DMA
|
||||
dma_set_num_transfers(DMA1, DMA_CH1, maxSamples / 2);
|
||||
dma1_ch1_Active = 1;
|
||||
// regs->CR2 |= ADC_CR2_SWSTART; //moved to setADC
|
||||
dma_enable(DMA1, DMA_CH1); // Enable the channel and start the transfer.
|
||||
//adc_calibrate(ADC1);
|
||||
//adc_calibrate(ADC2);
|
||||
samplingTime = micros();
|
||||
while (dma1_ch1_Active);
|
||||
samplingTime = (micros() - samplingTime);
|
||||
|
||||
dma_disable(DMA1, DMA_CH1); //End of trasfer, disable DMA and Continuous mode.
|
||||
// regs->CR2 &= ~ADC_CR2_CONT;
|
||||
|
||||
}
|
||||
|
||||
*/
|
|
@ -0,0 +1,30 @@
|
|||
#include <libmaple/adc.h>
|
||||
|
||||
|
||||
void start_single_convert(adc_dev* dev, uint8 channel);
|
||||
|
||||
void start_continuous_convert(adc_dev* dev, uint8 channel);
|
||||
|
||||
void enable_adc_irq(adc_dev* dev);
|
||||
|
||||
void enable_internal_reading(adc_dev *dev);
|
||||
|
||||
void internalRead(adc_dev *dev, uint8 channel);
|
||||
|
||||
void enable_awd_irq( adc_dev * dev);
|
||||
|
||||
void set_awd_low_limit( adc_dev * dev, uint32 limit);
|
||||
|
||||
void set_awd_high_limit( adc_dev * dev, uint32 limit);
|
||||
|
||||
void enable_awd( adc_dev * dev);
|
||||
|
||||
void set_awd_channel( adc_dev * dev, uint8 awd_channel);
|
||||
|
||||
void adc_set_reg_seq_channel( adc_dev * dev, unsigned char *channels, unsigned char len);
|
||||
|
||||
void set_continuous( adc_dev * dev);
|
||||
|
||||
uint8 poll_adc_convert(adc_dev *dev);
|
||||
|
||||
void adc_dma_enable(adc_dev * dev);
|
|
@ -149,4 +149,15 @@ tools.bmp_upload.path={runtime.tools.arm-none-eabi-gcc.path}/bin/
|
|||
tools.bmp_upload.upload.speed=230400
|
||||
tools.bmp_upload.upload.params.verbose=
|
||||
tools.bmp_upload.upload.params.quiet=-q --batch-silent
|
||||
tools.bmp_upload.upload.pattern="{path}{cmd}" -cd "{build.path}" -b {upload.speed} {upload.verbose} -ex "set debug remote 0" -ex "set target-async off" -ex "set remotetimeout 60" -ex "set mem inaccessible-by-default off" -ex "set confirm off" -ex "set height 0" -ex "target extended-remote {serial.port}" -ex "monitor swdp_scan" -ex "attach 1" -ex "x/wx 0x8000004" -ex "monitor erase_mass" -ex "echo 0x8000004 expect 0xffffffff after erase\n" -ex "x/wx 0x8000004" -ex "file {build.project_name}.elf" -ex "load" -ex "x/wx 0x08000004" -ex "tbreak main" -ex "run" -ex "echo \n\n\nUpload finished!" -ex "quit"
|
||||
tools.bmp_upload.upload.pattern="{path}{cmd}" -cd "{build.path}" -b {upload.speed} {upload.verbose} -ex "set debug remote 0" -ex "set target-async off" -ex "set remotetimeout 60" -ex "set mem inaccessible-by-default off" -ex "set confirm off" -ex "set height 0" -ex "target extended-remote {serial.port}" -ex "monitor swdp_scan" -ex "attach 1" -ex "x/wx 0x8000004" -ex "monitor erase_mass" -ex "echo 0x8000004 expect 0xffffffff after erase\n" -ex "x/wx 0x8000004" -ex "file {build.project_name}.elf" -ex "load" -ex "x/wx 0x08000004" -ex "tbreak main" -ex "run" -ex "echo \n\n\nUpload finished!" -ex "quit"
|
||||
|
||||
tools.jlink_upload.cmd=jlink_upload
|
||||
tools.jlink_upload.cmd.windows=jlink_upload.bat
|
||||
tools.jlink_upload.cmd.macosx=jlink_upload
|
||||
tools.jlink_upload.path={runtime.hardware.path}/tools/win
|
||||
tools.jlink_upload.path.macosx={runtime.hardware.path}/tools/macosx
|
||||
tools.jlink_upload.path.linux={runtime.hardware.path}/tools/linux
|
||||
tools.jlink_upload.path.linux64={runtime.hardware.path}/tools/linux64
|
||||
tools.jlink_upload.upload.params.verbose=-d
|
||||
tools.jlink_upload.upload.params.quiet=n
|
||||
tools.jlink_upload.upload.pattern="{path}/{cmd}" "{build.path}/{build.project_name}.bin"
|
||||
|
|
|
@ -42,6 +42,7 @@ extern "C"{
|
|||
#include <libmaple/libmaple.h>
|
||||
#include <libmaple/bitband.h>
|
||||
#include <libmaple/rcc.h>
|
||||
#include <libmaple/nvic.h>
|
||||
/* We include the series header below, after defining the register map
|
||||
* and device structs. */
|
||||
|
||||
|
@ -73,12 +74,30 @@ typedef struct adc_reg_map {
|
|||
__io uint32 DR; ///< Regular data register
|
||||
} adc_reg_map;
|
||||
|
||||
|
||||
/** ADC device type. */
|
||||
typedef struct adc_dev {
|
||||
adc_reg_map *regs; /**< Register map */
|
||||
rcc_clk_id clk_id; /**< RCC clock information */
|
||||
adc_reg_map *regs; /**< Register map */
|
||||
rcc_clk_id clk_id; /**< RCC clock information */
|
||||
nvic_irq_num irq_num; /* Added by bubulindo */
|
||||
voidFuncPtr handlers[]; /* Added by bubulindo EOC, JEOC, AWD Interrupts*/
|
||||
} adc_dev;
|
||||
|
||||
|
||||
//Added by bubulindo - Interrupt ID's for ADC
|
||||
typedef enum adc_interrupt_id {
|
||||
ADC_EOC, /**< Update interrupt. */
|
||||
ADC_AWD , /**< Capture/compare 1 interrupt. */
|
||||
ADC_JEOC,
|
||||
//ADC_JSTRT,
|
||||
//ADC_STRT, /**Analog WatchDog interrupt */
|
||||
} adc_interrupt_id;
|
||||
|
||||
//Added by bubulindo
|
||||
void adc_enable_irq(adc_dev* dev, uint8 interrupt);
|
||||
void adc_attach_interrupt(adc_dev *dev, uint8 interrupt, voidFuncPtr handler);
|
||||
|
||||
|
||||
/* Pull in the series header (which may need the above struct
|
||||
* definitions).
|
||||
*
|
||||
|
@ -244,10 +263,10 @@ typedef struct adc_dev {
|
|||
* Routines
|
||||
*/
|
||||
|
||||
void adc_init(const adc_dev *dev);
|
||||
void adc_set_extsel(const adc_dev *dev, adc_extsel_event event);
|
||||
void adc_set_sample_rate(const adc_dev *dev, adc_smp_rate smp_rate);
|
||||
uint16 adc_read(const adc_dev *dev, uint8 channel);
|
||||
void adc_init(adc_dev *dev);
|
||||
void adc_set_extsel(adc_dev *dev, adc_extsel_event event);
|
||||
void adc_set_sample_rate(adc_dev *dev, adc_smp_rate smp_rate);
|
||||
uint16 adc_read(adc_dev *dev, uint8 channel);
|
||||
|
||||
/**
|
||||
* @brief Set the ADC prescaler.
|
||||
|
@ -260,7 +279,7 @@ extern void adc_set_prescaler(adc_prescaler pre);
|
|||
* @brief Call a function on all ADC devices.
|
||||
* @param fn Function to call on each ADC device.
|
||||
*/
|
||||
extern void adc_foreach(void (*fn)(const adc_dev*));
|
||||
extern void adc_foreach(void (*fn)(adc_dev*));
|
||||
|
||||
struct gpio_dev;
|
||||
/**
|
||||
|
@ -270,7 +289,7 @@ struct gpio_dev;
|
|||
* @param gdev GPIO device to configure.
|
||||
* @param bit Bit on gdev to configure for ADC conversion.
|
||||
*/
|
||||
extern void adc_config_gpio(const struct adc_dev *dev,
|
||||
extern void adc_config_gpio(struct adc_dev *dev,
|
||||
struct gpio_dev *gdev,
|
||||
uint8 bit);
|
||||
|
||||
|
@ -284,7 +303,7 @@ extern void adc_config_gpio(const struct adc_dev *dev,
|
|||
* @param dev Device to enable.
|
||||
* @see adc_read()
|
||||
*/
|
||||
extern void adc_enable_single_swstart(const adc_dev* dev);
|
||||
extern void adc_enable_single_swstart(adc_dev* dev);
|
||||
|
||||
/**
|
||||
* @brief Set the regular channel sequence length.
|
||||
|
@ -295,7 +314,7 @@ extern void adc_enable_single_swstart(const adc_dev* dev);
|
|||
* @param dev ADC device.
|
||||
* @param length Regular channel sequence length, from 1 to 16.
|
||||
*/
|
||||
static inline void adc_set_reg_seqlen(const adc_dev *dev, uint8 length) {
|
||||
static inline void adc_set_reg_seqlen(adc_dev *dev, uint8 length) {
|
||||
uint32 tmp = dev->regs->SQR1;
|
||||
tmp &= ~ADC_SQR1_L;
|
||||
tmp |= (length - 1) << 20;
|
||||
|
@ -306,7 +325,7 @@ static inline void adc_set_reg_seqlen(const adc_dev *dev, uint8 length) {
|
|||
* @brief Enable an adc peripheral
|
||||
* @param dev ADC device to enable
|
||||
*/
|
||||
static inline void adc_enable(const adc_dev *dev) {
|
||||
static inline void adc_enable(adc_dev *dev) {
|
||||
*bb_perip(&dev->regs->CR2, ADC_CR2_ADON_BIT) = 1;
|
||||
}
|
||||
|
||||
|
@ -314,7 +333,7 @@ static inline void adc_enable(const adc_dev *dev) {
|
|||
* @brief Disable an ADC peripheral
|
||||
* @param dev ADC device to disable
|
||||
*/
|
||||
static inline void adc_disable(const adc_dev *dev) {
|
||||
static inline void adc_disable(adc_dev *dev) {
|
||||
*bb_perip(&dev->regs->CR2, ADC_CR2_ADON_BIT) = 0;
|
||||
}
|
||||
|
||||
|
|
|
@ -569,6 +569,8 @@ typedef enum timer_mode {
|
|||
/* TIMER_ONE_PULSE, TODO: In this mode, the timer can generate a single
|
||||
* pulse on a GPIO pin for a specified amount of
|
||||
* time. */
|
||||
|
||||
TIMER_ENCODER, //CARLOS Change
|
||||
} timer_mode;
|
||||
|
||||
/** Timer channel numbers */
|
||||
|
@ -620,6 +622,11 @@ void timer_attach_interrupt(timer_dev *dev,
|
|||
voidFuncPtr handler);
|
||||
void timer_detach_interrupt(timer_dev *dev, uint8 interrupt);
|
||||
|
||||
//CARLOS
|
||||
uint8 get_direction(timer_dev *dev);
|
||||
|
||||
|
||||
|
||||
/**
|
||||
* Initialize all timer devices on the chip.
|
||||
*/
|
||||
|
|
|
@ -43,12 +43,12 @@
|
|||
* Devices
|
||||
*/
|
||||
extern adc_dev adc1;
|
||||
extern const struct adc_dev *ADC1;
|
||||
extern struct adc_dev *ADC1;
|
||||
extern adc_dev adc2;
|
||||
extern const struct adc_dev *ADC2;
|
||||
extern struct adc_dev *ADC2;
|
||||
#if defined(STM32_HIGH_DENSITY) || defined(STM32_XL_DENSITY)
|
||||
extern adc_dev adc3;
|
||||
extern const struct adc_dev *ADC3;
|
||||
extern struct adc_dev *ADC3;
|
||||
#endif
|
||||
|
||||
/*
|
||||
|
@ -253,7 +253,7 @@ typedef enum adc_prescaler {
|
|||
* Routines
|
||||
*/
|
||||
|
||||
void adc_calibrate(const adc_dev *dev);
|
||||
void adc_calibrate(adc_dev *dev);
|
||||
|
||||
/**
|
||||
* @brief Set external trigger conversion mode event for regular channels
|
||||
|
@ -264,7 +264,7 @@ void adc_calibrate(const adc_dev *dev);
|
|||
* @param enable If 1, conversion on external events is enabled; if 0,
|
||||
* disabled.
|
||||
*/
|
||||
static inline void adc_set_exttrig(const adc_dev *dev, uint8 enable) {
|
||||
static inline void adc_set_exttrig(adc_dev *dev, uint8 enable) {
|
||||
*bb_perip(&dev->regs->CR2, ADC_CR2_EXTTRIG_BIT) = !!enable;
|
||||
}
|
||||
|
||||
|
|
|
@ -101,8 +101,9 @@ typedef union
|
|||
u16 w;
|
||||
struct BW
|
||||
{
|
||||
u8 bb1;
|
||||
/* Little Endian */
|
||||
u8 bb0;
|
||||
u8 bb1;
|
||||
}
|
||||
bw;
|
||||
} u16_u8;
|
||||
|
@ -211,6 +212,8 @@ USER_STANDARD_REQUESTS;
|
|||
#define USBwLength USBwLengths.w
|
||||
#define USBwLength0 USBwLengths.bw.bb0
|
||||
#define USBwLength1 USBwLengths.bw.bb1
|
||||
#define StatusInfo0 StatusInfo.bw.bb0
|
||||
#define StatusInfo1 StatusInfo.bw.bb1
|
||||
|
||||
/* Exported macro ------------------------------------------------------------*/
|
||||
/* Exported functions ------------------------------------------------------- */
|
||||
|
|
|
@ -179,7 +179,7 @@ nvic_init((uint32)VECT_TAB_ADDR, 0);
|
|||
*/
|
||||
}
|
||||
|
||||
static void adc_default_config(const adc_dev *dev) {
|
||||
static void adc_default_config( adc_dev *dev) {
|
||||
adc_enable_single_swstart(dev);
|
||||
adc_set_sample_rate(dev, wirish::priv::w_adc_smp);
|
||||
}
|
||||
|
|
|
@ -179,7 +179,7 @@ nvic_init((uint32)VECT_TAB_ADDR, 0);
|
|||
*/
|
||||
}
|
||||
|
||||
static void adc_default_config(const adc_dev *dev) {
|
||||
static void adc_default_config(adc_dev *dev) {
|
||||
adc_enable_single_swstart(dev);
|
||||
adc_set_sample_rate(dev, wirish::priv::w_adc_smp);
|
||||
}
|
||||
|
|
|
@ -179,7 +179,7 @@ nvic_init((uint32)VECT_TAB_ADDR, 0);
|
|||
*/
|
||||
}
|
||||
|
||||
static void adc_default_config(const adc_dev *dev) {
|
||||
static void adc_default_config(adc_dev *dev) {
|
||||
adc_enable_single_swstart(dev);
|
||||
adc_set_sample_rate(dev, wirish::priv::w_adc_smp);
|
||||
}
|
||||
|
|
|
@ -173,7 +173,7 @@ static void setup_nvic(void) {
|
|||
#endif
|
||||
}
|
||||
|
||||
static void adc_default_config(const adc_dev *dev) {
|
||||
static void adc_default_config(adc_dev *dev) {
|
||||
adc_enable_single_swstart(dev);
|
||||
adc_set_sample_rate(dev, wirish::priv::w_adc_smp);
|
||||
}
|
||||
|
|
|
@ -179,7 +179,7 @@ nvic_init((uint32)VECT_TAB_ADDR, 0);
|
|||
*/
|
||||
}
|
||||
|
||||
static void adc_default_config(const adc_dev *dev) {
|
||||
static void adc_default_config(adc_dev *dev) {
|
||||
adc_enable_single_swstart(dev);
|
||||
adc_set_sample_rate(dev, wirish::priv::w_adc_smp);
|
||||
}
|
||||
|
|
|
@ -179,7 +179,7 @@ nvic_init((uint32)VECT_TAB_ADDR, 0);
|
|||
*/
|
||||
}
|
||||
|
||||
static void adc_default_config(const adc_dev *dev) {
|
||||
static void adc_default_config(adc_dev *dev) {
|
||||
adc_enable_single_swstart(dev);
|
||||
adc_set_sample_rate(dev, wirish::priv::w_adc_smp);
|
||||
}
|
||||
|
|
|
@ -179,7 +179,7 @@ nvic_init((uint32)VECT_TAB_ADDR, 0);
|
|||
*/
|
||||
}
|
||||
|
||||
static void adc_default_config(const adc_dev *dev) {
|
||||
static void adc_default_config(adc_dev *dev) {
|
||||
adc_enable_single_swstart(dev);
|
||||
adc_set_sample_rate(dev, wirish::priv::w_adc_smp);
|
||||
}
|
||||
|
|
|
@ -179,7 +179,7 @@ nvic_init((uint32)VECT_TAB_ADDR, 0);
|
|||
*/
|
||||
}
|
||||
|
||||
static void adc_default_config(const adc_dev *dev) {
|
||||
static void adc_default_config(adc_dev *dev) {
|
||||
adc_enable_single_swstart(dev);
|
||||
adc_set_sample_rate(dev, wirish::priv::w_adc_smp);
|
||||
}
|
||||
|
|
|
@ -179,7 +179,7 @@ nvic_init((uint32)VECT_TAB_ADDR, 0);
|
|||
*/
|
||||
}
|
||||
|
||||
static void adc_default_config(const adc_dev *dev) {
|
||||
static void adc_default_config(adc_dev *dev) {
|
||||
adc_enable_single_swstart(dev);
|
||||
adc_set_sample_rate(dev, wirish::priv::w_adc_smp);
|
||||
}
|
||||
|
|
|
@ -181,7 +181,7 @@ nvic_init((uint32)VECT_TAB_ADDR, 0);
|
|||
*/
|
||||
}
|
||||
|
||||
static void adc_default_config(const adc_dev *dev) {
|
||||
static void adc_default_config( adc_dev *dev) {
|
||||
adc_enable_single_swstart(dev);
|
||||
adc_set_sample_rate(dev, wirish::priv::w_adc_smp);
|
||||
}
|
||||
|
|
|
@ -0,0 +1,157 @@
|
|||
/*
|
||||
* Hardware Timer as an Encoder interface.
|
||||
*
|
||||
* The STM32 Timers have the possibility of being used as an encoder interface.
|
||||
* This can be both a quadrature encoder (mode 3) or pulse encoder with a signal to give direction (modes 1 and 2).
|
||||
* The default behavior is for quadrature encoder.
|
||||
*
|
||||
* To avoid overflowing the encoder (which may or may not happen (although with 16 bits, it's likely), the following code
|
||||
* will interrupt every time the number of pulses that each revolution gives to increment/decrement a variable (ints).
|
||||
*
|
||||
* This means that the total number of pulses given by the encoder will be (ints * PPR) + timer.getCount()
|
||||
*
|
||||
* Attached is also a bit of code to simulate a quadrature encoder.
|
||||
* To test this library, make the connections as below:
|
||||
*
|
||||
* TIMER2 inputs -> Digital Pins used to simulate.
|
||||
* D2 -> D4
|
||||
* D3 -> D5
|
||||
*
|
||||
* COUNTING DIRECTION:
|
||||
* 0 means that it is upcounting, meaning that Channel A is leading Channel B
|
||||
*
|
||||
* EDGE COUNTING:
|
||||
*
|
||||
* mode 1 - only counts pulses on channel B
|
||||
* mode 2 - only counts pulses on Channel A
|
||||
* mode 3 - counts on both channels.
|
||||
*
|
||||
*/
|
||||
|
||||
|
||||
|
||||
#include "HardwareTimer.h"
|
||||
|
||||
//Encoder simulation stuff
|
||||
//NOT NEEDED WHEN CONNECTING A REAL ENCODER
|
||||
unsigned char mode = 0; //to issue steps...
|
||||
unsigned char dir = 'F'; // direction of movement of the encoder.
|
||||
|
||||
unsigned int freq = 100; //update frequency.
|
||||
unsigned long time = 0; //time variable for millis()
|
||||
unsigned char states[4]; //because I'm lazy...
|
||||
|
||||
|
||||
//Encoder stuff
|
||||
|
||||
//Pulses per revolution
|
||||
#define PPR 1024
|
||||
|
||||
HardwareTimer timer(2);
|
||||
|
||||
unsigned long ints = 0;
|
||||
|
||||
void func(){
|
||||
if (timer.getDirection()){
|
||||
ints--;
|
||||
} else{
|
||||
ints++;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void setup() {
|
||||
//define the Timer channels as inputs.
|
||||
pinMode(D2, INPUT_PULLUP); //channel A
|
||||
pinMode(D3, INPUT_PULLUP); //channel B
|
||||
|
||||
//configure timer as encoder
|
||||
timer.setMode(0, TIMER_ENCODER); //set mode, the channel is not used when in this mode.
|
||||
timer.pause(); //stop...
|
||||
timer.setPrescaleFactor(1); //normal for encoder to have the lowest or no prescaler.
|
||||
timer.setOverflow(PPR); //use this to match the number of pulse per revolution of the encoder. Most industrial use 1024 single channel steps.
|
||||
timer.setCount(0); //reset the counter.
|
||||
timer.setEdgeCounting(TIMER_SMCR_SMS_ENCODER3); //or TIMER_SMCR_SMS_ENCODER1 or TIMER_SMCR_SMS_ENCODER2. This uses both channels to count and ascertain direction.
|
||||
timer.attachInterrupt(0, func); //channel doesn't mean much here either.
|
||||
timer.resume(); //start the encoder...
|
||||
|
||||
//Setup encoder simulator
|
||||
pinMode(5, OUTPUT);
|
||||
pinMode(4, OUTPUT);
|
||||
|
||||
digitalWrite(5, HIGH);
|
||||
digitalWrite(4, LOW);
|
||||
states[0] = 0; //00
|
||||
states[1] = 1; //01
|
||||
states[2] = 3; //11
|
||||
states[3] = 2; //10
|
||||
|
||||
|
||||
}
|
||||
|
||||
//Support variables.
|
||||
unsigned long interval=0; //variable for status updates...
|
||||
char received = 0;
|
||||
|
||||
void loop() {
|
||||
//encoder code
|
||||
if (millis() - interval >= 1000) {
|
||||
Serial.print(timer.getCount());
|
||||
Serial.println(" counts");
|
||||
Serial.print("direction ");
|
||||
Serial.println(timer.getDirection());
|
||||
Serial.print("Full Revs: ");
|
||||
Serial.println(ints);
|
||||
interval = millis(); //update interval for user.
|
||||
}
|
||||
|
||||
|
||||
|
||||
/*
|
||||
EENCODER SIMULATION PART.
|
||||
|
||||
|
||||
*/
|
||||
/*
|
||||
*
|
||||
* Protocol...
|
||||
*
|
||||
* if received F - Move forward.
|
||||
* if received B - Move BackWard
|
||||
* if received 1 - Mode 1 (Channel B counts)
|
||||
* if received 2 - Mode 2 (Channel A counts)
|
||||
* if received 3 - Mode 3 (Counts on both channels)
|
||||
* if received 4 - Change prescaler to 4
|
||||
* if received 0 - change prescaler to 1
|
||||
* if received - - Increase Speed
|
||||
* if received + - Decrease Speed
|
||||
*/
|
||||
|
||||
//take care of comms...
|
||||
if (Serial.available() > 0) {
|
||||
received = Serial.read();
|
||||
if (received == 'F' || received == 'R') dir = received; //direction. Forward or Reverse.
|
||||
if (received == '1') timer.setEdgeCounting(TIMER_SMCR_SMS_ENCODER1); //count only the pulses from input 1
|
||||
if (received == '2') timer.setEdgeCounting(TIMER_SMCR_SMS_ENCODER2); //count only the pulses from input 2
|
||||
if (received == '3') timer.setEdgeCounting(TIMER_SMCR_SMS_ENCODER3); //count on both channels (default of the lib).
|
||||
if (received == '4') timer.setPrescaleFactor(4); //only updates on overflow, so you need to wait for an overflow. Not really used...
|
||||
if (received == '0') timer.setPrescaleFactor(1); //only updates on overflow, so you need to wait for an overflow.
|
||||
if (received == '-') freq+=50; //increase speed.
|
||||
if (received == '+') {
|
||||
freq-=50;
|
||||
if (freq <= 0) freq = 100; //smallest is 10 ms.
|
||||
}
|
||||
}
|
||||
|
||||
//simulate encoder pulses.
|
||||
if ( millis() - time >= freq) {
|
||||
time = millis(); //prepare next
|
||||
|
||||
if (dir == 'F') mode++;
|
||||
if (dir == 'R') mode --;
|
||||
|
||||
digitalWrite(4, (states[mode%4] & 0x01));
|
||||
digitalWrite(5, (states[mode%4] >> 1));
|
||||
}
|
||||
|
||||
}
|
|
@ -0,0 +1,9 @@
|
|||
#!/bin/bash
|
||||
|
||||
echo erase > "$1".jlink
|
||||
echo loadbin "$1" , 0x8000000 >> "$1".jlink
|
||||
echo r >> "$1".jlink
|
||||
echo q >> "$1".jlink
|
||||
|
||||
/opt/SEGGER/JLink_V610e/JLinkExe -device STM32F103C8 -if SWD -speed auto -CommanderScript "$1".jlink
|
||||
|
|
@ -0,0 +1,19 @@
|
|||
rem: @echo off
|
||||
rem: Note %~dp0 get path of this batch file
|
||||
rem: Need to change drive if My Documents is on a drive other than C:
|
||||
set driverLetter=%~dp0
|
||||
set driverLetter=%driverLetter:~0,2%
|
||||
%driverLetter%
|
||||
cd %~dp0
|
||||
rem: the two line below are needed to fix path issues with incorrect slashes before the bin file name
|
||||
set tmpBinFilePath=%1
|
||||
set tmpBinFilePath=%tmpBinFilePath:/=\%
|
||||
|
||||
rem: create commander script file with the tmp bin that the Arduino IDE creates
|
||||
|
||||
@echo erase > %tmpbinfilepath%.jlink
|
||||
@echo loadbin %tmpbinfilepath% , 0x8000000 >> %tmpbinfilepath%.jlink
|
||||
@echo r >> %tmpbinfilepath%.jlink
|
||||
@echo q >> %tmpbinfilepath%.jlink
|
||||
|
||||
JLink.exe -device STM32F103C8 -if SWD -speed auto -CommanderScript %tmpBinFilePath%.jlink
|
Loading…
Reference in New Issue