aboutsummaryrefslogtreecommitdiff
path: root/src/modules/commander
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/modules/commander
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/modules/commander')
-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
3 files changed, 89 insertions, 32 deletions
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.
*