rddrone-uavcan146 removed shared clock between hrt & rtc

Removed non-existing SW2 button
Fixed SW3 button pinmux
Added FlexCAN pin definition
hrt use external sirc clock
rtc use 32khz lpo clock
This commit is contained in:
Peter van der Perk 2020-03-27 12:00:10 +01:00 committed by David Sidrane
parent eb1bad0185
commit 9490f41f85
5 changed files with 21 additions and 25 deletions

View File

@ -113,15 +113,12 @@
/* The RDDRONE-UAVCAN146 supports two buttons:
*
* SW2 PTC12
* SW3 PTC13
* SW3 PTC14
*/
#define BUTTON_SW2 0
#define BUTTON_SW3 1
#define NUM_BUTTONS 2
#define BUTTON_SW3 0
#define NUM_BUTTONS 1
#define BUTTON_SW2_BIT (1 << BUTTON_SW2)
#define BUTTON_SW3_BIT (1 << BUTTON_SW3)
/* Alternate function pin selections ****************************************/
@ -152,4 +149,14 @@
#define PIN_LPI2C0_SCL PIN_LPI2C0_SCL_2 /* PTA3 */
#define PIN_LPI2C0_SDA PIN_LPI2C0_SDA_2 /* PTA2 */
/* CAN selections ***********************************************************/
#define PIN_CAN0_TX PIN_CAN0_TX_4 /* PTE5 */
#define PIN_CAN0_RX PIN_CAN0_RX_4 /* PTE4 */
#define PIN_CAN0_ENABLE (GPIO_OUTPUT | PIN_PORTE | PIN11 )
#define CAN0_ENABLE_OUT 0
#define PIN_CAN1_TX PIN_CAN1_TX_1 /* PTA13 */
#define PIN_CAN1_RX PIN_CAN1_RX_1 /* PTA12 */
#define PIN_CAN1_ENABLE (GPIO_OUTPUT | PIN_PORTE | PIN10 )
#define CAN1_ENABLE_OUT 0
#endif /* __BOARDS_ARM_RDDRONE_UAVCAN146_INCLUDE_BOARD_H */

View File

@ -79,14 +79,12 @@ __BEGIN_DECLS
#define GPIO_LED_G (PIN_PTD16 | GPIO_LOWDRIVE | GPIO_OUTPUT_ZERO)
#define GPIO_LED_B (PIN_PTD0 | GPIO_LOWDRIVE | GPIO_OUTPUT_ZERO)
/* Buttons. The RDDRONE-UAVCAN146 supports two buttons:
/* Buttons. The RDDRONE-UAVCAN146 supports one button:
*
* SW2 PTC12
* SW3 PTC13
* SW3 PTC14
*/
#define GPIO_SW2 (PIN_PTC12 | PIN_INT_BOTH)
#define GPIO_SW3 (PIN_PTC13 | PIN_INT_BOTH)
#define GPIO_SW3 (PIN_PTC14 | PIN_INT_BOTH)
/* SPI chip selects */

View File

@ -33,10 +33,9 @@
*
****************************************************************************/
/* The RDDRONE-UAVCAN146 supports two buttons:
/* The RDDRONE-UAVCAN146 supports one button:
*
* SW2 PTC12
* SW3 PTC13
* SW3 PTC14
*/
/****************************************************************************
@ -77,7 +76,6 @@ void board_button_initialize(void)
{
/* Configure the GPIO pins as interrupting inputs. */
s32k1xx_pinconfig(GPIO_SW2);
s32k1xx_pinconfig(GPIO_SW3);
}
@ -89,10 +87,6 @@ uint32_t board_buttons(void)
{
uint32_t ret = 0;
if (s32k1xx_gpioread(GPIO_SW2)) {
ret |= BUTTON_SW2_BIT;
}
if (s32k1xx_gpioread(GPIO_SW3)) {
ret |= BUTTON_SW3_BIT;
}
@ -130,10 +124,7 @@ int board_button_irq(int id, xcpt_t irqhandler, FAR void *arg)
/* Map the button id to the GPIO bit set. */
if (id == BUTTON_SW2) {
pinset = GPIO_SW2;
} else if (id == BUTTON_SW3) {
if (id == BUTTON_SW3) {
pinset = GPIO_SW3;
} else {

View File

@ -164,7 +164,7 @@ const struct clock_configuration_s g_initial_clkconfig = {
},
.lpoclk = /* Low Power Clock configuration. */
{
.rtc_source = SIM_RTCCLK_SEL_SOSCDIV1_CLK, /* RTCCLKSEL */
.rtc_source = SIM_RTCCLK_SEL_LPO_32K, /* RTCCLKSEL */
.lpo_source = SIM_LPO_CLK_SEL_LPO_128K, /* LPOCLKSEL */
.initialize = true, /* Initialize */
.lpo32k = true, /* LPO32KCLKEN */

View File

@ -312,7 +312,7 @@ static void hrt_tim_init(void)
/* Use FIXEDCLK src and enable the timer
* Set calculate prescaler for HRT_TIMER_FREQ */
rSC |= (FTM_SC_TOIE | FTM_SC_CLKS_FIXED |
rSC |= (FTM_SC_TOIE | FTM_SC_CLKS_EXTCLK |
(LOG_2(HRT_TIMER_CLOCK / HRT_TIMER_FREQ) << FTM_SC_PS_SHIFT
& FTM_SC_PS_MASK));