Paparazzi UAS
v5.15_devel-230-gc96ce27
Paparazzi is a free software Unmanned Aircraft System.
|
#include "boards/px4fmu/chibios/v4.0/board.h"
Go to the source code of this file.
#define ActuatorDefaultSet | ( | _x, | |
_y | |||
) | ActuatorPwmSet(_x,_y) |
#define ActuatorsDefaultCommit | ( | ) | ActuatorsPwmCommit() |
#define ActuatorsDefaultInit | ( | ) | ActuatorsPwmInit() |
#define AHB_CLK STM32_HCLK |
#define DEFAULT_ACTUATORS "subsystems/actuators/actuators_pwm.h" |
#define DefaultVoltageOfAdc | ( | adc | ) | ((3.3f/4096.0f) * 10.27708149f * adc) |
#define I2C1_CFG_DEF |
#define I2C1_CLOCK_SPEED 400000 |
#define I2C2_CFG_DEF |
#define LED_1_GPIO_ON gpio_clear |
#define LED_2_GPIO_ON gpio_clear |
#define LED_3_GPIO_ON gpio_clear |
#define MilliAmpereOfAdc | ( | adc | ) | ((3.3f/4096.0f) * 36367.51556f * adc) |
#define PERIPHERAL3V3_ENABLE_OFF gpio_clear |
#define PERIPHERAL3V3_ENABLE_ON gpio_set |
Definition at line 284 of file px4fmu.h.
Referenced by mcu_init().
#define PERIPHERAL3V3_ENABLE_PIN GPIO5 |
Definition at line 283 of file px4fmu.h.
Referenced by mcu_init().
#define PERIPHERAL3V3_ENABLE_PORT GPIOC |
Definition at line 282 of file px4fmu.h.
Referenced by mcu_init().
#define PWM_CONF1_DEF |
#define PWM_CONF4_DEF |
#define RADIO_CONTROL_POWER_ON gpio_clear |
#define SDLOG_BAT_CHAN AD1_1_CHANNEL |
#define SPI1_GPIO_AF GPIO_AF5 |
#define USE_BARO_BOARD 1 |