aboutsummaryrefslogtreecommitdiff
path: root/src/drivers/drv_pwm_output.h
diff options
context:
space:
mode:
authorJulian Oes <julian@oes.ch>2013-10-19 10:43:41 +0200
committerJulian Oes <julian@oes.ch>2013-10-19 10:43:41 +0200
commit1d3f25ee6c9983ec5da9de4d4f7b463f880f3a87 (patch)
treed9a0588a5c45d4c849c0a901a67f6779f02c39ca /src/drivers/drv_pwm_output.h
parent5d36971689566e2142a16643a77337f2e3613c35 (diff)
downloadpx4-firmware-1d3f25ee6c9983ec5da9de4d4f7b463f880f3a87.tar.gz
px4-firmware-1d3f25ee6c9983ec5da9de4d4f7b463f880f3a87.tar.bz2
px4-firmware-1d3f25ee6c9983ec5da9de4d4f7b463f880f3a87.zip
pwm systemcmd can now set the failsafe values, fmu uses failsafe values as well now, fix to only send the appropriate number of pwm values to IO at once
Diffstat (limited to 'src/drivers/drv_pwm_output.h')
-rw-r--r--src/drivers/drv_pwm_output.h18
1 files changed, 12 insertions, 6 deletions
diff --git a/src/drivers/drv_pwm_output.h b/src/drivers/drv_pwm_output.h
index 3357e67a5..f0dd713b2 100644
--- a/src/drivers/drv_pwm_output.h
+++ b/src/drivers/drv_pwm_output.h
@@ -154,23 +154,29 @@ ORB_DECLARE(output_pwm);
/** power up DSM receiver */
#define DSM_BIND_POWER_UP _IOC(_PWM_SERVO_BASE, 11)
+/** set the PWM value for failsafe */
+#define PWM_SERVO_SET_FAILSAFE_PWM _IOC(_PWM_SERVO_BASE, 12)
+
+/** get the PWM value for failsafe */
+#define PWM_SERVO_GET_FAILSAFE_PWM _IOC(_PWM_SERVO_BASE, 13)
+
/** set the PWM value when disarmed - should be no PWM (zero) by default */
-#define PWM_SERVO_SET_DISARMED_PWM _IOC(_PWM_SERVO_BASE, 12)
+#define PWM_SERVO_SET_DISARMED_PWM _IOC(_PWM_SERVO_BASE, 14)
/** get the PWM value when disarmed */
-#define PWM_SERVO_GET_DISARMED_PWM _IOC(_PWM_SERVO_BASE, 13)
+#define PWM_SERVO_GET_DISARMED_PWM _IOC(_PWM_SERVO_BASE, 15)
/** set the minimum PWM value the output will send */
-#define PWM_SERVO_SET_MIN_PWM _IOC(_PWM_SERVO_BASE, 14)
+#define PWM_SERVO_SET_MIN_PWM _IOC(_PWM_SERVO_BASE, 16)
/** get the minimum PWM value the output will send */
-#define PWM_SERVO_GET_MIN_PWM _IOC(_PWM_SERVO_BASE, 15)
+#define PWM_SERVO_GET_MIN_PWM _IOC(_PWM_SERVO_BASE, 17)
/** set the maximum PWM value the output will send */
-#define PWM_SERVO_SET_MAX_PWM _IOC(_PWM_SERVO_BASE, 16)
+#define PWM_SERVO_SET_MAX_PWM _IOC(_PWM_SERVO_BASE, 18)
/** get the maximum PWM value the output will send */
-#define PWM_SERVO_GET_MAX_PWM _IOC(_PWM_SERVO_BASE, 17)
+#define PWM_SERVO_GET_MAX_PWM _IOC(_PWM_SERVO_BASE, 19)
/** set a single servo to a specific value */
#define PWM_SERVO_SET(_servo) _IOC(_PWM_SERVO_BASE, 0x20 + _servo)