From e04d43218afdd3894a2043f6d026ad0271a0e5b2 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Mon, 6 Mar 2017 07:04:03 -1000 Subject: [PATCH] Revert "fmu add command line onshot mode" This reverts commit 22738b1213fff704d288ec84976fa84ff9535aba. The command was added due to a lack of my understanding of how the pwm command can be used. The command is not needed as the all flag can be used or a proper mask WHIHOUT -g fmu task mode_pwm pwm rate -a -r 50 -d /dev/pwm_output0 pwm arm pwm test -a -p 500 fmu task mode_pwm pwm oneshot -a -d /dev/pwm_output0 is the same as pwm oneshot -m 0xff -d /dev/pwm_output0 pwm arm pwm test -a -p 500 --- src/drivers/px4fmu/fmu.cpp | 56 -------------------------------------- 1 file changed, 56 deletions(-) diff --git a/src/drivers/px4fmu/fmu.cpp b/src/drivers/px4fmu/fmu.cpp index e28837a5f2..e49714b24a 100644 --- a/src/drivers/px4fmu/fmu.cpp +++ b/src/drivers/px4fmu/fmu.cpp @@ -131,9 +131,6 @@ public: MODE_4CAP, MODE_5CAP, MODE_6CAP, - MODE_4ONESHOT, - MODE_6ONESHOT, - MODE_8ONESHOT, }; PX4FMU(bool run_as_task); virtual ~PX4FMU(); @@ -614,18 +611,6 @@ PX4FMU::set_mode(Mode mode) _pwm_initialized = false; break; - case MODE_4ONESHOT: - DEVICE_DEBUG("MODE_4ONESHOT"); - - /* default output rates */ - _pwm_default_rate = 0; - _pwm_alt_rate = 0; - _pwm_alt_rate_channels = 0; - _pwm_mask = 0xf; - _pwm_initialized = false; - mode = MODE_4PWM; - break; - case MODE_4PWM: // v1 or v2 multi-port as 4 PWM outs DEVICE_DEBUG("MODE_4PWM"); @@ -640,18 +625,6 @@ PX4FMU::set_mode(Mode mode) #if defined(BOARD_HAS_PWM) && BOARD_HAS_PWM >= 6 - case MODE_6ONESHOT: - DEVICE_DEBUG("MODE_6ONESHOT"); - - /* default output rates */ - _pwm_default_rate = 0; - _pwm_alt_rate = 0; - _pwm_alt_rate_channels = 0; - _pwm_mask = 0x3f; - _pwm_initialized = false; - mode = MODE_6PWM; - break; - case MODE_6PWM: DEVICE_DEBUG("MODE_6PWM"); @@ -667,18 +640,6 @@ PX4FMU::set_mode(Mode mode) #if defined(BOARD_HAS_PWM) && BOARD_HAS_PWM >= 8 - case MODE_8ONESHOT: - DEVICE_DEBUG("MODE_8ONESHOT"); - - /* default output rates */ - _pwm_default_rate = 0; - _pwm_alt_rate = 0; - _pwm_alt_rate_channels = 0; - _pwm_mask = 0xff; - _pwm_initialized = false; - mode = MODE_8PWM; - break; - case MODE_8PWM: // AeroCore PWMs as 8 PWM outs DEVICE_DEBUG("MODE_8PWM"); /* default output rates */ @@ -2999,7 +2960,6 @@ enum PortMode { PORT_PWM3CAP1, PORT_PWM2CAP2, PORT_CAPTURE, - PORT_FULL_ONESHOT, }; PortMode g_port_mode; @@ -3019,19 +2979,6 @@ fmu_new_mode(PortMode new_mode) case PORT_MODE_UNSET: break; - case PORT_FULL_ONESHOT: -#if defined(BOARD_HAS_PWM) && BOARD_HAS_PWM == 4 - /* select 4-pin PWM mode */ - servo_mode = PX4FMU::MODE_4ONESHOT; -#endif -#if defined(BOARD_HAS_PWM) && BOARD_HAS_PWM == 6 - servo_mode = PX4FMU::MODE_6ONESHOT; -#endif -#if defined(BOARD_HAS_PWM) && BOARD_HAS_PWM == 8 - servo_mode = PX4FMU::MODE_8ONESHOT; -#endif - break; - case PORT_FULL_PWM: #if defined(BOARD_HAS_PWM) && BOARD_HAS_PWM == 4 @@ -3494,9 +3441,6 @@ fmu_main(int argc, char *argv[]) } else if (!strcmp(verb, "mode_rcin")) { exit(0); - } else if (!strcmp(verb, "mode_oneshot")) { - new_mode = PORT_FULL_ONESHOT; - } else if (!strcmp(verb, "mode_pwm")) { new_mode = PORT_FULL_PWM;