Browse Source

delete unused GPIO_SET_ALT_1

sbg
Daniel Agar 7 years ago
parent
commit
c6760cc6fb
  1. 3
      src/drivers/drv_gpio.h
  2. 4
      src/drivers/pwm_out_sim/pwm_out_sim.cpp
  3. 7
      src/drivers/px4fmu/fmu.cpp

3
src/drivers/drv_gpio.h

@ -71,9 +71,6 @@ @@ -71,9 +71,6 @@
/** configure the board GPIOs in (arg) as inputs */
#define GPIO_SET_INPUT GPIOC(2)
/** configure the board GPIOs in (arg) for the first alternate function (if supported) */
#define GPIO_SET_ALT_1 GPIOC(3)
/** configure the board GPIO (arg) for the second alternate function (if supported) */
#define GPIO_SET_ALT_2 GPIOC(4)

4
src/drivers/pwm_out_sim/pwm_out_sim.cpp

@ -900,10 +900,6 @@ hil_new_mode(PortMode new_mode) @@ -900,10 +900,6 @@ hil_new_mode(PortMode new_mode)
break;
}
// /* adjust GPIO config for serial mode(s) */
// if (gpio_bits != 0)
// g_pwm_sim->ioctl(0, GPIO_SET_ALT_1, gpio_bits);
/* (re)set the PWM output mode */
g_pwm_sim->set_mode(servo_mode);

7
src/drivers/px4fmu/fmu.cpp

@ -2699,12 +2699,6 @@ PX4FMU::gpio_set_function(uint32_t gpios, int function) @@ -2699,12 +2699,6 @@ PX4FMU::gpio_set_function(uint32_t gpios, int function)
break;
case GPIO_SET_ALT_1:
if (_gpio_tab[i].alt != 0) {
px4_arch_configgpio(_gpio_tab[i].alt);
}
break;
}
}
}
@ -2913,7 +2907,6 @@ PX4FMU::gpio_ioctl(struct file *filp, int cmd, unsigned long arg) @@ -2913,7 +2907,6 @@ PX4FMU::gpio_ioctl(struct file *filp, int cmd, unsigned long arg)
case GPIO_SET_OUTPUT_LOW:
case GPIO_SET_OUTPUT_HIGH:
case GPIO_SET_INPUT:
case GPIO_SET_ALT_1:
ret = gpio_set_function(arg, cmd);
break;

Loading…
Cancel
Save