aboutsummaryrefslogtreecommitdiff
path: root/src/modules
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules')
-rw-r--r--src/modules/commander/commander.cpp21
-rw-r--r--src/modules/px4iofirmware/mixer.cpp9
-rw-r--r--src/modules/px4iofirmware/protocol.h5
-rw-r--r--src/modules/px4iofirmware/registers.c3
-rw-r--r--src/modules/uORB/topics/actuator_armed.h3
-rw-r--r--src/modules/uORB/topics/vehicle_command.h1
6 files changed, 26 insertions, 16 deletions
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index 953feec2a..04450a44f 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -546,24 +546,19 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s
}
break;
-#if 0
/* Flight termination */
- case VEHICLE_CMD_DO_SET_SERVO: { //xxx: needs its own mavlink command
-
- //XXX: to enable the parachute, a param needs to be set
- //xxx: for safety only for now, param3 is unused by VEHICLE_CMD_DO_SET_SERVO
- if (armed_local->armed && cmd->param3 > 0.5 && parachute_enabled) {
- transition_result_t failsafe_res = failsafe_state_transition(status, FAILSAFE_STATE_TERMINATION);
- cmd_result = VEHICLE_CMD_RESULT_ACCEPTED;
-
+ case VEHICLE_CMD_DO_FLIGHTTERMINATION: {
+ if (cmd->param1 > 0.5f) {
+ //XXX update state machine?
+ armed_local->force_failsafe = true;
+ warnx("forcing failsafe");
} else {
- /* reject parachute depoyment not armed */
- cmd_result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
+ armed_local->force_failsafe = false;
+ warnx("disabling failsafe");
}
-
+ cmd_result = VEHICLE_CMD_RESULT_ACCEPTED;
}
break;
-#endif
case VEHICLE_CMD_DO_SET_HOME: {
bool use_current = cmd->param1 > 0.5f;
diff --git a/src/modules/px4iofirmware/mixer.cpp b/src/modules/px4iofirmware/mixer.cpp
index 2f721bf1e..606c639f9 100644
--- a/src/modules/px4iofirmware/mixer.cpp
+++ b/src/modules/px4iofirmware/mixer.cpp
@@ -111,7 +111,7 @@ mixer_tick(void)
r_status_flags |= PX4IO_P_STATUS_FLAGS_FMU_OK;
}
- /* default to failsafe mixing */
+ /* default to failsafe mixing - it will be forced below if flag is set */
source = MIX_FAILSAFE;
/*
@@ -155,6 +155,13 @@ mixer_tick(void)
}
/*
+ * Check if we should force failsafe - and do it if we have to
+ */
+ if (r_setup_arming & PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE) {
+ source = MIX_FAILSAFE;
+ }
+
+ /*
* Set failsafe status flag depending on mixing source
*/
if (source == MIX_FAILSAFE) {
diff --git a/src/modules/px4iofirmware/protocol.h b/src/modules/px4iofirmware/protocol.h
index d5a6b1ec4..050783687 100644
--- a/src/modules/px4iofirmware/protocol.h
+++ b/src/modules/px4iofirmware/protocol.h
@@ -179,6 +179,7 @@
#define PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE (1 << 5) /* Output of PWM right after startup enabled to help ESCs initialize and prevent them from beeping */
#define PX4IO_P_SETUP_ARMING_RC_HANDLING_DISABLED (1 << 6) /* Disable the IO-internal evaluation of the RC */
#define PX4IO_P_SETUP_ARMING_LOCKDOWN (1 << 7) /* If set, the system operates normally, but won't actuate any servos */
+#define PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE (1 << 8) /* If set, the system will always output the failsafe values */
#define PX4IO_P_SETUP_PWM_RATES 2 /* bitmask, 0 = low rate, 1 = high rate */
#define PX4IO_P_SETUP_PWM_DEFAULTRATE 3 /* 'low' PWM frame output rate in Hz */
@@ -253,6 +254,10 @@ enum { /* DSM bind states */
/* PWM failsafe values - zero disables the output */
#define PX4IO_PAGE_FAILSAFE_PWM 55 /**< 0..CONFIG_ACTUATOR_COUNT-1 */
+/* PWM failsafe values - zero disables the output */
+#define PX4IO_PAGE_SENSORS 56 /**< Sensors connected to PX4IO */
+#define PX4IO_P_SENSORS_ALTITUDE 0 /**< Altitude of an external sensor (HoTT or S.BUS2) */
+
/* Debug and test page - not used in normal operation */
#define PX4IO_PAGE_TEST 127
#define PX4IO_P_TEST_LED 0 /**< set the amber LED on/off */
diff --git a/src/modules/px4iofirmware/registers.c b/src/modules/px4iofirmware/registers.c
index b37259997..fcd53f1f1 100644
--- a/src/modules/px4iofirmware/registers.c
+++ b/src/modules/px4iofirmware/registers.c
@@ -189,7 +189,8 @@ volatile uint16_t r_page_setup[] =
PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM | \
PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE | \
PX4IO_P_SETUP_ARMING_RC_HANDLING_DISABLED | \
- PX4IO_P_SETUP_ARMING_LOCKDOWN)
+ PX4IO_P_SETUP_ARMING_LOCKDOWN | \
+ PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE)
#define PX4IO_P_SETUP_RATES_VALID ((1 << PX4IO_SERVO_COUNT) - 1)
#define PX4IO_P_SETUP_RELAYS_VALID ((1 << PX4IO_RELAY_CHANNELS) - 1)
diff --git a/src/modules/uORB/topics/actuator_armed.h b/src/modules/uORB/topics/actuator_armed.h
index a98d3fc3a..0f6c9aca1 100644
--- a/src/modules/uORB/topics/actuator_armed.h
+++ b/src/modules/uORB/topics/actuator_armed.h
@@ -56,6 +56,7 @@ struct actuator_armed_s {
bool armed; /**< Set to true if system is armed */
bool ready_to_arm; /**< Set to true if system is ready to be armed */
bool lockdown; /**< Set to true if actuators are forced to being disabled (due to emergency or HIL) */
+ bool force_failsafe; /**< Set to true if the actuators are forced to the failsafe position */
};
/**
@@ -65,4 +66,4 @@ struct actuator_armed_s {
/* register this as object request broker structure */
ORB_DECLARE(actuator_armed);
-#endif \ No newline at end of file
+#endif
diff --git a/src/modules/uORB/topics/vehicle_command.h b/src/modules/uORB/topics/vehicle_command.h
index c21a29b13..7db33d98b 100644
--- a/src/modules/uORB/topics/vehicle_command.h
+++ b/src/modules/uORB/topics/vehicle_command.h
@@ -76,6 +76,7 @@ enum VEHICLE_CMD {
VEHICLE_CMD_DO_REPEAT_RELAY = 182, /* Cycle a relay on and off for a desired number of cyles with a desired period. |Relay number| Cycle count| Cycle time (seconds, decimal)| Empty| Empty| Empty| Empty| */
VEHICLE_CMD_DO_SET_SERVO = 183, /* Set a servo to a desired PWM value. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Empty| Empty| Empty| Empty| Empty| */
VEHICLE_CMD_DO_REPEAT_SERVO = 184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty| */
+ VEHICLE_CMD_DO_FLIGHTTERMINATION=185, /* Terminate flight immediately |Flight termination activated if > 0.5| Empty| Empty| Empty| Empty| Empty| Empty| */
VEHICLE_CMD_DO_CONTROL_VIDEO = 200, /* Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */
VEHICLE_CMD_DO_LAST = 240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
VEHICLE_CMD_PREFLIGHT_CALIBRATION = 241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Accelerometer calibration: 0: no, 1: yes| Empty| Empty| */