From 220bd82b935f1e9459a528ca46b77b7c09ae07fa Mon Sep 17 00:00:00 2001
From: sanderux <sander@droneslab.com>
Date: Fri, 28 Jul 2017 15:30:53 +0200
Subject: [PATCH] Per channel PWM disarmed values

---
 ROMFS/px4fmu_common/init.d/rc.interface |  22 +++
 src/modules/sensors/sensor_params.c     | 231 +++++++++++++++++++++---
 src/systemcmds/pwm/pwm.cpp              |   4 +
 3 files changed, 236 insertions(+), 21 deletions(-)

diff --git a/ROMFS/px4fmu_common/init.d/rc.interface b/ROMFS/px4fmu_common/init.d/rc.interface
index ac94bfcb61..a4d7dfe618 100644
--- a/ROMFS/px4fmu_common/init.d/rc.interface
+++ b/ROMFS/px4fmu_common/init.d/rc.interface
@@ -102,6 +102,18 @@ then
 		fi
 	fi
 
+	#
+	# Per channel disarmed settings
+	#
+	pwm disarmed -c 1 -p p:PWM_MAIN_DIS1
+	pwm disarmed -c 2 -p p:PWM_MAIN_DIS2
+	pwm disarmed -c 3 -p p:PWM_MAIN_DIS3
+	pwm disarmed -c 4 -p p:PWM_MAIN_DIS4
+	pwm disarmed -c 5 -p p:PWM_MAIN_DIS5
+	pwm disarmed -c 6 -p p:PWM_MAIN_DIS6
+	pwm disarmed -c 7 -p p:PWM_MAIN_DIS7
+	pwm disarmed -c 8 -p p:PWM_MAIN_DIS8
+
 	if [ $FAILSAFE != none ]
 	then
 		pwm failsafe -d ${OUTPUT_DEV} ${FAILSAFE}
@@ -228,6 +240,16 @@ then
 			pwm disarmed -c ${PWM_ACHDIS} -p ${PWM_AUX_DISARMED} -d ${OUTPUT_AUX_DEV}
 		fi
 
+		#
+		# Per channel disarmed settings
+		#
+		pwm disarmed -c 1 -p p:PWM_AUX_DIS1 -d ${OUTPUT_AUX_DEV}
+		pwm disarmed -c 2 -p p:PWM_AUX_DIS2 -d ${OUTPUT_AUX_DEV}
+		pwm disarmed -c 3 -p p:PWM_AUX_DIS3 -d ${OUTPUT_AUX_DEV}
+		pwm disarmed -c 4 -p p:PWM_AUX_DIS4 -d ${OUTPUT_AUX_DEV}
+		pwm disarmed -c 5 -p p:PWM_AUX_DIS5 -d ${OUTPUT_AUX_DEV}
+		pwm disarmed -c 6 -p p:PWM_AUX_DIS6 -d ${OUTPUT_AUX_DEV}
+
 		if [ $FAILSAFE_AUX != none ]
 		then
 			pwm failsafe -d ${OUTPUT_AUX_DEV} ${FAILSAFE}
diff --git a/src/modules/sensors/sensor_params.c b/src/modules/sensors/sensor_params.c
index c1f2b4f475..0e22c8c573 100644
--- a/src/modules/sensors/sensor_params.c
+++ b/src/modules/sensors/sensor_params.c
@@ -3375,9 +3375,6 @@ PARAM_DEFINE_INT32(SENS_EN_THERMAL, -1);
 /**
  * Set the PWM output frequency for the main outputs
  *
- * IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM
- * REBOOT IN ORDER TO APPLY THE CHANGES.
- *
  * Set to 400 for industry default or 1000 for high frequency ESCs.
  *
  * Set to 0 for Oneshot125.
@@ -3394,9 +3391,6 @@ PARAM_DEFINE_INT32(PWM_RATE, 400);
 /**
  * Set the minimum PWM for the main outputs
  *
- * IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM
- * REBOOT IN ORDER TO APPLY THE CHANGES.
- *
  * Set to 1000 for industry default or 900 to increase servo travel.
  *
  * @reboot_required true
@@ -3411,9 +3405,6 @@ PARAM_DEFINE_INT32(PWM_MIN, 1000);
 /**
  * Set the maximum PWM for the main outputs
  *
- * IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM
- * REBOOT IN ORDER TO APPLY THE CHANGES.
- *
  * Set to 2000 for industry default or 2100 to increase servo travel.
  *
  * @reboot_required true
@@ -3428,9 +3419,6 @@ PARAM_DEFINE_INT32(PWM_MAX, 2000);
 /**
  * Set the disarmed PWM for the main outputs
  *
- * IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM
- * REBOOT IN ORDER TO APPLY THE CHANGES.
- *
  * 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.
  *
@@ -3444,10 +3432,217 @@ PARAM_DEFINE_INT32(PWM_MAX, 2000);
 PARAM_DEFINE_INT32(PWM_DISARMED, 900);
 
 /**
- * Set the minimum PWM for the auxiliary outputs
+ * Set the disarmed PWM for the main 1 output
+ *
+ * This is the PWM pulse the autopilot is outputting if not armed.
+ * When set to -1 the value for PWM_DISARMED will be used
+ *
+ * @reboot_required true
+ *
+ * @min -1
+ * @max 2200
+ * @unit us
+ * @group PWM Outputs
+ */
+PARAM_DEFINE_INT32(PWM_MAIN_DIS1, -1);
+
+/**
+ * Set the disarmed PWM for the main 2 output
+ *
+ * This is the PWM pulse the autopilot is outputting if not armed.
+ * When set to -1 the value for PWM_DISARMED will be used
+ *
+ * @reboot_required true
+ *
+ * @min -1
+ * @max 2200
+ * @unit us
+ * @group PWM Outputs
+ */
+PARAM_DEFINE_INT32(PWM_MAIN_DIS2, -1);
+
+/**
+ * Set the disarmed PWM for the main 3 output
+ *
+ * This is the PWM pulse the autopilot is outputting if not armed.
+ * When set to -1 the value for PWM_DISARMED will be used
+ *
+ * @reboot_required true
+ *
+ * @min -1
+ * @max 2200
+ * @unit us
+ * @group PWM Outputs
+ */
+PARAM_DEFINE_INT32(PWM_MAIN_DIS3, -1);
+
+/**
+ * Set the disarmed PWM for the main 4 output
+ *
+ * This is the PWM pulse the autopilot is outputting if not armed.
+ * When set to -1 the value for PWM_DISARMED will be used
+ *
+ * @reboot_required true
+ *
+ * @min -1
+ * @max 2200
+ * @unit us
+ * @group PWM Outputs
+ */
+PARAM_DEFINE_INT32(PWM_MAIN_DIS4, -1);
+
+/**
+ * Set the disarmed PWM for the main 5 output
+ *
+ * This is the PWM pulse the autopilot is outputting if not armed.
+ * When set to -1 the value for PWM_DISARMED will be used
+ *
+ * @reboot_required true
+ *
+ * @min -1
+ * @max 2200
+ * @unit us
+ * @group PWM Outputs
+ */
+PARAM_DEFINE_INT32(PWM_MAIN_DIS5, -1);
+
+/**
+ * Set the disarmed PWM for the main 6 output
+ *
+ * This is the PWM pulse the autopilot is outputting if not armed.
+ * When set to -1 the value for PWM_DISARMED will be used
+ *
+ * @reboot_required true
+ *
+ * @min -1
+ * @max 2200
+ * @unit us
+ * @group PWM Outputs
+ */
+PARAM_DEFINE_INT32(PWM_MAIN_DIS6, -1);
+
+/**
+ * Set the disarmed PWM for the main 7 output
  *
- * IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM
- * REBOOT IN ORDER TO APPLY THE CHANGES.
+ * This is the PWM pulse the autopilot is outputting if not armed.
+ * When set to -1 the value for PWM_DISARMED will be used
+ *
+ * @reboot_required true
+ *
+ * @min -1
+ * @max 2200
+ * @unit us
+ * @group PWM Outputs
+ */
+PARAM_DEFINE_INT32(PWM_MAIN_DIS7, -1);
+
+/**
+ * Set the disarmed PWM for the main 8 output
+ *
+ * This is the PWM pulse the autopilot is outputting if not armed.
+ * When set to -1 the value for PWM_DISARMED will be used
+ *
+ * @reboot_required true
+ *
+ * @min -1
+ * @max 2200
+ * @unit us
+ * @group PWM Outputs
+ */
+PARAM_DEFINE_INT32(PWM_MAIN_DIS8, -1);
+
+/**
+ * Set the disarmed PWM for the AUX 1 output
+ *
+ * This is the PWM pulse the autopilot is outputting if not armed.
+ * When set to -1 the value for PWM_AUX_DISARMED will be used
+ *
+ * @reboot_required true
+ *
+ * @min -1
+ * @max 2200
+ * @unit us
+ * @group PWM Outputs
+ */
+PARAM_DEFINE_INT32(PWM_AUX_DIS1, -1);
+
+/**
+ * Set the disarmed PWM for the AUX 2 output
+ *
+ * This is the PWM pulse the autopilot is outputting if not armed.
+ * When set to -1 the value for PWM_AUX_DISARMED will be used
+ *
+ * @reboot_required true
+ *
+ * @min -1
+ * @max 2200
+ * @unit us
+ * @group PWM Outputs
+ */
+PARAM_DEFINE_INT32(PWM_AUX_DIS2, -1);
+
+/**
+ * Set the disarmed PWM for the AUX 3 output
+ *
+ * This is the PWM pulse the autopilot is outputting if not armed.
+ * When set to -1 the value for PWM_AUX_DISARMED will be used
+ *
+ * @reboot_required true
+ *
+ * @min -1
+ * @max 2200
+ * @unit us
+ * @group PWM Outputs
+ */
+PARAM_DEFINE_INT32(PWM_AUX_DIS3, -1);
+
+/**
+ * Set the disarmed PWM for the AUX 4 output
+ *
+ * This is the PWM pulse the autopilot is outputting if not armed.
+ * When set to -1 the value for PWM_AUX_DISARMED will be used
+ *
+ * @reboot_required true
+ *
+ * @min -1
+ * @max 2200
+ * @unit us
+ * @group PWM Outputs
+ */
+PARAM_DEFINE_INT32(PWM_AUX_DIS4, -1);
+
+/**
+ * Set the disarmed PWM for the AUX 5 output
+ *
+ * This is the PWM pulse the autopilot is outputting if not armed.
+ * When set to -1 the value for PWM_AUX_DISARMED will be used
+ *
+ * @reboot_required true
+ *
+ * @min -1
+ * @max 2200
+ * @unit us
+ * @group PWM Outputs
+ */
+PARAM_DEFINE_INT32(PWM_AUX_DIS5, -1);
+
+/**
+ * Set the disarmed PWM for the AUX 6 output
+ *
+ * This is the PWM pulse the autopilot is outputting if not armed.
+ * When set to -1 the value for PWM_AUX_DISARMED will be used
+ *
+ * @reboot_required true
+ *
+ * @min -1
+ * @max 2200
+ * @unit us
+ * @group PWM Outputs
+ */
+PARAM_DEFINE_INT32(PWM_AUX_DIS6, -1);
+
+/**
+ * Set the minimum PWM for the auxiliary outputs
  *
  * Set to 1000 for default or 900 to increase servo travel
  *
@@ -3463,9 +3658,6 @@ PARAM_DEFINE_INT32(PWM_AUX_MIN, 1000);
 /**
  * Set the maximum PWM for the auxiliary outputs
  *
- * IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM
- * REBOOT IN ORDER TO APPLY THE CHANGES.
- *
  * Set to 2000 for default or 2100 to increase servo travel
  *
  * @reboot_required true
@@ -3480,9 +3672,6 @@ PARAM_DEFINE_INT32(PWM_AUX_MAX, 2000);
 /**
  * Set the disarmed PWM for auxiliary outputs
  *
- * IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM
- * REBOOT IN ORDER TO APPLY THE CHANGES.
- *
  * 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.
  *
diff --git a/src/systemcmds/pwm/pwm.cpp b/src/systemcmds/pwm/pwm.cpp
index 98705a603c..14d6fae1c9 100644
--- a/src/systemcmds/pwm/pwm.cpp
+++ b/src/systemcmds/pwm/pwm.cpp
@@ -543,6 +543,10 @@ pwm_main(int argc, char *argv[])
 			return 1;
 		}
 
+		if (pwm_value < 0) {
+			return 0;
+		}
+
 		if (pwm_value == 0) {
 			PX4_WARN("reading disarmed value of zero, disabling disarmed PWM");
 		}
-- 
GitLab