mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
HAL_ChibiOS: added palReadLineMode() function
used to change and restore line modes
This commit is contained in:
parent
645629baa2
commit
067de3849c
@ -276,3 +276,26 @@ void peripheral_power_enable(void)
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
#if defined(STM32F7) || defined(STM32F4)
|
||||
/*
|
||||
read mode of a pin. This allows a pin config to be read, changed and
|
||||
then written back
|
||||
*/
|
||||
iomode_t palReadLineMode(ioline_t line)
|
||||
{
|
||||
ioportid_t port = PAL_PORT(line);
|
||||
uint8_t pad = PAL_PAD(line);
|
||||
iomode_t ret = 0;
|
||||
ret |= (port->MODER >> (pad*2)) & 0x3;
|
||||
ret |= ((port->OTYPER >> pad)&1) << 2;
|
||||
ret |= ((port->OSPEEDR >> (pad*2))&3) << 3;
|
||||
ret |= ((port->PUPDR >> (pad*2))&3) << 5;
|
||||
if (pad < 8) {
|
||||
ret |= ((port->AFRL >> (pad*4))&0xF) << 7;
|
||||
} else {
|
||||
ret |= ((port->AFRH >> ((pad-8)*4))&0xF) << 7;
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
#endif
|
||||
|
@ -69,7 +69,15 @@ void peripheral_power_enable(void);
|
||||
|
||||
// initialise allocation subsystem
|
||||
void malloc_init(void);
|
||||
|
||||
|
||||
/*
|
||||
read mode of a pin. This allows a pin config to be read, changed and
|
||||
then written back
|
||||
*/
|
||||
#if defined(STM32F7) || defined(STM32F4)
|
||||
iomode_t palReadLineMode(ioline_t line);
|
||||
#endif
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
Loading…
Reference in New Issue
Block a user