Update to the STM32 ADC and CAN drivers

git-svn-id: https://nuttx.svn.sourceforge.net/svnroot/nuttx/trunk@4215 7fd9a85b-ad96-42d3-883c-3090e2eb8679
This commit is contained in:
patacongo 2011-12-22 21:55:54 +00:00
parent e2ef959d92
commit 60006bab7a
11 changed files with 276 additions and 92 deletions

View File

@ -98,7 +98,7 @@ int MAIN_NAME(int argc, char *argv[])
size_t readsize;
ssize_t nbytes;
#if defined(CONFIG_NSH_BUILTIN_APPS) || defined(CONFIG_EXAMPLES_ADC_NSAMPLES)
long nsamples;
long nloops;
#endif
int fd;
int errval = 0;
@ -110,14 +110,14 @@ int MAIN_NAME(int argc, char *argv[])
*/
#if defined(CONFIG_NSH_BUILTIN_APPS)
nsamples = 1;
nloops = 1;
if (argc > 1)
{
nsamples = strtol(argv[1], NULL, 10);
nloops = strtol(argv[1], NULL, 10);
}
message(MAIN_STRING "nsamples: %d\n", nsamples);
message(MAIN_STRING "nloops: %d\n", nloops);
#elif defined(CONFIG_EXAMPLES_ADC_NSAMPLES)
message(MAIN_STRING "nsamples: %d\n", CONFIG_EXAMPLES_ADC_NSAMPLES);
message(MAIN_STRING "nloops: %d\n", CONFIG_EXAMPLES_ADC_NSAMPLES);
#endif
/* Initialization of the ADC hardware is performed by logic external to
@ -150,9 +150,9 @@ int MAIN_NAME(int argc, char *argv[])
*/
#if defined(CONFIG_NSH_BUILTIN_APPS)
for (; nsamples > 0; nsamples--)
for (; nloops > 0; nloops--)
#elif defined(CONFIG_EXAMPLES_ADC_NSAMPLES)
for (nsamples = 0; nsamples < CONFIG_EXAMPLES_ADC_NSAMPLES; nsamples++)
for (nloops = 0; nloops < CONFIG_EXAMPLES_ADC_NSAMPLES; nloops++)
#else
for (;;)
#endif
@ -167,7 +167,6 @@ int MAIN_NAME(int argc, char *argv[])
readsize = CONFIG_EXAMPLES_ADC_GROUPSIZE * sizeof(struct adc_msg_s);
nbytes = read(fd, sample, readsize);
message("Bytes read: %d\n", nbytes);
/* Handle unexpected return values */
@ -201,7 +200,7 @@ int MAIN_NAME(int argc, char *argv[])
}
else
{
message("Sample: ");
message("Sample:\n");
for (i = 0; i < nsamples ; i++)
{
message("%d: channel: %d value: %d\n",

View File

@ -82,39 +82,39 @@
/* CAN mailbox registers (3 TX and 2 RX) */
#define STM32_CAN_TIR_OFFSET(m) (0x0180+0x0010*(m))
#define STM32_CAN_TIR_OFFSET(m) (0x0180+((m)<<4))
#define STM32_CAN_TI0R_OFFSET 0x0180 /* TX mailbox identifier register 0 */
#define STM32_CAN_TI1R_OFFSET 0x0190 /* TX mailbox identifier register 1 */
#define STM32_CAN_TI2R_OFFSET 0x01a0 /* TX mailbox identifier register 2 */
#define STM32_CAN_TDTR_OFFSET(m) (0x0184+0x0010*(m))
#define STM32_CAN_TDTR_OFFSET(m) (0x0184+((m)<<4))
#define STM32_CAN_TDT0R_OFFSET 0x0184 /* Mailbox data length control and time stamp register 0 */
#define STM32_CAN_TDT1R_OFFSET 0x0194 /* Mailbox data length control and time stamp register 1 */
#define STM32_CAN_TDT2R_OFFSET 0x01a4 /* Mailbox data length control and time stamp register 2 */
#define STM32_CAN_TDLR_OFFSET(m) (0x0188+0x0010*(m))
#define STM32_CAN_TDLR_OFFSET(m) (0x0188+((m)<<4))
#define STM32_CAN_TDL0R_OFFSET 0x0188 /* Mailbox data low register 0 */
#define STM32_CAN_TDL1R_OFFSET 0x0198 /* Mailbox data low register 1 */
#define STM32_CAN_TDL2R_OFFSET 0x01a8 /* Mailbox data low register 2 */
#define STM32_CAN_TDHR_OFFSET(m) (0x018c+0x0010*(m))
#define STM32_CAN_TDHR_OFFSET(m) (0x018c+((m)<<4))
#define STM32_CAN_TDH0R_OFFSET 0x018c /* Mailbox data high register 0 */
#define STM32_CAN_TDH1R_OFFSET 0x019c /* Mailbox data high register 1 */
#define STM32_CAN_TDH2R_OFFSET 0x01ac /* Mailbox data high register 2 */
#define STM32_CAN_RIR_OFFSET(m) (0x01b0+0x0010*(m))
#define STM32_CAN_RIR_OFFSET(m) (0x01b0+((m)<<4))
#define STM32_CAN_RI0R_OFFSET 0x01b0 /* Rx FIFO mailbox identifier register 0 */
#define STM32_CAN_RI1R_OFFSET 0x01c0 /* Rx FIFO mailbox identifier register 1 */
#define STM32_CAN_RDTR_OFFSET(m) (0x01b4+0x0010*(m))
#define STM32_CAN_RDTR_OFFSET(m) (0x01b4+((m)<<4))
#define STM32_CAN_RDT0R_OFFSET 0x01b4 /* Rx FIFO mailbox data length control and time stamp register 0 */
#define STM32_CAN_RDT1R_OFFSET 0x01c4 /* Rx FIFO mailbox data length control and time stamp register 1 */
#define STM32_CAN_RDLR_OFFSET(m) (0x01b8+0x0010*(m))
#define STM32_CAN_RDLR_OFFSET(m) (0x01b8+((m)<<4))
#define STM32_CAN_RDL0R_OFFSET 0x01b8 /* Receive FIFO mailbox data low register 0 */
#define STM32_CAN_RDL1R_OFFSET 0x01c8 /* Receive FIFO mailbox data low register 1 */
#define STM32_CAN_RDHR_OFFSET(m) (0x01bc+0x0010*(m))
#define STM32_CAN_RDHR_OFFSET(m) (0x01bc+((m)<<4))
#define STM32_CAN_RDH0R_OFFSET 0x01bc /* Receive FIFO mailbox data high register 0 */
#define STM32_CAN_RDH1R_OFFSET 0x01cc /* Receive FIFO mailbox data high register 1 */
@ -128,9 +128,14 @@
/* There are 14 or 28 filter banks (depending) on the device. Each filter bank is
* composed of two 32-bit registers, CAN_FiR:
* F0R1 Offset 0x240
* F0R2 Offset 0x244
* F1R1 Offset 0x248
* F1R2 Offset 0x24c
* ...
*/
#define STM32_CAN_FIR_OFFSET(b,i) (0x240+0x0010*(b)*0x004*(i))
#define STM32_CAN_FR_OFFSET(f,i) (0x240+((f)<<3)*(((i)-1)<<2))
/* Register Addresses ***************************************************************/

View File

@ -83,9 +83,16 @@
# define ADC_CR1_ALLINTS (ADC_CR1_AWDIE | ADC_CR1_EOCIE | ADC_CR1_JEOCIE | ADC_CR1_OVRIE)
#endif
/* The maximum number of channels that can be sampled */
/* The maximum number of channels that can be sampled. If dma support is
* not enabled, then only a single channel can be sampled. Otherwise,
* data overruns would occur.
*/
#define ADC_MAX_SAMPLES 16
#ifdef CONFIG_ADC_DMA
# define ADC_MAX_SAMPLES 16
#else
# define ADC_MAX_SAMPLES 1
#endif
/****************************************************************************
* Private Types
@ -154,7 +161,10 @@ static void adc_enable(FAR struct stm32_dev_s *priv, bool enable);
static void adc_timstart(FAR struct stm32_dev_s *priv, bool enable);
static int adc_timinit(FAR struct stm32_dev_s *priv);
#endif
#ifdef CONFIG_ADC_DMA
static void adc_startconv(FAR struct stm32_dev_s *priv, bool enable);
#endif
/****************************************************************************
* Private Data
@ -371,7 +381,7 @@ static void adc_tim_dumpregs(struct stm32_dev_s *priv, FAR const char *msg)
tim_getreg(priv, STM32_GTIM_CR2_OFFSET),
tim_getreg(priv, STM32_GTIM_SMCR_OFFSET),
tim_getreg(priv, STM32_GTIM_DIER_OFFSET));
avdbg(" SR: %04x EGR: XXXX CCMR1: %04x CCMR2: %04x\n",
avdbg(" SR: %04x EGR: 0000 CCMR1: %04x CCMR2: %04x\n",
tim_getreg(priv, STM32_GTIM_SR_OFFSET),
tim_getreg(priv, STM32_GTIM_CCMR1_OFFSET),
tim_getreg(priv, STM32_GTIM_CCMR2_OFFSET));
@ -476,9 +486,6 @@ static int adc_timinit(FAR struct stm32_dev_s *priv)
uint16_t ccer;
uint16_t egr;
avdbg("Num Channels:%d, ADC:%d, Channel:%d, trigger:%d, Extsel:%08x, Desired Freq:%d\n",
priv->nchannels, priv->intf, priv->current, priv->trigger, priv->extsel, priv->freq);
/* If the timer base address is zero, then this ADC was not configured to
* use a timer.
*/
@ -566,9 +573,6 @@ static int adc_timinit(FAR struct stm32_dev_s *priv)
reload = 65535;
}
avdbg("TIM%d PCLCK: %d frequency: %d TIMCLK: %d prescaler: %d reload: %d\n",
priv->intf, priv->pclck, priv->freq, timclk, prescaler, reload);
/* Set up the timer CR1 register */
cr1 = tim_getreg(priv, STM32_GTIM_CR1_OFFSET);
@ -622,8 +626,10 @@ static int adc_timinit(FAR struct stm32_dev_s *priv)
ocmode1 = (ATIM_CCMR_CCS_CCOUT << ATIM_CCMR1_CC1S_SHIFT) |
(ATIM_CCMR_MODE_PWM1 << ATIM_CCMR1_OC1M_SHIFT) |
ATIM_CCMR1_OC1PE;
/* Set the event CC1 */
egr = ATIM_EGR_CC1G;
avdbg("TimerX CC%d event\n", priv->trigger+1);
/* Set the duty cycle by writing to the CCR register for this channel */
@ -637,8 +643,10 @@ static int adc_timinit(FAR struct stm32_dev_s *priv)
ocmode1 = (ATIM_CCMR_CCS_CCOUT << ATIM_CCMR1_CC2S_SHIFT) |
(ATIM_CCMR_MODE_PWM1 << ATIM_CCMR1_OC2M_SHIFT) |
ATIM_CCMR1_OC2PE;
/* Set the event CC2 */
egr = ATIM_EGR_CC2G;
avdbg("TimerX CC%d event\n", priv->trigger+1);
/* Set the duty cycle by writing to the CCR register for this channel */
@ -652,8 +660,10 @@ static int adc_timinit(FAR struct stm32_dev_s *priv)
ocmode2 = (ATIM_CCMR_CCS_CCOUT << ATIM_CCMR2_CC3S_SHIFT) |
(ATIM_CCMR_MODE_PWM1 << ATIM_CCMR2_OC3M_SHIFT) |
ATIM_CCMR2_OC3PE;
/* Set the event CC3 */
egr = ATIM_EGR_CC3G;
avdbg("TimerX CC%d event\n", priv->trigger+1);
/* Set the duty cycle by writing to the CCR register for this channel */
@ -667,8 +677,10 @@ static int adc_timinit(FAR struct stm32_dev_s *priv)
ocmode2 = (ATIM_CCMR_CCS_CCOUT << ATIM_CCMR2_CC4S_SHIFT) |
(ATIM_CCMR_MODE_PWM1 << ATIM_CCMR2_OC4M_SHIFT) |
ATIM_CCMR2_OC4PE;
/* Set the event CC4 */
egr = ATIM_EGR_CC4G;
avdbg("TimerX CC%d event\n", priv->trigger+1);
/* Set the duty cycle by writing to the CCR register for this channel */
@ -678,9 +690,15 @@ static int adc_timinit(FAR struct stm32_dev_s *priv)
case 4: /* TimerX TRGO event */
{
#warning "missing logic, I want the Timer-x-CCx-event working first"
#warning "TRGO support not yet implemented"
/* Set the event TRGO */
egr = GTIM_EGR_TG;
avdbg("TimerX TRGO trigger=%d\n", priv->trigger);
/* Set the duty cycle by writing to the CCR register for this channel */
tim_putreg(priv, STM32_GTIM_CCR4_OFFSET, (uint16_t)(reload >> 1));
}
break;
@ -759,8 +777,9 @@ static int adc_timinit(FAR struct stm32_dev_s *priv)
cr1 |= GTIM_CR1_ARPE;
tim_putreg(priv, STM32_GTIM_CR1_OFFSET, cr1);
/* Enable the timer counter */
/* All but the CEN bit with the default config in CR1 */
/* Enable the timer counter
* All but the CEN bit with the default config in CR1
*/
adc_timstart(priv, true);
@ -774,7 +793,7 @@ static int adc_timinit(FAR struct stm32_dev_s *priv)
* Name: adc_startconv
*
* Description:
* Start (or stop) the ADC conversion process
* Start (or stop) the ADC conversion process in DMA mode
*
* Input Parameters:
* priv - A reference to the ADC block status
@ -784,6 +803,7 @@ static int adc_timinit(FAR struct stm32_dev_s *priv)
*
****************************************************************************/
#ifdef CONFIG_ADC_DMA
static void adc_startconv(struct stm32_dev_s *priv, bool enable)
{
uint32_t regval;
@ -805,6 +825,7 @@ static void adc_startconv(struct stm32_dev_s *priv, bool enable)
}
adc_putreg(priv, STM32_ADC_CR2_OFFSET,regval);
}
#endif
/****************************************************************************
* Name: adc_rccreset
@ -890,6 +911,8 @@ static void adc_rccreset(struct stm32_dev_s *priv, bool reset)
* Name: adc_enable
*
* Description : Enables or disables the specified ADC peripheral.
* Also, starts a conversion when the ADC is not
* triggered by timers
*
* Input Parameters:
*
@ -1001,25 +1024,26 @@ static void adc_reset(FAR struct adc_dev_s *dev)
regval = adc_getreg(priv, STM32_ADC_CR2_OFFSET);
/* Clear CONT, ALIGN (Right = 0) */
/* Clear CONT, continuous mode disable */
regval &= ~ADC_CR2_CONT;
regval &= ~ADC_CR2_ALIGN;
/*Set ALIGN (Right = 0) */
regval &= ~ADC_CR2_ALIGN;
adc_putreg(priv, STM32_ADC_CR2_OFFSET, regval);
#if 0 /* I'm not sure about this*/
#if 0
#ifdef CONFIG_STM32_STM32F10XX
/* ADC reset calibaration register */
regval |= ADC_CR2_RSTCAL;
adc_putreg(priv, STM32_ADC_CR2_OFFSET, regval);
usleep(10);
usleep(5);
/* A/D Calibration */
regval |= ADC_CR2_CAL;
adc_putreg(priv, STM32_ADC_CR2_OFFSET, regval);
usleep(10);
#endif
#endif
@ -1047,7 +1071,7 @@ static void adc_reset(FAR struct adc_dev_s *dev)
/* Set the number of conversions */
DEBUGASSERT(priv->nchannels <= 16);
DEBUGASSERT(priv->nchannels <= ADC_MAX_SAMPLES);
regval |= (((uint32_t)priv->nchannels-1) << ADC_SQR1_L_SHIFT);
adc_putreg(priv, STM32_ADC_SQR1_OFFSET, regval);
@ -1084,7 +1108,6 @@ static void adc_reset(FAR struct adc_dev_s *dev)
adc_getreg(priv, STM32_ADC_SQR1_OFFSET),
adc_getreg(priv, STM32_ADC_SQR2_OFFSET),
adc_getreg(priv, STM32_ADC_SQR3_OFFSET));
avdbg("\n");
}
/****************************************************************************
@ -1107,8 +1130,6 @@ static int adc_setup(FAR struct adc_dev_s *dev)
FAR struct stm32_dev_s *priv = (FAR struct stm32_dev_s *)dev->ad_priv;
int ret;
avdbg("intf: ADC%d\n", priv->intf);
/* Attach the ADC interrupt */
ret = irq_attach(priv->irq, priv->isr);
@ -1120,8 +1141,6 @@ static int adc_setup(FAR struct adc_dev_s *dev)
up_enable_irq(priv->irq);
}
avdbg("Returning %d\n",ret);
return ret;
}
@ -1142,8 +1161,6 @@ static void adc_shutdown(FAR struct adc_dev_s *dev)
{
FAR struct stm32_dev_s *priv = (FAR struct stm32_dev_s *)dev->ad_priv;
avdbg("intf: ADC%d irq: %d\n", priv->intf, priv->irq);
/* Disable ADC interrupts and detach the ADC interrupt handler */
up_disable_irq(priv->irq);
@ -1203,7 +1220,6 @@ static void adc_rxint(FAR struct adc_dev_s *dev, bool enable)
static int adc_ioctl(FAR struct adc_dev_s *dev, int cmd, unsigned long arg)
{
avdbg("Entry\n");
return -ENOTTY;
}
@ -1226,8 +1242,6 @@ static int adc_interrupt(FAR struct adc_dev_s *dev)
uint32_t regval;
int32_t value;
avdbg("intf: ADC%d\n", priv->intf);
/* Identifies the interruption AWD or EOC */
adcsr = adc_getreg(priv, STM32_ADC_SR_OFFSET);
@ -1241,7 +1255,7 @@ static int adc_interrupt(FAR struct adc_dev_s *dev)
if ((adcsr & ADC_SR_EOC) != 0)
{
/* Read the converted value and clear EOC bit
*(It is cleared by reading the ADC_DR)
* (It is cleared by reading the ADC_DR)
*/
value = adc_getreg(priv, STM32_ADC_DR_OFFSET);
@ -1255,7 +1269,6 @@ static int adc_interrupt(FAR struct adc_dev_s *dev)
*/
adc_receive(dev, priv->chanlist[priv->current], value);
avdbg("Calling adc_receive(chanlist[%d], data=%d)\n", priv->current, value);
/* Set the channel number of the next channel that will complete conversion */
@ -1265,12 +1278,7 @@ static int adc_interrupt(FAR struct adc_dev_s *dev)
{
/* Restart the conversion sequence from the beginning */
avdbg("Last conversion done, conversion=%d\n",priv->current);
/* Reset the index to the first channel to be converted */
priv->current = 0;
}
}
@ -1295,8 +1303,6 @@ static int adc12_interrupt(int irq, void *context)
uint32_t regval;
uint32_t pending;
avdbg("irq: %d\n", irq);
/* Check for pending ADC1 interrupts */
#ifdef CONFIG_STM32_ADC1
@ -1344,8 +1350,6 @@ static int adc3_interrupt(int irq, void *context)
uint32_t regval;
uint32_t pending;
avdbg("irq: %d\n", irq);
/* Check for pending ADC3 interrupts */
regval = getreg32(STM32_ADC3_SR);
@ -1379,8 +1383,6 @@ static int adc123_interrupt(int irq, void *context)
uint32_t regval;
uint32_t pending;
avdbg("irq: %d\n", irq);
/* Check for pending ADC1 interrupts */
#ifdef CONFIG_STM32_ADC1
@ -1437,10 +1439,6 @@ static int adc123_interrupt(int irq, void *context)
* Then, take the chanlist array and store it in the SQR Regs,
* chanlist[0] -> ADC_SQR3_SQ1
* chanlist[1] -> ADC_SQR3_SQ2
* chanlist[2] -> ADC_SQR3_SQ3
* chanlist[3] -> ADC_SQR3_SQ4
* chanlist[4] -> ADC_SQR3_SQ5
* chanlist[5] -> ADC_SQR3_SQ6
* ...
* chanlist[15]-> ADC_SQR1_SQ16
*
@ -1496,7 +1494,10 @@ struct adc_dev_s *stm32_adcinitialize(int intf, const uint8_t *chanlist, int nch
/* Configure the selected ADC */
priv = dev->ad_priv;
DEBUGASSERT(nchannels <= ADC_MAX_SAMPLES);
priv->nchannels = nchannels;
memcpy(priv->chanlist, chanlist, nchannels);
return dev;
}

View File

@ -161,6 +161,12 @@
#if defined(CONFIG_STM32_ADC1) || defined(CONFIG_STM32_ADC2) || defined(CONFIG_STM32_ADC3)
/* DMA support is not yet implemented for this driver */
#ifdef CONFIG_ADC_DMA
# warning "DMA is not supported by the current driver"
#endif
/* Timer configuration: If a timer trigger is specified, then get information
* about the timer.
*/

View File

@ -85,6 +85,10 @@
# define canllvdbg(x...)
#endif
#if !defined(CONFIG_DEBUG) || !defined(CONFIG_DEBUG_CAN)
# undef CONFIG_CAN_REGDEBUG
#endif
/****************************************************************************
* Private Types
****************************************************************************/
@ -106,6 +110,15 @@ struct stm32_can_s
static uint32_t can_getreg(struct stm32_can_s *priv, int offset);
static void can_putreg(struct stm32_can_s *priv, int offset, uint32_t value);
#ifdef CONFIG_CAN_REGDEBUG
static void can_dumpctrlregs(struct stm32_can_s *priv, FAR const char *msg);
static void can_dumpmbregs(struct stm32_can_s *priv, FAR const char *msg);
static void can_dumpfiltregs(struct stm32_can_s *priv, FAR const char *msg);
#else
# define can_dumpctrlregs(priv,msg)
# define can_dumpmbregs(priv,msg)
# define can_dumpfiltregs(priv,msg)
#endif
/* CAN driver methods */
@ -218,6 +231,7 @@ static uint32_t can_getreg(struct stm32_can_s *priv, int offset)
* offset - The offset to the register to read
*
* Returned Value:
* None
*
****************************************************************************/
@ -226,6 +240,154 @@ static void can_putreg(struct stm32_can_s *priv, int offset, uint32_t value)
putreg32(value, priv->base + offset);
}
/****************************************************************************
* Name: can_dumpctrlregs
*
* Description:
* Dump the contents of all CAN control registers
*
* Input Parameters:
* priv - A reference to the CAN block status
*
* Returned Value:
* None
*
****************************************************************************/
#ifdef CONFIG_CAN_REGDEBUG
static void can_dumpctrlregs(struct stm32_can_s *priv, FAR const char *msg)
{
if (msg)
{
canlldbg("Control Registers: %s\n", msg);
}
else
{
canlldbg("Control Registers:\n");
}
/* CAN control and status registers */
lldbg(" MCR: %08x MSR: %08x TSR: %08x\n",
can_getreg(priv, STM32_CAN_MCR_OFFSET),
can_getreg(priv, STM32_CAN_MSR_OFFSET),
can_getreg(priv, STM32_CAN_TSR_OFFSET));
lldbg(" RF0R: %08x RF1R: %08x\n",
can_getreg(priv, STM32_CAN_RF0R_OFFSET),
can_getreg(priv, STM32_CAN_RF1R_OFFSET));
lldbg(" IER: %08x ESR: %08x BTR: %08x\n",
can_getreg(priv, STM32_CAN_IER_OFFSET),
can_getreg(priv, STM32_CAN_ESR_OFFSET),
can_getreg(priv, STM32_CAN_BTR_OFFSET));
}
#endif
/****************************************************************************
* Name: can_dumpmbregs
*
* Description:
* Dump the contents of all CAN mailbox registers
*
* Input Parameters:
* priv - A reference to the CAN block status
*
* Returned Value:
* None
*
****************************************************************************/
#ifdef CONFIG_CAN_REGDEBUG
static void can_dumpmbregs(struct stm32_can_s *priv, FAR const char *msg)
{
if (msg)
{
canlldbg("Mailbox Registers: %s\n", msg);
}
else
{
canlldbg("Mailbox Registers:\n");
}
/* CAN mailbox registers (3 TX and 2 RX) */
lldbg(" TI0R: %08x TDT0R: %08x TDL0R: %08x TDH0R: %08x\n",
can_getreg(priv, STM32_CAN_TI0R_OFFSET),
can_getreg(priv, STM32_CAN_TDT0R_OFFSET),
can_getreg(priv, STM32_CAN_TDL0R_OFFSET),
can_getreg(priv, STM32_CAN_TDH0R_OFFSET));
lldbg(" TI1R: %08x TDT1R: %08x TDL1R: %08x TDH1R: %08x\n",
can_getreg(priv, STM32_CAN_TI1R_OFFSET),
can_getreg(priv, STM32_CAN_TDT1R_OFFSET),
can_getreg(priv, STM32_CAN_TDL1R_OFFSET),
can_getreg(priv, STM32_CAN_TDH1R_OFFSET));
lldbg(" TI2R: %08x TDT2R: %08x TDL2R: %08x TDH2R: %08x\n",
can_getreg(priv, STM32_CAN_TI2R_OFFSET),
can_getreg(priv, STM32_CAN_TDT2R_OFFSET),
can_getreg(priv, STM32_CAN_TDL2R_OFFSET),
can_getreg(priv, STM32_CAN_TDH2R_OFFSET));
lldbg(" RI0R: %08x RDT0R: %08x RDL0R: %08x RDH0R: %08x\n",
can_getreg(priv, STM32_CAN_RI0R_OFFSET),
can_getreg(priv, STM32_CAN_RDT0R_OFFSET),
can_getreg(priv, STM32_CAN_RDL0R_OFFSET),
can_getreg(priv, STM32_CAN_RDH0R_OFFSET));
lldbg(" RI1R: %08x RDT1R: %08x RDL1R: %08x RDH1R: %08x\n",
can_getreg(priv, STM32_CAN_RI1R_OFFSET),
can_getreg(priv, STM32_CAN_RDT1R_OFFSET),
can_getreg(priv, STM32_CAN_RDL1R_OFFSET),
can_getreg(priv, STM32_CAN_RDH1R_OFFSET));
}
#endif
/****************************************************************************
* Name: can_dumpfiltregs
*
* Description:
* Dump the contents of all CAN filter registers
*
* Input Parameters:
* priv - A reference to the CAN block status
*
* Returned Value:
* None
*
****************************************************************************/
#ifdef CONFIG_CAN_REGDEBUG
static void can_dumpfiltregs(struct stm32_can_s *priv, FAR const char *msg)
{
int i;
if (msg)
{
canlldbg("Filter Registers: %s\n", msg);
}
else
{
canlldbg("Filter Registers:\n");
}
lldbg(" FMR: %08x FM1R: %08x FS1R: %08x FSA1R: %08x FA1R: %08x\n",
can_getreg(priv, STM32_CAN_FMR_OFFSET),
can_getreg(priv, STM32_CAN_FM1R_OFFSET),
can_getreg(priv, STM32_CAN_FS1R_OFFSET),
can_getreg(priv, STM32_CAN_FFA1R_OFFSET),
can_getreg(priv, STM32_CAN_FA1R_OFFSET));
for (i = 0; i < CAN_NFILTERS; i++)
{
lldbg(" F%dR1: %08x F%dR2: %08x\n",
i, can_getreg(priv, STM32_CAN_FR_OFFSET(i,1)),
i, can_getreg(priv, STM32_CAN_FR_OFFSET(i,2)));
}
}
#endif
/****************************************************************************
* Name: can_reset
*
@ -310,7 +472,7 @@ static int can_setup(FAR struct can_dev_s *dev)
FAR struct stm32_can_s *priv = dev->cd_priv;
int ret;
canllvdbg("CAN%d\n", priv->port);
canllvdbg("CAN%d irq: %d\n", priv->port, priv->canrx0);
/* CAN cell initialization */
@ -321,6 +483,9 @@ static int can_setup(FAR struct can_dev_s *dev)
return ret;
}
can_dumpctrlregs(priv, "After cell initialization");
can_dumpmbregs(priv, NULL);
/* CAN filter initialization */
ret = can_filterinit(priv);
@ -329,6 +494,7 @@ static int can_setup(FAR struct can_dev_s *dev)
canlldbg("CAN%d filter initialization failed: %d\n", priv->port, ret);
return ret;
}
can_dumpfiltregs(priv, "After filter initialization");
/* Attach only the CAN RX FIFO 0 interrupts. The others are not used */
@ -626,6 +792,7 @@ static int can_send(FAR struct can_dev_s *dev, FAR struct can_msg_s *msg)
*/
(void)can_txdone(dev);
can_dumpmbregs(priv, "After send");
return OK;
}
@ -728,6 +895,8 @@ static int can_rx0interrupt(int irq, void *context)
return OK;
}
can_dumpmbregs(priv, "RX0 interrupt");
/* Get the CAN identifier. Only standard 11-bit IDs are supported */
regval = can_getreg(priv, STM32_CAN_RI0R_OFFSET);
@ -906,7 +1075,8 @@ static int can_bittiming(struct stm32_can_s *priv)
tmp = ((brp - 1) << CAN_BTR_BRP_SHIFT) | ((ts1 - 1) << CAN_BTR_TS1_SHIFT) |
((ts2 - 1) << CAN_BTR_TS2_SHIFT) | ((1 - 1) << CAN_BTR_SJW_SHIFT);
#ifdef CONFIG_CAN_LOOPBACK
tmp |= (CAN_BTR_LBKM | CAN_BTR_SILM);
//tmp |= (CAN_BTR_LBKM | CAN_BTR_SILM);
tmp |= CAN_BTR_LBKM;
#endif
can_putreg(priv, STM32_CAN_BTR_OFFSET, tmp);
@ -1067,8 +1237,8 @@ static int can_filterinit(struct stm32_can_s *priv)
* composed of two 32-bit registers, CAN_FiR:
*/
can_putreg(priv, STM32_CAN_FIR_OFFSET(priv->filter, 0), 0);
can_putreg(priv, STM32_CAN_FIR_OFFSET(priv->filter, 1), 0);
can_putreg(priv, STM32_CAN_FR_OFFSET(priv->filter, 1), 0);
can_putreg(priv, STM32_CAN_FR_OFFSET(priv->filter, 2), 0);
/* Set Id/Mask mode for the filter */
@ -1135,10 +1305,8 @@ FAR struct can_dev_s *stm32_caninitialize(int port)
* file must have been disambiguated in the board.h file.
*/
#ifndef CONFIG_CAN_LOOPBACK
stm32_configgpio(GPIO_CAN1_RX);
stm32_configgpio(GPIO_CAN1_TX);
#endif
}
else
#endif
@ -1153,10 +1321,8 @@ FAR struct can_dev_s *stm32_caninitialize(int port)
* file must have been disambiguated in the board.h file.
*/
#ifndef CONFIG_CAN_LOOPBACK
stm32_configgpio(GPIO_CAN2_RX);
stm32_configgpio(GPIO_CAN2_TX);
#endif
}
else
#endif

View File

@ -499,6 +499,8 @@ HY-Mini specific Configuration Options
mode for testing. The STM32 CAN driver does support loopback mode.
CONFIG_CAN1_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN1 is defined.
CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN2 is defined.
CONFIG_CAN_REGDEBUG - If CONFIG_DEBUG is set, this will generate an
dump of all CAN registers.
HY-MiniSTM32V LCD Hardware Configuration (SSD1289 controler)

View File

@ -587,6 +587,8 @@ STM3210E-EVAL-specific Configuration Options
mode for testing. The STM32 CAN driver does support loopback mode.
CONFIG_CAN1_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN1 is defined.
CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN2 is defined.
CONFIG_CAN_REGDEBUG - If CONFIG_DEBUG is set, this will generate an
dump of all CAN registers.
STM3210E-EVAL LCD Hardware Configuration

View File

@ -76,19 +76,19 @@
/* The number of ADC channels in the conversion list */
#define ADC_NCHANNELS 2
#define ADC_NCHANNELS 1
/************************************************************************************
* Private Data
************************************************************************************/
/* Identifying number of each ADC channel: Variable Resistor and BNC_CN5 */
/* Identifying number of each ADC channel: Variable Resistor */
static const uint8_t g_chanlist[ADC_NCHANNELS] = {14, 11};
static const uint8_t g_chanlist[ADC_NCHANNELS] = {14};
/* Configurations of pins used byte each ADC channels */
static const uint32_t g_pinlist[ADC_NCHANNELS] = {GPIO_ADC1_IN14 , GPIO_ADC1_IN11};
static const uint32_t g_pinlist[ADC_NCHANNELS] = {GPIO_ADC1_IN14};
/************************************************************************************
* Private Functions

View File

@ -254,6 +254,8 @@ Configuration Options:
CONFIG_CAN1_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN1 is defined.
CONFIG_STM32_CAN2 - Enable support for CAN1
CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN2 is defined.
CONFIG_CAN_REGDEBUG - If CONFIG_DEBUG is set, this will generate an
dump of all CAN registers.
STM3240G-EVAL-specific Configuration Options
============================================
@ -528,6 +530,8 @@ STM3240G-EVAL-specific Configuration Options
mode for testing. The STM32 CAN driver does support loopback mode.
CONFIG_CAN1_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN1 is defined.
CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN2 is defined.
CONFIG_CAN_REGDEBUG - If CONFIG_DEBUG is set, this will generate an
dump of all CAN registers.
STM3240G-EVAL LCD Hardware Configuration

View File

@ -74,10 +74,8 @@
* PD1 = FSMC_D3 & CAN1_TX
*/
#ifndef CONFIG_CAN_LOOPBACK
# if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_FSMC)
# warning "The STM3250G-EVAL will only support one of CAN1 and FSMC"
# endif
#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_FSMC)
# warning "The STM3250G-EVAL will only support one of CAN1 and FSMC"
#endif
/* The USB OTG HS ULPI bus is shared with CAN2 bus:
@ -86,10 +84,8 @@
* PB5 = ULPI_D7 & CAN2_RX
*/
#ifndef CONFIG_CAN_LOOPBACK
# if defined(CONFIG_STM32_CAN2) && defined(CONFIG_STM32_OTGHS)
# warning "The STM3250G-EVAL will only support one of CAN2 and USB OTG HS"
# endif
#if defined(CONFIG_STM32_CAN2) && defined(CONFIG_STM32_OTGHS)
# warning "The STM3250G-EVAL will only support one of CAN2 and USB OTG HS"
#endif
/* STM3240G-EVAL GPIOs ******************************************************************************/

View File

@ -274,8 +274,12 @@ static ssize_t adc_read(FAR struct file *filep, FAR char *buffer, size_t buflen)
/* Will the next message in the FIFO fit into the user buffer? */
if (ret + msglen > buflen)
if (nread + msglen > buflen)
{
/* No.. break out of the loop now with nread equal to the actual
* number of bytes transferred.
*/
break;
}
@ -417,4 +421,3 @@ int adc_register(FAR const char *path, FAR struct adc_dev_s *dev)
return register_driver(path, &adc_fops, 0444, dev);
}