update credits
[librepilot.git] / flight / pios / stm32f30x / pios_gpio.c
blobb87ed6e0a48b7bfd96b4e3a299c7bf31e4b16522
1 /**
2 ******************************************************************************
3 * @addtogroup PIOS PIOS Core hardware abstraction layer
4 * @{
5 * @addtogroup PIOS_GPIO GPIO Functions
6 * @brief STM32 Hardware GPIO handling code
7 * @{
9 * @file pios_gpio.c
10 * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
11 * @brief GPIO functions, init, toggle, on & off.
12 * @see The GNU Public License (GPL) Version 3
14 *****************************************************************************/
16 * This program is free software; you can redistribute it and/or modify
17 * it under the terms of the GNU General Public License as published by
18 * the Free Software Foundation; either version 3 of the License, or
19 * (at your option) any later version.
21 * This program is distributed in the hope that it will be useful, but
22 * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
23 * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
24 * for more details.
26 * You should have received a copy of the GNU General Public License along
27 * with this program; if not, write to the Free Software Foundation, Inc.,
28 * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
31 #include "pios.h"
33 #ifdef PIOS_INCLUDE_GPIO
35 #include <pios_gpio_priv.h>
37 /**
38 * Initialises all the GPIO's
40 int32_t PIOS_GPIO_Init(uint32_t *gpios_dev_id, const struct pios_gpio_cfg *cfg)
42 PIOS_Assert(cfg);
43 *gpios_dev_id = (uint32_t)cfg;
45 for (uint8_t i = 0; i < cfg->num_gpios; i++) {
46 const struct pios_gpio *gpio = &(cfg->gpios[i]);
48 /* Enable the peripheral clock for the GPIO */
49 switch ((uint32_t)gpio->pin.gpio) {
50 case (uint32_t)GPIOA:
51 RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOA, ENABLE);
52 break;
53 case (uint32_t)GPIOB:
54 RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOB, ENABLE);
55 break;
56 case (uint32_t)GPIOC:
57 RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOC, ENABLE);
58 break;
59 case (uint32_t)GPIOD:
60 RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOD, ENABLE);
61 break;
62 case (uint32_t)GPIOE:
63 RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOE, ENABLE);
64 break;
65 case (uint32_t)GPIOF:
66 RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOF, ENABLE);
67 break;
68 default:
69 PIOS_Assert(0);
70 break;
73 if (gpio->remap) {
74 GPIO_PinAFConfig(gpio->pin.gpio, gpio->pin.init.GPIO_Pin, gpio->remap);
77 GPIO_Init(gpio->pin.gpio, &((struct pios_gpio *)gpio)->pin.init);
79 PIOS_GPIO_Off(*gpios_dev_id, i);
82 return 0;
85 /**
86 * Turn on GPIO
87 * \param[in] GPIO GPIO id
89 void PIOS_GPIO_On(uint32_t gpios_dev_id, uint8_t gpio_id)
91 const struct pios_gpio_cfg *gpio_cfg = (const struct pios_gpio_cfg *)gpios_dev_id;
93 PIOS_Assert(gpio_cfg);
95 if (gpio_id >= gpio_cfg->num_gpios) {
96 /* GPIO index out of range */
97 return;
100 const struct pios_gpio *gpio = &(gpio_cfg->gpios[gpio_id]);
102 if (gpio->active_low) {
103 GPIO_ResetBits(gpio->pin.gpio, gpio->pin.init.GPIO_Pin);
104 } else {
105 GPIO_SetBits(gpio->pin.gpio, gpio->pin.init.GPIO_Pin);
110 * Turn off GPIO
111 * \param[in] GPIO GPIO id
113 void PIOS_GPIO_Off(uint32_t gpios_dev_id, uint8_t gpio_id)
115 const struct pios_gpio_cfg *gpio_cfg = (const struct pios_gpio_cfg *)gpios_dev_id;
117 PIOS_Assert(gpio_cfg);
119 if (gpio_id >= gpio_cfg->num_gpios) {
120 /* GPIO index out of range */
121 return;
124 const struct pios_gpio *gpio = &(gpio_cfg->gpios[gpio_id]);
126 if (gpio->active_low) {
127 GPIO_SetBits(gpio->pin.gpio, gpio->pin.init.GPIO_Pin);
128 } else {
129 GPIO_ResetBits(gpio->pin.gpio, gpio->pin.init.GPIO_Pin);
134 * Toggle GPIO on/off
135 * \param[in] GPIO GPIO id
137 void PIOS_GPIO_Toggle(uint32_t gpios_dev_id, uint8_t gpio_id)
139 const struct pios_gpio_cfg *gpio_cfg = (const struct pios_gpio_cfg *)gpios_dev_id;
141 PIOS_Assert(gpio_cfg);
143 if (gpio_id >= gpio_cfg->num_gpios) {
144 /* GPIO index out of range */
145 return;
148 const struct pios_gpio *gpio = &(gpio_cfg->gpios[gpio_id]);
150 if (GPIO_ReadOutputDataBit(gpio->pin.gpio, gpio->pin.init.GPIO_Pin) == Bit_SET) {
151 if (gpio->active_low) {
152 PIOS_GPIO_On(gpios_dev_id, gpio_id);
153 } else {
154 PIOS_GPIO_Off(gpios_dev_id, gpio_id);
156 } else {
157 if (gpio->active_low) {
158 PIOS_GPIO_Off(gpios_dev_id, gpio_id);
159 } else {
160 PIOS_GPIO_On(gpios_dev_id, gpio_id);
165 #endif /* PIOS_INCLUDE_GPIO */
168 * @}
169 * @}