aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2015-02-26 17:57:58 +0100
committerLorenz Meier <lm@inf.ethz.ch>2015-02-28 11:22:19 +0100
commitdfdf741b130d02681092cbbf3b49c1f0d051f14f (patch)
tree83d61db832814f3e9e94497baadef2a2f71f20e1
parent07970689d4d326c9140bc128ddf495d056bf5fd6 (diff)
downloadpx4-firmware-dfdf741b130d02681092cbbf3b49c1f0d051f14f.tar.gz
px4-firmware-dfdf741b130d02681092cbbf3b49c1f0d051f14f.tar.bz2
px4-firmware-dfdf741b130d02681092cbbf3b49c1f0d051f14f.zip
FMU: Make peripheral rail power controllable
-rw-r--r--src/drivers/drv_gpio.h2
-rw-r--r--src/drivers/px4fmu/fmu.cpp59
2 files changed, 61 insertions, 0 deletions
diff --git a/src/drivers/drv_gpio.h b/src/drivers/drv_gpio.h
index bacafe1dc..be9604b6e 100644
--- a/src/drivers/drv_gpio.h
+++ b/src/drivers/drv_gpio.h
@@ -159,4 +159,6 @@
#define GPIO_SENSOR_RAIL_RESET GPIOC(13)
+#define GPIO_PERIPHERAL_RAIL_RESET GPIOC(14)
+
#endif /* _DRV_GPIO_H */
diff --git a/src/drivers/px4fmu/fmu.cpp b/src/drivers/px4fmu/fmu.cpp
index 8e7e93679..b5907c1cc 100644
--- a/src/drivers/px4fmu/fmu.cpp
+++ b/src/drivers/px4fmu/fmu.cpp
@@ -182,6 +182,7 @@ private:
void gpio_reset(void);
void sensor_reset(int ms);
+ void peripheral_reset(int ms);
void gpio_set_function(uint32_t gpios, int function);
void gpio_write(uint32_t gpios, int function);
uint32_t gpio_read(void);
@@ -1376,6 +1377,29 @@ PX4FMU::sensor_reset(int ms)
#endif
}
+void
+PX4FMU::peripheral_reset(int ms)
+{
+#if defined(CONFIG_ARCH_BOARD_PX4FMU_V2)
+
+ if (ms < 1) {
+ ms = 1;
+ }
+
+ /* set the peripheral rails off */
+ stm32_configgpio(GPIO_VDD_5V_PERIPH_EN);
+ stm32_gpiowrite(GPIO_VDD_5V_PERIPH_EN, 0);
+
+ /* wait for the peripheral rail to reach GND */
+ usleep(ms * 1000);
+ warnx("reset done, %d ms", ms);
+
+ /* re-enable power */
+
+ /* switch the peripheral rail back on */
+ stm32_gpiowrite(GPIO_VDD_5V_PERIPH_EN, 1);
+#endif
+}
void
PX4FMU::gpio_reset(void)
@@ -1488,6 +1512,10 @@ PX4FMU::gpio_ioctl(struct file *filp, int cmd, unsigned long arg)
sensor_reset(arg);
break;
+ case GPIO_PERIPHERAL_RAIL_RESET:
+ peripheral_reset(arg);
+ break;
+
case GPIO_SET_OUTPUT:
case GPIO_SET_INPUT:
case GPIO_SET_ALT_1:
@@ -1675,6 +1703,24 @@ sensor_reset(int ms)
}
void
+peripheral_reset(int ms)
+{
+ int fd;
+
+ fd = open(PX4FMU_DEVICE_PATH, O_RDWR);
+
+ if (fd < 0) {
+ errx(1, "open fail");
+ }
+
+ if (ioctl(fd, GPIO_PERIPHERAL_RAIL_RESET, ms) < 0) {
+ warnx("peripheral rail reset failed");
+ }
+
+ close(fd);
+}
+
+void
test(void)
{
int fd;
@@ -1895,6 +1941,19 @@ fmu_main(int argc, char *argv[])
exit(0);
}
+ if (!strcmp(verb, "peripheral_reset")) {
+ if (argc > 2) {
+ int reset_time = strtol(argv[2], 0, 0);
+ peripheral_reset(reset_time);
+
+ } else {
+ peripheral_reset(0);
+ warnx("resettet default time");
+ }
+
+ exit(0);
+ }
+
if (!strcmp(verb, "i2c")) {
if (argc > 3) {
int bus = strtol(argv[2], 0, 0);