Revert "px4io: replace safety_off state with safety button event (#19558)"

This reverts commit 12a81979a8.
This commit is contained in:
Igor Misic
2022-05-19 15:27:08 +02:00
committed by Daniel Agar
parent 6aefcbb6cf
commit 554283655c
26 changed files with 190 additions and 69 deletions
+1 -1
View File
@@ -927,7 +927,7 @@ PARAM_DEFINE_INT32(COM_PREARM_MODE, 0);
/**
* Enable force safety
*
* Force safety when the vehicle disarms
* Force safety when the vehicle disarms. Not supported when safety button used over PX4IO board.
*
* @boolean
* @group Commander
+10
View File
@@ -187,6 +187,13 @@ static int do_esc_calibration_ioctl(orb_advert_t *mavlink_log_pub)
goto Out;
}
/* tell IO to switch off safety without using the safety switch */
if (px4_ioctl(fd, PWM_SERVO_SET_FORCE_SAFETY_OFF, 0) != PX4_OK) {
calibration_log_critical(mavlink_log_pub, CAL_QGC_FAILED_MSG, "Unable to force safety off");
return_code = PX4_ERROR;
goto Out;
}
calibration_log_info(mavlink_log_pub, "[cal] Connect battery now");
timeout_start = hrt_absolute_time();
@@ -226,6 +233,9 @@ static int do_esc_calibration_ioctl(orb_advert_t *mavlink_log_pub)
Out:
if (fd != -1) {
if (px4_ioctl(fd, PWM_SERVO_SET_FORCE_SAFETY_ON, 0) != PX4_OK) {
calibration_log_info(mavlink_log_pub, CAL_QGC_FAILED_MSG, "Safety switch still off");
}
if (px4_ioctl(fd, PWM_SERVO_DISARM, 0) != PX4_OK) {
calibration_log_info(mavlink_log_pub, CAL_QGC_FAILED_MSG, "Servos still armed");
+1 -1
View File
@@ -39,7 +39,7 @@ add_library(px4iofirmware
mixer.cpp
px4io.cpp
registers.c
safety_button.cpp
safety.cpp
serial.cpp
)
+4 -2
View File
@@ -134,11 +134,13 @@ mixer_tick()
* FMU or from the mixer.
*
*/
should_arm = (r_status_flags & PX4IO_P_STATUS_FLAGS_INIT_OK) /* IO initialised without error */
should_arm = (r_status_flags & PX4IO_P_STATUS_FLAGS_INIT_OK) /* IO initialised without error */
&& (r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) /* and IO is armed */
&& (r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED) /* and FMU is armed */
;
should_arm_nothrottle = ((r_status_flags & PX4IO_P_STATUS_FLAGS_INIT_OK) /* IO initialised without error */
should_arm_nothrottle = ((r_status_flags & PX4IO_P_STATUS_FLAGS_INIT_OK) /* IO initialised without error */
&& (r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) /* and IO is armed */
&& ((r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_PREARMED) /* and FMU is prearmed */
|| (r_status_flags & PX4IO_P_STATUS_FLAGS_RAW_PWM) /* or direct PWM is set */
));
+8 -5
View File
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2012-2022 PX4 Development Team. All rights reserved.
* Copyright (c) 2012-2017 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
@@ -114,7 +114,6 @@
#define PX4IO_P_STATUS_FLAGS_FMU_INITIALIZED (1 << 11) /* FMU was initialized and OK once */
#define PX4IO_P_STATUS_FLAGS_RC_ST24 (1 << 12) /* ST24 input is valid */
#define PX4IO_P_STATUS_FLAGS_RC_SUMD (1 << 13) /* SUMD input is valid */
#define PX4IO_P_STATUS_FLAGS_SAFETY_BUTTON_EVENT (1 << 14) /* px4io safety button was pressed for longer than 1 second */
#define PX4IO_P_STATUS_ALARMS 3 /* alarm flags - alarms latch, write 1 to a bit to clear it */
#define PX4IO_P_STATUS_ALARMS_RC_LOST (1 << 0) /* timed out waiting for RC input */
@@ -185,8 +184,12 @@ enum { /* DSM bind states */
#define PX4IO_P_SETUP_CRC 11 /* get CRC of IO firmware */
/* storage space of 12 occupied by CRC */
#define PX4IO_P_SETUP_SAFETY_BUTTON_ACK 14 /**< ACK from FMU when it gets safety button pressed status */
#define PX4IO_P_SETUP_SAFETY_OFF 15 /**< FMU inform PX4IO about safety_off for LED indication*/
#define PX4IO_P_SETUP_FORCE_SAFETY_OFF 12 /* force safety switch into
'armed' (PWM enabled) state - this is a non-data write and
hence index 12 can safely be used. */
#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_P_SETUP_SBUS_RATE 16 /**< frame rate of SBUS1 output in Hz */
#define PX4IO_P_SETUP_THERMAL 17 /**< thermal management */
#define PX4IO_P_SETUP_ENABLE_FLIGHTTERMINATION 18 /**< flight termination; false if the circuit breaker (CBRK_FLIGHTTERM) is set */
@@ -209,7 +212,7 @@ enum { /* DSM bind states */
#define PX4IO_PAGE_TEST 127
#define PX4IO_P_TEST_LED 0 /**< set the amber LED on/off */
/* PWM disarmed values that are active */
/* PWM disarmed values that are active, even when SAFETY_SAFE */
#define PX4IO_PAGE_DISARMED_PWM 109 /* 0..CONFIG_ACTUATOR_COUNT-1 */
/**
+6 -4
View File
@@ -154,7 +154,8 @@ show_debug_messages(void)
static void
update_mem_usage(void)
{
if (/* FMU is armed */ (r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED)) {
if (/* IO armed */ (r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF)
/* and FMU is armed */ && (r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED)) {
return;
}
@@ -182,7 +183,8 @@ ring_blink(void)
{
#if defined(LED_GREEN)
if (/* FMU is armed */ (r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED)) {
if (/* IO armed */ (r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF)
/* and FMU is armed */ && (r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED)) {
LED_GREEN(true);
return;
}
@@ -312,8 +314,8 @@ extern "C" __EXPORT int user_start(int argc, char *argv[])
ENABLE_SBUS_OUT(false);
#endif
/* start the safety button handler */
safety_button_init();
/* start the safety switch handler */
safety_init();
/* initialise the control inputs */
controls_init();
+4 -2
View File
@@ -131,6 +131,8 @@ extern struct sys_state_s system_state;
# define ADC_VSERVO 4
# define ADC_RSSI 5
#define BUTTON_SAFETY px4_arch_gpioread(GPIO_BTN_SAFETY)
#define PX4_CRITICAL_SECTION(cmd) { irqstate_t flags = px4_enter_critical_section(); cmd; px4_leave_critical_section(flags); }
void atomic_modify_or(volatile uint16_t *target, uint16_t modification);
@@ -143,9 +145,9 @@ void atomic_modify_and(volatile uint16_t *target, uint16_t modification);
extern void mixer_tick(void);
/**
* Safety button/LED.
* Safety switch/LED.
*/
extern void safety_button_init(void);
extern void safety_init(void);
extern void failsafe_led_init(void);
/**
+11 -8
View File
@@ -413,7 +413,7 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
break;
case PX4IO_P_SETUP_REBOOT_BL:
if (r_status_flags & PX4IO_P_STATUS_FLAGS_OUTPUTS_ARMED) {
if (r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) {
// don't allow reboot while armed
break;
}
@@ -433,19 +433,22 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
dsm_bind(value & 0x0f, (value >> 4) & 0xF);
break;
case PX4IO_P_SETUP_SAFETY_BUTTON_ACK:
// clear safety button pressed flag so it can be used again
r_status_flags &= ~PX4IO_P_STATUS_FLAGS_SAFETY_BUTTON_EVENT;
case PX4IO_P_SETUP_FORCE_SAFETY_ON:
if (value == PX4IO_FORCE_SAFETY_MAGIC) {
r_status_flags &= ~PX4IO_P_STATUS_FLAGS_SAFETY_OFF;
} else {
return -1;
}
break;
case PX4IO_P_SETUP_SAFETY_OFF:
if (value) {
case PX4IO_P_SETUP_FORCE_SAFETY_OFF:
if (value == PX4IO_FORCE_SAFETY_MAGIC) {
r_status_flags |= PX4IO_P_STATUS_FLAGS_SAFETY_OFF;
} else {
r_status_flags &= ~PX4IO_P_STATUS_FLAGS_SAFETY_OFF;
return -1;
}
break;
@@ -32,7 +32,7 @@
****************************************************************************/
/**
* @file safety_button.cpp
* @file safety.cpp
* Safety button logic.
*
* @author Lorenz Meier <lorenz@px4.io>
@@ -46,7 +46,7 @@
#include "px4io.h"
static struct hrt_call safety_button_call;
static struct hrt_call arming_call;
static struct hrt_call failsafe_call;
/*
@@ -59,23 +59,30 @@ static unsigned counter = 0;
* Define the various LED flash sequences for each system state.
*/
#define LED_PATTERN_FMU_OK_TO_ARM 0x0003 /**< slow blinking */
#define LED_PATTERN_FMU_REFUSE_TO_ARM 0x5555 /**< fast blinking */
#define LED_PATTERN_FMU_REFUSE_TO_ARM 0x5555 /**< fast blinking */
#define LED_PATTERN_IO_ARMED 0x5050 /**< long off, then double blink */
#define LED_PATTERN_FMU_ARMED 0x5500 /**< long off, then quad blink */
#define LED_PATTERN_IO_FMU_ARMED 0xffff /**< constantly on */
static unsigned blink_counter = 0;
#define SAFETY_SWITCH_THRESHOLD 10
/*
* IMPORTANT: The arming state machine critically
* depends on using the same threshold
* for arming and disarming. Since disarming
* is quite deadly for the system, a similar
* length can be justified.
*/
#define ARM_COUNTER_THRESHOLD 10
static void safety_button_check(void *arg);
static void safety_check_button(void *arg);
static void failsafe_blink(void *arg);
void
safety_button_init(void)
safety_init(void)
{
/* arrange for the button handler to be called at 10Hz */
hrt_call_every(&safety_button_call, 1000, 100000, safety_button_check, NULL);
hrt_call_every(&arming_call, 1000, 100000, safety_check_button, NULL);
}
void
@@ -86,20 +93,26 @@ failsafe_led_init(void)
}
static void
safety_button_check(void *arg)
safety_check_button(void *arg)
{
const bool safety_button_pressed = px4_arch_gpioread(GPIO_BTN_SAFETY);
const bool safety_button_pressed = BUTTON_SAFETY;
/* Keep safety button pressed for one second to trigger safety button event.
* The logic to prevent turning on safety again is in the commander.
/* Keep safety button pressed for one second to turn off safety
*
* Note that safety cannot be turned on again by button because a button
* hardware problem could accidentally disable it in flight.
*/
if (safety_button_pressed && !(r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) &&
(r_setup_arming & PX4IO_P_SETUP_ARMING_IO_ARM_OK)) {
if (safety_button_pressed && !(r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_BUTTON_EVENT)) {
if (counter <= ARM_COUNTER_THRESHOLD) {
counter++;
counter++;
}
if (counter >= SAFETY_SWITCH_THRESHOLD) {
atomic_modify_or(&r_status_flags, PX4IO_P_STATUS_FLAGS_SAFETY_BUTTON_EVENT);
if (counter == ARM_COUNTER_THRESHOLD) {
// switch safety off -> ready to arm state
atomic_modify_or(&r_status_flags, PX4IO_P_STATUS_FLAGS_SAFETY_OFF);
}
} else {