Browse Source

drivers: allow forcing the safety switch on

This allows forcing the safety switch to the on position from software
which stops the pwm outputs
sbg
Andrew Tridgell 10 years ago
parent
commit
dd23d0acbc
  1. 3
      src/drivers/drv_pwm_output.h
  2. 1
      src/drivers/px4fmu/fmu.cpp
  3. 5
      src/drivers/px4io/px4io.cpp
  4. 1
      src/modules/px4iofirmware/protocol.h
  5. 6
      src/modules/px4iofirmware/registers.c

3
src/drivers/drv_pwm_output.h

@ -213,6 +213,9 @@ ORB_DECLARE(output_pwm);
/** make failsafe non-recoverable (termination) if it occurs */ /** make failsafe non-recoverable (termination) if it occurs */
#define PWM_SERVO_SET_TERMINATION_FAILSAFE _IOC(_PWM_SERVO_BASE, 25) #define PWM_SERVO_SET_TERMINATION_FAILSAFE _IOC(_PWM_SERVO_BASE, 25)
/** force safety switch on (to enable use of safety switch) */
#define PWM_SERVO_SET_FORCE_SAFETY_ON _IOC(_PWM_SERVO_BASE, 26)
/* /*
* *
* *

1
src/drivers/px4fmu/fmu.cpp

@ -829,6 +829,7 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
case PWM_SERVO_SET_ARM_OK: case PWM_SERVO_SET_ARM_OK:
case PWM_SERVO_CLEAR_ARM_OK: case PWM_SERVO_CLEAR_ARM_OK:
case PWM_SERVO_SET_FORCE_SAFETY_OFF: case PWM_SERVO_SET_FORCE_SAFETY_OFF:
case PWM_SERVO_SET_FORCE_SAFETY_ON:
// these are no-ops, as no safety switch // these are no-ops, as no safety switch
break; break;

5
src/drivers/px4io/px4io.cpp

@ -2278,6 +2278,11 @@ PX4IO::ioctl(file * filep, int cmd, unsigned long arg)
ret = io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_FORCE_SAFETY_OFF, PX4IO_FORCE_SAFETY_MAGIC); ret = io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_FORCE_SAFETY_OFF, PX4IO_FORCE_SAFETY_MAGIC);
break; break;
case PWM_SERVO_SET_FORCE_SAFETY_ON:
/* force safety switch on */
ret = io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_FORCE_SAFETY_ON, PX4IO_FORCE_SAFETY_MAGIC);
break;
case PWM_SERVO_SET_FORCE_FAILSAFE: case PWM_SERVO_SET_FORCE_FAILSAFE:
/* force failsafe mode instantly */ /* force failsafe mode instantly */
if (arg == 0) { if (arg == 0) {

1
src/modules/px4iofirmware/protocol.h

@ -221,6 +221,7 @@ enum { /* DSM bind states */
hence index 12 can safely be used. */ hence index 12 can safely be used. */
#define PX4IO_P_SETUP_RC_THR_FAILSAFE_US 13 /**< the throttle failsafe pulse length in microseconds */ #define PX4IO_P_SETUP_RC_THR_FAILSAFE_US 13 /**< the throttle failsafe pulse length in microseconds */
#define PX4IO_P_SETUP_FORCE_SAFETY_ON 14 /* force safety switch into 'disarmed' (PWM disabled state) */
#define PX4IO_FORCE_SAFETY_MAGIC 22027 /* required argument for force safety (random) */ #define PX4IO_FORCE_SAFETY_MAGIC 22027 /* required argument for force safety (random) */
/* autopilot control values, -10000..10000 */ /* autopilot control values, -10000..10000 */

6
src/modules/px4iofirmware/registers.c

@ -603,6 +603,12 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
dsm_bind(value & 0x0f, (value >> 4) & 0xF); dsm_bind(value & 0x0f, (value >> 4) & 0xF);
break; break;
case PX4IO_P_SETUP_FORCE_SAFETY_ON:
if (value == PX4IO_FORCE_SAFETY_MAGIC) {
r_status_flags &= ~PX4IO_P_STATUS_FLAGS_SAFETY_OFF;
}
break;
case PX4IO_P_SETUP_FORCE_SAFETY_OFF: case PX4IO_P_SETUP_FORCE_SAFETY_OFF:
if (value == PX4IO_FORCE_SAFETY_MAGIC) { if (value == PX4IO_FORCE_SAFETY_MAGIC) {
r_status_flags |= PX4IO_P_STATUS_FLAGS_SAFETY_OFF; r_status_flags |= PX4IO_P_STATUS_FLAGS_SAFETY_OFF;

Loading…
Cancel
Save