File for the integration of pysimCoder with NUTTX
This commit is contained in:
parent
f54aef9977
commit
9a2cb311a3
@ -735,7 +735,7 @@ static int adc_timinit(FAR struct stm32_dev_s *priv)
|
||||
* position.
|
||||
*/
|
||||
|
||||
ainfo("Initializing timers extsel = 0x%08x\n", priv->extsel);
|
||||
ainfo("Initializing timers extsel = 0x%08lx\n", priv->extsel);
|
||||
|
||||
adc_modifyreg(priv, STM32_ADC_EXTREG_OFFSET,
|
||||
ADC_EXTREG_EXTEN_MASK | ADC_EXTREG_EXTSEL_MASK,
|
||||
|
@ -58,6 +58,8 @@
|
||||
#include "arm_arch.h"
|
||||
|
||||
#include "chip.h"
|
||||
|
||||
#include "stm32_rcc.h"
|
||||
#include "stm32_can.h"
|
||||
#include "stm32_gpio.h"
|
||||
|
||||
@ -949,7 +951,7 @@ static int stm32can_ioctl(FAR struct can_dev_s *dev, int cmd,
|
||||
DEBUGASSERT(brp >= 1 && brp <= CAN_BTR_BRP_MAX);
|
||||
}
|
||||
|
||||
caninfo("TS1: %d TS2: %d BRP: %d\n",
|
||||
caninfo("TS1: %d TS2: %d BRP: %lu\n",
|
||||
bt->bt_tseg1, bt->bt_tseg2, brp);
|
||||
|
||||
/* Configure bit timing. */
|
||||
@ -1407,7 +1409,7 @@ static bool stm32can_txready(FAR struct can_dev_s *dev)
|
||||
/* Return true if any mailbox is available */
|
||||
|
||||
regval = stm32can_getreg(priv, STM32_CAN_TSR_OFFSET);
|
||||
caninfo("CAN%d TSR: %08x\n", priv->port, regval);
|
||||
caninfo("CAN%d TSR: %08lx\n", priv->port, regval);
|
||||
|
||||
return stm32can_txmb0empty(regval) || stm32can_txmb1empty(regval) ||
|
||||
stm32can_txmb2empty(regval);
|
||||
@ -1439,7 +1441,7 @@ static bool stm32can_txempty(FAR struct can_dev_s *dev)
|
||||
/* Return true if all mailboxes are available */
|
||||
|
||||
regval = stm32can_getreg(priv, STM32_CAN_TSR_OFFSET);
|
||||
caninfo("CAN%d TSR: %08x\n", priv->port, regval);
|
||||
caninfo("CAN%d TSR: %08lx\n", priv->port, regval);
|
||||
|
||||
return stm32can_txmb0empty(regval) && stm32can_txmb1empty(regval) &&
|
||||
stm32can_txmb2empty(regval);
|
||||
@ -1745,7 +1747,7 @@ static int stm32can_bittiming(FAR struct stm32_can_s *priv)
|
||||
uint32_t ts1;
|
||||
uint32_t ts2;
|
||||
|
||||
caninfo("CAN%d PCLK1: %d baud: %d\n",
|
||||
caninfo("CAN%d PCLK1: %ld baud: %ld\n",
|
||||
priv->port, STM32_PCLK1_FREQUENCY, priv->baud);
|
||||
|
||||
/* Try to get CAN_BIT_QUANTA quanta in one bit_time.
|
||||
@ -1798,7 +1800,7 @@ static int stm32can_bittiming(FAR struct stm32_can_s *priv)
|
||||
DEBUGASSERT(brp >= 1 && brp <= CAN_BTR_BRP_MAX);
|
||||
}
|
||||
|
||||
caninfo("TS1: %d TS2: %d BRP: %d\n", ts1, ts2, brp);
|
||||
caninfo("TS1: %ld TS2: %ld BRP: %ld\n", ts1, ts2, brp);
|
||||
|
||||
/* Configure bit timing. This also does the following, less obvious
|
||||
* things. Unless loopback mode is enabled, it:
|
||||
@ -1915,7 +1917,7 @@ static int stm32can_exitinitmode(FAR struct stm32_can_s *priv)
|
||||
|
||||
if (timeout < 1)
|
||||
{
|
||||
canerr("ERROR: Timed out waiting to exit initialization mode: %08x\n",
|
||||
canerr("ERROR: Timed out waiting to exit initialization mode: %08lx\n",
|
||||
regval);
|
||||
return -ETIMEDOUT;
|
||||
}
|
||||
|
@ -54,6 +54,7 @@
|
||||
#include "arm_internal.h"
|
||||
#include "arm_arch.h"
|
||||
|
||||
#include "stm32_rcc.h"
|
||||
#include "chip.h"
|
||||
#include "stm32_pwm.h"
|
||||
#include "stm32_gpio.h"
|
||||
@ -1126,7 +1127,7 @@ static int pwm_timer(FAR struct stm32_pwmtimer_s *priv,
|
||||
DEBUGASSERT(priv != NULL && info != NULL);
|
||||
|
||||
#if defined(CONFIG_PWM_MULTICHAN)
|
||||
pwminfo("TIM%u frequency: %u\n",
|
||||
pwminfo("TIM%u frequency: %lu\n",
|
||||
priv->timid, info->frequency);
|
||||
#elif defined(CONFIG_PWM_PULSECOUNT)
|
||||
pwminfo("TIM%u channel: %u frequency: %u duty: %08x count: %u\n",
|
||||
@ -1209,8 +1210,8 @@ static int pwm_timer(FAR struct stm32_pwmtimer_s *priv,
|
||||
reload--;
|
||||
}
|
||||
|
||||
pwminfo("TIM%u PCLK: %u frequency: %u "
|
||||
"TIMCLK: %u prescaler: %u reload: %u\n",
|
||||
pwminfo("TIM%u PCLK: %lu frequency: %lu "
|
||||
"TIMCLK: %lu prescaler: %lu reload: %lu\n",
|
||||
priv->timid, priv->pclk, info->frequency,
|
||||
timclk, prescaler, reload);
|
||||
|
||||
@ -1413,7 +1414,7 @@ static int pwm_timer(FAR struct stm32_pwmtimer_s *priv,
|
||||
|
||||
ccr = b16toi(duty * reload + b16HALF);
|
||||
|
||||
pwminfo("ccr: %u\n", ccr);
|
||||
pwminfo("ccr: %lu\n", ccr);
|
||||
|
||||
switch (mode)
|
||||
{
|
||||
@ -1675,7 +1676,7 @@ static int pwm_update_duty(FAR struct stm32_pwmtimer_s *priv,
|
||||
|
||||
DEBUGASSERT(priv != NULL);
|
||||
|
||||
pwminfo("TIM%u channel: %u duty: %08x\n",
|
||||
pwminfo("TIM%u channel: %u duty: %08lx\n",
|
||||
priv->timid, channel, duty);
|
||||
|
||||
#ifndef CONFIG_PWM_MULTICHAN
|
||||
@ -1694,7 +1695,7 @@ static int pwm_update_duty(FAR struct stm32_pwmtimer_s *priv,
|
||||
|
||||
ccr = b16toi(duty * reload + b16HALF);
|
||||
|
||||
pwminfo("ccr: %u\n", ccr);
|
||||
pwminfo("ccr: %lu\n", ccr);
|
||||
|
||||
switch (channel)
|
||||
{
|
||||
@ -2006,7 +2007,8 @@ static void pwm_set_apb_clock(FAR struct stm32_pwmtimer_s *priv, bool on)
|
||||
|
||||
/* Enable/disable APB 1/2 clock for timer */
|
||||
|
||||
pwminfo("RCC_APBxENR base: %08x bits: %04x\n", regaddr, en_bit);
|
||||
pwminfo("RCC_APBxENR base: %08lx bits: %04lx\n",
|
||||
regaddr, en_bit);
|
||||
|
||||
if (on)
|
||||
{
|
||||
@ -2062,7 +2064,7 @@ static int pwm_setup(FAR struct pwm_lowerhalf_s *dev)
|
||||
continue;
|
||||
}
|
||||
|
||||
pwminfo("pincfg: %08x\n", pincfg);
|
||||
pwminfo("pincfg: %08lx\n", pincfg);
|
||||
|
||||
stm32_configgpio(pincfg);
|
||||
pwm_dumpgpio(pincfg, "PWM setup");
|
||||
@ -2113,7 +2115,7 @@ static int pwm_shutdown(FAR struct pwm_lowerhalf_s *dev)
|
||||
continue;
|
||||
}
|
||||
|
||||
pwminfo("pincfg: %08x\n", pincfg);
|
||||
pwminfo("pincfg: %08lx\n", pincfg);
|
||||
|
||||
pincfg &= (GPIO_PORT_MASK | GPIO_PIN_MASK);
|
||||
pincfg |= GPIO_INPUT | GPIO_FLOAT;
|
||||
@ -2373,7 +2375,7 @@ static int pwm_stop(FAR struct pwm_lowerhalf_s *dev)
|
||||
putreg32(regval, regaddr);
|
||||
leave_critical_section(flags);
|
||||
|
||||
pwminfo("regaddr: %08x resetbit: %08x\n", regaddr, resetbit);
|
||||
pwminfo("regaddr: %08lx resetbit: %08lx\n", regaddr, resetbit);
|
||||
pwm_dumpregs(priv, "After stop");
|
||||
return OK;
|
||||
}
|
||||
|
@ -55,6 +55,7 @@
|
||||
#include "arm_internal.h"
|
||||
#include "arm_arch.h"
|
||||
|
||||
#include "stm32_rcc.h"
|
||||
#include "stm32_gpio.h"
|
||||
#include "stm32_tim.h"
|
||||
#include "stm32_qencoder.h"
|
||||
@ -1000,7 +1001,7 @@ static int stm32_shutdown(FAR struct qe_lowerhalf_s *lower)
|
||||
putreg32(regval, regaddr);
|
||||
leave_critical_section(flags);
|
||||
|
||||
sninfo("regaddr: %08x resetbit: %08x\n", regaddr, resetbit);
|
||||
sninfo("regaddr: %08lx resetbit: %08lx\n", regaddr, resetbit);
|
||||
stm32_dumpregs(priv, "After stop");
|
||||
|
||||
/* Disable clocking to the timer */
|
||||
|
@ -167,7 +167,6 @@
|
||||
#define STM32_RCC_DCKCFGR2_SDMMC2SRC RCC_DCKCFGR2_SDMMC2SEL_48MHZ
|
||||
#define STM32_RCC_DCKCFGR2_DSISRC RCC_DCKCFGR2_DSISEL_PHY
|
||||
|
||||
|
||||
/* Several prescalers allow the configuration of the two AHB buses, the
|
||||
* high-speed APB (APB2) and the low-speed APB (APB1) domains. The maximum
|
||||
* frequency of the two AHB buses is 216 MHz while the maximum frequency of
|
||||
@ -211,10 +210,10 @@
|
||||
#define STM32_APB2_TIM10_CLKIN (2*STM32_PCLK2_FREQUENCY)
|
||||
#define STM32_APB2_TIM11_CLKIN (2*STM32_PCLK2_FREQUENCY)
|
||||
|
||||
/* SDMMC dividers. Note that slower clocking is required when DMA is disabled
|
||||
* in order to avoid RX overrun/TX underrun errors due to delayed responses
|
||||
* to service FIFOs in interrupt driven mode. These values have not been
|
||||
* tuned!!!
|
||||
/* SDMMC dividers. Note that slower clocking is required when DMA
|
||||
* is disabledin order to avoid RX overrun/TX underrun errors due
|
||||
* to delayed responses to service FIFOs in interrupt driven mode.
|
||||
* These values have not been tuned!!!
|
||||
*
|
||||
* SDMMCCLK=48MHz, SDMMC_CK=SDMMCCLK/(118+2)=400 KHz
|
||||
*/
|
||||
@ -248,7 +247,7 @@
|
||||
# define GPIO_SDMMC2_D3 GPIO_SDMMC2_D3_1
|
||||
#endif
|
||||
|
||||
/* DMA Channel/Stream Selections *********************************************/
|
||||
/* DMA Channel/Stream Selections ********************************************/
|
||||
|
||||
/* Stream selections are arbitrary for now but might become important in the
|
||||
* future if we set aside more DMA channels/streams.
|
||||
@ -267,7 +266,6 @@
|
||||
#define DMAMAP_SDMMC1 DMAMAP_SDMMC1_1
|
||||
#define DMAMAP_SDMMC2 DMAMAP_SDMMC2_1
|
||||
|
||||
|
||||
/* FLASH wait states
|
||||
*
|
||||
* --------- ---------- -----------
|
||||
@ -311,13 +309,14 @@
|
||||
#define BOARD_LED3_BIT (1 << BOARD_LED3)
|
||||
|
||||
/* If CONFIG_ARCH_LEDS is defined, the usage by the board port is defined in
|
||||
* include/board.h and src/stm32_leds.c. The LEDs are used to encode OS-related
|
||||
* events as follows:
|
||||
* include/board.h and src/stm32_leds.c. The LEDs are used to encode
|
||||
* OS-relatedevents as follows:
|
||||
*
|
||||
*
|
||||
* SYMBOL Meaning LED state
|
||||
* Red Green Blue
|
||||
* ---------------------- -------------------------- ------ ------ ----*/
|
||||
* ---------------------- -------------------------- ------ ------ ----
|
||||
*/
|
||||
|
||||
#define LED_STARTED 0 /* NuttX has been started OFF OFF OFF */
|
||||
#define LED_HEAPALLOCATE 1 /* Heap has been allocated OFF OFF ON */
|
||||
@ -350,6 +349,22 @@
|
||||
|
||||
/* TIM */
|
||||
|
||||
/* Quadrature encoder
|
||||
* Default is to use timer 8 (16-bit) and encoder on PC6/PC7
|
||||
* We use here TIM2 with a 32-bit counter on PA15/PB3
|
||||
*/
|
||||
#define GPIO_TIM2_CH1IN GPIO_TIM2_CH1IN_2
|
||||
#define GPIO_TIM2_CH2IN GPIO_TIM2_CH2IN_2
|
||||
|
||||
/* PWM
|
||||
* Use Timer 3
|
||||
*/
|
||||
|
||||
#define GPIO_TIM3_CH1OUT GPIO_TIM3_CH1OUT_1
|
||||
#define GPIO_TIM3_CH2OUT GPIO_TIM3_CH2OUT_1
|
||||
#define GPIO_TIM3_CH3OUT GPIO_TIM3_CH3OUT_1
|
||||
#define GPIO_TIM3_CH4OUT GPIO_TIM3_CH4OUT_1
|
||||
|
||||
#define GPIO_TIM1_CH1OUT GPIO_TIM1_CH1OUT_1
|
||||
#define GPIO_TIM2_CH1OUT GPIO_TIM2_CH1OUT_1
|
||||
#define GPIO_TIM3_CH1OUT GPIO_TIM3_CH1OUT_1
|
||||
@ -359,8 +374,8 @@
|
||||
|
||||
/* USART6:
|
||||
*
|
||||
* These configurations assume that you are using a standard Arduio RS-232 shield
|
||||
* with the serial interface with RX on pin D0 and TX on pin D1:
|
||||
* These configurations assume that you are using a standard Arduio RS-232
|
||||
* shield with the serial interface with RX on pin D0 and TX on pin D1:
|
||||
*
|
||||
* -------- ---------------
|
||||
* STM32F7
|
||||
@ -508,5 +523,12 @@
|
||||
#define GPIO_ETH_RMII_TX_EN GPIO_ETH_RMII_TX_EN_2
|
||||
#define GPIO_ETH_RMII_TXD0 GPIO_ETH_RMII_TXD0_2
|
||||
#define GPIO_ETH_RMII_TXD1 GPIO_ETH_RMII_TXD1_1
|
||||
#define GPIO_ETH_MII_COL GPIO_ETH_COL_1
|
||||
|
||||
/* CAN Bus
|
||||
* CAN1 on pin PD0/PD1
|
||||
*/
|
||||
#define GPIO_CAN1_TX GPIO_CAN1_TX_3
|
||||
#define GPIO_CAN1_RX GPIO_CAN1_RX_3
|
||||
|
||||
#endif /* __BOARDS_ARM_STM32F7_NUCLEO_144_INCLUDE_BOARD_H */
|
||||
|
@ -72,4 +72,12 @@ ifeq ($(CONFIG_STM32_ROMFS),y)
|
||||
CSRCS += stm32_romfs_initialize.c
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_SENSORS_QENCODER),y)
|
||||
CSRCS += stm32_qencoder.c
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_CAN),y)
|
||||
CSRCS += stm32_can.c
|
||||
endif
|
||||
|
||||
include $(TOPDIR)/boards/Board.mk
|
||||
|
@ -182,15 +182,26 @@
|
||||
|
||||
/* GPIO pins used by the GPIO Subsystem */
|
||||
|
||||
#define BOARD_NGPIOIN 1 /* Amount of GPIO Input pins */
|
||||
#define BOARD_NGPIOOUT 1 /* Amount of GPIO Output pins */
|
||||
#define BOARD_NGPIOINT 1 /* Amount of GPIO Input w/ Interruption pins */
|
||||
#define BOARD_NGPIOIN 4 /* Amount of GPIO Input pins */
|
||||
#define BOARD_NGPIOOUT 4 /* Amount of GPIO Output pins */
|
||||
#define BOARD_NGPIOINT 1 /* Amount of GPIO Input w/ Interruption pins */
|
||||
|
||||
#define GPIO_IN1 (GPIO_INPUT | GPIO_FLOAT | GPIO_PORTB | GPIO_PIN0)
|
||||
#define GPIO_OUT1 (GPIO_OUTPUT | GPIO_OUTPUT | GPIO_SPEED_50MHz | \
|
||||
GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN1)
|
||||
#define GPIO_INT1 (GPIO_INPUT | GPIO_FLOAT | GPIO_PORTB | GPIO_PIN2)
|
||||
|
||||
#define GPIO_IN1 (GPIO_INPUT | GPIO_FLOAT | GPIO_PORTE | GPIO_PIN8)
|
||||
#define GPIO_IN2 (GPIO_INPUT | GPIO_FLOAT | GPIO_PORTE | GPIO_PIN7)
|
||||
#define GPIO_IN3 (GPIO_INPUT | GPIO_FLOAT | GPIO_PORTE | GPIO_PIN10)
|
||||
#define GPIO_IN4 (GPIO_INPUT | GPIO_FLOAT | GPIO_PORTE | GPIO_PIN12)
|
||||
|
||||
#define GPIO_OUT1 (GPIO_OUTPUT | GPIO_OUTPUT | GPIO_SPEED_50MHz | \
|
||||
GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN13)
|
||||
#define GPIO_OUT2 (GPIO_OUTPUT | GPIO_OUTPUT | GPIO_SPEED_50MHz | \
|
||||
GPIO_OUTPUT_SET | GPIO_PORTE | GPIO_PIN9)
|
||||
#define GPIO_OUT3 (GPIO_OUTPUT | GPIO_OUTPUT | GPIO_SPEED_50MHz | \
|
||||
GPIO_OUTPUT_SET | GPIO_PORTE | GPIO_PIN11)
|
||||
#define GPIO_OUT4 (GPIO_OUTPUT | GPIO_OUTPUT | GPIO_SPEED_50MHz | \
|
||||
GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN14)
|
||||
|
||||
/****************************************************************************
|
||||
* Public Data
|
||||
****************************************************************************/
|
||||
@ -301,5 +312,13 @@ int stm32_adc_setup(void);
|
||||
int stm32_bbsram_int(void);
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Name: stm32F746_qencoder_initialize
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef CONFIG_SENSORS_QENCODER
|
||||
int stm32f7_qencoder_initialize(FAR const char *devpath, int timer);
|
||||
#endif
|
||||
|
||||
#endif /* __ASSEMBLY__ */
|
||||
#endif /* __BOARDS_ARM_STM32F7_NUCLEO_144_SRC_NUCLEO_144_H */
|
||||
|
@ -44,6 +44,7 @@
|
||||
#include <sys/types.h>
|
||||
#include <debug.h>
|
||||
#include <syslog.h>
|
||||
#include <stdio.h>
|
||||
|
||||
#include "nucleo-144.h"
|
||||
#include <nuttx/fs/fs.h>
|
||||
@ -52,6 +53,18 @@
|
||||
#include "stm32_romfs.h"
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_DEV_GPIO
|
||||
int stm32_gpio_initialize(void);
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_SENSORS_QENCODER
|
||||
int stm32f7_qencoder_initialize(FAR const char *devpath, int timer);
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32F7_CAN
|
||||
int stm32f7_can_setup(void);
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
@ -184,6 +197,29 @@ int board_app_initialize(uintptr_t arg)
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_SENSORS_QENCODER
|
||||
char buf[9];
|
||||
|
||||
sprintf(buf, "/dev/qe0");
|
||||
ret = stm32f7_qencoder_initialize(buf, 2);
|
||||
if (ret < 0)
|
||||
{
|
||||
syslog(LOG_ERR,
|
||||
"ERROR: Failed to register the qencoder: %d\n",
|
||||
ret);
|
||||
return ret;
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_CAN
|
||||
ret = stm32f7_can_setup();
|
||||
if (ret < 0)
|
||||
{
|
||||
syslog(LOG_ERR, "ERROR: stm32f7_can_setup failed: %d\n", ret);
|
||||
return ret;
|
||||
}
|
||||
#endif
|
||||
|
||||
UNUSED(ret);
|
||||
return OK;
|
||||
}
|
||||
|
@ -122,6 +122,9 @@ static const struct gpio_operations_s gpint_ops =
|
||||
static const uint32_t g_gpioinputs[BOARD_NGPIOIN] =
|
||||
{
|
||||
GPIO_IN1,
|
||||
GPIO_IN2,
|
||||
GPIO_IN3,
|
||||
GPIO_IN4,
|
||||
};
|
||||
|
||||
static struct stm32gpio_dev_s g_gpin[BOARD_NGPIOIN];
|
||||
@ -133,6 +136,9 @@ static struct stm32gpio_dev_s g_gpin[BOARD_NGPIOIN];
|
||||
static const uint32_t g_gpiooutputs[BOARD_NGPIOOUT] =
|
||||
{
|
||||
GPIO_OUT1,
|
||||
GPIO_OUT2,
|
||||
GPIO_OUT3,
|
||||
GPIO_OUT4,
|
||||
};
|
||||
|
||||
static struct stm32gpio_dev_s g_gpout[BOARD_NGPIOOUT];
|
||||
|
@ -989,7 +989,7 @@ static inline ssize_t can_rtrread(FAR struct file *filep,
|
||||
|
||||
request->ci_msg->cm_hdr.ch_rtr = 1;
|
||||
ret = can_write(filep,
|
||||
request->ci_msg,
|
||||
(const char *) request->ci_msg,
|
||||
CAN_MSGLEN(request->ci_msg->cm_hdr.ch_dlc));
|
||||
request->ci_msg->cm_hdr.ch_rtr = 0;
|
||||
#else
|
||||
|
@ -862,11 +862,12 @@ int rwb_initialize(FAR struct rwbuffer_s *rwb)
|
||||
rwb->rhbuffer = kmm_malloc(allocsize);
|
||||
if (!rwb->rhbuffer)
|
||||
{
|
||||
ferr("Read-ahead buffer kmm_malloc(%d) failed\n", allocsize);
|
||||
ferr("Read-ahead buffer kmm_malloc(%" PRIu32 ") failed\n",
|
||||
allocsize);
|
||||
return -ENOMEM;
|
||||
}
|
||||
|
||||
finfo("Read-ahead buffer size: %d bytes\n", allocsize);
|
||||
finfo("Read-ahead buffer size: %" PRIu32 " bytes\n", allocsize);
|
||||
}
|
||||
#endif /* CONFIG_DRVR_READAHEAD */
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user