diff --git a/ROMFS/px4fmu_common/init.d/airframes/13013_deltaquad b/ROMFS/px4fmu_common/init.d/airframes/13013_deltaquad index 984ea09e99..827d0ae971 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13013_deltaquad +++ b/ROMFS/px4fmu_common/init.d/airframes/13013_deltaquad @@ -99,8 +99,6 @@ param set-default MPC_YAWRAUTO_MAX 20 param set-default NAV_LOITER_RAD 100 -param set-default PWM_AUX_DISARM 950 - param set-default PWM_MAIN_DIS5 1500 param set-default PWM_MAIN_DIS6 1500 param set-default PWM_MAIN_DIS7 900 diff --git a/ROMFS/px4fmu_common/init.d/airframes/13014_vtol_babyshark b/ROMFS/px4fmu_common/init.d/airframes/13014_vtol_babyshark index 519c0279ff..e5eaebe9a7 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13014_vtol_babyshark +++ b/ROMFS/px4fmu_common/init.d/airframes/13014_vtol_babyshark @@ -76,7 +76,6 @@ param set-default NAV_ACC_RAD 3 param set-default PWM_MAIN_DIS3 1000 param set-default PWM_MAIN_MIN3 1120 -param set-default PWM_MAIN_MIN 950 param set-default SENS_BOARD_ROT 4 diff --git a/ROMFS/px4fmu_common/init.d/airframes/17003_TF-G2 b/ROMFS/px4fmu_common/init.d/airframes/17003_TF-G2 index d6b2feb2c0..4596edf8d7 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/17003_TF-G2 +++ b/ROMFS/px4fmu_common/init.d/airframes/17003_TF-G2 @@ -24,9 +24,6 @@ param set-default BAT1_CAPACITY 3300 param set-default BAT1_N_CELLS 3 -param set-default PWM_AUX_RATE 50 -param set-default PWM_MAIN_RATE 50 - param set-default SENS_BOARD_ROT 4 param set-default FW_AIRSPD_MAX 20 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4016_holybro_px4vision b/ROMFS/px4fmu_common/init.d/airframes/4016_holybro_px4vision index 6b832b431c..48704001d3 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4016_holybro_px4vision +++ b/ROMFS/px4fmu_common/init.d/airframes/4016_holybro_px4vision @@ -80,9 +80,6 @@ param set-default CP_GO_NO_DATA 1 # Navigator Parameters param set-default NAV_ACC_RAD 2 -# use oneshot motor output protocol -param set-default PWM_MAIN_RATE 0 - # RTL Parameters param set-default RTL_DESCEND_ALT 5 param set-default RTL_RETURN_ALT 5 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4052_holybro_qav250 b/ROMFS/px4fmu_common/init.d/airframes/4052_holybro_qav250 index 68103e15a7..5f29750ece 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4052_holybro_qav250 +++ b/ROMFS/px4fmu_common/init.d/airframes/4052_holybro_qav250 @@ -44,8 +44,6 @@ param set-default MPC_THR_HOVER 0.25 param set-default MPC_THR_MIN 0.05 param set-default MPC_Z_VEL_I_ACC 1.7 -param set-default PWM_MAIN_MIN 1050 - param set-default THR_MDL_FAC 0.3 param set-default CA_ROTOR_COUNT 4 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4071_ifo b/ROMFS/px4fmu_common/init.d/airframes/4071_ifo index a1b816a5b6..f6a39c8865 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4071_ifo +++ b/ROMFS/px4fmu_common/init.d/airframes/4071_ifo @@ -32,7 +32,6 @@ param set-default IMU_DGYRO_CUTOFF 90 param set-default IMU_GYRO_CUTOFF 100 # System -param set-default PWM_MAIN_MIN 1100 param set-default SENS_BOARD_ROT 10 diff --git a/ROMFS/px4fmu_common/init.d/airframes/6002_draco_r b/ROMFS/px4fmu_common/init.d/airframes/6002_draco_r index da3cf3571d..0827fb42d8 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/6002_draco_r +++ b/ROMFS/px4fmu_common/init.d/airframes/6002_draco_r @@ -61,7 +61,6 @@ param set-default IMU_GYRO_CUTOFF 100 param set-default THR_MDL_FAC 0.25 # System -param set-default PWM_MAIN_MIN 1100 param set-default PWM_MAIN_DIS5 980 param set-default PWM_MAIN_DIS6 980 diff --git a/ROMFS/px4fmu_common/init.d/rc.fw_defaults b/ROMFS/px4fmu_common/init.d/rc.fw_defaults index 6f5d9cdf6a..df26a114ca 100644 --- a/ROMFS/px4fmu_common/init.d/rc.fw_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.fw_defaults @@ -46,8 +46,6 @@ param set-default MIS_DIST_WPS 5000 param set-default MIS_LTRMIN_ALT 25 param set-default MIS_TAKEOFF_ALT 25 -param set-default PWM_MAIN_RATE 50 - # # FW takeoff acceleration can easily exceed ublox GPS 2G default. # diff --git a/ROMFS/px4fmu_common/init.d/rc.mc_defaults b/ROMFS/px4fmu_common/init.d/rc.mc_defaults index 25861aae45..7b2b9b095d 100644 --- a/ROMFS/px4fmu_common/init.d/rc.mc_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.mc_defaults @@ -20,8 +20,4 @@ param set-default NAV_ACC_RAD 2 param set-default RTL_RETURN_ALT 30 param set-default RTL_DESCEND_ALT 10 -param set-default PWM_MAIN_MAX 1950 -param set-default PWM_MAIN_MIN 1075 -param set-default PWM_MAIN_RATE 400 - param set-default GPS_UBX_DYNMODEL 6 diff --git a/ROMFS/px4fmu_common/init.d/rc.uuv_defaults b/ROMFS/px4fmu_common/init.d/rc.uuv_defaults index bb28c26222..3398fac3f5 100644 --- a/ROMFS/px4fmu_common/init.d/rc.uuv_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.uuv_defaults @@ -9,7 +9,3 @@ set VEHICLE_TYPE uuv # MAV_TYPE_SUBMARINE 12 param set-default MAV_TYPE 12 - -param set-default PWM_MAIN_MAX 1950 -param set-default PWM_MAIN_MIN 1050 -param set-default PWM_MAIN_DISARM 1500 diff --git a/ROMFS/px4fmu_common/init.d/rc.vtol_defaults b/ROMFS/px4fmu_common/init.d/rc.vtol_defaults index ea2bf54566..2745a250f9 100644 --- a/ROMFS/px4fmu_common/init.d/rc.vtol_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.vtol_defaults @@ -36,9 +36,6 @@ param set-default MC_YAW_P 2 param set-default MC_YAWRATE_MAX 120 param set-default MPC_MAN_Y_MAX 90 -param set-default PWM_AUX_RATE 50 -param set-default PWM_MAIN_RATE 400 - param set-default RTL_TYPE 1 param set-default WV_EN 1 diff --git a/posix-configs/bbblue/px4.config b/posix-configs/bbblue/px4.config index 7ae7ed0f27..ce973f2cff 100644 --- a/posix-configs/bbblue/px4.config +++ b/posix-configs/bbblue/px4.config @@ -18,16 +18,6 @@ param set CBRK_SUPPLY_CHK 894281 # 4001: Generic Quadrotor X; 4011: DJI Flame Wheel F450 param set SYS_AUTOSTART 4011 -# DJI ESCs do not support calibration and need higher PWM_MIN -# http://www.dji.com/e2000/info indicates E2000 Operating Pulse Width: 1120 to 1920 μs -# It seems that all latest DJI ESC have the same range. -# Note that the setting here applies to all PWM channels. -# param set PWM_MAIN_MIN 1120 -# param set PWM_MAIN_MAX 1920 -# Not using DJI 430 LITE ESC anymore due to its hiccups: -# each random motor stop would cause a scary flip in the fly -# Replacing with 4 BLHeli32 (Wraith32 V2) ESCs solved the main problem in BBBlue porting - # Broadcast heartbeats on local network. This allows a ground control station # to automatically find the drone on the local network. diff --git a/posix-configs/bbblue/px4_fw.config b/posix-configs/bbblue/px4_fw.config index 7e3d6f0e74..158d5239c0 100644 --- a/posix-configs/bbblue/px4_fw.config +++ b/posix-configs/bbblue/px4_fw.config @@ -18,16 +18,6 @@ param set CBRK_SUPPLY_CHK 894281 # 4001: Generic Quadrotor X; 4011: DJI Flame Wheel F450 param set SYS_AUTOSTART 4011 -# DJI ESCs do not support calibration and need higher PWM_MIN -# http://www.dji.com/e2000/info indicates E2000 Operating Pulse Width: 1120 to 1920 μs -# It seems that all latest DJI ESC have the same range. -# Note that the setting here applies to all PWM channels. -# param set PWM_MAIN_MIN 1120 -# param set PWM_MAIN_MAX 1920 -# Not using DJI 430 LITE ESC anymore due to its hiccups: -# each random motor stop would cause a scary flip in the fly -# Replacing with 4 BLHeli32 (Wraith32 V2) ESCs solved the main problem in BBBlue porting - # Broadcast heartbeats on local network. This allows a ground control station # to automatically find the drone on the local network. diff --git a/src/lib/CMakeLists.txt b/src/lib/CMakeLists.txt index b0ea548871..1601c4d4e6 100644 --- a/src/lib/CMakeLists.txt +++ b/src/lib/CMakeLists.txt @@ -57,7 +57,6 @@ add_subdirectory(npfg) add_subdirectory(perf) add_subdirectory(pid) add_subdirectory(pid_design) -add_subdirectory(pwm) add_subdirectory(rate_control) add_subdirectory(rc) add_subdirectory(sensor_calibration) diff --git a/src/lib/parameters/param_translation.cpp b/src/lib/parameters/param_translation.cpp index deb3c709ed..0bb35fbf58 100644 --- a/src/lib/parameters/param_translation.cpp +++ b/src/lib/parameters/param_translation.cpp @@ -109,33 +109,6 @@ bool param_modify_on_import(bson_node_t node) } } - // 2021-01-31 (v1.12 alpha): translate PWM_MIN/PWM_MAX/PWM_DISARMED to PWM_MAIN - { - if (strcmp("PWM_MIN", node->name) == 0) { - strcpy(node->name, "PWM_MAIN_MIN"); - PX4_INFO("copying %s -> %s", "PWM_MIN", "PWM_MAIN_MIN"); - return true; - } - - if (strcmp("PWM_MAX", node->name) == 0) { - strcpy(node->name, "PWM_MAIN_MAX"); - PX4_INFO("copying %s -> %s", "PWM_MAX", "PWM_MAIN_MAX"); - return true; - } - - if (strcmp("PWM_RATE", node->name) == 0) { - strcpy(node->name, "PWM_MAIN_RATE"); - PX4_INFO("copying %s -> %s", "PWM_RATE", "PWM_MAIN_RATE"); - return true; - } - - if (strcmp("PWM_DISARMED", node->name) == 0) { - strcpy(node->name, "PWM_MAIN_DISARM"); - PX4_INFO("copying %s -> %s", "PWM_DISARMED", "PWM_MAIN_DISARM"); - return true; - } - } - // 2021-04-30: translate ASPD_STALL to FW_AIRSPD_STALL { if (strcmp("ASPD_STALL", node->name) == 0) { diff --git a/src/lib/pwm/CMakeLists.txt b/src/lib/pwm/CMakeLists.txt deleted file mode 100644 index cde11992f1..0000000000 --- a/src/lib/pwm/CMakeLists.txt +++ /dev/null @@ -1,36 +0,0 @@ -############################################################################ -# -# Copyright (c) 2021 PX4 Development Team. All rights reserved. -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions -# are met: -# -# 1. Redistributions of source code must retain the above copyright -# notice, this list of conditions and the following disclaimer. -# 2. Redistributions in binary form must reproduce the above copyright -# notice, this list of conditions and the following disclaimer in -# the documentation and/or other materials provided with the -# distribution. -# 3. Neither the name PX4 nor the names of its contributors may be -# used to endorse or promote products derived from this software -# without specific prior written permission. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS -# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED -# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE. -# -############################################################################ - -set_property(GLOBAL APPEND PROPERTY PX4_MODULE_CONFIG_FILES ${CMAKE_CURRENT_SOURCE_DIR}/pwm_main_params.yaml) -set_property(GLOBAL APPEND PROPERTY PX4_MODULE_CONFIG_FILES ${CMAKE_CURRENT_SOURCE_DIR}/pwm_aux_params.yaml) -set_property(GLOBAL APPEND PROPERTY PX4_MODULE_CONFIG_FILES ${CMAKE_CURRENT_SOURCE_DIR}/pwm_extra_params.yaml) diff --git a/src/lib/pwm/pwm_aux_params.yaml b/src/lib/pwm/pwm_aux_params.yaml deleted file mode 100644 index 2e659c9d41..0000000000 --- a/src/lib/pwm/pwm_aux_params.yaml +++ /dev/null @@ -1,101 +0,0 @@ -__max_num_config_instances: &max_num_config_instances 8 - -module_name: pwm_out - -parameters: - - group: PWM Outputs - definitions: - - PWM_AUX_OUT: - description: - short: PWM channels used as ESC outputs - long: | - Number representing the channels e.g. 134 - Channel 1, 3 and 4. - Global e.g. PWM_AUX_MIN/MAX/DISARM limits only apply to these channels. - type: int32 - min: 0 - max: 123456789 - default: 0 - - PWM_AUX_RATE: - description: - short: PWM aux output frequency - long: | - Set to 400 for industry default or 1000 for high frequency ESCs. - Set to 0 for Oneshot125. - type: int32 - unit: Hz - min: -1 - max: 2000 - default: 50 - - PWM_AUX_MIN: - description: - short: PWM aux minimum value - long: | - Set to 1000 for industry default or 900 to increase servo travel. - type: int32 - unit: us - min: 800 - max: 1400 - default: 1000 - - PWM_AUX_MAX: - description: - short: PWM aux maximum value - long: | - Set to 2000 for industry default or 2100 to increase servo travel. - type: int32 - unit: us - min: 1600 - max: 2200 - default: 2000 - - PWM_AUX_DISARM: - description: - short: PWM aux disarmed value - long: | - This is the PWM pulse the autopilot is outputting if not armed. - The main use of this parameter is to silence ESCs when they are disarmed. - type: int32 - unit: us - min: 0 - max: 2200 - default: 1500 - - PWM_AUX_TRIM${i}: - description: - short: PWM aux ${i} trim value - long: | - Set to normalized offset - type: float - min: -0.2 - max: 0.2 - decimal: 2 - num_instances: *max_num_config_instances - instance_start: 1 - default: 0 - - PWM_AUX_REV${i}: - description: - short: PWM aux ${i} reverse value - long: | - Enable to invert the channel. - Warning: Use this parameter when connected to a servo only. - For a brushless motor, invert manually two phases to reverse the direction. - type: boolean - num_instances: *max_num_config_instances - instance_start: 1 - default: 0 - - PWM_AUX_RATE${i}: - description: - short: PWM aux ${i} rate - long: | - Set the default PWM output frequency for the aux outputs - type: int32 - unit: Hz - min: 0 - max: 400 - instance_start: 1 - default: 50 diff --git a/src/lib/pwm/pwm_extra_params.yaml b/src/lib/pwm/pwm_extra_params.yaml deleted file mode 100644 index fcacc754ce..0000000000 --- a/src/lib/pwm/pwm_extra_params.yaml +++ /dev/null @@ -1,147 +0,0 @@ -__max_num_config_instances: &max_num_config_instances 8 - -module_name: pwm_out - -parameters: - - group: PWM Outputs - definitions: - - PWM_EXTRA_RATE: - description: - short: PWM extra output frequency - long: | - Set to 400 for industry default or 1000 for high frequency ESCs. - Set to 0 for Oneshot125. - type: int32 - unit: Hz - min: -1 - max: 2000 - default: 50 - - PWM_EXTRA_MIN: - description: - short: PWM extra minimum value - long: | - Set to 1000 for industry default or 900 to increase servo travel. - type: int32 - unit: us - min: 800 - max: 1400 - default: 1000 - - PWM_EXTRA_MAX: - description: - short: PWM extra maximum value - long: | - Set to 2000 for industry default or 2100 to increase servo travel. - type: int32 - unit: us - min: 1600 - max: 2200 - default: 2000 - - PWM_EXTRA_DISARM: - description: - short: PWM extra disarmed value - long: | - This is the PWM pulse the autopilot is outputting if not armed. - The main use of this parameter is to silence ESCs when they are disarmed. - type: int32 - unit: us - min: 0 - max: 2200 - default: 1500 - - PWM_EXTRA_MIN${i}: - description: - short: PWM extra ${i} minimum value - long: | - This is the minimum PWM pulse the autopilot is allowed to output. - When set to -1 the value for PWM_EXTRA_MIN will be used - type: int32 - unit: us - min: -1 - max: 1600 - num_instances: *max_num_config_instances - instance_start: 1 - default: -1 - - PWM_EXTRA_MAX${i}: - description: - short: PWM extra ${i} maximum value - long: | - This is the maximum PWM pulse the autopilot is allowed to output. - When set to -1 the value for PWM_EXTRA_MAX will be used - type: int32 - unit: us - min: -1 - max: 2150 - num_instances: *max_num_config_instances - instance_start: 1 - default: -1 - - PWM_EXTRA_FAIL${i}: - description: - short: PWM extra ${i} failsafe value - long: | - This is the PWM pulse the autopilot is outputting if in failsafe mode. - When set to -1 the value is set automatically depending if the actuator - is a motor (900us) or a servo (1500us) - type: int32 - unit: us - min: 0 - max: 2150 - num_instances: *max_num_config_instances - instance_start: 1 - default: 0 - - PWM_EXTRA_DIS${i}: - description: - short: PWM extra ${i} disarmed value - long: | - This is the PWM pulse the autopilot is outputting if not armed. - When set to -1 the value for PWM_EXTRA_DISARM will be used - type: int32 - unit: us - min: -1 - max: 2150 - num_instances: *max_num_config_instances - instance_start: 1 - default: -1 - - PWM_EXTRA_TRIM${i}: - description: - short: PWM extra ${i} trim value - long: | - Set to normalized offset - type: float - min: -0.2 - max: 0.2 - decimal: 2 - num_instances: *max_num_config_instances - instance_start: 1 - default: 0 - - PWM_EXTRA_REV${i}: - description: - short: PWM extra ${i} reverse value - long: | - Enable to invert the channel. - Warning: Use this parameter when connected to a servo only. - For a brushless motor, invert manually two phases to reverse the direction. - type: boolean - num_instances: *max_num_config_instances - instance_start: 1 - default: 0 - - PWM_EXTRA_RATE${i}: - description: - short: PWM extra ${i} rate - long: | - Set the default PWM output frequency for the main outputs - type: int32 - unit: Hz - min: 0 - max: 400 - instance_start: 1 - default: 50 diff --git a/src/lib/pwm/pwm_main_params.yaml b/src/lib/pwm/pwm_main_params.yaml deleted file mode 100644 index ec4b5be769..0000000000 --- a/src/lib/pwm/pwm_main_params.yaml +++ /dev/null @@ -1,101 +0,0 @@ -__max_num_config_instances: &max_num_config_instances 14 - -module_name: pwm_out - -parameters: - - group: PWM Outputs - definitions: - - PWM_MAIN_OUT: - description: - short: PWM channels used as ESC outputs - long: | - Number representing the channels e.g. 134 - Channel 1, 3 and 4. - Global e.g. PWM_MAIN_MIN/MAX/DISARM limits only apply to these channels. - type: int32 - min: 0 - max: 123456789 - default: 0 - - PWM_MAIN_RATE: - description: - short: PWM main output frequency - long: | - Set to 400 for industry default or 1000 for high frequency ESCs. - Set to 0 for Oneshot125. - type: int32 - unit: Hz - min: -1 - max: 2000 - default: 400 - - PWM_MAIN_MIN: - description: - short: PWM main minimum value - long: | - Set to 1000 for industry default or 900 to increase servo travel. - type: int32 - unit: us - min: 800 - max: 1400 - default: 1000 - - PWM_MAIN_MAX: - description: - short: PWM main maximum value - long: | - Set to 2000 for industry default or 2100 to increase servo travel. - type: int32 - unit: us - min: 1600 - max: 2200 - default: 2000 - - PWM_MAIN_DISARM: - description: - short: PWM main disarmed value - long: | - This is the PWM pulse the autopilot is outputting if not armed. - The main use of this parameter is to silence ESCs when they are disarmed. - type: int32 - unit: us - min: 0 - max: 2200 - default: 900 - - PWM_MAIN_TRIM${i}: - description: - short: PWM main ${i} trim value - long: | - Set to normalized offset - type: float - min: -0.2 - max: 0.2 - decimal: 2 - num_instances: *max_num_config_instances - instance_start: 1 - default: 0 - - PWM_MAIN_REV${i}: - description: - short: PWM main ${i} reverse value - long: | - Enable to invert the channel. - Warning: Use this parameter when connected to a servo only. - For a brushless motor, invert manually two phases to reverse the direction. - type: boolean - num_instances: *max_num_config_instances - instance_start: 1 - default: 0 - - PWM_MAIN_RATE${i}: - description: - short: PWM main ${i} rate - long: | - Set the default PWM output frequency for the main outputs - type: int32 - unit: Hz - min: 0 - max: 400 - instance_start: 1 - default: 50