aboutsummaryrefslogtreecommitdiff
path: root/src
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2013-06-09 14:09:09 +0200
committerLorenz Meier <lm@inf.ethz.ch>2013-06-09 14:09:09 +0200
commit1deced7629e7d140a931c42657f75da512696c7e (patch)
tree08f8e321f23420437802751c3b9cbb8c3875f2e8 /src
parentb12678014ff9b500912ec44f6f9c771af3bdd217 (diff)
downloadpx4-firmware-1deced7629e7d140a931c42657f75da512696c7e.tar.gz
px4-firmware-1deced7629e7d140a931c42657f75da512696c7e.tar.bz2
px4-firmware-1deced7629e7d140a931c42657f75da512696c7e.zip
Added safety status feedback, disallow arming of a rotary wing with engaged safety
Diffstat (limited to 'src')
-rw-r--r--src/drivers/px4io/px4io.cpp33
-rw-r--r--src/modules/commander/commander.c82
-rw-r--r--src/modules/commander/state_machine_helper.c35
-rw-r--r--src/modules/commander/state_machine_helper.h4
-rw-r--r--src/modules/uORB/objects_common.cpp4
-rw-r--r--src/modules/uORB/topics/actuator_controls.h7
-rw-r--r--src/modules/uORB/topics/safety.h60
-rw-r--r--src/modules/uORB/topics/vehicle_status.h2
8 files changed, 189 insertions, 38 deletions
diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp
index 19163cebe..bc65c4f25 100644
--- a/src/drivers/px4io/px4io.cpp
+++ b/src/drivers/px4io/px4io.cpp
@@ -80,6 +80,7 @@
#include <uORB/topics/rc_channels.h>
#include <uORB/topics/battery_status.h>
#include <uORB/topics/parameter_update.h>
+#include <uORB/topics/safety.h>
#include <debug.h>
#include <mavlink/mavlink_log.h>
@@ -161,6 +162,7 @@ private:
orb_advert_t _to_actuators_effective; ///< effective actuator controls topic
orb_advert_t _to_outputs; ///< mixed servo outputs topic
orb_advert_t _to_battery; ///< battery status / voltage
+ orb_advert_t _to_safety; ///< status of safety
actuator_outputs_s _outputs; ///< mixed outputs
actuator_controls_effective_s _controls_effective; ///< effective controls
@@ -883,6 +885,25 @@ PX4IO::io_handle_status(uint16_t status)
_status = status;
}
+ /**
+ * Get and handle the safety status
+ */
+ struct safety_s safety;
+ safety.timestamp = hrt_absolute_time();
+
+ if (status & PX4IO_P_STATUS_FLAGS_ARMED) {
+ safety.status = SAFETY_STATUS_UNLOCKED;
+ } else {
+ safety.status = SAFETY_STATUS_SAFE;
+ }
+
+ /* lazily publish the safety status */
+ if (_to_safety > 0) {
+ orb_publish(ORB_ID(safety), _to_safety, &safety);
+ } else {
+ _to_safety = orb_advertise(ORB_ID(safety), &safety);
+ }
+
return ret;
}
@@ -912,7 +933,7 @@ PX4IO::io_get_status()
io_handle_status(regs[0]);
io_handle_alarms(regs[1]);
-
+
/* only publish if battery has a valid minimum voltage */
if (regs[2] > 3300) {
battery_status_s battery_status;
@@ -946,6 +967,7 @@ PX4IO::io_get_status()
_to_battery = orb_advertise(ORB_ID(battery_status), &battery_status);
}
}
+
return ret;
}
@@ -1273,7 +1295,7 @@ PX4IO::print_status()
uint16_t flags = io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_FLAGS);
printf("status 0x%04x%s%s%s%s%s%s%s%s%s%s%s%s\n",
flags,
- ((flags & PX4IO_P_STATUS_FLAGS_ARMED) ? " ARMED" : ""),
+ ((flags & PX4IO_P_STATUS_FLAGS_ARMED) ? " SAFETY_UNLOCKED" : ""),
((flags & PX4IO_P_STATUS_FLAGS_OVERRIDE) ? " OVERRIDE" : ""),
((flags & PX4IO_P_STATUS_FLAGS_RC_OK) ? " RC_OK" : " RC_FAIL"),
((flags & PX4IO_P_STATUS_FLAGS_RC_PPM) ? " PPM" : ""),
@@ -1634,6 +1656,11 @@ test(void)
if (ioctl(fd, PWM_SERVO_GET_COUNT, (unsigned long)&servo_count))
err(1, "failed to get servo count");
+ /* tell IO that its ok to disable its safety with the switch */
+ ret = ioctl(fd, PWM_SERVO_SET_ARM_OK, 0);
+ if (ret != OK)
+ err(1, "PWM_SERVO_SET_ARM_OK");
+
if (ioctl(fd, PWM_SERVO_ARM, 0))
err(1, "failed to arm servos");
@@ -1682,7 +1709,7 @@ test(void)
/* Check if user wants to quit */
char c;
if (read(console, &c, 1) == 1) {
- if (c == 0x03 || c == 0x63) {
+ if (c == 0x03 || c == 0x63 || c == 'q') {
warnx("User abort\n");
close(console);
exit(0);
diff --git a/src/modules/commander/commander.c b/src/modules/commander/commander.c
index aab8f3e04..937c515e6 100644
--- a/src/modules/commander/commander.c
+++ b/src/modules/commander/commander.c
@@ -81,6 +81,7 @@
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/differential_pressure.h>
+#include <uORB/topics/safety.h>
#include <mavlink/mavlink_log.h>
#include <systemlib/param/param.h>
@@ -1281,6 +1282,8 @@ int commander_thread_main(int argc, char *argv[])
current_status.flag_vector_flight_mode_ok = false;
/* set battery warning flag */
current_status.battery_warning = VEHICLE_BATTERY_WARNING_NONE;
+ /* set safety device detection flag */
+ current_status.flag_safety_present = false;
/* advertise to ORB */
stat_pub = orb_advertise(ORB_ID(vehicle_status), &current_status);
@@ -1377,6 +1380,12 @@ int commander_thread_main(int argc, char *argv[])
memset(&battery, 0, sizeof(battery));
battery.voltage_v = 0.0f;
+ /* subscribe to safety topic */
+ int safety_sub = orb_subscribe(ORB_ID(safety));
+ struct safety_s safety;
+ memset(&safety, 0, sizeof(safety));
+ safety.status = SAFETY_STATUS_NOT_PRESENT;
+
// uint8_t vehicle_state_previous = current_status.state_machine;
float voltage_previous = 0.0f;
@@ -1396,6 +1405,39 @@ int commander_thread_main(int argc, char *argv[])
/* Get current values */
bool new_data;
+
+ /* update parameters */
+ orb_check(param_changed_sub, &new_data);
+
+ if (new_data || param_init_forced) {
+ param_init_forced = false;
+ /* parameters changed */
+ orb_copy(ORB_ID(parameter_update), param_changed_sub, &param_changed);
+
+
+ /* update parameters */
+ if (!current_status.flag_system_armed) {
+ if (param_get(_param_sys_type, &(current_status.system_type)) != OK) {
+ warnx("failed setting new system type");
+ }
+
+ /* disable manual override for all systems that rely on electronic stabilization */
+ if (current_status.system_type == VEHICLE_TYPE_QUADROTOR ||
+ current_status.system_type == VEHICLE_TYPE_HEXAROTOR ||
+ current_status.system_type == VEHICLE_TYPE_OCTOROTOR) {
+ current_status.flag_external_manual_override_ok = false;
+
+ } else {
+ current_status.flag_external_manual_override_ok = true;
+ }
+
+ /* check and update system / component ID */
+ param_get(_param_system_id, &(current_status.system_id));
+ param_get(_param_component_id, &(current_status.component_id));
+
+ }
+ }
+
orb_check(sp_man_sub, &new_data);
if (new_data) {
@@ -1431,36 +1473,17 @@ int commander_thread_main(int argc, char *argv[])
handle_command(stat_pub, &current_status, &cmd);
}
- /* update parameters */
- orb_check(param_changed_sub, &new_data);
-
- if (new_data || param_init_forced) {
- param_init_forced = false;
- /* parameters changed */
- orb_copy(ORB_ID(parameter_update), param_changed_sub, &param_changed);
-
-
- /* update parameters */
- if (!current_status.flag_system_armed) {
- if (param_get(_param_sys_type, &(current_status.system_type)) != OK) {
- warnx("failed setting new system type");
- }
-
- /* disable manual override for all systems that rely on electronic stabilization */
- if (current_status.system_type == VEHICLE_TYPE_QUADROTOR ||
- current_status.system_type == VEHICLE_TYPE_HEXAROTOR ||
- current_status.system_type == VEHICLE_TYPE_OCTOROTOR) {
- current_status.flag_external_manual_override_ok = false;
-
- } else {
- current_status.flag_external_manual_override_ok = true;
- }
+ orb_check(safety_sub, &new_data);
- /* check and update system / component ID */
- param_get(_param_system_id, &(current_status.system_id));
- param_get(_param_component_id, &(current_status.component_id));
+ if (new_data) {
+ /* got safety change */
+ orb_copy(ORB_ID(safety), safety_sub, &safety);
- }
+ /* handle it */
+ current_status.flag_safety_present = (safety.status != SAFETY_STATUS_NOT_PRESENT);
+
+ if (current_status.flag_safety_present)
+ current_status.flag_safety_safe = (safety.status == SAFETY_STATUS_SAFE);
}
/* update global position estimate */
@@ -1699,7 +1722,8 @@ int commander_thread_main(int argc, char *argv[])
state_changed = true;
}
- if (orb_check(ORB_ID(vehicle_gps_position), &new_data)) {
+ orb_check(ORB_ID(vehicle_gps_position), &new_data);
+ if (new_data) {
orb_copy(ORB_ID(vehicle_gps_position), gps_sub, &gps_position);
diff --git a/src/modules/commander/state_machine_helper.c b/src/modules/commander/state_machine_helper.c
index ab728c7bb..ac603abfd 100644
--- a/src/modules/commander/state_machine_helper.c
+++ b/src/modules/commander/state_machine_helper.c
@@ -65,6 +65,18 @@ static const char *system_state_txt[] = {
};
+bool is_multirotor(const struct vehicle_status_s *current_status)
+{
+ return ((current_status->system_type == VEHICLE_TYPE_QUADROTOR) ||
+ (current_status->system_type == VEHICLE_TYPE_HEXAROTOR) ||
+ (current_status->system_type == VEHICLE_TYPE_OCTOROTOR));
+}
+
+bool is_rotary_wing(const struct vehicle_status_s *current_status)
+{
+ return is_multirotor(current_status);
+}
+
/**
* Transition from one state to another
*/
@@ -513,6 +525,25 @@ void update_state_machine_no_position_fix(int status_pub, struct vehicle_status_
void update_state_machine_arm(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd)
{
if (current_status->state_machine == SYSTEM_STATE_STANDBY) {
+
+ /* reject arming if safety status is wrong */
+ if (current_status->flag_safety_present) {
+
+ /*
+ * The operator should not touch the vehicle if
+ * its armed, so we don't allow arming in the
+ * first place
+ */
+ if (is_rotary_wing(current_status)) {
+
+ /* safety is in safe position, disallow arming */
+ if (current_status->flag_safety_safe) {
+ mavlink_log_critical(mavlink_fd, "DISENGAGE SAFETY BEFORE ARMING!");
+ }
+
+ }
+ }
+
printf("[cmd] arming\n");
do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_GROUND_READY);
}
@@ -538,9 +569,7 @@ void update_state_machine_mode_manual(int status_pub, struct vehicle_status_s *c
current_status->flag_control_manual_enabled = true;
/* set behaviour based on airframe */
- if ((current_status->system_type == VEHICLE_TYPE_QUADROTOR) ||
- (current_status->system_type == VEHICLE_TYPE_HEXAROTOR) ||
- (current_status->system_type == VEHICLE_TYPE_OCTOROTOR)) {
+ if (is_rotary_wing(current_status)) {
/* assuming a rotary wing, set to SAS */
current_status->manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_SAS;
diff --git a/src/modules/commander/state_machine_helper.h b/src/modules/commander/state_machine_helper.h
index 2f2ccc729..95b48d326 100644
--- a/src/modules/commander/state_machine_helper.h
+++ b/src/modules/commander/state_machine_helper.h
@@ -47,6 +47,10 @@
#include <uORB/uORB.h>
#include <uORB/topics/vehicle_status.h>
+bool is_multirotor(const struct vehicle_status_s *current_status);
+
+bool is_rotary_wing(const struct vehicle_status_s *current_status);
+
/**
* Switch to new state with no checking.
*
diff --git a/src/modules/uORB/objects_common.cpp b/src/modules/uORB/objects_common.cpp
index 4197f6fb2..e2df31651 100644
--- a/src/modules/uORB/objects_common.cpp
+++ b/src/modules/uORB/objects_common.cpp
@@ -154,3 +154,7 @@ ORB_DEFINE(actuator_outputs_3, struct actuator_outputs_s);
#include "topics/debug_key_value.h"
ORB_DEFINE(debug_key_value, struct debug_key_value_s);
+
+/* status of the system safety device */
+#include "topics/safety.h"
+ORB_DEFINE(safety, struct safety_s);
diff --git a/src/modules/uORB/topics/actuator_controls.h b/src/modules/uORB/topics/actuator_controls.h
index b7c4196c0..745c5bc87 100644
--- a/src/modules/uORB/topics/actuator_controls.h
+++ b/src/modules/uORB/topics/actuator_controls.h
@@ -68,9 +68,10 @@ ORB_DECLARE(actuator_controls_3);
/** global 'actuator output is live' control. */
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 armed; /**< Set to true if system is armed */
+ bool ready_to_arm; /**< Set to true if system is ready to be armed */
+ bool throttle_locked; /**< Set to true if the trottle is locked to zero */
+ bool lockdown; /**< Set to true if actuators are forced to being disabled (due to emergency or HIL) */
};
ORB_DECLARE(actuator_armed);
diff --git a/src/modules/uORB/topics/safety.h b/src/modules/uORB/topics/safety.h
new file mode 100644
index 000000000..19e8e8d45
--- /dev/null
+++ b/src/modules/uORB/topics/safety.h
@@ -0,0 +1,60 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 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
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file safety.h
+ *
+ * Status of an attached safety device
+ */
+
+#ifndef TOPIC_SAFETY_H
+#define TOPIC_SAFETY_H
+
+#include <stdint.h>
+#include "../uORB.h"
+
+enum SAFETY_STATUS {
+ SAFETY_STATUS_NOT_PRESENT,
+ SAFETY_STATUS_SAFE,
+ SAFETY_STATUS_UNLOCKED
+};
+
+struct safety_s {
+ uint64_t timestamp; /**< output timestamp in us since system boot */
+ enum SAFETY_STATUS status;
+};
+
+/* actuator output sets; this list can be expanded as more drivers emerge */
+ORB_DECLARE(safety);
+
+#endif /* TOPIC_SAFETY_H */
diff --git a/src/modules/uORB/topics/vehicle_status.h b/src/modules/uORB/topics/vehicle_status.h
index c7c1048f6..07660614b 100644
--- a/src/modules/uORB/topics/vehicle_status.h
+++ b/src/modules/uORB/topics/vehicle_status.h
@@ -214,6 +214,8 @@ struct vehicle_status_s
bool flag_valid_launch_position; /**< indicates a valid launch position */
bool flag_valid_home_position; /**< indicates a valid home position (a valid home position is not always a valid launch) */
bool flag_airspeed_valid; /**< set to true by the commander app if there is a valid airspeed measurement available */
+ bool flag_safety_present; /**< indicates that a safety switch is present */
+ bool flag_safety_safe; /**< safety switch is in safe position */
};
/**