aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--Documentation/flight_mode_state_machine.odgbin18105 -> 22619 bytes
-rw-r--r--Documentation/flight_mode_state_machine.pdfbin23031 -> 110086 bytes
-rw-r--r--makefiles/config_px4fmu-v1_default.mk1
-rw-r--r--src/drivers/ardrone_interface/ardrone_interface.c13
-rw-r--r--src/drivers/blinkm/blinkm.cpp68
-rw-r--r--src/drivers/hil/hil.cpp17
-rw-r--r--src/drivers/mkblctrl/mkblctrl.cpp19
-rw-r--r--src/drivers/px4fmu/fmu.cpp27
-rw-r--r--src/drivers/px4io/px4io.cpp336
-rw-r--r--src/drivers/stm32/tone_alarm/tone_alarm.cpp29
-rw-r--r--src/examples/fixedwing_control/main.c9
-rw-r--r--src/examples/flow_position_control/flow_position_control_main.c19
-rw-r--r--src/examples/flow_position_estimator/flow_position_estimator_main.c34
-rw-r--r--src/examples/flow_speed_control/flow_speed_control_main.c20
-rwxr-xr-xsrc/modules/attitude_estimator_ekf/attitude_estimator_ekf_params.c48
-rw-r--r--src/modules/commander/accelerometer_calibration.c38
-rw-r--r--src/modules/commander/accelerometer_calibration.h3
-rw-r--r--src/modules/commander/airspeed_calibration.c111
-rw-r--r--src/modules/commander/airspeed_calibration.h46
-rw-r--r--src/modules/commander/baro_calibration.c54
-rw-r--r--src/modules/commander/baro_calibration.h46
-rw-r--r--src/modules/commander/calibration_routines.c1
-rw-r--r--src/modules/commander/commander.c1880
-rw-r--r--src/modules/commander/commander.h4
-rw-r--r--src/modules/commander/commander_helper.c129
-rw-r--r--src/modules/commander/commander_helper.h66
-rw-r--r--src/modules/commander/gyro_calibration.c151
-rw-r--r--src/modules/commander/gyro_calibration.h46
-rw-r--r--src/modules/commander/mag_calibration.c278
-rw-r--r--src/modules/commander/mag_calibration.h46
-rw-r--r--src/modules/commander/module.mk8
-rw-r--r--src/modules/commander/rc_calibration.c83
-rw-r--r--src/modules/commander/rc_calibration.h46
-rw-r--r--src/modules/commander/state_machine_helper.c1098
-rw-r--r--src/modules/commander/state_machine_helper.h162
-rw-r--r--src/modules/controllib/fixedwing.cpp29
-rw-r--r--src/modules/fixedwing_att_control/fixedwing_att_control_att.c4
-rw-r--r--src/modules/fixedwing_att_control/fixedwing_att_control_main.c163
-rw-r--r--src/modules/fixedwing_att_control/fixedwing_att_control_rate.c6
-rw-r--r--src/modules/fixedwing_pos_control/fixedwing_pos_control_main.c10
-rw-r--r--src/modules/gpio_led/gpio_led.c15
-rw-r--r--src/modules/mavlink/mavlink.c114
-rw-r--r--src/modules/mavlink/orb_listener.c22
-rw-r--r--src/modules/mavlink/orb_topics.h4
-rw-r--r--src/modules/mavlink_onboard/mavlink.c126
-rw-r--r--src/modules/mavlink_onboard/mavlink_receiver.c2
-rw-r--r--src/modules/mavlink_onboard/orb_topics.h4
-rw-r--r--src/modules/mavlink_onboard/util.h3
-rw-r--r--src/modules/multirotor_att_control/multirotor_att_control_main.c189
-rw-r--r--src/modules/multirotor_att_control/multirotor_attitude_control.c46
-rw-r--r--src/modules/multirotor_att_control/multirotor_attitude_control.h5
-rw-r--r--src/modules/multirotor_att_control/multirotor_rate_control.c17
-rw-r--r--src/modules/multirotor_att_control/multirotor_rate_control.h4
-rw-r--r--src/modules/px4iofirmware/mixer.cpp134
-rw-r--r--src/modules/px4iofirmware/protocol.h20
-rw-r--r--src/modules/px4iofirmware/px4io.h3
-rw-r--r--src/modules/px4iofirmware/registers.c123
-rw-r--r--src/modules/px4iofirmware/safety.c10
-rw-r--r--src/modules/sdlog2/sdlog2.c90
-rw-r--r--src/modules/sdlog2/sdlog2_messages.h33
-rw-r--r--src/modules/sensors/sensor_params.c10
-rw-r--r--src/modules/sensors/sensors.cpp108
-rw-r--r--src/modules/systemlib/pid/pid.c6
-rw-r--r--src/modules/systemlib/pid/pid.h2
-rw-r--r--src/modules/uORB/objects_common.cpp10
-rw-r--r--src/modules/uORB/topics/actuator_controls.h15
-rw-r--r--src/modules/uORB/topics/actuator_safety.h66
-rw-r--r--src/modules/uORB/topics/manual_control_setpoint.h12
-rw-r--r--src/modules/uORB/topics/rc_channels.h22
-rw-r--r--src/modules/uORB/topics/vehicle_control_debug.h87
-rw-r--r--src/modules/uORB/topics/vehicle_control_mode.h91
-rw-r--r--src/modules/uORB/topics/vehicle_status.h155
-rw-r--r--src/systemcmds/esc_calib/esc_calib.c250
-rw-r--r--src/systemcmds/esc_calib/module.mk41
-rw-r--r--src/systemcmds/pwm/pwm.c48
-rw-r--r--src/systemcmds/reboot/reboot.c3
76 files changed, 4490 insertions, 2548 deletions
diff --git a/Documentation/flight_mode_state_machine.odg b/Documentation/flight_mode_state_machine.odg
index b630ecb40..2d119bd8c 100644
--- a/Documentation/flight_mode_state_machine.odg
+++ b/Documentation/flight_mode_state_machine.odg
Binary files differ
diff --git a/Documentation/flight_mode_state_machine.pdf b/Documentation/flight_mode_state_machine.pdf
index cd234ada7..af41953ee 100644
--- a/Documentation/flight_mode_state_machine.pdf
+++ b/Documentation/flight_mode_state_machine.pdf
Binary files differ
diff --git a/makefiles/config_px4fmu-v1_default.mk b/makefiles/config_px4fmu-v1_default.mk
index 213eb651b..ea1e38ff7 100644
--- a/makefiles/config_px4fmu-v1_default.mk
+++ b/makefiles/config_px4fmu-v1_default.mk
@@ -46,6 +46,7 @@ MODULES += systemcmds/param
MODULES += systemcmds/perf
MODULES += systemcmds/preflight_check
MODULES += systemcmds/pwm
+MODULES += systemcmds/esc_calib
MODULES += systemcmds/reboot
MODULES += systemcmds/top
MODULES += systemcmds/tests
diff --git a/src/drivers/ardrone_interface/ardrone_interface.c b/src/drivers/ardrone_interface/ardrone_interface.c
index 735bdb41a..187820372 100644
--- a/src/drivers/ardrone_interface/ardrone_interface.c
+++ b/src/drivers/ardrone_interface/ardrone_interface.c
@@ -55,6 +55,7 @@
#include <uORB/uORB.h>
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/actuator_controls.h>
+#include <uORB/topics/actuator_safety.h>
#include <systemlib/systemlib.h>
@@ -247,13 +248,13 @@ int ardrone_interface_thread_main(int argc, char *argv[])
memset(&state, 0, sizeof(state));
struct actuator_controls_s actuator_controls;
memset(&actuator_controls, 0, sizeof(actuator_controls));
- struct actuator_armed_s armed;
- armed.armed = false;
+ struct actuator_safety_s safety;
+ safety.armed = false;
/* subscribe to attitude, motor setpoints and system state */
int actuator_controls_sub = orb_subscribe(ORB_ID_VEHICLE_ATTITUDE_CONTROLS);
int state_sub = orb_subscribe(ORB_ID(vehicle_status));
- int armed_sub = orb_subscribe(ORB_ID(actuator_armed));
+ int safety_sub = orb_subscribe(ORB_ID(actuator_safety));
printf("[ardrone_interface] Motors initialized - ready.\n");
fflush(stdout);
@@ -322,16 +323,14 @@ int ardrone_interface_thread_main(int argc, char *argv[])
} else {
/* MAIN OPERATION MODE */
- /* get a local copy of the vehicle state */
- orb_copy(ORB_ID(vehicle_status), state_sub, &state);
/* get a local copy of the actuator controls */
orb_copy(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_controls_sub, &actuator_controls);
- orb_copy(ORB_ID(actuator_armed), armed_sub, &armed);
+ orb_copy(ORB_ID(actuator_safety), safety_sub, &safety);
/* for now only spin if armed and immediately shut down
* if in failsafe
*/
- if (armed.armed && !armed.lockdown) {
+ if (safety.armed && !safety.lockdown) {
ardrone_mixing_and_output(ardrone_write, &actuator_controls);
} else {
diff --git a/src/drivers/blinkm/blinkm.cpp b/src/drivers/blinkm/blinkm.cpp
index 3fabfd9a5..a11f88477 100644
--- a/src/drivers/blinkm/blinkm.cpp
+++ b/src/drivers/blinkm/blinkm.cpp
@@ -116,6 +116,7 @@
#include <poll.h>
#include <uORB/uORB.h>
#include <uORB/topics/vehicle_status.h>
+#include <uORB/topics/actuator_safety.h>
#include <uORB/topics/vehicle_gps_position.h>
static const float MAX_CELL_VOLTAGE = 4.3f;
@@ -376,6 +377,7 @@ BlinkM::led()
static int vehicle_status_sub_fd;
static int vehicle_gps_position_sub_fd;
+ static int actuator_safety_sub_fd;
static int num_of_cells = 0;
static int detected_cells_runcount = 0;
@@ -386,6 +388,7 @@ BlinkM::led()
static int led_interval = 1000;
static int no_data_vehicle_status = 0;
+ static int no_data_actuator_safety = 0;
static int no_data_vehicle_gps_position = 0;
static bool topic_initialized = false;
@@ -398,6 +401,9 @@ BlinkM::led()
vehicle_status_sub_fd = orb_subscribe(ORB_ID(vehicle_status));
orb_set_interval(vehicle_status_sub_fd, 1000);
+ actuator_safety_sub_fd = orb_subscribe(ORB_ID(actuator_safety));
+ orb_set_interval(actuator_safety_sub_fd, 1000);
+
vehicle_gps_position_sub_fd = orb_subscribe(ORB_ID(vehicle_gps_position));
orb_set_interval(vehicle_gps_position_sub_fd, 1000);
@@ -452,12 +458,14 @@ BlinkM::led()
if (led_thread_runcount == 15) {
/* obtained data for the first file descriptor */
struct vehicle_status_s vehicle_status_raw;
+ struct actuator_safety_s actuator_safety;
struct vehicle_gps_position_s vehicle_gps_position_raw;
memset(&vehicle_status_raw, 0, sizeof(vehicle_status_raw));
memset(&vehicle_gps_position_raw, 0, sizeof(vehicle_gps_position_raw));
bool new_data_vehicle_status;
+ bool new_data_actuator_safety;
bool new_data_vehicle_gps_position;
orb_check(vehicle_status_sub_fd, &new_data_vehicle_status);
@@ -471,6 +479,17 @@ BlinkM::led()
no_data_vehicle_status = 3;
}
+ orb_check(actuator_safety_sub_fd, &new_data_actuator_safety);
+
+ if (new_data_actuator_safety) {
+ orb_copy(ORB_ID(actuator_safety), actuator_safety_sub_fd, &actuator_safety);
+ no_data_actuator_safety = 0;
+ } else {
+ no_data_actuator_safety++;
+ if(no_data_vehicle_status >= 3)
+ no_data_vehicle_status = 3;
+ }
+
orb_check(vehicle_gps_position_sub_fd, &new_data_vehicle_gps_position);
if (new_data_vehicle_gps_position) {
@@ -486,15 +505,15 @@ BlinkM::led()
/* get number of used satellites in navigation */
num_of_used_sats = 0;
- //for(int satloop=0; satloop<20; satloop++) {
- for(int satloop=0; satloop<sizeof(vehicle_gps_position_raw.satellite_used); satloop++) {
- if(vehicle_gps_position_raw.satellite_used[satloop] == 1) {
+
+ for (unsigned satloop = 0; satloop < (sizeof(vehicle_gps_position_raw.satellite_used) / sizeof(vehicle_gps_position_raw.satellite_used[0])); satloop++) {
+ if (vehicle_gps_position_raw.satellite_used[satloop] == 1) {
num_of_used_sats++;
}
}
- if(new_data_vehicle_status || no_data_vehicle_status < 3){
- if(num_of_cells == 0) {
+ if (new_data_vehicle_status || no_data_vehicle_status < 3) {
+ if (num_of_cells == 0) {
/* looking for lipo cells that are connected */
printf("<blinkm> checking cells\n");
for(num_of_cells = 2; num_of_cells < 7; num_of_cells++) {
@@ -530,7 +549,7 @@ BlinkM::led()
} else {
/* no battery warnings here */
- if(vehicle_status_raw.flag_system_armed == false) {
+ if(actuator_safety.armed == false) {
/* system not armed */
led_color_1 = LED_RED;
led_color_2 = LED_RED;
@@ -555,26 +574,27 @@ BlinkM::led()
led_blink = LED_BLINK;
/* handle 4th led - flightmode indicator */
- switch((int)vehicle_status_raw.flight_mode) {
- case VEHICLE_FLIGHT_MODE_MANUAL:
- led_color_4 = LED_AMBER;
- break;
-
- case VEHICLE_FLIGHT_MODE_STAB:
- led_color_4 = LED_YELLOW;
- break;
-
- case VEHICLE_FLIGHT_MODE_HOLD:
- led_color_4 = LED_BLUE;
- break;
-
- case VEHICLE_FLIGHT_MODE_AUTO:
- led_color_4 = LED_GREEN;
- break;
- }
+#warning fix this
+// switch((int)vehicle_status_raw.flight_mode) {
+// case VEHICLE_FLIGHT_MODE_MANUAL:
+// led_color_4 = LED_AMBER;
+// break;
+//
+// case VEHICLE_FLIGHT_MODE_STAB:
+// led_color_4 = LED_YELLOW;
+// break;
+//
+// case VEHICLE_FLIGHT_MODE_HOLD:
+// led_color_4 = LED_BLUE;
+// break;
+//
+// case VEHICLE_FLIGHT_MODE_AUTO:
+// led_color_4 = LED_GREEN;
+// break;
+// }
if(new_data_vehicle_gps_position || no_data_vehicle_gps_position < 3) {
- /* handling used sat´s */
+ /* handling used sat�s */
if(num_of_used_sats >= 7) {
led_color_1 = LED_OFF;
led_color_2 = LED_OFF;
diff --git a/src/drivers/hil/hil.cpp b/src/drivers/hil/hil.cpp
index bd027ce0b..15fbf8c88 100644
--- a/src/drivers/hil/hil.cpp
+++ b/src/drivers/hil/hil.cpp
@@ -75,6 +75,7 @@
#include <systemlib/mixer/mixer.h>
#include <uORB/topics/actuator_controls.h>
+#include <uORB/topics/actuator_safety.h>
#include <uORB/topics/actuator_outputs.h>
#include <systemlib/err.h>
@@ -108,7 +109,7 @@ private:
int _current_update_rate;
int _task;
int _t_actuators;
- int _t_armed;
+ int _t_safety;
orb_advert_t _t_outputs;
unsigned _num_outputs;
bool _primary_pwm_device;
@@ -161,7 +162,7 @@ HIL::HIL() :
_current_update_rate(0),
_task(-1),
_t_actuators(-1),
- _t_armed(-1),
+ _t_safety(-1),
_t_outputs(0),
_num_outputs(0),
_primary_pwm_device(false),
@@ -321,8 +322,8 @@ HIL::task_main()
/* force a reset of the update rate */
_current_update_rate = 0;
- _t_armed = orb_subscribe(ORB_ID(actuator_armed));
- orb_set_interval(_t_armed, 200); /* 5Hz update rate */
+ _t_safety = orb_subscribe(ORB_ID(actuator_safety));
+ orb_set_interval(_t_safety, 200); /* 5Hz update rate */
/* advertise the mixed control outputs */
actuator_outputs_s outputs;
@@ -334,7 +335,7 @@ HIL::task_main()
pollfd fds[2];
fds[0].fd = _t_actuators;
fds[0].events = POLLIN;
- fds[1].fd = _t_armed;
+ fds[1].fd = _t_safety;
fds[1].events = POLLIN;
unsigned num_outputs;
@@ -426,15 +427,15 @@ HIL::task_main()
/* how about an arming update? */
if (fds[1].revents & POLLIN) {
- actuator_armed_s aa;
+ actuator_safety_s aa;
/* get new value */
- orb_copy(ORB_ID(actuator_armed), _t_armed, &aa);
+ orb_copy(ORB_ID(actuator_safety), _t_safety, &aa);
}
}
::close(_t_actuators);
- ::close(_t_armed);
+ ::close(_t_safety);
/* make sure servos are off */
// up_pwm_servo_deinit();
diff --git a/src/drivers/mkblctrl/mkblctrl.cpp b/src/drivers/mkblctrl/mkblctrl.cpp
index b54b7aba1..f187f22a6 100644
--- a/src/drivers/mkblctrl/mkblctrl.cpp
+++ b/src/drivers/mkblctrl/mkblctrl.cpp
@@ -74,6 +74,7 @@
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/actuator_controls_effective.h>
#include <uORB/topics/actuator_outputs.h>
+#include <uORB/topics/actuator_safety.h>
#include <systemlib/err.h>
@@ -132,7 +133,7 @@ private:
int _current_update_rate;
int _task;
int _t_actuators;
- int _t_armed;
+ int _t_actuator_safety;
unsigned int _motor;
int _px4mode;
int _frametype;
@@ -240,7 +241,7 @@ MK::MK(int bus) :
_update_rate(50),
_task(-1),
_t_actuators(-1),
- _t_armed(-1),
+ _t_actuator_safety(-1),
_t_outputs(0),
_t_actuators_effective(0),
_num_outputs(0),
@@ -496,8 +497,8 @@ MK::task_main()
/* force a reset of the update rate */
_current_update_rate = 0;
- _t_armed = orb_subscribe(ORB_ID(actuator_armed));
- orb_set_interval(_t_armed, 200); /* 5Hz update rate */
+ _t_actuator_safety = orb_subscribe(ORB_ID(actuator_safety));
+ orb_set_interval(_t_actuator_safety, 200); /* 5Hz update rate */
/* advertise the mixed control outputs */
actuator_outputs_s outputs;
@@ -519,7 +520,7 @@ MK::task_main()
pollfd fds[2];
fds[0].fd = _t_actuators;
fds[0].events = POLLIN;
- fds[1].fd = _t_armed;
+ fds[1].fd = _t_actuator_safety;
fds[1].events = POLLIN;
log("starting");
@@ -625,13 +626,13 @@ MK::task_main()
/* how about an arming update? */
if (fds[1].revents & POLLIN) {
- actuator_armed_s aa;
+ actuator_safety_s as;
/* get new value */
- orb_copy(ORB_ID(actuator_armed), _t_armed, &aa);
+ orb_copy(ORB_ID(actuator_safety), _t_actuator_safety, &as);
/* update PWM servo armed status if armed and not locked down */
- mk_servo_arm(aa.armed && !aa.lockdown);
+ mk_servo_arm(as.armed && !as.lockdown);
}
@@ -639,7 +640,7 @@ MK::task_main()
::close(_t_actuators);
::close(_t_actuators_effective);
- ::close(_t_armed);
+ ::close(_t_actuator_safety);
/* make sure servos are off */
diff --git a/src/drivers/px4fmu/fmu.cpp b/src/drivers/px4fmu/fmu.cpp
index 5147ac500..05951f74c 100644
--- a/src/drivers/px4fmu/fmu.cpp
+++ b/src/drivers/px4fmu/fmu.cpp
@@ -69,6 +69,7 @@
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/actuator_controls_effective.h>
#include <uORB/topics/actuator_outputs.h>
+#include <uORB/topics/actuator_safety.h>
#include <systemlib/err.h>
#include <systemlib/ppm_decode.h>
@@ -104,7 +105,7 @@ private:
unsigned _current_update_rate;
int _task;
int _t_actuators;
- int _t_armed;
+ int _t_actuator_safety;
orb_advert_t _t_outputs;
orb_advert_t _t_actuators_effective;
unsigned _num_outputs;
@@ -174,7 +175,7 @@ PX4FMU::PX4FMU() :
_current_update_rate(0),
_task(-1),
_t_actuators(-1),
- _t_armed(-1),
+ _t_actuator_safety(-1),
_t_outputs(0),
_t_actuators_effective(0),
_num_outputs(0),
@@ -376,8 +377,8 @@ PX4FMU::task_main()
/* force a reset of the update rate */
_current_update_rate = 0;
- _t_armed = orb_subscribe(ORB_ID(actuator_armed));
- orb_set_interval(_t_armed, 200); /* 5Hz update rate */
+ _t_actuator_safety = orb_subscribe(ORB_ID(actuator_safety));
+ orb_set_interval(_t_actuator_safety, 200); /* 5Hz update rate */
/* advertise the mixed control outputs */
actuator_outputs_s outputs;
@@ -396,7 +397,7 @@ PX4FMU::task_main()
pollfd fds[2];
fds[0].fd = _t_actuators;
fds[0].events = POLLIN;
- fds[1].fd = _t_armed;
+ fds[1].fd = _t_actuator_safety;
fds[1].events = POLLIN;
unsigned num_outputs = (_mode == MODE_2PWM) ? 2 : 4;
@@ -499,13 +500,13 @@ PX4FMU::task_main()
/* how about an arming update? */
if (fds[1].revents & POLLIN) {
- actuator_armed_s aa;
+ actuator_safety_s as;
/* get new value */
- orb_copy(ORB_ID(actuator_armed), _t_armed, &aa);
+ orb_copy(ORB_ID(actuator_safety), _t_actuator_safety, &as);
/* update PWM servo armed status if armed and not locked down */
- bool set_armed = aa.armed && !aa.lockdown;
+ bool set_armed = as.armed && !as.lockdown;
if (set_armed != _armed) {
_armed = set_armed;
up_pwm_servo_arm(set_armed);
@@ -535,7 +536,7 @@ PX4FMU::task_main()
::close(_t_actuators);
::close(_t_actuators_effective);
- ::close(_t_armed);
+ ::close(_t_actuator_safety);
/* make sure servos are off */
up_pwm_servo_deinit();
@@ -1021,12 +1022,12 @@ fake(int argc, char *argv[])
if (handle < 0)
errx(1, "advertise failed");
- actuator_armed_s aa;
+ actuator_safety_s as;
- aa.armed = true;
- aa.lockdown = false;
+ as.armed = true;
+ as.lockdown = false;
- handle = orb_advertise(ORB_ID(actuator_armed), &aa);
+ handle = orb_advertise(ORB_ID(actuator_safety), &as);
if (handle < 0)
errx(1, "advertise failed 2");
diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp
index 19163cebe..df2f18270 100644
--- a/src/drivers/px4io/px4io.cpp
+++ b/src/drivers/px4io/px4io.cpp
@@ -75,6 +75,7 @@
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/actuator_controls_effective.h>
#include <uORB/topics/actuator_outputs.h>
+#include <uORB/topics/actuator_safety.h>
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/vehicle_command.h>
#include <uORB/topics/rc_channels.h>
@@ -125,6 +126,21 @@ public:
int set_failsafe_values(const uint16_t *vals, unsigned len);
/**
+ * Set the minimum PWM signals when armed
+ */
+ int set_min_values(const uint16_t *vals, unsigned len);
+
+ /**
+ * Set the maximum PWM signal when armed
+ */
+ int set_max_values(const uint16_t *vals, unsigned len);
+
+ /**
+ * Set an idle PWM signal that is active right after startup, even when SAFETY_SAFE
+ */
+ int set_idle_values(const uint16_t *vals, unsigned len);
+
+ /**
* Print the current status of IO
*/
void print_status();
@@ -152,7 +168,7 @@ private:
/* subscribed topics */
int _t_actuators; ///< actuator controls topic
- int _t_armed; ///< system armed control topic
+ int _t_actuator_safety; ///< system armed control topic
int _t_vstatus; ///< system / vehicle status
int _t_param; ///< parameter update topic
@@ -161,6 +177,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
@@ -327,13 +344,14 @@ PX4IO::PX4IO() :
_status(0),
_alarms(0),
_t_actuators(-1),
- _t_armed(-1),
+ _t_actuator_safety(-1),
_t_vstatus(-1),
_t_param(-1),
_to_input_rc(0),
_to_actuators_effective(0),
_to_outputs(0),
_to_battery(0),
+ _to_safety(0),
_primary_pwm_device(false),
_battery_amp_per_volt(90.0f/5.0f), // this matches the 3DR current sensor
_battery_amp_bias(0),
@@ -387,6 +405,40 @@ PX4IO::init()
*/
_retries = 2;
+ /* get IO's last seen FMU state */
+ int val = io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING);
+ if (val == _io_reg_get_error) {
+ mavlink_log_emergency(_mavlink_fd, "[IO] ERROR! FAILED READING STATE");
+ }
+ uint16_t arming = val;
+
+ /* get basic software version */
+ /* basic configuration */
+ usleep(5000);
+
+ unsigned proto_version = io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_PROTOCOL_VERSION);
+ unsigned sw_version = io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_SOFTWARE_VERSION);
+
+ if (proto_version != PX4IO_P_CONFIG_PROTOCOL_VERSION_MAGIC) {
+ mavlink_log_emergency(_mavlink_fd, "[IO] ERROR! PROTO VER MISMATCH: v%u vs v%u\n",
+ proto_version,
+ PX4IO_P_CONFIG_PROTOCOL_VERSION_MAGIC);
+
+ mavlink_log_emergency(_mavlink_fd, "[IO] Please update PX4IO firmware.");
+ log("protocol version mismatch (v%u on IO vs v%u on FMU)", proto_version, PX4IO_P_CONFIG_PROTOCOL_VERSION_MAGIC);
+ return 1;
+ }
+
+ if (sw_version != PX4IO_P_CONFIG_SOFTWARE_VERSION_MAGIC) {
+ mavlink_log_emergency(_mavlink_fd, "[IO] ERROR! SOFTWARE VER MISMATCH: v%u vs v%u\n",
+ proto_version,
+ PX4IO_P_CONFIG_SOFTWARE_VERSION_MAGIC);
+
+ mavlink_log_emergency(_mavlink_fd, "[IO] Please update PX4IO firmware.");
+ log("software version mismatch (v%u on IO vs v%u on FMU)", sw_version, PX4IO_P_CONFIG_SOFTWARE_VERSION_MAGIC);
+ return 1;
+ }
+
/* get some parameters */
_max_actuators = io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_ACTUATOR_COUNT);
_max_controls = io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_CONTROL_COUNT);
@@ -412,41 +464,44 @@ PX4IO::init()
* in this case.
*/
- uint16_t reg;
+ printf("arming 0x%04x%s%s%s%s\n",
+ arming,
+ ((arming & PX4IO_P_SETUP_ARMING_FMU_ARMED) ? " FMU_ARMED" : ""),
+ ((arming & PX4IO_P_SETUP_ARMING_IO_ARM_OK) ? " IO_ARM_OK" : ""),
+ ((arming & PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK) ? " MANUAL_OVERRIDE_OK" : ""),
+ ((arming & PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK) ? " INAIR_RESTART_OK" : ""),
+ ((arming & PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM) ? " FAILSAFE CUSTOM" : ""));
- /* get IO's last seen FMU state */
- ret = io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING, &reg, sizeof(reg));
- if (ret != OK)
- return ret;
/*
* in-air restart is only tried if the IO board reports it is
* already armed, and has been configured for in-air restart
*/
- if ((reg & PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK) &&
- (reg & PX4IO_P_SETUP_ARMING_FMU_ARMED)) {
+ if ((arming & PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK) &&
+ (arming & PX4IO_P_SETUP_ARMING_FMU_ARMED)) {
mavlink_log_emergency(_mavlink_fd, "[IO] RECOVERING FROM FMU IN-AIR RESTART");
+ log("INAIR RESTART RECOVERY (needs commander app running)");
/* WARNING: COMMANDER app/vehicle status must be initialized.
* If this fails (or the app is not started), worst-case IO
* remains untouched (so manual override is still available).
*/
- int vstatus_sub = orb_subscribe(ORB_ID(vehicle_status));
+ int safety_sub = orb_subscribe(ORB_ID(actuator_safety));
/* fill with initial values, clear updated flag */
- vehicle_status_s status;
+ struct actuator_safety_s safety;
uint64_t try_start_time = hrt_absolute_time();
bool updated = false;
- /* keep checking for an update, ensure we got a recent state,
+ /* keep checking for an update, ensure we got a arming information,
not something that was published a long time ago. */
do {
- orb_check(vstatus_sub, &updated);
+ orb_check(safety_sub, &updated);
if (updated) {
/* got data, copy and exit loop */
- orb_copy(ORB_ID(vehicle_status), vstatus_sub, &status);
+ orb_copy(ORB_ID(actuator_safety), safety_sub, &safety);
break;
}
@@ -472,35 +527,41 @@ PX4IO::init()
cmd.param6 = 0;
cmd.param7 = 0;
cmd.command = VEHICLE_CMD_COMPONENT_ARM_DISARM;
- cmd.target_system = status.system_id;
- cmd.target_component = status.component_id;
- cmd.source_system = status.system_id;
- cmd.source_component = status.component_id;
+ // cmd.target_system = status.system_id;
+ // cmd.target_component = status.component_id;
+ // cmd.source_system = status.system_id;
+ // cmd.source_component = status.component_id;
/* ask to confirm command */
cmd.confirmation = 1;
/* send command once */
- (void)orb_advertise(ORB_ID(vehicle_command), &cmd);
+ orb_advert_t pub = orb_advertise(ORB_ID(vehicle_command), &cmd);
/* spin here until IO's state has propagated into the system */
do {
- orb_check(vstatus_sub, &updated);
+ orb_check(safety_sub, &updated);
if (updated) {
- orb_copy(ORB_ID(vehicle_status), vstatus_sub, &status);
+ orb_copy(ORB_ID(actuator_safety), safety_sub, &safety);
}
- /* wait 10 ms */
- usleep(10000);
+ /* wait 50 ms */
+ usleep(50000);
/* abort after 5s */
- if ((hrt_absolute_time() - try_start_time)/1000 > 50000) {
+ if ((hrt_absolute_time() - try_start_time)/1000 > 2000) {
log("failed to recover from in-air restart (2), aborting IO driver init.");
return 1;
}
- /* keep waiting for state change for 10 s */
- } while (!status.flag_system_armed);
+ /* re-send if necessary */
+ if (!safety.armed) {
+ orb_publish(ORB_ID(vehicle_command), pub, &cmd);
+ log("re-sending arm cmd");
+ }
+
+ /* keep waiting for state change for 2 s */
+ } while (!safety.armed);
/* regular boot, no in-air restart, init IO */
} else {
@@ -510,7 +571,8 @@ PX4IO::init()
io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING,
PX4IO_P_SETUP_ARMING_FMU_ARMED |
PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK |
- PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK, 0);
+ PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK |
+ PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE, 0);
/* publish RC config to IO */
ret = io_set_rc_config();
@@ -538,7 +600,7 @@ PX4IO::init()
return -errno;
}
- mavlink_log_info(_mavlink_fd, "[IO] init ok");
+ mavlink_log_info(_mavlink_fd, "[IO] init ok (sw v.%u)", sw_version);
return OK;
}
@@ -564,8 +626,8 @@ PX4IO::task_main()
ORB_ID(actuator_controls_1));
orb_set_interval(_t_actuators, 20); /* default to 50Hz */
- _t_armed = orb_subscribe(ORB_ID(actuator_armed));
- orb_set_interval(_t_armed, 200); /* 5Hz update rate */
+ _t_actuator_safety = orb_subscribe(ORB_ID(actuator_safety));
+ orb_set_interval(_t_actuator_safety, 200); /* 5Hz update rate */
_t_vstatus = orb_subscribe(ORB_ID(vehicle_status));
orb_set_interval(_t_vstatus, 200); /* 5Hz update rate max. */
@@ -577,7 +639,7 @@ PX4IO::task_main()
pollfd fds[4];
fds[0].fd = _t_actuators;
fds[0].events = POLLIN;
- fds[1].fd = _t_armed;
+ fds[1].fd = _t_actuator_safety;
fds[1].events = POLLIN;
fds[2].fd = _t_vstatus;
fds[2].events = POLLIN;
@@ -711,24 +773,65 @@ PX4IO::set_failsafe_values(const uint16_t *vals, unsigned len)
}
int
+PX4IO::set_min_values(const uint16_t *vals, unsigned len)
+{
+ uint16_t regs[_max_actuators];
+
+ if (len > _max_actuators)
+ /* fail with error */
+ return E2BIG;
+
+ /* copy values to registers in IO */
+ return io_reg_set(PX4IO_PAGE_CONTROL_MIN_PWM, 0, vals, len);
+}
+
+int
+PX4IO::set_max_values(const uint16_t *vals, unsigned len)
+{
+ uint16_t regs[_max_actuators];
+
+ if (len > _max_actuators)
+ /* fail with error */
+ return E2BIG;
+
+ /* copy values to registers in IO */
+ return io_reg_set(PX4IO_PAGE_CONTROL_MAX_PWM, 0, vals, len);
+}
+
+int
+PX4IO::set_idle_values(const uint16_t *vals, unsigned len)
+{
+ uint16_t regs[_max_actuators];
+
+ if (len > _max_actuators)
+ /* fail with error */
+ return E2BIG;
+
+ printf("Sending IDLE values\n");
+
+ /* copy values to registers in IO */
+ return io_reg_set(PX4IO_PAGE_IDLE_PWM, 0, vals, len);
+}
+
+
+int
PX4IO::io_set_arming_state()
{
- actuator_armed_s armed; ///< system armed state
+ actuator_safety_s safety; ///< system armed state
vehicle_status_s vstatus; ///< overall system state
- orb_copy(ORB_ID(actuator_armed), _t_armed, &armed);
+ orb_copy(ORB_ID(actuator_safety), _t_actuator_safety, &safety);
orb_copy(ORB_ID(vehicle_status), _t_vstatus, &vstatus);
uint16_t set = 0;
uint16_t clear = 0;
- if (armed.armed && !armed.lockdown) {
+ if (safety.armed && !safety.lockdown) {
set |= PX4IO_P_SETUP_ARMING_FMU_ARMED;
} else {
clear |= PX4IO_P_SETUP_ARMING_FMU_ARMED;
}
-
- if (armed.ready_to_arm) {
+ if (safety.ready_to_arm) {
set |= PX4IO_P_SETUP_ARMING_IO_ARM_OK;
} else {
clear |= PX4IO_P_SETUP_ARMING_IO_ARM_OK;
@@ -861,14 +964,14 @@ PX4IO::io_handle_status(uint16_t status)
*/
/* check for IO reset - force it back to armed if necessary */
- if (_status & PX4IO_P_STATUS_FLAGS_ARMED && !(status & PX4IO_P_STATUS_FLAGS_ARMED)
+ if (_status & PX4IO_P_STATUS_FLAGS_SAFETY_OFF && !(status & PX4IO_P_STATUS_FLAGS_SAFETY_OFF)
&& !(status & PX4IO_P_STATUS_FLAGS_ARM_SYNC)) {
/* set the arming flag */
- ret = io_reg_modify(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_FLAGS, 0, PX4IO_P_STATUS_FLAGS_ARMED | PX4IO_P_STATUS_FLAGS_ARM_SYNC);
+ ret = io_reg_modify(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_FLAGS, 0, PX4IO_P_STATUS_FLAGS_SAFETY_OFF | PX4IO_P_STATUS_FLAGS_ARM_SYNC);
/* set new status */
_status = status;
- _status &= PX4IO_P_STATUS_FLAGS_ARMED;
+ _status &= PX4IO_P_STATUS_FLAGS_SAFETY_OFF;
} else if (!(_status & PX4IO_P_STATUS_FLAGS_ARM_SYNC)) {
/* set the sync flag */
@@ -883,6 +986,29 @@ PX4IO::io_handle_status(uint16_t status)
_status = status;
}
+ /**
+ * Get and handle the safety status
+ */
+ struct actuator_safety_s safety;
+ safety.timestamp = hrt_absolute_time();
+
+ orb_copy(ORB_ID(actuator_safety), _t_actuator_safety, &safety);
+
+ if (status & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) {
+ safety.safety_off = true;
+ safety.safety_switch_available = true;
+ } else {
+ safety.safety_off = false;
+ safety.safety_switch_available = true;
+ }
+
+ /* lazily publish the safety status */
+ if (_to_safety > 0) {
+ orb_publish(ORB_ID(actuator_safety), _to_safety, &safety);
+ } else {
+ _to_safety = orb_advertise(ORB_ID(actuator_safety), &safety);
+ }
+
return ret;
}
@@ -912,7 +1038,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 +1072,7 @@ PX4IO::io_get_status()
_to_battery = orb_advertise(ORB_ID(battery_status), &battery_status);
}
}
+
return ret;
}
@@ -1183,6 +1310,7 @@ PX4IO::io_reg_modify(uint8_t page, uint8_t offset, uint16_t clearbits, uint16_t
uint16_t value;
ret = io_reg_get(page, offset, &value, 1);
+
if (ret)
return ret;
value &= ~clearbits;
@@ -1273,7 +1401,8 @@ 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_OUTPUTS_ARMED) ? " OUTPUTS_ARMED" : ""),
+ ((flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) ? " SAFETY_OFF" : " SAFETY_SAFE"),
((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" : ""),
@@ -1335,12 +1464,14 @@ PX4IO::print_status()
/* setup and state */
printf("features 0x%04x\n", io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_FEATURES));
uint16_t arming = io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING);
- printf("arming 0x%04x%s%s%s%s\n",
+ printf("arming 0x%04x%s%s%s%s%s%s\n",
arming,
((arming & PX4IO_P_SETUP_ARMING_FMU_ARMED) ? " FMU_ARMED" : ""),
((arming & PX4IO_P_SETUP_ARMING_IO_ARM_OK) ? " IO_ARM_OK" : ""),
((arming & PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK) ? " MANUAL_OVERRIDE_OK" : ""),
- ((arming & PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK) ? " INAIR_RESTART_OK" : ""));
+ ((arming & PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM) ? " FAILSAFE_CUSTOM" : ""),
+ ((arming & PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK) ? " INAIR_RESTART_OK" : ""),
+ ((arming & PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE) ? " ALWAYS_PWM_ENABLE" : ""));
printf("rates 0x%04x default %u alt %u relays 0x%04x\n",
io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_RATES),
io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_DEFAULTRATE),
@@ -1367,7 +1498,10 @@ PX4IO::print_status()
}
printf("failsafe");
for (unsigned i = 0; i < _max_actuators; i++)
- printf(" %u", io_reg_get(PX4IO_PAGE_FAILSAFE_PWM, i));
+ printf(" %u\n", io_reg_get(PX4IO_PAGE_FAILSAFE_PWM, i));
+ printf("\nidle values");
+ for (unsigned i = 0; i < _max_actuators; i++)
+ printf(" %u", io_reg_get(PX4IO_PAGE_IDLE_PWM, i));
printf("\n");
}
@@ -1634,6 +1768,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 +1821,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);
@@ -1792,6 +1931,111 @@ px4io_main(int argc, char *argv[])
exit(0);
}
+ if (!strcmp(argv[1], "min")) {
+
+ if (argc < 3) {
+ errx(1, "min command needs at least one channel value (PWM)");
+ }
+
+ if (g_dev != nullptr) {
+
+ /* set values for first 8 channels, fill unassigned channels with 900. */
+ uint16_t min[8];
+
+ for (int i = 0; i < sizeof(min) / sizeof(min[0]); i++)
+ {
+ /* set channel to commanline argument or to 900 for non-provided channels */
+ if (argc > i + 2) {
+ min[i] = atoi(argv[i+2]);
+ if (min[i] < 900 || min[i] > 1200) {
+ errx(1, "value out of range of 900 < value < 1200. Aborting.");
+ }
+ } else {
+ /* a zero value will the default */
+ min[i] = 0;
+ }
+ }
+
+ int ret = g_dev->set_min_values(min, sizeof(min) / sizeof(min[0]));
+
+ if (ret != OK)
+ errx(ret, "failed setting min values");
+ } else {
+ errx(1, "not loaded");
+ }
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "max")) {
+
+ if (argc < 3) {
+ errx(1, "max command needs at least one channel value (PWM)");
+ }
+
+ if (g_dev != nullptr) {
+
+ /* set values for first 8 channels, fill unassigned channels with 2100. */
+ uint16_t max[8];
+
+ for (int i = 0; i < sizeof(max) / sizeof(max[0]); i++)
+ {
+ /* set channel to commanline argument or to 2100 for non-provided channels */
+ if (argc > i + 2) {
+ max[i] = atoi(argv[i+2]);
+ if (max[i] < 1800 || max[i] > 2100) {
+ errx(1, "value out of range of 1800 < value < 2100. Aborting.");
+ }
+ } else {
+ /* a zero value will the default */
+ max[i] = 0;
+ }
+ }
+
+ int ret = g_dev->set_max_values(max, sizeof(max) / sizeof(max[0]));
+
+ if (ret != OK)
+ errx(ret, "failed setting max values");
+ } else {
+ errx(1, "not loaded");
+ }
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "idle")) {
+
+ if (argc < 3) {
+ errx(1, "max command needs at least one channel value (PWM)");
+ }
+
+ if (g_dev != nullptr) {
+
+ /* set values for first 8 channels, fill unassigned channels with 0. */
+ uint16_t idle[8];
+
+ for (int i = 0; i < sizeof(idle) / sizeof(idle[0]); i++)
+ {
+ /* set channel to commanline argument or to 0 for non-provided channels */
+ if (argc > i + 2) {
+ idle[i] = atoi(argv[i+2]);
+ if (idle[i] < 900 || idle[i] > 2100) {
+ errx(1, "value out of range of 900 < value < 2100. Aborting.");
+ }
+ } else {
+ /* a zero value will the default */
+ idle[i] = 0;
+ }
+ }
+
+ int ret = g_dev->set_idle_values(idle, sizeof(idle) / sizeof(idle[0]));
+
+ if (ret != OK)
+ errx(ret, "failed setting idle values");
+ } else {
+ errx(1, "not loaded");
+ }
+ exit(0);
+ }
+
if (!strcmp(argv[1], "recovery")) {
if (g_dev != nullptr) {
@@ -1919,5 +2163,5 @@ px4io_main(int argc, char *argv[])
monitor();
out:
- errx(1, "need a command, try 'start', 'stop', 'status', 'test', 'monitor', 'debug', 'recovery', 'limit', 'current', 'failsafe' or 'update'");
+ errx(1, "need a command, try 'start', 'stop', 'status', 'test', 'monitor', 'debug', 'recovery', 'limit', 'current', 'failsafe', 'min, 'max', 'idle' or 'update'");
}
diff --git a/src/drivers/stm32/tone_alarm/tone_alarm.cpp b/src/drivers/stm32/tone_alarm/tone_alarm.cpp
index 167ef30a8..e1409a815 100644
--- a/src/drivers/stm32/tone_alarm/tone_alarm.cpp
+++ b/src/drivers/stm32/tone_alarm/tone_alarm.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * 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
@@ -241,6 +241,8 @@ private:
static const unsigned _default_ntunes;
static const uint8_t _note_tab[];
+ unsigned _default_tune_number; // number of currently playing default tune (0 for none)
+
const char *_user_tune;
const char *_tune; // current tune string
@@ -456,6 +458,11 @@ const char * const ToneAlarm::_default_tunes[] = {
"O1B8O2G+8E8B8G+8O3E8O2B8O3E8O2B8O3G+8E8B8"
"O3G+8O4E4P8E16E16E8E8E8E8E4P8E16E4P8O2E16"
"O2E2P64",
+ "MNT75L1O2G", //arming warning
+ "MBNT100a8", //battery warning slow
+ "MBNT255a8a8a8a8a8a8a8a8a8a8a8a8a8a8a8a8"
+ "a8a8a8a8a8a8a8a8a8a8a8a8a8a8a8a8"
+ "a8a8a8a8a8a8a8a8a8a8a8a8a8a8a8a8", //battery warning fast // XXX why is there a break before a repetition
};
const unsigned ToneAlarm::_default_ntunes = sizeof(_default_tunes) / sizeof(_default_tunes[0]);
@@ -471,6 +478,7 @@ extern "C" __EXPORT int tone_alarm_main(int argc, char *argv[]);
ToneAlarm::ToneAlarm() :
CDev("tone_alarm", "/dev/tone_alarm"),
+ _default_tune_number(0),
_user_tune(nullptr),
_tune(nullptr),
_next(nullptr)
@@ -803,8 +811,12 @@ tune_error:
// stop (and potentially restart) the tune
tune_end:
stop_note();
- if (_repeat)
+ if (_repeat) {
start_tune(_tune);
+ } else {
+ _tune = nullptr;
+ _default_tune_number = 0;
+ }
return;
}
@@ -873,8 +885,17 @@ ToneAlarm::ioctl(file *filp, int cmd, unsigned long arg)
_tune = nullptr;
_next = nullptr;
} else {
- // play the selected tune
- start_tune(_default_tunes[arg - 1]);
+ /* don't interrupt alarms unless they are repeated */
+ if (_tune != nullptr && !_repeat) {
+ /* abort and let the current tune finish */
+ result = -EBUSY;
+ } else if (_repeat && _default_tune_number == arg) {
+ /* requested repeating tune already playing */
+ } else {
+ // play the selected tune
+ _default_tune_number = arg;
+ start_tune(_default_tunes[arg - 1]);
+ }
}
} else {
result = -EINVAL;
diff --git a/src/examples/fixedwing_control/main.c b/src/examples/fixedwing_control/main.c
index 27888523b..ae33a3702 100644
--- a/src/examples/fixedwing_control/main.c
+++ b/src/examples/fixedwing_control/main.c
@@ -380,9 +380,10 @@ int fixedwing_control_thread_main(int argc, char *argv[])
/* control */
- /* if in auto mode, fly global position setpoint */
- if (vstatus.state_machine == SYSTEM_STATE_AUTO ||
- vstatus.state_machine == SYSTEM_STATE_STABILIZED) {
+#warning fix this
+#if 0
+ if (vstatus.navigation_state == NAVIGATION_STATE_AUTO_ ||
+ vstatus.navigation_state == NAVIGATION_STATE_STABILIZED) {
/* simple heading control */
control_heading(&global_pos, &global_sp, &att, &att_sp);
@@ -400,6 +401,7 @@ int fixedwing_control_thread_main(int argc, char *argv[])
/* set flaps to zero */
actuators.control[4] = 0.0f;
+ } else if (vstatus.navigation_state == NAVIGATION_STATE_MANUAL) {
/* if in manual mode, decide between attitude stabilization (SAS) and full manual pass-through */
} else if (vstatus.state_machine == SYSTEM_STATE_MANUAL) {
if (vstatus.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_SAS) {
@@ -465,6 +467,7 @@ int fixedwing_control_thread_main(int argc, char *argv[])
}
}
}
+#endif
/* publish rates */
orb_publish(ORB_ID(vehicle_rates_setpoint), rates_pub, &rates_sp);
diff --git a/src/examples/flow_position_control/flow_position_control_main.c b/src/examples/flow_position_control/flow_position_control_main.c
index c177c8fd2..ecc133f63 100644
--- a/src/examples/flow_position_control/flow_position_control_main.c
+++ b/src/examples/flow_position_control/flow_position_control_main.c
@@ -55,7 +55,8 @@
#include <drivers/drv_hrt.h>
#include <uORB/uORB.h>
#include <uORB/topics/parameter_update.h>
-#include <uORB/topics/vehicle_status.h>
+#include <uORB/topics/actuator_safety.h>
+#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/manual_control_setpoint.h>
#include <uORB/topics/vehicle_local_position.h>
@@ -158,7 +159,8 @@ flow_position_control_thread_main(int argc, char *argv[])
const float time_scale = powf(10.0f,-6.0f);
/* structures */
- struct vehicle_status_s vstatus;
+ struct actuator_safety_s safety;
+ struct vehicle_control_mode_s control_mode;
struct vehicle_attitude_s att;
struct manual_control_setpoint_s manual;
struct filtered_bottom_flow_s filtered_flow;
@@ -169,7 +171,8 @@ flow_position_control_thread_main(int argc, char *argv[])
/* subscribe to attitude, motor setpoints and system state */
int parameter_update_sub = orb_subscribe(ORB_ID(parameter_update));
int vehicle_attitude_sub = orb_subscribe(ORB_ID(vehicle_attitude));
- int vehicle_status_sub = orb_subscribe(ORB_ID(vehicle_status));
+ int safety_sub = orb_subscribe(ORB_ID(actuator_safety));
+ int control_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode));
int manual_control_setpoint_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
int filtered_bottom_flow_sub = orb_subscribe(ORB_ID(filtered_bottom_flow));
int vehicle_local_position_sub = orb_subscribe(ORB_ID(vehicle_local_position));
@@ -258,7 +261,7 @@ flow_position_control_thread_main(int argc, char *argv[])
perf_begin(mc_loop_perf);
/* get a local copy of the vehicle state */
- orb_copy(ORB_ID(vehicle_status), vehicle_status_sub, &vstatus);
+ orb_copy(ORB_ID(actuator_safety), safety_sub, &safety);
/* get a local copy of manual setpoint */
orb_copy(ORB_ID(manual_control_setpoint), manual_control_setpoint_sub, &manual);
/* get a local copy of attitude */
@@ -268,7 +271,7 @@ flow_position_control_thread_main(int argc, char *argv[])
/* get a local copy of local position */
orb_copy(ORB_ID(vehicle_local_position), vehicle_local_position_sub, &local_pos);
- if (vstatus.state_machine == SYSTEM_STATE_AUTO)
+ if (control_mode.flag_control_velocity_enabled)
{
float manual_pitch = manual.pitch / params.rc_scale_pitch; // 0 to 1
float manual_roll = manual.roll / params.rc_scale_roll; // 0 to 1
@@ -490,7 +493,7 @@ flow_position_control_thread_main(int argc, char *argv[])
/* store actual height for speed estimation */
last_local_pos_z = local_pos.z;
- speed_sp.thrust_sp = thrust_control;
+ speed_sp.thrust_sp = thrust_control; //manual.throttle;
speed_sp.timestamp = hrt_absolute_time();
/* publish new speed setpoint */
@@ -527,7 +530,6 @@ flow_position_control_thread_main(int argc, char *argv[])
if(isfinite(manual.throttle))
speed_sp.thrust_sp = manual.throttle;
}
-
/* measure in what intervals the controller runs */
perf_count(mc_interval_perf);
perf_end(mc_loop_perf);
@@ -576,7 +578,8 @@ flow_position_control_thread_main(int argc, char *argv[])
close(parameter_update_sub);
close(vehicle_attitude_sub);
close(vehicle_local_position_sub);
- close(vehicle_status_sub);
+ close(safety_sub);
+ close(control_mode_sub);
close(manual_control_setpoint_sub);
close(speed_sp_pub);
diff --git a/src/examples/flow_position_estimator/flow_position_estimator_main.c b/src/examples/flow_position_estimator/flow_position_estimator_main.c
index c0b16d2e7..8f84307a7 100644
--- a/src/examples/flow_position_estimator/flow_position_estimator_main.c
+++ b/src/examples/flow_position_estimator/flow_position_estimator_main.c
@@ -56,7 +56,8 @@
#include <math.h>
#include <uORB/uORB.h>
#include <uORB/topics/parameter_update.h>
-#include <uORB/topics/vehicle_status.h>
+#include <uORB/topics/actuator_safety.h>
+#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_attitude_setpoint.h>
#include <uORB/topics/vehicle_local_position.h>
@@ -143,8 +144,8 @@ int flow_position_estimator_thread_main(int argc, char *argv[])
printf("[flow position estimator] starting\n");
/* rotation matrix for transformation of optical flow speed vectors */
- static const int8_t rotM_flow_sensor[3][3] = {{ 0, 1, 0 },
- { -1, 0, 0 },
+ static const int8_t rotM_flow_sensor[3][3] = {{ 0, -1, 0 },
+ { 1, 0, 0 },
{ 0, 0, 1 }}; // 90deg rotated
const float time_scale = powf(10.0f,-6.0f);
static float speed[3] = {0.0f, 0.0f, 0.0f};
@@ -158,8 +159,10 @@ int flow_position_estimator_thread_main(int argc, char *argv[])
static float sonar_lp = 0.0f;
/* subscribe to vehicle status, attitude, sensors and flow*/
- struct vehicle_status_s vstatus;
- memset(&vstatus, 0, sizeof(vstatus));
+ struct actuator_safety_s safety;
+ memset(&safety, 0, sizeof(safety));
+ struct vehicle_control_mode_s control_mode;
+ memset(&control_mode, 0, sizeof(control_mode));
struct vehicle_attitude_s att;
memset(&att, 0, sizeof(att));
struct vehicle_attitude_setpoint_s att_sp;
@@ -170,8 +173,11 @@ int flow_position_estimator_thread_main(int argc, char *argv[])
/* subscribe to parameter changes */
int parameter_update_sub = orb_subscribe(ORB_ID(parameter_update));
- /* subscribe to vehicle status */
- int vehicle_status_sub = orb_subscribe(ORB_ID(vehicle_status));
+ /* subscribe to safety topic */
+ int safety_sub = orb_subscribe(ORB_ID(actuator_safety));
+
+ /* subscribe to safety topic */
+ int control_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode));
/* subscribe to attitude */
int vehicle_attitude_sub = orb_subscribe(ORB_ID(vehicle_attitude));
@@ -218,6 +224,7 @@ int flow_position_estimator_thread_main(int argc, char *argv[])
while (!thread_should_exit)
{
+
if (sensors_ready)
{
/*This runs at the rate of the sensors */
@@ -263,7 +270,8 @@ int flow_position_estimator_thread_main(int argc, char *argv[])
/* got flow, updating attitude and status as well */
orb_copy(ORB_ID(vehicle_attitude), vehicle_attitude_sub, &att);
orb_copy(ORB_ID(vehicle_attitude_setpoint), vehicle_attitude_setpoint_sub, &att_sp);
- orb_copy(ORB_ID(vehicle_status), vehicle_status_sub, &vstatus);
+ orb_copy(ORB_ID(actuator_safety), safety_sub, &safety);
+ orb_copy(ORB_ID(vehicle_control_mode), control_mode_sub, &control_mode);
/* vehicle state estimation */
float sonar_new = flow.ground_distance_m;
@@ -273,14 +281,15 @@ int flow_position_estimator_thread_main(int argc, char *argv[])
* -> accept sonar measurements after reaching calibration distance (values between 0.3m and 1.0m for some time)
* -> minimum sonar value 0.3m
*/
+
if (!vehicle_liftoff)
{
- if (vstatus.flag_system_armed && att_sp.thrust > params.minimum_liftoff_thrust && sonar_new > 0.3f && sonar_new < 1.0f)
+ if (safety.armed && att_sp.thrust > params.minimum_liftoff_thrust && sonar_new > 0.3f && sonar_new < 1.0f)
vehicle_liftoff = true;
}
else
{
- if (!vstatus.flag_system_armed || (att_sp.thrust < params.minimum_liftoff_thrust && sonar_new <= 0.3f))
+ if (!safety.armed || (att_sp.thrust < params.minimum_liftoff_thrust && sonar_new <= 0.3f))
vehicle_liftoff = false;
}
@@ -347,7 +356,7 @@ int flow_position_estimator_thread_main(int argc, char *argv[])
}
/* filtering ground distance */
- if (!vehicle_liftoff || !vstatus.flag_system_armed)
+ if (!vehicle_liftoff || !safety.armed)
{
/* not possible to fly */
sonar_valid = false;
@@ -444,7 +453,8 @@ int flow_position_estimator_thread_main(int argc, char *argv[])
close(vehicle_attitude_setpoint_sub);
close(vehicle_attitude_sub);
- close(vehicle_status_sub);
+ close(safety_sub);
+ close(control_mode_sub);
close(parameter_update_sub);
close(optical_flow_sub);
diff --git a/src/examples/flow_speed_control/flow_speed_control_main.c b/src/examples/flow_speed_control/flow_speed_control_main.c
index 9648728c8..4f60e34f2 100644
--- a/src/examples/flow_speed_control/flow_speed_control_main.c
+++ b/src/examples/flow_speed_control/flow_speed_control_main.c
@@ -55,7 +55,8 @@
#include <drivers/drv_hrt.h>
#include <uORB/uORB.h>
#include <uORB/topics/parameter_update.h>
-#include <uORB/topics/vehicle_status.h>
+#include <uORB/topics/actuator_safety.h>
+#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_attitude_setpoint.h>
#include <uORB/topics/vehicle_bodyframe_speed_setpoint.h>
@@ -155,7 +156,8 @@ flow_speed_control_thread_main(int argc, char *argv[])
uint32_t counter = 0;
/* structures */
- struct vehicle_status_s vstatus;
+ struct actuator_safety_s safety;
+ struct vehicle_control_mode_s control_mode;
struct filtered_bottom_flow_s filtered_flow;
struct vehicle_bodyframe_speed_setpoint_s speed_sp;
@@ -164,7 +166,8 @@ flow_speed_control_thread_main(int argc, char *argv[])
/* subscribe to attitude, motor setpoints and system state */
int parameter_update_sub = orb_subscribe(ORB_ID(parameter_update));
int vehicle_attitude_sub = orb_subscribe(ORB_ID(vehicle_attitude));
- int vehicle_status_sub = orb_subscribe(ORB_ID(vehicle_status));
+ int safety_sub = orb_subscribe(ORB_ID(actuator_safety));
+ int control_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode));
int filtered_bottom_flow_sub = orb_subscribe(ORB_ID(filtered_bottom_flow));
int vehicle_bodyframe_speed_setpoint_sub = orb_subscribe(ORB_ID(vehicle_bodyframe_speed_setpoint));
@@ -226,14 +229,16 @@ flow_speed_control_thread_main(int argc, char *argv[])
{
perf_begin(mc_loop_perf);
- /* get a local copy of the vehicle state */
- orb_copy(ORB_ID(vehicle_status), vehicle_status_sub, &vstatus);
+ /* get a local copy of the safety topic */
+ orb_copy(ORB_ID(actuator_safety), safety_sub, &safety);
+ /* get a local copy of the control mode */
+ orb_copy(ORB_ID(vehicle_control_mode), control_mode_sub, &control_mode);
/* get a local copy of filtered bottom flow */
orb_copy(ORB_ID(filtered_bottom_flow), filtered_bottom_flow_sub, &filtered_flow);
/* get a local copy of bodyframe speed setpoint */
orb_copy(ORB_ID(vehicle_bodyframe_speed_setpoint), vehicle_bodyframe_speed_setpoint_sub, &speed_sp);
- if (vstatus.state_machine == SYSTEM_STATE_AUTO)
+ if (control_mode.flag_control_velocity_enabled)
{
/* calc new roll/pitch */
float pitch_body = -(speed_sp.vx - filtered_flow.vx) * params.speed_p;
@@ -350,7 +355,8 @@ flow_speed_control_thread_main(int argc, char *argv[])
close(vehicle_attitude_sub);
close(vehicle_bodyframe_speed_setpoint_sub);
close(filtered_bottom_flow_sub);
- close(vehicle_status_sub);
+ close(safety_sub);
+ close(control_mode_sub);
close(att_sp_pub);
perf_print_counter(mc_loop_perf);
diff --git a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_params.c b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_params.c
index 7d3812abd..52dac652b 100755
--- a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_params.c
+++ b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_params.c
@@ -44,42 +44,42 @@
/* Extended Kalman Filter covariances */
/* gyro process noise */
-PARAM_DEFINE_FLOAT(EKF_ATT_V2_Q0, 1e-4f);
-PARAM_DEFINE_FLOAT(EKF_ATT_V2_Q1, 0.08f);
-PARAM_DEFINE_FLOAT(EKF_ATT_V2_Q2, 0.009f);
+PARAM_DEFINE_FLOAT(EKF_ATT_V3_Q0, 1e-4f);
+PARAM_DEFINE_FLOAT(EKF_ATT_V3_Q1, 0.08f);
+PARAM_DEFINE_FLOAT(EKF_ATT_V3_Q2, 0.009f);
/* gyro offsets process noise */
-PARAM_DEFINE_FLOAT(EKF_ATT_V2_Q3, 0.005f);
-PARAM_DEFINE_FLOAT(EKF_ATT_V2_Q4, 0.0f);
+PARAM_DEFINE_FLOAT(EKF_ATT_V3_Q3, 0.005f);
+PARAM_DEFINE_FLOAT(EKF_ATT_V3_Q4, 0.0f);
/* gyro measurement noise */
-PARAM_DEFINE_FLOAT(EKF_ATT_V2_R0, 0.0008f);
-PARAM_DEFINE_FLOAT(EKF_ATT_V2_R1, 0.8f);
-PARAM_DEFINE_FLOAT(EKF_ATT_V2_R2, 1.0f);
+PARAM_DEFINE_FLOAT(EKF_ATT_V3_R0, 0.0008f);
+PARAM_DEFINE_FLOAT(EKF_ATT_V3_R1, 10000.0f);
+PARAM_DEFINE_FLOAT(EKF_ATT_V3_R2, 1.0f);
/* accelerometer measurement noise */
-PARAM_DEFINE_FLOAT(EKF_ATT_V2_R3, 0.0f);
+PARAM_DEFINE_FLOAT(EKF_ATT_V3_R3, 0.0f);
/* offsets in roll, pitch and yaw of sensor plane and body */
-PARAM_DEFINE_FLOAT(ATT_ROLL_OFFS, 0.0f);
-PARAM_DEFINE_FLOAT(ATT_PITCH_OFFS, 0.0f);
-PARAM_DEFINE_FLOAT(ATT_YAW_OFFS, 0.0f);
+PARAM_DEFINE_FLOAT(ATT_ROLL_OFF3, 0.0f);
+PARAM_DEFINE_FLOAT(ATT_PITCH_OFF3, 0.0f);
+PARAM_DEFINE_FLOAT(ATT_YAW_OFF3, 0.0f);
int parameters_init(struct attitude_estimator_ekf_param_handles *h)
{
/* PID parameters */
- h->q0 = param_find("EKF_ATT_V2_Q0");
- h->q1 = param_find("EKF_ATT_V2_Q1");
- h->q2 = param_find("EKF_ATT_V2_Q2");
- h->q3 = param_find("EKF_ATT_V2_Q3");
- h->q4 = param_find("EKF_ATT_V2_Q4");
+ h->q0 = param_find("EKF_ATT_V3_Q0");
+ h->q1 = param_find("EKF_ATT_V3_Q1");
+ h->q2 = param_find("EKF_ATT_V3_Q2");
+ h->q3 = param_find("EKF_ATT_V3_Q3");
+ h->q4 = param_find("EKF_ATT_V3_Q4");
- h->r0 = param_find("EKF_ATT_V2_R0");
- h->r1 = param_find("EKF_ATT_V2_R1");
- h->r2 = param_find("EKF_ATT_V2_R2");
- h->r3 = param_find("EKF_ATT_V2_R3");
+ h->r0 = param_find("EKF_ATT_V3_R0");
+ h->r1 = param_find("EKF_ATT_V3_R1");
+ h->r2 = param_find("EKF_ATT_V3_R2");
+ h->r3 = param_find("EKF_ATT_V3_R3");
- h->roll_off = param_find("ATT_ROLL_OFFS");
- h->pitch_off = param_find("ATT_PITCH_OFFS");
- h->yaw_off = param_find("ATT_YAW_OFFS");
+ h->roll_off = param_find("ATT_ROLL_OFF3");
+ h->pitch_off = param_find("ATT_PITCH_OFF3");
+ h->yaw_off = param_find("ATT_YAW_OFF3");
return OK;
}
diff --git a/src/modules/commander/accelerometer_calibration.c b/src/modules/commander/accelerometer_calibration.c
index 48a36ac26..50234a45e 100644
--- a/src/modules/commander/accelerometer_calibration.c
+++ b/src/modules/commander/accelerometer_calibration.c
@@ -104,32 +104,39 @@
*/
#include "accelerometer_calibration.h"
+#include "commander_helper.h"
+#include <unistd.h>
+#include <stdio.h>
#include <poll.h>
+#include <fcntl.h>
+#include <sys/prctl.h>
+#include <math.h>
+#include <string.h>
+
+
#include <drivers/drv_hrt.h>
#include <uORB/topics/sensor_combined.h>
#include <drivers/drv_accel.h>
#include <systemlib/conversions.h>
+#include <systemlib/param/param.h>
+#include <systemlib/err.h>
#include <mavlink/mavlink_log.h>
-void do_accel_calibration(int status_pub, struct vehicle_status_s *status, int mavlink_fd);
-int do_accel_calibration_mesurements(int mavlink_fd, float accel_offs[3], float accel_scale[3]);
+int do_accel_calibration_measurements(int mavlink_fd, float accel_offs[3], float accel_scale[3]);
int detect_orientation(int mavlink_fd, int sub_sensor_combined);
int read_accelerometer_avg(int sensor_combined_sub, float accel_avg[3], int samples_num);
int mat_invert3(float src[3][3], float dst[3][3]);
int calculate_calibration_values(float accel_ref[6][3], float accel_T[3][3], float accel_offs[3], float g);
-void do_accel_calibration(int status_pub, struct vehicle_status_s *status, int mavlink_fd) {
+void do_accel_calibration(int mavlink_fd) {
/* announce change */
mavlink_log_info(mavlink_fd, "accel calibration started");
- /* set to accel calibration mode */
- status->flag_preflight_accel_calibration = true;
- state_machine_publish(status_pub, status, mavlink_fd);
/* measure and calculate offsets & scales */
float accel_offs[3];
float accel_scale[3];
- int res = do_accel_calibration_mesurements(mavlink_fd, accel_offs, accel_scale);
+ int res = do_accel_calibration_measurements(mavlink_fd, accel_offs, accel_scale);
if (res == OK) {
/* measurements complete successfully, set parameters */
@@ -165,24 +172,17 @@ void do_accel_calibration(int status_pub, struct vehicle_status_s *status, int m
}
mavlink_log_info(mavlink_fd, "accel calibration done");
- tune_confirm();
- sleep(2);
- tune_confirm();
- sleep(2);
- /* third beep by cal end routine */
+ tune_positive();
} else {
/* measurements error */
mavlink_log_info(mavlink_fd, "accel calibration aborted");
- tune_error();
- sleep(2);
+ tune_negative();
}
/* exit accel calibration mode */
- status->flag_preflight_accel_calibration = false;
- state_machine_publish(status_pub, status, mavlink_fd);
}
-int do_accel_calibration_mesurements(int mavlink_fd, float accel_offs[3], float accel_scale[3]) {
+int do_accel_calibration_measurements(int mavlink_fd, float accel_offs[3], float accel_scale[3]) {
const int samples_num = 2500;
float accel_ref[6][3];
bool data_collected[6] = { false, false, false, false, false, false };
@@ -232,7 +232,7 @@ int do_accel_calibration_mesurements(int mavlink_fd, float accel_offs[3], float
str_ptr = sprintf(str, "meas result for %s: [ %.2f %.2f %.2f ]", orientation_strs[orient], accel_ref[orient][0], accel_ref[orient][1], accel_ref[orient][2]);
mavlink_log_info(mavlink_fd, str);
data_collected[orient] = true;
- tune_confirm();
+ tune_neutral();
}
close(sensor_combined_sub);
@@ -399,7 +399,7 @@ int mat_invert3(float src[3][3], float dst[3][3]) {
float det = src[0][0] * (src[1][1] * src[2][2] - src[1][2] * src[2][1]) -
src[0][1] * (src[1][0] * src[2][2] - src[1][2] * src[2][0]) +
src[0][2] * (src[1][0] * src[2][1] - src[1][1] * src[2][0]);
- if (det == 0.0)
+ if (det == 0.0f)
return ERROR; // Singular matrix
dst[0][0] = (src[1][1] * src[2][2] - src[1][2] * src[2][1]) / det;
diff --git a/src/modules/commander/accelerometer_calibration.h b/src/modules/commander/accelerometer_calibration.h
index f93a867ba..3275d9461 100644
--- a/src/modules/commander/accelerometer_calibration.h
+++ b/src/modules/commander/accelerometer_calibration.h
@@ -44,8 +44,7 @@
#define ACCELEROMETER_CALIBRATION_H_
#include <stdint.h>
-#include <uORB/topics/vehicle_status.h>
-void do_accel_calibration(int status_pub, struct vehicle_status_s *status, int mavlink_fd);
+void do_accel_calibration(int mavlink_fd);
#endif /* ACCELEROMETER_CALIBRATION_H_ */
diff --git a/src/modules/commander/airspeed_calibration.c b/src/modules/commander/airspeed_calibration.c
new file mode 100644
index 000000000..feaf11aee
--- /dev/null
+++ b/src/modules/commander/airspeed_calibration.c
@@ -0,0 +1,111 @@
+/****************************************************************************
+ *
+ * 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 airspeed_calibration.c
+ * Airspeed sensor calibration routine
+ */
+
+#include "airspeed_calibration.h"
+#include "commander_helper.h"
+
+#include <stdio.h>
+#include <poll.h>
+#include <math.h>
+#include <drivers/drv_hrt.h>
+#include <uORB/topics/sensor_combined.h>
+#include <uORB/topics/differential_pressure.h>
+#include <mavlink/mavlink_log.h>
+#include <systemlib/param/param.h>
+#include <systemlib/err.h>
+
+void do_airspeed_calibration(int mavlink_fd)
+{
+ /* give directions */
+ mavlink_log_info(mavlink_fd, "airspeed calibration starting, keep it still");
+
+ const int calibration_count = 2500;
+
+ int diff_pres_sub = orb_subscribe(ORB_ID(differential_pressure));
+ struct differential_pressure_s diff_pres;
+
+ int calibration_counter = 0;
+ float diff_pres_offset = 0.0f;
+
+ while (calibration_counter < calibration_count) {
+
+ /* wait blocking for new data */
+ struct pollfd fds[1] = { { .fd = diff_pres_sub, .events = POLLIN } };
+
+ int poll_ret = poll(fds, 1, 1000);
+
+ if (poll_ret) {
+ orb_copy(ORB_ID(differential_pressure), diff_pres_sub, &diff_pres);
+ diff_pres_offset += diff_pres.differential_pressure_pa;
+ calibration_counter++;
+
+ } else if (poll_ret == 0) {
+ /* any poll failure for 1s is a reason to abort */
+ mavlink_log_info(mavlink_fd, "airspeed calibration aborted");
+ return;
+ }
+ }
+
+ diff_pres_offset = diff_pres_offset / calibration_count;
+
+ if (isfinite(diff_pres_offset)) {
+
+ if (param_set(param_find("SENS_DPRES_OFF"), &(diff_pres_offset))) {
+ mavlink_log_critical(mavlink_fd, "Setting offs failed!");
+ }
+
+ /* auto-save to EEPROM */
+ int save_ret = param_save_default();
+
+ if (save_ret != 0) {
+ warn("WARNING: auto-save of params to storage failed");
+ }
+
+ //char buf[50];
+ //sprintf(buf, "[cmd] accel cal: x:%8.4f y:%8.4f z:%8.4f\n", (double)accel_offset[0], (double)accel_offset[1], (double)accel_offset[2]);
+ //mavlink_log_info(mavlink_fd, buf);
+ mavlink_log_info(mavlink_fd, "airspeed calibration done");
+
+ tune_positive();
+
+ } else {
+ mavlink_log_info(mavlink_fd, "airspeed calibration FAILED (NaN)");
+ }
+
+ close(diff_pres_sub);
+}
diff --git a/src/modules/commander/airspeed_calibration.h b/src/modules/commander/airspeed_calibration.h
new file mode 100644
index 000000000..92f5651ec
--- /dev/null
+++ b/src/modules/commander/airspeed_calibration.h
@@ -0,0 +1,46 @@
+/****************************************************************************
+ *
+ * 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 gyro_calibration.h
+ * Airspeed sensor calibration routine
+ */
+
+#ifndef AIRSPEED_CALIBRATION_H_
+#define AIRSPEED_CALIBRATION_H_
+
+#include <stdint.h>
+
+void do_airspeed_calibration(int mavlink_fd);
+
+#endif /* AIRSPEED_CALIBRATION_H_ */ \ No newline at end of file
diff --git a/src/modules/commander/baro_calibration.c b/src/modules/commander/baro_calibration.c
new file mode 100644
index 000000000..a70594794
--- /dev/null
+++ b/src/modules/commander/baro_calibration.c
@@ -0,0 +1,54 @@
+/****************************************************************************
+ *
+ * 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 baro_calibration.c
+ * Barometer calibration routine
+ */
+
+#include "baro_calibration.h"
+
+#include <poll.h>
+#include <math.h>
+#include <fcntl.h>
+#include <drivers/drv_hrt.h>
+#include <uORB/topics/sensor_combined.h>
+#include <drivers/drv_baro.h>
+#include <mavlink/mavlink_log.h>
+#include <systemlib/param/param.h>
+
+void do_baro_calibration(int mavlink_fd)
+{
+ // TODO implement this
+ return;
+}
diff --git a/src/modules/commander/baro_calibration.h b/src/modules/commander/baro_calibration.h
new file mode 100644
index 000000000..ac0f4be36
--- /dev/null
+++ b/src/modules/commander/baro_calibration.h
@@ -0,0 +1,46 @@
+/****************************************************************************
+ *
+ * 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 mag_calibration.h
+ * Barometer calibration routine
+ */
+
+#ifndef BARO_CALIBRATION_H_
+#define BARO_CALIBRATION_H_
+
+#include <stdint.h>
+
+void do_baro_calibration(int mavlink_fd);
+
+#endif /* BARO_CALIBRATION_H_ */ \ No newline at end of file
diff --git a/src/modules/commander/calibration_routines.c b/src/modules/commander/calibration_routines.c
index a26938637..799cd4269 100644
--- a/src/modules/commander/calibration_routines.c
+++ b/src/modules/commander/calibration_routines.c
@@ -217,3 +217,4 @@ int sphere_fit_least_squares(const float x[], const float y[], const float z[],
return 0;
}
+
diff --git a/src/modules/commander/commander.c b/src/modules/commander/commander.c
index 67f053e22..9d52d4f1c 100644
--- a/src/modules/commander/commander.c
+++ b/src/modules/commander/commander.c
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
* Author: Petri Tanskanen <petri.tanskanen@inf.ethz.ch>
* Lorenz Meier <lm@inf.ethz.ch>
* Thomas Gubler <thomasgubler@student.ethz.ch>
@@ -60,13 +60,9 @@
#include <debug.h>
#include <sys/prctl.h>
#include <string.h>
-#include <drivers/drv_led.h>
-#include <drivers/drv_hrt.h>
-#include <drivers/drv_tone_alarm.h>
-#include "state_machine_helper.h"
-#include "systemlib/systemlib.h"
#include <math.h>
#include <poll.h>
+
#include <uORB/uORB.h>
#include <uORB/topics/sensor_combined.h>
#include <uORB/topics/battery_status.h>
@@ -77,24 +73,33 @@
#include <uORB/topics/vehicle_local_position.h>
#include <uORB/topics/vehicle_gps_position.h>
#include <uORB/topics/vehicle_command.h>
+#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/subsystem_info.h>
#include <uORB/topics/actuator_controls.h>
+#include <uORB/topics/actuator_safety.h>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/differential_pressure.h>
#include <mavlink/mavlink_log.h>
+#include <drivers/drv_led.h>
+#include <drivers/drv_hrt.h>
+#include <drivers/drv_tone_alarm.h>
+
+#include <mavlink/mavlink_log.h>
#include <systemlib/param/param.h>
#include <systemlib/systemlib.h>
#include <systemlib/err.h>
+#include <systemlib/cpuload.h>
-/* XXX MOVE CALIBRATION TO SENSORS APP THREAD */
-#include <drivers/drv_accel.h>
-#include <drivers/drv_gyro.h>
-#include <drivers/drv_mag.h>
-#include <drivers/drv_baro.h>
-
+#include "commander_helper.h"
+#include "state_machine_helper.h"
#include "calibration_routines.h"
#include "accelerometer_calibration.h"
+#include "gyro_calibration.h"
+#include "mag_calibration.h"
+#include "baro_calibration.h"
+#include "rc_calibration.h"
+#include "airspeed_calibration.h"
PARAM_DEFINE_INT32(SYS_FAILSAVE_LL, 0); /**< Go into low-level failsafe after 0 ms */
//PARAM_DEFINE_INT32(SYS_FAILSAVE_HL, 0); /**< Go into high-level failsafe after 0 ms */
@@ -102,9 +107,12 @@ PARAM_DEFINE_FLOAT(TRIM_ROLL, 0.0f);
PARAM_DEFINE_FLOAT(TRIM_PITCH, 0.0f);
PARAM_DEFINE_FLOAT(TRIM_YAW, 0.0f);
-#include <systemlib/cpuload.h>
+
extern struct system_load_s system_load;
+#define LOW_VOLTAGE_BATTERY_HYSTERESIS_TIME_MS 1000.0f
+#define CRITICAL_VOLTAGE_BATTERY_HYSTERESIS_TIME_MS 100.0f
+
/* Decouple update interval and hysteris counters, all depends on intervals */
#define COMMANDER_MONITORING_INTERVAL 50000
#define COMMANDER_MONITORING_LOOPSPERMSEC (1/(COMMANDER_MONITORING_INTERVAL/1000.0f))
@@ -121,25 +129,38 @@ extern struct system_load_s system_load;
#define GPS_QUALITY_GOOD_HYSTERIS_TIME_MS 5000
#define GPS_QUALITY_GOOD_COUNTER_LIMIT (GPS_QUALITY_GOOD_HYSTERIS_TIME_MS*COMMANDER_MONITORING_LOOPSPERMSEC)
+#define LOCAL_POSITION_TIMEOUT 1000000 /**< consider the local position estimate invalid after 1s */
+
/* File descriptors */
static int leds;
-static int buzzer;
static int mavlink_fd;
-static bool commander_initialized = false;
-static struct vehicle_status_s current_status; /**< Main state machine */
-static orb_advert_t stat_pub;
-
-// static uint16_t nofix_counter = 0;
-// static uint16_t gotfix_counter = 0;
-
-static unsigned int failsafe_lowlevel_timeout_ms;
+/* flags */
+static bool commander_initialized = false;
static bool thread_should_exit = false; /**< daemon exit flag */
static bool thread_running = false; /**< daemon status flag */
static int daemon_task; /**< Handle of daemon task / thread */
+/* timout until lowlevel failsafe */
+static unsigned int failsafe_lowlevel_timeout_ms;
+
+/* tasks waiting for low prio thread */
+enum {
+ LOW_PRIO_TASK_NONE = 0,
+ LOW_PRIO_TASK_PARAM_SAVE,
+ LOW_PRIO_TASK_PARAM_LOAD,
+ LOW_PRIO_TASK_GYRO_CALIBRATION,
+ LOW_PRIO_TASK_MAG_CALIBRATION,
+ LOW_PRIO_TASK_ALTITUDE_CALIBRATION,
+ LOW_PRIO_TASK_RC_CALIBRATION,
+ LOW_PRIO_TASK_ACCEL_CALIBRATION,
+ LOW_PRIO_TASK_AIRSPEED_CALIBRATION
+} low_prio_task;
+
+
/* pthread loops */
-static void *orb_receive_loop(void *arg);
+void *orb_receive_loop(void *arg);
+void *commander_low_prio_loop(void *arg);
__EXPORT int commander_main(int argc, char *argv[]);
@@ -148,26 +169,24 @@ __EXPORT int commander_main(int argc, char *argv[]);
*/
int commander_thread_main(int argc, char *argv[]);
-static int buzzer_init(void);
-static void buzzer_deinit(void);
-static int led_init(void);
-static void led_deinit(void);
-static int led_toggle(int led);
-static int led_on(int led);
-static int led_off(int led);
-static void do_gyro_calibration(int status_pub, struct vehicle_status_s *status);
-static void do_mag_calibration(int status_pub, struct vehicle_status_s *status);
-static void do_rc_calibration(int status_pub, struct vehicle_status_s *status);
-static void handle_command(int status_pub, struct vehicle_status_s *current_status, struct vehicle_command_s *cmd);
+int led_init(void);
+void led_deinit(void);
+int led_toggle(int led);
+int led_on(int led);
+int led_off(int led);
+void do_reboot(void);
-int trigger_audio_alarm(uint8_t old_mode, uint8_t old_state, uint8_t new_mode, uint8_t new_state);
+
+void handle_command(int status_pub, struct vehicle_status_s *current_status, struct vehicle_command_s *cmd, int safety_pub, struct actuator_safety_s *safety);
+
+// int trigger_audio_alarm(uint8_t old_mode, uint8_t old_state, uint8_t new_mode, uint8_t new_state);
/**
* Print the correct usage.
*/
-static void usage(const char *reason);
+void usage(const char *reason);
/**
* Sort calibration values.
@@ -179,25 +198,8 @@ static void usage(const char *reason);
*/
// static void cal_bsort(float a[], int n);
-static int buzzer_init()
-{
- buzzer = open("/dev/tone_alarm", O_WRONLY);
-
- if (buzzer < 0) {
- warnx("Buzzer: open fail\n");
- return ERROR;
- }
-
- return 0;
-}
-
-static void buzzer_deinit()
-{
- close(buzzer);
-}
-
-static int led_init()
+int led_init()
{
leds = open(LED_DEVICE_PATH, 0);
@@ -214,12 +216,12 @@ static int led_init()
return 0;
}
-static void led_deinit()
+void led_deinit()
{
close(leds);
}
-static int led_toggle(int led)
+int led_toggle(int led)
{
static int last_blue = LED_ON;
static int last_amber = LED_ON;
@@ -231,830 +233,288 @@ static int led_toggle(int led)
return ioctl(leds, ((led == LED_BLUE) ? last_blue : last_amber), led);
}
-static int led_on(int led)
+int led_on(int led)
{
return ioctl(leds, LED_ON, led);
}
-static int led_off(int led)
+int led_off(int led)
{
return ioctl(leds, LED_OFF, led);
}
-enum AUDIO_PATTERN {
- AUDIO_PATTERN_ERROR = 2,
- AUDIO_PATTERN_NOTIFY_POSITIVE = 3,
- AUDIO_PATTERN_NOTIFY_NEUTRAL = 4,
- AUDIO_PATTERN_NOTIFY_NEGATIVE = 5,
- AUDIO_PATTERN_NOTIFY_CHARGE = 6
-};
-
-int trigger_audio_alarm(uint8_t old_mode, uint8_t old_state, uint8_t new_mode, uint8_t new_state)
-{
-
- /* Trigger alarm if going into any error state */
- if (((new_state == SYSTEM_STATE_GROUND_ERROR) && (old_state != SYSTEM_STATE_GROUND_ERROR)) ||
- ((new_state == SYSTEM_STATE_MISSION_ABORT) && (old_state != SYSTEM_STATE_MISSION_ABORT))) {
- ioctl(buzzer, TONE_SET_ALARM, 0);
- ioctl(buzzer, TONE_SET_ALARM, AUDIO_PATTERN_ERROR);
- }
-
- /* Trigger neutral on arming / disarming */
- if (((new_state == SYSTEM_STATE_GROUND_READY) && (old_state != SYSTEM_STATE_GROUND_READY))) {
- ioctl(buzzer, TONE_SET_ALARM, 0);
- ioctl(buzzer, TONE_SET_ALARM, AUDIO_PATTERN_NOTIFY_NEUTRAL);
- }
-
- /* Trigger Tetris on being bored */
-
- return 0;
-}
-
-void tune_confirm(void)
-{
- ioctl(buzzer, TONE_SET_ALARM, 3);
-}
-
-void tune_error(void)
-{
- ioctl(buzzer, TONE_SET_ALARM, 4);
-}
-
-void do_rc_calibration(int status_pub, struct vehicle_status_s *status)
-{
- if (current_status.offboard_control_signal_lost) {
- mavlink_log_critical(mavlink_fd, "TRIM CAL: ABORT. No RC signal.");
- return;
- }
-
- int sub_man = orb_subscribe(ORB_ID(manual_control_setpoint));
- struct manual_control_setpoint_s sp;
- orb_copy(ORB_ID(manual_control_setpoint), sub_man, &sp);
-
- /* set parameters */
-
- float p = sp.roll;
- param_set(param_find("TRIM_ROLL"), &p);
- p = sp.pitch;
- param_set(param_find("TRIM_PITCH"), &p);
- p = sp.yaw;
- param_set(param_find("TRIM_YAW"), &p);
-
- /* store to permanent storage */
- /* auto-save to EEPROM */
- int save_ret = param_save_default();
-
- if (save_ret != 0) {
- mavlink_log_critical(mavlink_fd, "TRIM CAL: WARN: auto-save of params failed");
- }
-
- mavlink_log_info(mavlink_fd, "trim calibration done");
-}
-
-void do_mag_calibration(int status_pub, struct vehicle_status_s *status)
-{
-
- /* set to mag calibration mode */
- status->flag_preflight_mag_calibration = true;
- state_machine_publish(status_pub, status, mavlink_fd);
-
- int sub_mag = orb_subscribe(ORB_ID(sensor_mag));
- struct mag_report mag;
-
- /* 45 seconds */
- uint64_t calibration_interval = 45 * 1000 * 1000;
-
- /* maximum 2000 values */
- const unsigned int calibration_maxcount = 500;
- unsigned int calibration_counter = 0;
-
- /* limit update rate to get equally spaced measurements over time (in ms) */
- orb_set_interval(sub_mag, (calibration_interval / 1000) / calibration_maxcount);
-
- // XXX old cal
- // * FLT_MIN is not the most negative float number,
- // * but the smallest number by magnitude float can
- // * represent. Use -FLT_MAX to initialize the most
- // * negative number
-
- // float mag_max[3] = {-FLT_MAX, -FLT_MAX, -FLT_MAX};
- // float mag_min[3] = {FLT_MAX, FLT_MAX, FLT_MAX};
-
- int fd = open(MAG_DEVICE_PATH, O_RDONLY);
-
- /* erase old calibration */
- struct mag_scale mscale_null = {
- 0.0f,
- 1.0f,
- 0.0f,
- 1.0f,
- 0.0f,
- 1.0f,
- };
-
- if (OK != ioctl(fd, MAGIOCSSCALE, (long unsigned int)&mscale_null)) {
- warn("WARNING: failed to set scale / offsets for mag");
- mavlink_log_info(mavlink_fd, "failed to set scale / offsets for mag");
- }
-
- /* calibrate range */
- if (OK != ioctl(fd, MAGIOCCALIBRATE, fd)) {
- warnx("failed to calibrate scale");
- }
-
- close(fd);
-
- /* calibrate offsets */
-
- // uint64_t calibration_start = hrt_absolute_time();
-
- uint64_t axis_deadline = hrt_absolute_time();
- uint64_t calibration_deadline = hrt_absolute_time() + calibration_interval;
-
- const char axislabels[3] = { 'X', 'Y', 'Z'};
- int axis_index = -1;
-
- float *x = (float *)malloc(sizeof(float) * calibration_maxcount);
- float *y = (float *)malloc(sizeof(float) * calibration_maxcount);
- float *z = (float *)malloc(sizeof(float) * calibration_maxcount);
-
- if (x == NULL || y == NULL || z == NULL) {
- warnx("mag cal failed: out of memory");
- mavlink_log_info(mavlink_fd, "mag cal failed: out of memory");
- warnx("x:%p y:%p z:%p\n", x, y, z);
- return;
- }
-
- tune_confirm();
- sleep(2);
- tune_confirm();
-
- while (hrt_absolute_time() < calibration_deadline &&
- calibration_counter < calibration_maxcount) {
-
- /* wait blocking for new data */
- struct pollfd fds[1] = { { .fd = sub_mag, .events = POLLIN } };
-
- /* user guidance */
- if (hrt_absolute_time() >= axis_deadline &&
- axis_index < 3) {
-
- axis_index++;
-
- char buf[50];
- sprintf(buf, "Please rotate around %c", axislabels[axis_index]);
- mavlink_log_info(mavlink_fd, buf);
- tune_confirm();
-
- axis_deadline += calibration_interval / 3;
- }
-
- if (!(axis_index < 3)) {
- break;
- }
-
- // int axis_left = (int64_t)axis_deadline - (int64_t)hrt_absolute_time();
-
- // if ((axis_left / 1000) == 0 && axis_left > 0) {
- // char buf[50];
- // sprintf(buf, "[cmd] %d seconds left for axis %c", axis_left, axislabels[axis_index]);
- // mavlink_log_info(mavlink_fd, buf);
- // }
-
- int poll_ret = poll(fds, 1, 1000);
-
- if (poll_ret) {
- orb_copy(ORB_ID(sensor_mag), sub_mag, &mag);
-
- x[calibration_counter] = mag.x;
- y[calibration_counter] = mag.y;
- z[calibration_counter] = mag.z;
-
- /* get min/max values */
-
- // if (mag.x < mag_min[0]) {
- // mag_min[0] = mag.x;
- // }
- // else if (mag.x > mag_max[0]) {
- // mag_max[0] = mag.x;
- // }
-
- // if (raw.magnetometer_ga[1] < mag_min[1]) {
- // mag_min[1] = raw.magnetometer_ga[1];
- // }
- // else if (raw.magnetometer_ga[1] > mag_max[1]) {
- // mag_max[1] = raw.magnetometer_ga[1];
- // }
-
- // if (raw.magnetometer_ga[2] < mag_min[2]) {
- // mag_min[2] = raw.magnetometer_ga[2];
- // }
- // else if (raw.magnetometer_ga[2] > mag_max[2]) {
- // mag_max[2] = raw.magnetometer_ga[2];
- // }
-
- calibration_counter++;
-
- } else if (poll_ret == 0) {
- /* any poll failure for 1s is a reason to abort */
- mavlink_log_info(mavlink_fd, "mag cal canceled (timed out)");
- break;
- }
- }
-
- float sphere_x;
- float sphere_y;
- float sphere_z;
- float sphere_radius;
-
- sphere_fit_least_squares(x, y, z, calibration_counter, 100, 0.0f, &sphere_x, &sphere_y, &sphere_z, &sphere_radius);
-
- free(x);
- free(y);
- free(z);
-
- if (isfinite(sphere_x) && isfinite(sphere_y) && isfinite(sphere_z)) {
-
- fd = open(MAG_DEVICE_PATH, 0);
-
- struct mag_scale mscale;
-
- if (OK != ioctl(fd, MAGIOCGSCALE, (long unsigned int)&mscale))
- warn("WARNING: failed to get scale / offsets for mag");
-
- mscale.x_offset = sphere_x;
- mscale.y_offset = sphere_y;
- mscale.z_offset = sphere_z;
-
- if (OK != ioctl(fd, MAGIOCSSCALE, (long unsigned int)&mscale))
- warn("WARNING: failed to set scale / offsets for mag");
-
- close(fd);
-
- /* announce and set new offset */
-
- if (param_set(param_find("SENS_MAG_XOFF"), &(mscale.x_offset))) {
- warnx("Setting X mag offset failed!\n");
- }
-
- if (param_set(param_find("SENS_MAG_YOFF"), &(mscale.y_offset))) {
- warnx("Setting Y mag offset failed!\n");
- }
-
- if (param_set(param_find("SENS_MAG_ZOFF"), &(mscale.z_offset))) {
- warnx("Setting Z mag offset failed!\n");
- }
-
- if (param_set(param_find("SENS_MAG_XSCALE"), &(mscale.x_scale))) {
- warnx("Setting X mag scale failed!\n");
- }
-
- if (param_set(param_find("SENS_MAG_YSCALE"), &(mscale.y_scale))) {
- warnx("Setting Y mag scale failed!\n");
- }
-
- if (param_set(param_find("SENS_MAG_ZSCALE"), &(mscale.z_scale))) {
- warnx("Setting Z mag scale failed!\n");
- }
-
- /* auto-save to EEPROM */
- int save_ret = param_save_default();
-
- if (save_ret != 0) {
- warn("WARNING: auto-save of params to storage failed");
- mavlink_log_info(mavlink_fd, "FAILED storing calibration");
- }
-
- warnx("\tscale: %.6f %.6f %.6f\n \toffset: %.6f %.6f %.6f\nradius: %.6f GA\n",
- (double)mscale.x_scale, (double)mscale.y_scale, (double)mscale.z_scale,
- (double)mscale.x_offset, (double)mscale.y_offset, (double)mscale.z_offset, (double)sphere_radius);
-
- char buf[52];
- sprintf(buf, "mag off: x:%.2f y:%.2f z:%.2f Ga", (double)mscale.x_offset,
- (double)mscale.y_offset, (double)mscale.z_offset);
- mavlink_log_info(mavlink_fd, buf);
-
- sprintf(buf, "mag scale: x:%.2f y:%.2f z:%.2f", (double)mscale.x_scale,
- (double)mscale.y_scale, (double)mscale.z_scale);
- mavlink_log_info(mavlink_fd, buf);
-
- mavlink_log_info(mavlink_fd, "mag calibration done");
-
- tune_confirm();
- sleep(2);
- tune_confirm();
- sleep(2);
- /* third beep by cal end routine */
-
- } else {
- mavlink_log_info(mavlink_fd, "mag calibration FAILED (NaN in sphere fit)");
- }
-
- /* disable calibration mode */
- status->flag_preflight_mag_calibration = false;
- state_machine_publish(status_pub, status, mavlink_fd);
-
- close(sub_mag);
-}
-
-void do_gyro_calibration(int status_pub, struct vehicle_status_s *status)
-{
- /* set to gyro calibration mode */
- status->flag_preflight_gyro_calibration = true;
- state_machine_publish(status_pub, status, mavlink_fd);
-
- const int calibration_count = 5000;
-
- int sub_sensor_combined = orb_subscribe(ORB_ID(sensor_combined));
- struct sensor_combined_s raw;
-
- int calibration_counter = 0;
- float gyro_offset[3] = {0.0f, 0.0f, 0.0f};
-
- /* set offsets to zero */
- int fd = open(GYRO_DEVICE_PATH, 0);
- struct gyro_scale gscale_null = {
- 0.0f,
- 1.0f,
- 0.0f,
- 1.0f,
- 0.0f,
- 1.0f,
- };
-
- if (OK != ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gscale_null))
- warn("WARNING: failed to set scale / offsets for gyro");
-
- close(fd);
-
- while (calibration_counter < calibration_count) {
-
- /* wait blocking for new data */
- struct pollfd fds[1] = { { .fd = sub_sensor_combined, .events = POLLIN } };
-
- int poll_ret = poll(fds, 1, 1000);
-
- if (poll_ret) {
- orb_copy(ORB_ID(sensor_combined), sub_sensor_combined, &raw);
- gyro_offset[0] += raw.gyro_rad_s[0];
- gyro_offset[1] += raw.gyro_rad_s[1];
- gyro_offset[2] += raw.gyro_rad_s[2];
- calibration_counter++;
-
- } else if (poll_ret == 0) {
- /* any poll failure for 1s is a reason to abort */
- mavlink_log_info(mavlink_fd, "gyro calibration aborted, retry");
- return;
- }
- }
-
- gyro_offset[0] = gyro_offset[0] / calibration_count;
- gyro_offset[1] = gyro_offset[1] / calibration_count;
- gyro_offset[2] = gyro_offset[2] / calibration_count;
-
- /* exit gyro calibration mode */
- status->flag_preflight_gyro_calibration = false;
- state_machine_publish(status_pub, status, mavlink_fd);
-
- if (isfinite(gyro_offset[0]) && isfinite(gyro_offset[1]) && isfinite(gyro_offset[2])) {
-
- if (param_set(param_find("SENS_GYRO_XOFF"), &(gyro_offset[0]))
- || param_set(param_find("SENS_GYRO_YOFF"), &(gyro_offset[1]))
- || param_set(param_find("SENS_GYRO_ZOFF"), &(gyro_offset[2]))) {
- mavlink_log_critical(mavlink_fd, "Setting gyro offsets failed!");
- }
-
- /* set offsets to actual value */
- fd = open(GYRO_DEVICE_PATH, 0);
- struct gyro_scale gscale = {
- gyro_offset[0],
- 1.0f,
- gyro_offset[1],
- 1.0f,
- gyro_offset[2],
- 1.0f,
- };
-
- if (OK != ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gscale))
- warn("WARNING: failed to set scale / offsets for gyro");
-
- close(fd);
-
- /* auto-save to EEPROM */
- int save_ret = param_save_default();
-
- if (save_ret != 0) {
- warn("WARNING: auto-save of params to storage failed");
- }
-
- // char buf[50];
- // sprintf(buf, "cal: x:%8.4f y:%8.4f z:%8.4f", (double)gyro_offset[0], (double)gyro_offset[1], (double)gyro_offset[2]);
- // mavlink_log_info(mavlink_fd, buf);
- mavlink_log_info(mavlink_fd, "gyro calibration done");
-
- tune_confirm();
- sleep(2);
- tune_confirm();
- sleep(2);
- /* third beep by cal end routine */
-
- } else {
- mavlink_log_info(mavlink_fd, "gyro calibration FAILED (NaN)");
- }
-
- close(sub_sensor_combined);
-}
-
-void do_airspeed_calibration(int status_pub, struct vehicle_status_s *status)
+void do_reboot()
{
- /* announce change */
-
- mavlink_log_info(mavlink_fd, "keep it still");
- /* set to accel calibration mode */
- status->flag_preflight_airspeed_calibration = true;
- state_machine_publish(status_pub, status, mavlink_fd);
-
- const int calibration_count = 2500;
-
- int diff_pres_sub = orb_subscribe(ORB_ID(differential_pressure));
- struct differential_pressure_s diff_pres;
-
- int calibration_counter = 0;
- float diff_pres_offset = 0.0f;
-
- while (calibration_counter < calibration_count) {
-
- /* wait blocking for new data */
- struct pollfd fds[1] = { { .fd = diff_pres_sub, .events = POLLIN } };
-
- int poll_ret = poll(fds, 1, 1000);
-
- if (poll_ret) {
- orb_copy(ORB_ID(differential_pressure), diff_pres_sub, &diff_pres);
- diff_pres_offset += diff_pres.differential_pressure_pa;
- calibration_counter++;
-
- } else if (poll_ret == 0) {
- /* any poll failure for 1s is a reason to abort */
- mavlink_log_info(mavlink_fd, "airspeed calibration aborted");
- return;
- }
- }
-
- diff_pres_offset = diff_pres_offset / calibration_count;
-
- if (isfinite(diff_pres_offset)) {
-
- if (param_set(param_find("SENS_DPRES_OFF"), &(diff_pres_offset))) {
- mavlink_log_critical(mavlink_fd, "Setting offs failed!");
- }
-
- /* auto-save to EEPROM */
- int save_ret = param_save_default();
-
- if (save_ret != 0) {
- warn("WARNING: auto-save of params to storage failed");
- }
-
- //char buf[50];
- //sprintf(buf, "[cmd] accel cal: x:%8.4f y:%8.4f z:%8.4f\n", (double)accel_offset[0], (double)accel_offset[1], (double)accel_offset[2]);
- //mavlink_log_info(mavlink_fd, buf);
- mavlink_log_info(mavlink_fd, "airspeed calibration done");
-
- tune_confirm();
- sleep(2);
- tune_confirm();
- sleep(2);
- /* third beep by cal end routine */
-
- } else {
- mavlink_log_info(mavlink_fd, "airspeed calibration FAILED (NaN)");
- }
-
- /* exit airspeed calibration mode */
- status->flag_preflight_airspeed_calibration = false;
- state_machine_publish(status_pub, status, mavlink_fd);
-
- close(diff_pres_sub);
+ mavlink_log_critical(mavlink_fd, "REBOOTING SYSTEM");
+ usleep(500000);
+ up_systemreset();
+ /* SPECIAL CASE: NEVER RETURNS FROM THIS FUNCTION CALL */
}
-void handle_command(int status_pub, struct vehicle_status_s *current_vehicle_status, struct vehicle_command_s *cmd)
+void handle_command(int status_pub, struct vehicle_status_s *current_vehicle_status, struct vehicle_command_s *cmd, int safety_pub, struct actuator_safety_s *safety)
{
/* result of the command */
uint8_t result = VEHICLE_CMD_RESULT_UNSUPPORTED;
- /* announce command handling */
- tune_confirm();
-
-
- /* supported command handling start */
-
/* request to set different system mode */
switch (cmd->command) {
- case VEHICLE_CMD_DO_SET_MODE: {
- if (OK == update_state_machine_mode_request(status_pub, current_vehicle_status, mavlink_fd, (uint8_t)cmd->param1)) {
- result = VEHICLE_CMD_RESULT_ACCEPTED;
+ case VEHICLE_CMD_DO_SET_MODE:
- } else {
- result = VEHICLE_CMD_RESULT_DENIED;
- }
- }
- break;
+ /* request to activate HIL */
+ if ((int)cmd->param1 & VEHICLE_MODE_FLAG_HIL_ENABLED) {
- case VEHICLE_CMD_COMPONENT_ARM_DISARM: {
- /* request to arm */
- if ((int)cmd->param1 == 1) {
- if (OK == update_state_machine_mode_request(status_pub, current_vehicle_status, mavlink_fd, VEHICLE_MODE_FLAG_SAFETY_ARMED)) {
+ if (OK == hil_state_transition(status_pub, current_vehicle_status, mavlink_fd, HIL_STATE_ON)) {
result = VEHICLE_CMD_RESULT_ACCEPTED;
-
} else {
result = VEHICLE_CMD_RESULT_DENIED;
}
+ }
- /* request to disarm */
-
- } else if ((int)cmd->param1 == 0) {
- if (OK == update_state_machine_mode_request(status_pub, current_vehicle_status, mavlink_fd, VEHICLE_MODE_FLAG_SAFETY_ARMED)) {
+ if ((int)cmd->param1 & VEHICLE_MODE_FLAG_SAFETY_ARMED) {
+ if (OK == arming_state_transition(status_pub, current_vehicle_status, ARMING_STATE_ARMED, safety_pub, safety, mavlink_fd)) {
result = VEHICLE_CMD_RESULT_ACCEPTED;
-
} else {
result = VEHICLE_CMD_RESULT_DENIED;
}
- }
- }
- break;
-
- /* request for an autopilot reboot */
- case VEHICLE_CMD_PREFLIGHT_REBOOT_SHUTDOWN: {
- if ((int)cmd->param1 == 1) {
- if (OK == do_state_update(status_pub, current_vehicle_status, mavlink_fd, SYSTEM_STATE_REBOOT)) {
- /* SPECIAL CASE: SYSTEM WILL NEVER RETURN HERE */
+ } else {
+ if (OK == arming_state_transition(status_pub, current_vehicle_status, ARMING_STATE_STANDBY, safety_pub, safety, mavlink_fd)) {
result = VEHICLE_CMD_RESULT_ACCEPTED;
-
} else {
- /* system may return here */
result = VEHICLE_CMD_RESULT_DENIED;
}
}
- }
- break;
-// /* request to land */
-// case VEHICLE_CMD_NAV_LAND:
-// {
-// //TODO: add check if landing possible
-// //TODO: add landing maneuver
-//
-// if (0 == update_state_machine_custom_mode_request(status_pub, current_vehicle_status, SYSTEM_STATE_ARMED)) {
-// result = VEHICLE_CMD_RESULT_ACCEPTED;
-// } }
-// break;
-//
-// /* request to takeoff */
-// case VEHICLE_CMD_NAV_TAKEOFF:
-// {
-// //TODO: add check if takeoff possible
-// //TODO: add takeoff maneuver
-//
-// if (0 == update_state_machine_custom_mode_request(status_pub, current_vehicle_status, SYSTEM_STATE_AUTO)) {
-// result = VEHICLE_CMD_RESULT_ACCEPTED;
-// }
-// }
-// break;
-//
- /* preflight calibration */
- case VEHICLE_CMD_PREFLIGHT_CALIBRATION: {
- bool handled = false;
+ break;
- /* gyro calibration */
- if ((int)(cmd->param1) == 1) {
- /* transition to calibration state */
- do_state_update(status_pub, &current_status, mavlink_fd, SYSTEM_STATE_PREFLIGHT);
-
- if (current_status.state_machine == SYSTEM_STATE_PREFLIGHT) {
- mavlink_log_info(mavlink_fd, "starting gyro cal");
- tune_confirm();
- do_gyro_calibration(status_pub, &current_status);
- mavlink_log_info(mavlink_fd, "finished gyro cal");
- tune_confirm();
- do_state_update(status_pub, &current_status, mavlink_fd, SYSTEM_STATE_STANDBY);
- result = VEHICLE_CMD_RESULT_ACCEPTED;
+ case VEHICLE_CMD_COMPONENT_ARM_DISARM:
+ /* request to arm */
+ if ((int)cmd->param1 == 1) {
+ if (OK == arming_state_transition(status_pub, current_vehicle_status, ARMING_STATE_ARMED, safety_pub, safety, mavlink_fd)) {
+ result = VEHICLE_CMD_RESULT_ACCEPTED;
} else {
- mavlink_log_critical(mavlink_fd, "REJECTING gyro cal");
result = VEHICLE_CMD_RESULT_DENIED;
}
-
- handled = true;
- }
-
- /* magnetometer calibration */
- if ((int)(cmd->param2) == 1) {
- /* transition to calibration state */
- do_state_update(status_pub, &current_status, mavlink_fd, SYSTEM_STATE_PREFLIGHT);
-
- if (current_status.state_machine == SYSTEM_STATE_PREFLIGHT) {
- mavlink_log_info(mavlink_fd, "starting mag cal");
- tune_confirm();
- do_mag_calibration(status_pub, &current_status);
- mavlink_log_info(mavlink_fd, "finished mag cal");
- tune_confirm();
- do_state_update(status_pub, &current_status, mavlink_fd, SYSTEM_STATE_STANDBY);
+ /* request to disarm */
+ } else if ((int)cmd->param1 == 0) {
+ if (OK == arming_state_transition(status_pub, current_vehicle_status, ARMING_STATE_STANDBY, safety_pub, safety, mavlink_fd)) {
result = VEHICLE_CMD_RESULT_ACCEPTED;
-
} else {
- mavlink_log_critical(mavlink_fd, "REJECTING mag cal");
result = VEHICLE_CMD_RESULT_DENIED;
}
-
- handled = true;
}
- /* zero-altitude pressure calibration */
- if ((int)(cmd->param3) == 1) {
- /* transition to calibration state */
- do_state_update(status_pub, &current_status, mavlink_fd, SYSTEM_STATE_PREFLIGHT);
+ break;
- if (current_status.state_machine == SYSTEM_STATE_PREFLIGHT) {
- mavlink_log_info(mavlink_fd, "zero altitude cal. not implemented");
- tune_confirm();
+ case VEHICLE_CMD_PREFLIGHT_REBOOT_SHUTDOWN: {
- } else {
- mavlink_log_critical(mavlink_fd, "REJECTING altitude calibration");
- result = VEHICLE_CMD_RESULT_DENIED;
- }
+ /* request for an autopilot reboot */
+ if ((int)cmd->param1 == 1) {
+ if (OK == arming_state_transition(status_pub, current_vehicle_status, ARMING_STATE_REBOOT, safety_pub, safety, mavlink_fd)) {
+ /* reboot is executed later, after positive tune is sent */
+ result = VEHICLE_CMD_RESULT_ACCEPTED;
+ tune_positive();
+ /* SPECIAL CASE: SYSTEM WILL NEVER RETURN HERE */
+ do_reboot();
- handled = true;
+ } else {
+ /* system may return here */
+ result = VEHICLE_CMD_RESULT_DENIED;
+ tune_negative();
+ }
+ }
}
+ break;
- /* trim calibration */
- if ((int)(cmd->param4) == 1) {
- /* transition to calibration state */
- do_state_update(status_pub, &current_status, mavlink_fd, SYSTEM_STATE_PREFLIGHT);
-
- if (current_status.state_machine == SYSTEM_STATE_PREFLIGHT) {
- mavlink_log_info(mavlink_fd, "starting trim cal");
- tune_confirm();
- do_rc_calibration(status_pub, &current_status);
- mavlink_log_info(mavlink_fd, "finished trim cal");
- tune_confirm();
- do_state_update(status_pub, &current_status, mavlink_fd, SYSTEM_STATE_STANDBY);
- result = VEHICLE_CMD_RESULT_ACCEPTED;
-
- } else {
- mavlink_log_critical(mavlink_fd, "REJECTING trim cal");
- result = VEHICLE_CMD_RESULT_DENIED;
- }
+ // /* request to land */
+ // case VEHICLE_CMD_NAV_LAND:
+ // {
+ // //TODO: add check if landing possible
+ // //TODO: add landing maneuver
+ //
+ // if (0 == update_state_machine_custom_mode_request(status_pub, current_vehicle_status, SYSTEM_STATE_ARMED)) {
+ // result = VEHICLE_CMD_RESULT_ACCEPTED;
+ // } }
+ // break;
+ //
+ // /* request to takeoff */
+ // case VEHICLE_CMD_NAV_TAKEOFF:
+ // {
+ // //TODO: add check if takeoff possible
+ // //TODO: add takeoff maneuver
+ //
+ // if (0 == update_state_machine_custom_mode_request(status_pub, current_vehicle_status, SYSTEM_STATE_AUTO)) {
+ // result = VEHICLE_CMD_RESULT_ACCEPTED;
+ // }
+ // }
+ // break;
+ //
+ /* preflight calibration */
+ case VEHICLE_CMD_PREFLIGHT_CALIBRATION:
- handled = true;
- }
+ /* gyro calibration */
+ if ((int)(cmd->param1) == 1) {
- /* accel calibration */
- if ((int)(cmd->param5) == 1) {
- /* transition to calibration state */
- do_state_update(status_pub, &current_status, mavlink_fd, SYSTEM_STATE_PREFLIGHT);
-
- if (current_status.state_machine == SYSTEM_STATE_PREFLIGHT) {
- mavlink_log_info(mavlink_fd, "CMD starting accel cal");
- tune_confirm();
- do_accel_calibration(status_pub, &current_status, mavlink_fd);
- tune_confirm();
- mavlink_log_info(mavlink_fd, "CMD finished accel cal");
- do_state_update(status_pub, &current_status, mavlink_fd, SYSTEM_STATE_STANDBY);
- result = VEHICLE_CMD_RESULT_ACCEPTED;
+ /* check if no other task is scheduled */
+ if(low_prio_task == LOW_PRIO_TASK_NONE) {
+ /* try to go to INIT/PREFLIGHT arming state */
+ if (OK == arming_state_transition(status_pub, current_vehicle_status, ARMING_STATE_INIT, safety_pub, safety, mavlink_fd)) {
+ result = VEHICLE_CMD_RESULT_ACCEPTED;
+ /* now set the task for the low prio thread */
+ low_prio_task = LOW_PRIO_TASK_GYRO_CALIBRATION;
+ } else {
+ result = VEHICLE_CMD_RESULT_DENIED;
+ }
} else {
- mavlink_log_critical(mavlink_fd, "REJECTING accel cal");
- result = VEHICLE_CMD_RESULT_DENIED;
+ result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
}
-
- handled = true;
}
- /* airspeed calibration */
- if ((int)(cmd->param6) == 1) { //xxx: this is not defined by the mavlink protocol
- /* transition to calibration state */
- do_state_update(status_pub, &current_status, mavlink_fd, SYSTEM_STATE_PREFLIGHT);
-
- if (current_status.state_machine == SYSTEM_STATE_PREFLIGHT) {
- mavlink_log_info(mavlink_fd, "CMD starting airspeed cal");
- tune_confirm();
- do_airspeed_calibration(status_pub, &current_status);
- tune_confirm();
- mavlink_log_info(mavlink_fd, "CMD finished airspeed cal");
- do_state_update(status_pub, &current_status, mavlink_fd, SYSTEM_STATE_STANDBY);
- result = VEHICLE_CMD_RESULT_ACCEPTED;
+ /* magnetometer calibration */
+ if ((int)(cmd->param2) == 1) {
+
+ /* check if no other task is scheduled */
+ if(low_prio_task == LOW_PRIO_TASK_NONE) {
+ /* try to go to INIT/PREFLIGHT arming state */
+ if (OK == arming_state_transition(status_pub, current_vehicle_status, ARMING_STATE_INIT, safety_pub, safety, mavlink_fd)) {
+ result = VEHICLE_CMD_RESULT_ACCEPTED;
+ /* now set the task for the low prio thread */
+ low_prio_task = LOW_PRIO_TASK_MAG_CALIBRATION;
+ } else {
+ result = VEHICLE_CMD_RESULT_DENIED;
+ }
} else {
- mavlink_log_critical(mavlink_fd, "REJECTING airspeed cal");
- result = VEHICLE_CMD_RESULT_DENIED;
+ result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
}
-
- handled = true;
}
- /* none found */
- if (!handled) {
- //warnx("refusing unsupported calibration request\n");
- mavlink_log_critical(mavlink_fd, "CMD refusing unsup. calib. request");
- result = VEHICLE_CMD_RESULT_UNSUPPORTED;
- }
- }
- break;
- case VEHICLE_CMD_PREFLIGHT_STORAGE: {
- if (current_status.flag_system_armed &&
- ((current_status.system_type == VEHICLE_TYPE_QUADROTOR) ||
- (current_status.system_type == VEHICLE_TYPE_HEXAROTOR) ||
- (current_status.system_type == VEHICLE_TYPE_OCTOROTOR))) {
- /* do not perform expensive memory tasks on multirotors in flight */
- // XXX this is over-safe, as soon as cmd is in low prio thread this can be allowed
- mavlink_log_info(mavlink_fd, "REJECTING save cmd while multicopter armed");
+ // /* zero-altitude pressure calibration */
+ // if ((int)(cmd->param3) == 1) {
- } else {
+ // /* check if no other task is scheduled */
+ // if(low_prio_task == LOW_PRIO_TASK_NONE) {
- // XXX move this to LOW PRIO THREAD of commander app
- /* Read all parameters from EEPROM to RAM */
+ // /* try to go to INIT/PREFLIGHT arming state */
+ // if (OK == arming_state_transition(status_pub, current_vehicle_status, ARMING_STATE_INIT, safety_pub, safety, mavlink_fd)) {
+ // result = VEHICLE_CMD_RESULT_ACCEPTED;
+ // /* now set the task for the low prio thread */
+ // low_prio_task = LOW_PRIO_TASK_ALTITUDE_CALIBRATION;
+ // } else {
+ // result = VEHICLE_CMD_RESULT_DENIED;
+ // }
+ // } else {
+ // result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
+ // }
+ // }
- if (((int)(cmd->param1)) == 0) {
- /* read all parameters from EEPROM to RAM */
- int read_ret = param_load_default();
- if (read_ret == OK) {
- //warnx("[mavlink pm] Loaded EEPROM params in RAM\n");
- mavlink_log_info(mavlink_fd, "OK loading params from");
- mavlink_log_info(mavlink_fd, param_get_default_file());
- result = VEHICLE_CMD_RESULT_ACCEPTED;
+ // /* trim calibration */
+ // if ((int)(cmd->param4) == 1) {
- } else if (read_ret == 1) {
- mavlink_log_info(mavlink_fd, "OK no changes in");
- mavlink_log_info(mavlink_fd, param_get_default_file());
- result = VEHICLE_CMD_RESULT_ACCEPTED;
+ // /* check if no other task is scheduled */
+ // if(low_prio_task == LOW_PRIO_TASK_NONE) {
- } else {
- if (read_ret < -1) {
- mavlink_log_info(mavlink_fd, "ERR loading params from");
- mavlink_log_info(mavlink_fd, param_get_default_file());
+ // /* try to go to INIT/PREFLIGHT arming state */
+ // if (OK == arming_state_transition(status_pub, current_vehicle_status, ARMING_STATE_INIT, safety_pub, safety, mavlink_fd)) {
+ // result = VEHICLE_CMD_RESULT_ACCEPTED;
+ // /* now set the task for the low prio thread */
+ // low_prio_task = LOW_PRIO_TASK_RC_CALIBRATION;
+ // } else {
+ // result = VEHICLE_CMD_RESULT_DENIED;
+ // }
+ // } else {
+ // result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
+ // }
+ // }
- } else {
- mavlink_log_info(mavlink_fd, "ERR no param file named");
- mavlink_log_info(mavlink_fd, param_get_default_file());
- }
- result = VEHICLE_CMD_RESULT_FAILED;
+ /* accel calibration */
+ if ((int)(cmd->param5) == 1) {
+
+ /* check if no other task is scheduled */
+ if(low_prio_task == LOW_PRIO_TASK_NONE) {
+
+ /* try to go to INIT/PREFLIGHT arming state */
+ if (OK == arming_state_transition(status_pub, current_vehicle_status, ARMING_STATE_INIT, safety_pub, safety, mavlink_fd)) {
+ result = VEHICLE_CMD_RESULT_ACCEPTED;
+ /* now set the task for the low prio thread */
+ low_prio_task = LOW_PRIO_TASK_ACCEL_CALIBRATION;
+ } else {
+ result = VEHICLE_CMD_RESULT_DENIED;
}
+ } else {
+ result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
+ }
+ }
- } else if (((int)(cmd->param1)) == 1) {
+ /* airspeed calibration */
+ if ((int)(cmd->param6) == 1) {
- /* write all parameters from RAM to EEPROM */
- int write_ret = param_save_default();
+ /* check if no other task is scheduled */
+ if(low_prio_task == LOW_PRIO_TASK_NONE) {
- if (write_ret == OK) {
- mavlink_log_info(mavlink_fd, "OK saved param file");
- mavlink_log_info(mavlink_fd, param_get_default_file());
+ /* try to go to INIT/PREFLIGHT arming state */
+ if (OK == arming_state_transition(status_pub, current_vehicle_status, ARMING_STATE_INIT, safety_pub, safety, mavlink_fd)) {
result = VEHICLE_CMD_RESULT_ACCEPTED;
-
+ /* now set the task for the low prio thread */
+ low_prio_task = LOW_PRIO_TASK_AIRSPEED_CALIBRATION;
} else {
- if (write_ret < -1) {
- mavlink_log_info(mavlink_fd, "ERR params file does not exit:");
- mavlink_log_info(mavlink_fd, param_get_default_file());
+ result = VEHICLE_CMD_RESULT_DENIED;
+ }
+ } else {
+ result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
+ }
+ }
+ break;
- } else {
- mavlink_log_info(mavlink_fd, "ERR writing params to");
- mavlink_log_info(mavlink_fd, param_get_default_file());
- }
+ case VEHICLE_CMD_PREFLIGHT_STORAGE:
- result = VEHICLE_CMD_RESULT_FAILED;
- }
+ if (((int)(cmd->param1)) == 0) {
+
+ /* check if no other task is scheduled */
+ if(low_prio_task == LOW_PRIO_TASK_NONE) {
+ low_prio_task = LOW_PRIO_TASK_PARAM_LOAD;
+ result = VEHICLE_CMD_RESULT_ACCEPTED;
+ } else {
+ result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
+ }
+
+
+ } else if (((int)(cmd->param1)) == 1) {
+ /* check if no other task is scheduled */
+ if(low_prio_task == LOW_PRIO_TASK_NONE) {
+ low_prio_task = LOW_PRIO_TASK_PARAM_SAVE;
+ result = VEHICLE_CMD_RESULT_ACCEPTED;
} else {
- mavlink_log_info(mavlink_fd, "[pm] refusing unsupp. STOR request");
- result = VEHICLE_CMD_RESULT_UNSUPPORTED;
+ result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
}
}
- }
break;
- default: {
- mavlink_log_critical(mavlink_fd, "[cmd] refusing unsupported command");
- result = VEHICLE_CMD_RESULT_UNSUPPORTED;
- /* announce command rejection */
- ioctl(buzzer, TONE_SET_ALARM, 4);
- }
+ default:
+ mavlink_log_critical(mavlink_fd, "[cmd] refusing unsupported command");
+ result = VEHICLE_CMD_RESULT_UNSUPPORTED;
break;
}
/* supported command handling stop */
if (result == VEHICLE_CMD_RESULT_FAILED ||
result == VEHICLE_CMD_RESULT_DENIED ||
- result == VEHICLE_CMD_RESULT_UNSUPPORTED) {
- ioctl(buzzer, TONE_SET_ALARM, 5);
+ result == VEHICLE_CMD_RESULT_UNSUPPORTED ||
+ result == VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED) {
+
+ tune_negative();
} else if (result == VEHICLE_CMD_RESULT_ACCEPTED) {
- tune_confirm();
+
+ tune_positive();
}
/* send any requested ACKs */
@@ -1065,7 +525,7 @@ void handle_command(int status_pub, struct vehicle_status_s *current_vehicle_sta
}
-static void *orb_receive_loop(void *arg) //handles status information coming from subsystems (present, enabled, health), these values do not indicate the quality (variance) of the signal
+void *orb_receive_loop(void *arg) //handles status information coming from subsystems (present, enabled, health), these values do not indicate the quality (variance) of the signal
{
/* Set thread name */
prctl(PR_SET_NAME, "commander orb rcv", getpid());
@@ -1168,8 +628,7 @@ float battery_remaining_estimate_voltage(float voltage)
return ret;
}
-static void
-usage(const char *reason)
+void usage(const char *reason)
{
if (reason)
fprintf(stderr, "%s\n", reason);
@@ -1235,6 +694,9 @@ int commander_thread_main(int argc, char *argv[])
commander_initialized = false;
bool home_position_set = false;
+ bool battery_tune_played = false;
+ bool arm_tune_played = false;
+
/* set parameters */
failsafe_lowlevel_timeout_ms = 0;
param_get(param_find("SYS_FAILSAVE_LL"), &failsafe_lowlevel_timeout_ms);
@@ -1244,60 +706,108 @@ int commander_thread_main(int argc, char *argv[])
param_t _param_component_id = param_find("MAV_COMP_ID");
/* welcome user */
- warnx("I am in command now!\n");
+ warnx("[commander] starting");
/* pthreads for command and subsystem info handling */
// pthread_t command_handling_thread;
pthread_t subsystem_info_thread;
+ pthread_t commander_low_prio_thread;
/* initialize */
if (led_init() != 0) {
- warnx("ERROR: Failed to initialize leds\n");
+ warnx("ERROR: Failed to initialize leds");
}
- if (buzzer_init() != 0) {
- warnx("ERROR: Failed to initialize buzzer\n");
+ if (buzzer_init() != OK) {
+ warnx("ERROR: Failed to initialize buzzer");
}
mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
if (mavlink_fd < 0) {
- warnx("ERROR: Failed to open MAVLink log stream, start mavlink app first.\n");
+ warnx("ERROR: Failed to open MAVLink log stream, start mavlink app first.");
}
-
+
+ /* Main state machine */
+ struct vehicle_status_s current_status;
+ orb_advert_t status_pub;
/* make sure we are in preflight state */
memset(&current_status, 0, sizeof(current_status));
- current_status.state_machine = SYSTEM_STATE_PREFLIGHT;
- current_status.flag_system_armed = false;
+
+ /* safety topic */
+ struct actuator_safety_s safety;
+ orb_advert_t safety_pub;
+ /* Initialize safety with all false */
+ memset(&safety, 0, sizeof(safety));
+
+
+ /* flags for control apps */
+ struct vehicle_control_mode_s control_mode;
+ orb_advert_t control_mode_pub;
+
+ /* Initialize all flags to false */
+ memset(&control_mode, 0, sizeof(control_mode));
+
+ current_status.navigation_state = NAVIGATION_STATE_INIT;
+ current_status.arming_state = ARMING_STATE_INIT;
+ current_status.hil_state = HIL_STATE_OFF;
+
/* neither manual nor offboard control commands have been received */
current_status.offboard_control_signal_found_once = false;
current_status.rc_signal_found_once = false;
+
/* mark all signals lost as long as they haven't been found */
current_status.rc_signal_lost = true;
current_status.offboard_control_signal_lost = true;
+
/* allow manual override initially */
current_status.flag_external_manual_override_ok = true;
+
/* flag position info as bad, do not allow auto mode */
- current_status.flag_vector_flight_mode_ok = false;
+ // 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 */
+
+ /* XXX do we need this? */
+ //current_status.flag_safety_present = false;
+
+ // XXX for now just set sensors as initialized
+ current_status.condition_system_sensors_initialized = true;
+
+ // XXX just disable offboard control for now
+ control_mode.flag_control_offboard_enabled = false;
/* advertise to ORB */
- stat_pub = orb_advertise(ORB_ID(vehicle_status), &current_status);
+ status_pub = orb_advertise(ORB_ID(vehicle_status), &current_status);
/* publish current state machine */
- state_machine_publish(stat_pub, &current_status, mavlink_fd);
+
+ /* publish the new state */
+ current_status.counter++;
+ current_status.timestamp = hrt_absolute_time();
+ orb_publish(ORB_ID(vehicle_status), status_pub, &current_status);
+
+
+ safety_pub = orb_advertise(ORB_ID(actuator_safety), &safety);
+
+ /* but also subscribe to it */
+ int safety_sub = orb_subscribe(ORB_ID(actuator_safety));
+
+ control_mode_pub = orb_advertise(ORB_ID(vehicle_control_mode), &control_mode);
/* home position */
orb_advert_t home_pub = -1;
struct home_position_s home;
memset(&home, 0, sizeof(home));
- if (stat_pub < 0) {
+ if (status_pub < 0) {
warnx("ERROR: orb_advertise for topic vehicle_status failed (uorb app running?).\n");
warnx("exiting.");
exit(ERROR);
}
+ // XXX needed?
mavlink_log_info(mavlink_fd, "system is running");
/* create pthreads */
@@ -1306,9 +816,18 @@ int commander_thread_main(int argc, char *argv[])
pthread_attr_setstacksize(&subsystem_info_attr, 2048);
pthread_create(&subsystem_info_thread, &subsystem_info_attr, orb_receive_loop, &current_status);
+ pthread_attr_t commander_low_prio_attr;
+ pthread_attr_init(&commander_low_prio_attr);
+ pthread_attr_setstacksize(&commander_low_prio_attr, 2048);
+
+ struct sched_param param;
+ /* low priority */
+ param.sched_priority = SCHED_PRIORITY_DEFAULT - 50;
+ (void)pthread_attr_setschedparam(&commander_low_prio_attr, &param);
+ pthread_create(&commander_low_prio_thread, &commander_low_prio_attr, commander_low_prio_loop, NULL);
+
/* Start monitoring loop */
uint16_t counter = 0;
- uint8_t flight_env;
/* Initialize to 0.0V */
float battery_voltage = 0.0f;
@@ -1317,12 +836,14 @@ int commander_thread_main(int argc, char *argv[])
bool critical_battery_voltage_actions_done = false;
uint8_t low_voltage_counter = 0;
uint16_t critical_voltage_counter = 0;
- int16_t mode_switch_rc_value;
float bat_remain = 1.0f;
uint16_t stick_off_counter = 0;
uint16_t stick_on_counter = 0;
+ /* XXX what exactly is this for? */
+ uint64_t last_print_time = 0;
+
/* Subscribe to manual control data */
int sp_man_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
struct manual_control_setpoint_s sp_man;
@@ -1333,11 +854,13 @@ int commander_thread_main(int argc, char *argv[])
struct offboard_control_setpoint_s sp_offboard;
memset(&sp_offboard, 0, sizeof(sp_offboard));
+ /* Subscribe to global position */
int global_position_sub = orb_subscribe(ORB_ID(vehicle_global_position));
struct vehicle_global_position_s global_position;
memset(&global_position, 0, sizeof(global_position));
uint64_t last_global_position_time = 0;
+ /* Subscribe to local position data */
int local_position_sub = orb_subscribe(ORB_ID(vehicle_local_position));
struct vehicle_local_position_s local_position;
memset(&local_position, 0, sizeof(local_position));
@@ -1348,10 +871,13 @@ int commander_thread_main(int argc, char *argv[])
* position estimator and commander. RAW GPS is more than good enough for a
* non-flying vehicle.
*/
+
+ /* Subscribe to GPS topic */
int gps_sub = orb_subscribe(ORB_ID(vehicle_gps_position));
struct vehicle_gps_position_s gps_position;
memset(&gps_position, 0, sizeof(gps_position));
+ /* Subscribe to sensor topic */
int sensor_sub = orb_subscribe(ORB_ID(sensor_combined));
struct sensor_combined_s sensors;
memset(&sensors, 0, sizeof(sensors));
@@ -1387,7 +913,9 @@ int commander_thread_main(int argc, char *argv[])
thread_running = true;
uint64_t start_time = hrt_absolute_time();
- uint64_t failsave_ll_start_time = 0;
+
+ /* XXX use this! */
+ //uint64_t failsave_ll_start_time = 0;
bool state_changed = true;
bool param_init_forced = true;
@@ -1396,6 +924,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 (!safety.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) {
@@ -1428,8 +989,9 @@ int commander_thread_main(int argc, char *argv[])
orb_copy(ORB_ID(vehicle_command), cmd_sub, &cmd);
/* handle it */
- handle_command(stat_pub, &current_status, &cmd);
+ handle_command(status_pub, &current_status, &cmd, safety_pub, &safety);
}
+
/* update parameters */
orb_check(param_changed_sub, &new_data);
@@ -1439,9 +1001,8 @@ int commander_thread_main(int argc, char *argv[])
/* parameters changed */
orb_copy(ORB_ID(parameter_update), param_changed_sub, &param_changed);
-
/* update parameters */
- if (!current_status.flag_system_armed) {
+ if (!safety.armed) {
if (param_get(_param_sys_type, &(current_status.system_type)) != OK) {
warnx("failed setting new system type");
}
@@ -1459,10 +1020,16 @@ int commander_thread_main(int argc, char *argv[])
/* check and update system / component ID */
param_get(_param_system_id, &(current_status.system_id));
param_get(_param_component_id, &(current_status.component_id));
-
}
}
+ /* update safety topic */
+ orb_check(safety_sub, &new_data);
+
+ if (new_data) {
+ orb_copy(ORB_ID(actuator_safety), safety_sub, &safety);
+ }
+
/* update global position estimate */
orb_check(global_position_sub, &new_data);
@@ -1481,6 +1048,13 @@ int commander_thread_main(int argc, char *argv[])
last_local_position_time = local_position.timestamp;
}
+ /* set the condition to valid if there has recently been a local position estimate */
+ if (hrt_absolute_time() - last_local_position_time < LOCAL_POSITION_TIMEOUT) {
+ current_status.condition_local_position_valid = true;
+ } else {
+ current_status.condition_local_position_valid = false;
+ }
+
/* update battery status */
orb_check(battery_sub, &new_data);
if (new_data) {
@@ -1499,10 +1073,11 @@ int commander_thread_main(int argc, char *argv[])
/* Slow but important 8 Hz checks */
if (counter % ((1000000 / COMMANDER_MONITORING_INTERVAL) / 8) == 0) {
- /* toggle activity (blue) led at 1 Hz in standby, 10 Hz in armed mode */
- if ((current_status.state_machine == SYSTEM_STATE_GROUND_READY ||
+
+ /* XXX if armed */
+ if ((false /*current_status.state_machine == SYSTEM_STATE_GROUND_READY ||
current_status.state_machine == SYSTEM_STATE_AUTO ||
- current_status.state_machine == SYSTEM_STATE_MANUAL)) {
+ current_status.state_machine == SYSTEM_STATE_MANUAL*/)) {
/* armed, solid */
led_on(LED_AMBER);
@@ -1537,45 +1112,18 @@ int commander_thread_main(int argc, char *argv[])
} else if (bat_remain < 0.3f && (low_voltage_counter > LOW_VOLTAGE_BATTERY_COUNTER_LIMIT)) {
/* toggle arming (red) at 5 Hz on low battery or error */
led_toggle(LED_AMBER);
-
- } else {
- // /* Constant error indication in standby mode without GPS */
- // if (!current_status.gps_valid) {
- // led_on(LED_AMBER);
-
- // } else {
- // led_off(LED_AMBER);
- // }
}
- if (counter % (1000000 / COMMANDER_MONITORING_INTERVAL) == 0) {
- /* compute system load */
- uint64_t interval_runtime = system_load.tasks[0].total_runtime - last_idle_time;
-
- if (last_idle_time > 0)
- current_status.load = 1000 - (interval_runtime / 1000); //system load is time spent in non-idle
-
- last_idle_time = system_load.tasks[0].total_runtime;
- }
}
- // // XXX Export patterns and threshold to parameters
- /* Trigger audio event for low battery */
- if (bat_remain < 0.1f && battery_voltage_valid && (counter % ((1000000 / COMMANDER_MONITORING_INTERVAL) / 4) == 0)) {
- /* For less than 10%, start be really annoying at 5 Hz */
- ioctl(buzzer, TONE_SET_ALARM, 0);
- ioctl(buzzer, TONE_SET_ALARM, 3);
-
- } else if (bat_remain < 0.1f && battery_voltage_valid && (counter % ((1000000 / COMMANDER_MONITORING_INTERVAL) / 4) == 2)) {
- ioctl(buzzer, TONE_SET_ALARM, 0);
+ if (counter % (1000000 / COMMANDER_MONITORING_INTERVAL) == 0) {
+ /* compute system load */
+ uint64_t interval_runtime = system_load.tasks[0].total_runtime - last_idle_time;
- } else if (bat_remain < 0.2f && battery_voltage_valid && (counter % ((1000000 / COMMANDER_MONITORING_INTERVAL) / 2) == 0)) {
- /* For less than 20%, start be slightly annoying at 1 Hz */
- ioctl(buzzer, TONE_SET_ALARM, 0);
- tune_confirm();
+ if (last_idle_time > 0)
+ current_status.load = 1000 - (interval_runtime / 1000); //system load is time spent in non-idle
- } else if (bat_remain < 0.2f && battery_voltage_valid && (counter % ((1000000 / COMMANDER_MONITORING_INTERVAL) / 2) == 2)) {
- ioctl(buzzer, TONE_SET_ALARM, 0);
+ last_idle_time = system_load.tasks[0].total_runtime;
}
/* Check battery voltage */
@@ -1599,13 +1147,14 @@ int commander_thread_main(int argc, char *argv[])
low_voltage_counter++;
}
- /* Critical, this is rather an emergency, kill signal to sdlog and change state machine */
+ /* Critical, this is rather an emergency, change state machine */
else if (battery_voltage_valid && (bat_remain < 0.1f /* XXX MAGIC NUMBER */) && (false == critical_battery_voltage_actions_done && true == low_battery_voltage_actions_done)) {
if (critical_voltage_counter > CRITICAL_VOLTAGE_BATTERY_COUNTER_LIMIT) {
critical_battery_voltage_actions_done = true;
mavlink_log_critical(mavlink_fd, "[cmd] EMERGENCY! CRITICAL BATTERY!");
current_status.battery_warning = VEHICLE_BATTERY_WARNING_ALERT;
- state_machine_emergency(stat_pub, &current_status, mavlink_fd);
+ // XXX implement this
+ // state_machine_emergency(status_pub, &current_status, mavlink_fd);
}
critical_voltage_counter++;
@@ -1617,6 +1166,14 @@ int commander_thread_main(int argc, char *argv[])
/* End battery voltage check */
+ /* If in INIT state, try to proceed to STANDBY state */
+ if (current_status.arming_state == ARMING_STATE_INIT) {
+ // XXX check for sensors
+ arming_state_transition(status_pub, &current_status, ARMING_STATE_STANDBY, safety_pub, &safety, mavlink_fd);
+ } else {
+ // XXX: Add emergency stuff if sensors are lost
+ }
+
/*
* Check for valid position information.
@@ -1628,53 +1185,53 @@ int commander_thread_main(int argc, char *argv[])
*/
/* store current state to reason later about a state change */
- bool vector_flight_mode_ok = current_status.flag_vector_flight_mode_ok;
- bool global_pos_valid = current_status.flag_global_position_valid;
- bool local_pos_valid = current_status.flag_local_position_valid;
- bool airspeed_valid = current_status.flag_airspeed_valid;
+ // bool vector_flight_mode_ok = current_status.flag_vector_flight_mode_ok;
+ bool global_pos_valid = current_status.condition_global_position_valid;
+ bool local_pos_valid = current_status.condition_local_position_valid;
+ bool airspeed_valid = current_status.condition_airspeed_valid;
+
/* check for global or local position updates, set a timeout of 2s */
- if (hrt_absolute_time() - last_global_position_time < 2000000) {
- current_status.flag_global_position_valid = true;
+ if (hrt_absolute_time() - last_global_position_time < 2000000 && hrt_absolute_time() > 2000000) {
+ current_status.condition_global_position_valid = true;
// XXX check for controller status and home position as well
} else {
- current_status.flag_global_position_valid = false;
+ current_status.condition_global_position_valid = false;
}
- if (hrt_absolute_time() - last_local_position_time < 2000000) {
- current_status.flag_local_position_valid = true;
+ if (hrt_absolute_time() - last_local_position_time < 2000000 && hrt_absolute_time() > 2000000) {
+ current_status.condition_local_position_valid = true;
// XXX check for controller status and home position as well
} else {
- current_status.flag_local_position_valid = false;
+ current_status.condition_local_position_valid = false;
}
/* Check for valid airspeed/differential pressure measurements */
- if (hrt_absolute_time() - last_diff_pres_time < 2000000) {
- current_status.flag_airspeed_valid = true;
+ if (hrt_absolute_time() - last_diff_pres_time < 2000000 && hrt_absolute_time() > 2000000) {
+ current_status.condition_airspeed_valid = true;
} else {
- current_status.flag_airspeed_valid = false;
+ current_status.condition_airspeed_valid = false;
}
/*
* Consolidate global position and local position valid flags
* for vector flight mode.
*/
- if (current_status.flag_local_position_valid ||
- current_status.flag_global_position_valid) {
- current_status.flag_vector_flight_mode_ok = true;
+ // if (current_status.condition_local_position_valid ||
+ // current_status.condition_global_position_valid) {
+ // current_status.flag_vector_flight_mode_ok = true;
- } else {
- current_status.flag_vector_flight_mode_ok = false;
- }
+ // } else {
+ // current_status.flag_vector_flight_mode_ok = false;
+ // }
/* consolidate state change, flag as changed if required */
- if (vector_flight_mode_ok != current_status.flag_vector_flight_mode_ok ||
- global_pos_valid != current_status.flag_global_position_valid ||
- local_pos_valid != current_status.flag_local_position_valid ||
- airspeed_valid != current_status.flag_airspeed_valid) {
+ if (global_pos_valid != current_status.condition_global_position_valid ||
+ local_pos_valid != current_status.condition_local_position_valid ||
+ airspeed_valid != current_status.condition_airspeed_valid) {
state_changed = true;
}
@@ -1688,18 +1245,20 @@ int commander_thread_main(int argc, char *argv[])
* 2) The system has not aquired position lock before
* 3) The system is not armed (on the ground)
*/
- if (!current_status.flag_valid_launch_position &&
- !vector_flight_mode_ok && current_status.flag_vector_flight_mode_ok &&
- !current_status.flag_system_armed) {
- /* first time a valid position, store it and emit it */
-
- // XXX implement storage and publication of RTL position
- current_status.flag_valid_launch_position = true;
- current_status.flag_auto_flight_mode_ok = true;
- state_changed = true;
- }
+ // if (!current_status.flag_valid_launch_position &&
+ // !vector_flight_mode_ok && current_status.flag_vector_flight_mode_ok &&
+ // !current_status.flag_system_armed) {
+ // first time a valid position, store it and emit it
+
+ // // XXX implement storage and publication of RTL position
+ // current_status.flag_valid_launch_position = true;
+ // current_status.flag_auto_flight_mode_ok = true;
+ // state_changed = true;
+ // }
+
+ orb_check(gps_sub, &new_data);
+ if (new_data) {
- if (orb_check(ORB_ID(vehicle_gps_position), &new_data)) {
orb_copy(ORB_ID(vehicle_gps_position), gps_sub, &gps_position);
@@ -1724,10 +1283,10 @@ int commander_thread_main(int argc, char *argv[])
if (gps_position.fix_type == GPS_FIX_TYPE_3D
&& (hdop_m < hdop_threshold_m)
- && (vdop_m < vdop_threshold_m)
+ && (vdop_m < vdop_threshold_m) // XXX note that vdop is 0 for mtk
&& !home_position_set
&& (hrt_absolute_time() - gps_position.timestamp_position < 2000000)
- && !current_status.flag_system_armed) {
+ && !safety.armed) {
warnx("setting home position");
/* copy position data to uORB home message, store it locally as well */
@@ -1750,7 +1309,7 @@ int commander_thread_main(int argc, char *argv[])
/* mark home position as set */
home_position_set = true;
- tune_confirm();
+ tune_positive();
}
}
@@ -1760,100 +1319,268 @@ int commander_thread_main(int argc, char *argv[])
if ((hrt_absolute_time() - sp_man.timestamp) < 100000) {
- // /*
- // * Check if manual control modes have to be switched
- // */
- // if (!isfinite(sp_man.manual_mode_switch)) {
- // warnx("man mode sw not finite\n");
-
- // /* this switch is not properly mapped, set default */
- // if ((current_status.system_type == VEHICLE_TYPE_QUADROTOR) ||
- // (current_status.system_type == VEHICLE_TYPE_HEXAROTOR) ||
- // (current_status.system_type == VEHICLE_TYPE_OCTOROTOR)) {
-
- // /* assuming a rotary wing, fall back to SAS */
- // current_status.manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_SAS;
- // current_status.flag_control_attitude_enabled = true;
- // current_status.flag_control_rates_enabled = true;
- // } else {
-
- // /* assuming a fixed wing, fall back to direct pass-through */
- // current_status.manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_DIRECT;
- // current_status.flag_control_attitude_enabled = false;
- // current_status.flag_control_rates_enabled = false;
- // }
+ /*
+ * Check if manual control modes have to be switched
+ */
+ if (!isfinite(sp_man.mode_switch)) {
- // } else if (sp_man.manual_mode_switch < -STICK_ON_OFF_LIMIT) {
+ warnx("mode sw not finite");
+ /* no valid stick position, go to default */
+ current_status.mode_switch = MODE_SWITCH_MANUAL;
- // /* bottom stick position, set direct mode for vehicles supporting it */
- // if ((current_status.system_type == VEHICLE_TYPE_QUADROTOR) ||
- // (current_status.system_type == VEHICLE_TYPE_HEXAROTOR) ||
- // (current_status.system_type == VEHICLE_TYPE_OCTOROTOR)) {
+ } else if (sp_man.mode_switch < -STICK_ON_OFF_LIMIT) {
- // /* assuming a rotary wing, fall back to SAS */
- // current_status.manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_SAS;
- // current_status.flag_control_attitude_enabled = true;
- // current_status.flag_control_rates_enabled = true;
- // } else {
+ /* bottom stick position, go to manual mode */
+ current_status.mode_switch = MODE_SWITCH_MANUAL;
- // /* assuming a fixed wing, set to direct pass-through as requested */
- // current_status.manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_DIRECT;
- // current_status.flag_control_attitude_enabled = false;
- // current_status.flag_control_rates_enabled = false;
- // }
+ } else if (sp_man.mode_switch > STICK_ON_OFF_LIMIT) {
- // } else if (sp_man.manual_mode_switch > STICK_ON_OFF_LIMIT) {
+ /* top stick position, set auto/mission for all vehicle types */
+ current_status.mode_switch = MODE_SWITCH_AUTO;
- // /* top stick position, set SAS for all vehicle types */
- // current_status.manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_SAS;
- // current_status.flag_control_attitude_enabled = true;
- // current_status.flag_control_rates_enabled = true;
+ } else {
- // } else {
- // /* center stick position, set rate control */
- // current_status.manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_RATES;
- // current_status.flag_control_attitude_enabled = false;
- // current_status.flag_control_rates_enabled = true;
- // }
+ /* center stick position, set seatbelt/simple control */
+ current_status.mode_switch = MODE_SWITCH_SEATBELT;
+ }
// warnx("man ctrl mode: %d\n", (int)current_status.manual_control_mode);
/*
- * Check if manual stability control modes have to be switched
- */
- if (!isfinite(sp_man.manual_sas_switch)) {
+ * Check if land/RTL is requested
+ */
+ if (!isfinite(sp_man.return_switch)) {
/* this switch is not properly mapped, set default */
- current_status.manual_sas_mode = VEHICLE_MANUAL_SAS_MODE_ROLL_PITCH_ABS_YAW_ABS;
+ current_status.return_switch = RETURN_SWITCH_NONE;
- } else if (sp_man.manual_sas_switch < -STICK_ON_OFF_LIMIT) {
+ } else if (sp_man.return_switch < -STICK_ON_OFF_LIMIT) {
/* bottom stick position, set altitude hold */
- current_status.manual_sas_mode = VEHICLE_MANUAL_SAS_MODE_ALTITUDE;
+ current_status.return_switch = RETURN_SWITCH_NONE;
- } else if (sp_man.manual_sas_switch > STICK_ON_OFF_LIMIT) {
+ } else if (sp_man.return_switch > STICK_ON_OFF_LIMIT) {
/* top stick position */
- current_status.manual_sas_mode = VEHICLE_MANUAL_SAS_MODE_SIMPLE;
+ current_status.return_switch = RETURN_SWITCH_RETURN;
} else {
/* center stick position, set default */
- current_status.manual_sas_mode = VEHICLE_MANUAL_SAS_MODE_ROLL_PITCH_ABS_YAW_ABS;
+ current_status.return_switch = RETURN_SWITCH_NONE;
+ }
+
+ /* check mission switch */
+ if (!isfinite(sp_man.mission_switch)) {
+
+ /* this switch is not properly mapped, set default */
+ current_status.mission_switch = MISSION_SWITCH_NONE;
+
+ } else if (sp_man.mission_switch > STICK_ON_OFF_LIMIT) {
+
+ /* top switch position */
+ current_status.mission_switch = MISSION_SWITCH_MISSION;
+
+ } else if (sp_man.mission_switch < -STICK_ON_OFF_LIMIT) {
+
+ /* bottom switch position */
+ current_status.mission_switch = MISSION_SWITCH_NONE;
+
+ } else {
+
+ /* center switch position, set default */
+ current_status.mission_switch = MISSION_SWITCH_NONE; // XXX default?
+ }
+
+ /* Now it's time to handle the stick inputs */
+
+ switch (current_status.arming_state) {
+
+ /* evaluate the navigation state when disarmed */
+ case ARMING_STATE_STANDBY:
+
+ /* just manual, XXX this might depend on the return switch */
+ if (current_status.mode_switch == MODE_SWITCH_MANUAL) {
+
+ if (navigation_state_transition(status_pub, &current_status, NAVIGATION_STATE_MANUAL_STANDBY, control_mode_pub, &control_mode, mavlink_fd) != OK) {
+ // These is not supposed to happen
+ warnx("ERROR: Navigation state MANUAL_STANDBY rejected");
+ }
+
+ /* Try seatbelt or fallback to manual */
+ } else if (current_status.mode_switch == MODE_SWITCH_SEATBELT) {
+
+ if (navigation_state_transition(status_pub, &current_status, NAVIGATION_STATE_SEATBELT_STANDBY, control_mode_pub, &control_mode, mavlink_fd) != OK) {
+ // fallback to MANUAL_STANDBY
+ if (navigation_state_transition(status_pub, &current_status, NAVIGATION_STATE_MANUAL_STANDBY, control_mode_pub, &control_mode, mavlink_fd) != OK) {
+ // These is not supposed to happen
+ warnx("ERROR: Navigation state MANUAL_STANDBY rejected");
+ }
+ }
+
+ /* Try auto or fallback to seatbelt or even manual */
+ } else if (current_status.mode_switch == MODE_SWITCH_AUTO) {
+
+ if (navigation_state_transition(status_pub, &current_status, NAVIGATION_STATE_AUTO_STANDBY, control_mode_pub, &control_mode, mavlink_fd) != OK) {
+ // first fallback to SEATBELT_STANDY
+ if (navigation_state_transition(status_pub, &current_status, NAVIGATION_STATE_SEATBELT_STANDBY, control_mode_pub, &control_mode, mavlink_fd) != OK) {
+ // or fallback to MANUAL_STANDBY
+ if (navigation_state_transition(status_pub, &current_status, NAVIGATION_STATE_MANUAL_STANDBY, control_mode_pub, &control_mode, mavlink_fd) != OK) {
+ // These is not supposed to happen
+ warnx("ERROR: Navigation state MANUAL_STANDBY rejected");
+ }
+ }
+ }
+ }
+
+ break;
+
+ /* evaluate the navigation state when armed */
+ case ARMING_STATE_ARMED:
+
+ /* Always accept manual mode */
+ if (current_status.mode_switch == MODE_SWITCH_MANUAL) {
+
+ if (navigation_state_transition(status_pub, &current_status, NAVIGATION_STATE_MANUAL, control_mode_pub, &control_mode, mavlink_fd) != OK) {
+ // These is not supposed to happen
+ warnx("ERROR: Navigation state MANUAL rejected");
+ }
+
+ /* SEATBELT_STANDBY (fallback: MANUAL) */
+ } else if (current_status.mode_switch == MODE_SWITCH_SEATBELT
+ && current_status.return_switch == RETURN_SWITCH_NONE) {
+
+ if (navigation_state_transition(status_pub, &current_status, NAVIGATION_STATE_SEATBELT, control_mode_pub, &control_mode, mavlink_fd) != OK) {
+ // fallback to MANUAL_STANDBY
+ if (navigation_state_transition(status_pub, &current_status, NAVIGATION_STATE_MANUAL, control_mode_pub, &control_mode, mavlink_fd) != OK) {
+ // These is not supposed to happen
+ warnx("ERROR: Navigation state MANUAL rejected");
+ }
+ }
+
+ /* SEATBELT_DESCENT (fallback: MANUAL) */
+ } else if (current_status.mode_switch == MODE_SWITCH_SEATBELT
+ && current_status.return_switch == RETURN_SWITCH_RETURN) {
+
+ if (navigation_state_transition(status_pub, &current_status, NAVIGATION_STATE_SEATBELT_DESCENT, control_mode_pub, &control_mode, mavlink_fd) != OK) {
+ // fallback to MANUAL_STANDBY
+ if (navigation_state_transition(status_pub, &current_status, NAVIGATION_STATE_MANUAL, control_mode_pub, &control_mode, mavlink_fd) != OK) {
+ // These is not supposed to happen
+ warnx("ERROR: Navigation state MANUAL rejected");
+ }
+ }
+
+ /* AUTO_LOITER (fallback: SEATBELT, MANUAL) */
+ } else if (current_status.mode_switch == MODE_SWITCH_AUTO
+ && current_status.return_switch == RETURN_SWITCH_NONE
+ && current_status.mission_switch == MISSION_SWITCH_NONE) {
+
+ /* we might come from the disarmed state AUTO_STANDBY */
+ if (navigation_state_transition(status_pub, &current_status, NAVIGATION_STATE_AUTO_READY, control_mode_pub, &control_mode, mavlink_fd) != OK) {
+ if (navigation_state_transition(status_pub, &current_status, NAVIGATION_STATE_SEATBELT, control_mode_pub, &control_mode, mavlink_fd) != OK) {
+ // fallback to MANUAL_STANDBY
+ if (navigation_state_transition(status_pub, &current_status, NAVIGATION_STATE_MANUAL, control_mode_pub, &control_mode, mavlink_fd) != OK) {
+ // These is not supposed to happen
+ warnx("ERROR: Navigation state MANUAL rejected");
+ }
+ }
+ /* or from some other armed state like SEATBELT or MANUAL */
+ } else if (navigation_state_transition(status_pub, &current_status, NAVIGATION_STATE_AUTO_LOITER, control_mode_pub, &control_mode, mavlink_fd) != OK) {
+ if (navigation_state_transition(status_pub, &current_status, NAVIGATION_STATE_SEATBELT, control_mode_pub, &control_mode, mavlink_fd) != OK) {
+ // fallback to MANUAL_STANDBY
+ if (navigation_state_transition(status_pub, &current_status, NAVIGATION_STATE_MANUAL, control_mode_pub, &control_mode, mavlink_fd) != OK) {
+ // These is not supposed to happen
+ warnx("ERROR: Navigation state MANUAL rejected");
+ }
+ }
+ }
+
+ /* AUTO_MISSION (fallback: SEATBELT, MANUAL) */
+ } else if (current_status.mode_switch == MODE_SWITCH_AUTO
+ && current_status.return_switch == RETURN_SWITCH_NONE
+ && current_status.mission_switch == MISSION_SWITCH_MISSION) {
+
+ if (navigation_state_transition(status_pub, &current_status, NAVIGATION_STATE_AUTO_MISSION, control_mode_pub, &control_mode, mavlink_fd) != OK) {
+ if (navigation_state_transition(status_pub, &current_status, NAVIGATION_STATE_SEATBELT, control_mode_pub, &control_mode, mavlink_fd) != OK) {
+ // fallback to MANUAL_STANDBY
+ if (navigation_state_transition(status_pub, &current_status, NAVIGATION_STATE_MANUAL, control_mode_pub, &control_mode, mavlink_fd) != OK) {
+ // These is not supposed to happen
+ warnx("ERROR: Navigation state MANUAL rejected");
+ }
+ }
+ }
+
+ /* AUTO_RTL (fallback: SEATBELT_DESCENT, MANUAL) */
+ } else if (current_status.mode_switch == MODE_SWITCH_AUTO
+ && current_status.return_switch == RETURN_SWITCH_RETURN
+ && (current_status.mission_switch == MISSION_SWITCH_NONE || current_status.mission_switch == MISSION_SWITCH_MISSION)) {
+
+ if (navigation_state_transition(status_pub, &current_status, NAVIGATION_STATE_AUTO_RTL, control_mode_pub, &control_mode, mavlink_fd) != OK) {
+ if (navigation_state_transition(status_pub, &current_status, NAVIGATION_STATE_SEATBELT_DESCENT, control_mode_pub, &control_mode, mavlink_fd) != OK) {
+ // fallback to MANUAL_STANDBY
+ if (navigation_state_transition(status_pub, &current_status, NAVIGATION_STATE_MANUAL, control_mode_pub, &control_mode, mavlink_fd) != OK) {
+ // These is not supposed to happen
+ warnx("ERROR: Navigation state MANUAL rejected");
+ }
+ }
+ }
+ }
+ break;
+
+ // XXX we might be missing something that triggers a transition from RTL to LAND
+
+ case ARMING_STATE_ARMED_ERROR:
+
+ // XXX work out fail-safe scenarios
+ break;
+
+ case ARMING_STATE_STANDBY_ERROR:
+
+ // XXX work out fail-safe scenarios
+ break;
+
+ case ARMING_STATE_REBOOT:
+
+ // XXX I don't think we should end up here
+ break;
+
+ case ARMING_STATE_IN_AIR_RESTORE:
+
+ // XXX not sure what to do here
+ break;
+ default:
+ break;
+ }
+ /* handle the case where RC signal was regained */
+ if (!current_status.rc_signal_found_once) {
+ current_status.rc_signal_found_once = true;
+ mavlink_log_critical(mavlink_fd, "DETECTED RC SIGNAL FIRST TIME.");
+
+ } else {
+ if (current_status.rc_signal_lost) {
+ mavlink_log_critical(mavlink_fd, "[cmd] RECOVERY - RC SIGNAL GAINED!");
+ }
}
/*
- * Check if left stick is in lower left position --> switch to standby state.
- * Do this only for multirotors, not for fixed wing aircraft.
- */
- if (((current_status.system_type == VEHICLE_TYPE_QUADROTOR) ||
- (current_status.system_type == VEHICLE_TYPE_HEXAROTOR) ||
- (current_status.system_type == VEHICLE_TYPE_OCTOROTOR)
- ) &&
- ((sp_man.yaw < -STICK_ON_OFF_LIMIT)) &&
- (sp_man.throttle < STICK_THRUST_RANGE * 0.2f)) {
+ * Check if left stick is in lower left position --> switch to standby state.
+ * Do this only for multirotors, not for fixed wing aircraft.
+ */
+ // printf("checking\n");
+ if ((sp_man.yaw < -STICK_ON_OFF_LIMIT) && (sp_man.throttle < STICK_THRUST_RANGE * 0.2f)) {
if (stick_off_counter > STICK_ON_OFF_COUNTER_LIMIT) {
- update_state_machine_disarm(stat_pub, &current_status, mavlink_fd);
- stick_on_counter = 0;
+
+ if((current_status.system_type == VEHICLE_TYPE_QUADROTOR) ||
+ (current_status.system_type == VEHICLE_TYPE_HEXAROTOR) ||
+ (current_status.system_type == VEHICLE_TYPE_OCTOROTOR)
+ ) {
+ arming_state_transition(status_pub, &current_status, ARMING_STATE_STANDBY, safety_pub, &safety, mavlink_fd);
+ tune_positive();
+
+ } else {
+ mavlink_log_critical(mavlink_fd, "STICK DISARM not allowed");
+ tune_negative();
+ }
+ stick_off_counter = 0;
} else {
stick_off_counter++;
@@ -1864,8 +1591,9 @@ int commander_thread_main(int argc, char *argv[])
/* check if left stick is in lower right position --> arm */
if (sp_man.yaw > STICK_ON_OFF_LIMIT && sp_man.throttle < STICK_THRUST_RANGE * 0.2f) {
if (stick_on_counter > STICK_ON_OFF_COUNTER_LIMIT) {
- update_state_machine_arm(stat_pub, &current_status, mavlink_fd);
+ arming_state_transition(status_pub, &current_status, ARMING_STATE_ARMED, safety_pub, &safety, mavlink_fd);
stick_on_counter = 0;
+ tune_positive();
} else {
stick_on_counter++;
@@ -1873,49 +1601,24 @@ int commander_thread_main(int argc, char *argv[])
}
}
- /* check manual override switch - switch to manual or auto mode */
- if (sp_man.manual_override_switch > STICK_ON_OFF_LIMIT) {
- /* enable manual override */
- update_state_machine_mode_manual(stat_pub, &current_status, mavlink_fd);
-
- } else if (sp_man.manual_override_switch < -STICK_ON_OFF_LIMIT) {
- // /* check auto mode switch for correct mode */
- // if (sp_man.auto_mode_switch > STICK_ON_OFF_LIMIT) {
- // /* enable guided mode */
- // update_state_machine_mode_guided(stat_pub, &current_status, mavlink_fd);
-
- // } else if (sp_man.auto_mode_switch < -STICK_ON_OFF_LIMIT) {
- // XXX hardcode to auto for now
- update_state_machine_mode_auto(stat_pub, &current_status, mavlink_fd);
-
- // }
-
- } else {
- /* center stick position, set SAS for all vehicle types */
- update_state_machine_mode_stabilized(stat_pub, &current_status, mavlink_fd);
- }
-
- /* handle the case where RC signal was regained */
- if (!current_status.rc_signal_found_once) {
- current_status.rc_signal_found_once = true;
- mavlink_log_critical(mavlink_fd, "DETECTED RC SIGNAL FIRST TIME.");
-
- } else {
- if (current_status.rc_signal_lost) mavlink_log_critical(mavlink_fd, "[cmd] RECOVERY - RC SIGNAL GAINED!");
- }
-
current_status.rc_signal_cutting_off = false;
current_status.rc_signal_lost = false;
current_status.rc_signal_lost_interval = 0;
} else {
- static uint64_t last_print_time = 0;
/* print error message for first RC glitch and then every 5 s / 5000 ms) */
if (!current_status.rc_signal_cutting_off || ((hrt_absolute_time() - last_print_time) > 5000000)) {
/* only complain if the offboard control is NOT active */
current_status.rc_signal_cutting_off = true;
mavlink_log_critical(mavlink_fd, "CRITICAL - NO REMOTE SIGNAL!");
+
+ if (!current_status.rc_signal_cutting_off) {
+ printf("Reason: not rc_signal_cutting_off\n");
+ } else {
+ printf("last print time: %llu\n", last_print_time);
+ }
+
last_print_time = hrt_absolute_time();
}
@@ -1947,60 +1650,60 @@ int commander_thread_main(int argc, char *argv[])
if (!current_status.rc_signal_found_once && sp_offboard.timestamp != 0) {
if ((hrt_absolute_time() - sp_offboard.timestamp) < 5000000) {
- /* decide about attitude control flag, enable in att/pos/vel */
- bool attitude_ctrl_enabled = (sp_offboard.mode == OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE ||
- sp_offboard.mode == OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY ||
- sp_offboard.mode == OFFBOARD_CONTROL_MODE_DIRECT_POSITION);
+ // /* decide about attitude control flag, enable in att/pos/vel */
+ // bool attitude_ctrl_enabled = (sp_offboard.mode == OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE ||
+ // sp_offboard.mode == OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY ||
+ // sp_offboard.mode == OFFBOARD_CONTROL_MODE_DIRECT_POSITION);
- /* decide about rate control flag, enable it always XXX (for now) */
- bool rates_ctrl_enabled = true;
+ // /* decide about rate control flag, enable it always XXX (for now) */
+ // bool rates_ctrl_enabled = true;
- /* set up control mode */
- if (current_status.flag_control_attitude_enabled != attitude_ctrl_enabled) {
- current_status.flag_control_attitude_enabled = attitude_ctrl_enabled;
- state_changed = true;
- }
+ // /* set up control mode */
+ // if (current_status.flag_control_attitude_enabled != attitude_ctrl_enabled) {
+ // current_status.flag_control_attitude_enabled = attitude_ctrl_enabled;
+ // state_changed = true;
+ // }
- if (current_status.flag_control_rates_enabled != rates_ctrl_enabled) {
- current_status.flag_control_rates_enabled = rates_ctrl_enabled;
- state_changed = true;
- }
+ // if (current_status.flag_control_rates_enabled != rates_ctrl_enabled) {
+ // current_status.flag_control_rates_enabled = rates_ctrl_enabled;
+ // state_changed = true;
+ // }
- /* handle the case where offboard control signal was regained */
- if (!current_status.offboard_control_signal_found_once) {
- current_status.offboard_control_signal_found_once = true;
- /* enable offboard control, disable manual input */
- current_status.flag_control_manual_enabled = false;
- current_status.flag_control_offboard_enabled = true;
- state_changed = true;
- tune_confirm();
+ // /* handle the case where offboard control signal was regained */
+ // if (!current_status.offboard_control_signal_found_once) {
+ // current_status.offboard_control_signal_found_once = true;
+ // /* enable offboard control, disable manual input */
+ // current_status.flag_control_manual_enabled = false;
+ // current_status.flag_control_offboard_enabled = true;
+ // state_changed = true;
+ // tune_positive();
- mavlink_log_critical(mavlink_fd, "DETECTED OFFBOARD SIGNAL FIRST");
+ // mavlink_log_critical(mavlink_fd, "DETECTED OFFBOARD SIGNAL FIRST");
- } else {
- if (current_status.offboard_control_signal_lost) {
- mavlink_log_critical(mavlink_fd, "RECOVERY OFFBOARD CONTROL");
- state_changed = true;
- tune_confirm();
- }
- }
+ // } else {
+ // if (current_status.offboard_control_signal_lost) {
+ // mavlink_log_critical(mavlink_fd, "RECOVERY OFFBOARD CONTROL");
+ // state_changed = true;
+ // tune_positive();
+ // }
+ // }
current_status.offboard_control_signal_weak = false;
current_status.offboard_control_signal_lost = false;
current_status.offboard_control_signal_lost_interval = 0;
+ // XXX check if this is correct
/* arm / disarm on request */
- if (sp_offboard.armed && !current_status.flag_system_armed) {
- update_state_machine_arm(stat_pub, &current_status, mavlink_fd);
- /* switch to stabilized mode = takeoff */
- update_state_machine_mode_stabilized(stat_pub, &current_status, mavlink_fd);
+ if (sp_offboard.armed && !safety.armed) {
+
+ arming_state_transition(status_pub, &current_status, ARMING_STATE_ARMED, safety_pub, &safety, mavlink_fd);
+
+ } else if (!sp_offboard.armed && safety.armed) {
- } else if (!sp_offboard.armed && current_status.flag_system_armed) {
- update_state_machine_disarm(stat_pub, &current_status, mavlink_fd);
+ arming_state_transition(status_pub, &current_status, ARMING_STATE_STANDBY, safety_pub, &safety, mavlink_fd);
}
} else {
- static uint64_t last_print_time = 0;
/* print error message for first RC glitch and then every 5 s / 5000 ms) */
if (!current_status.offboard_control_signal_weak || ((hrt_absolute_time() - last_print_time) > 5000000)) {
@@ -2016,7 +1719,7 @@ int commander_thread_main(int argc, char *argv[])
if (current_status.offboard_control_signal_lost_interval > 100000) {
current_status.offboard_control_signal_lost = true;
current_status.failsave_lowlevel_start_time = hrt_absolute_time();
- tune_confirm();
+ tune_positive();
/* kill motors after timeout */
if (hrt_absolute_time() - current_status.failsave_lowlevel_start_time > failsafe_lowlevel_timeout_ms * 1000) {
@@ -2028,29 +1731,60 @@ int commander_thread_main(int argc, char *argv[])
}
+
+
current_status.counter++;
current_status.timestamp = hrt_absolute_time();
+ // XXX this is missing
/* If full run came back clean, transition to standby */
- if (current_status.state_machine == SYSTEM_STATE_PREFLIGHT &&
- current_status.flag_preflight_gyro_calibration == false &&
- current_status.flag_preflight_mag_calibration == false &&
- current_status.flag_preflight_accel_calibration == false) {
- /* All ok, no calibration going on, go to standby */
- do_state_update(stat_pub, &current_status, mavlink_fd, SYSTEM_STATE_STANDBY);
- }
+ // if (current_status.state_machine == SYSTEM_STATE_PREFLIGHT &&
+ // current_status.flag_preflight_gyro_calibration == false &&
+ // current_status.flag_preflight_mag_calibration == false &&
+ // current_status.flag_preflight_accel_calibration == false) {
+ // /* All ok, no calibration going on, go to standby */
+ // do_state_update(status_pub, &current_status, mavlink_fd, SYSTEM_STATE_STANDBY);
+ // }
/* publish at least with 1 Hz */
if (counter % (1000000 / COMMANDER_MONITORING_INTERVAL) == 0 || state_changed) {
- publish_armed_status(&current_status);
- orb_publish(ORB_ID(vehicle_status), stat_pub, &current_status);
+
+ orb_publish(ORB_ID(vehicle_status), status_pub, &current_status);
state_changed = false;
}
+
+
/* Store old modes to detect and act on state transitions */
voltage_previous = current_status.voltage_battery;
+
+ /* play tone according to evaluation result */
+ /* check if we recently armed */
+ if (!arm_tune_played && safety.armed && ( !safety.safety_switch_available || (safety.safety_off && safety.safety_switch_available))) {
+ if (tune_arm() == OK)
+ arm_tune_played = true;
+
+ /* Trigger audio event for low battery */
+ } else if (bat_remain < 0.1f && battery_voltage_valid) {
+ if (tune_critical_bat() == OK)
+ battery_tune_played = true;
+ } else if (bat_remain < 0.2f && battery_voltage_valid) {
+ if (tune_low_bat() == OK)
+ battery_tune_played = true;
+ } else if(battery_tune_played) {
+ tune_stop();
+ battery_tune_played = false;
+ }
+
+ /* reset arm_tune_played when disarmed */
+ if (!(safety.armed && ( !safety.safety_switch_available || (safety.safety_off && safety.safety_switch_available)))) {
+ arm_tune_played = false;
+ }
+
+
+ /* XXX use this voltage_previous */
fflush(stdout);
counter++;
usleep(COMMANDER_MONITORING_INTERVAL);
@@ -2059,6 +1793,7 @@ int commander_thread_main(int argc, char *argv[])
/* wait for threads to complete */
// pthread_join(command_handling_thread, NULL);
pthread_join(subsystem_info_thread, NULL);
+ pthread_join(commander_low_prio_thread, NULL);
/* close fds */
led_deinit();
@@ -2069,10 +1804,93 @@ int commander_thread_main(int argc, char *argv[])
close(sensor_sub);
close(cmd_sub);
- warnx("exiting..\n");
+ warnx("exiting");
fflush(stdout);
thread_running = false;
return 0;
}
+
+
+void *commander_low_prio_loop(void *arg)
+{
+ /* Set thread name */
+ prctl(PR_SET_NAME, "commander low prio", getpid());
+
+ while (!thread_should_exit) {
+
+ switch (low_prio_task) {
+
+ case LOW_PRIO_TASK_PARAM_LOAD:
+
+ if (0 == param_load_default()) {
+ mavlink_log_info(mavlink_fd, "Param load success");
+ } else {
+ mavlink_log_critical(mavlink_fd, "Param load ERROR");
+ tune_error();
+ }
+ low_prio_task = LOW_PRIO_TASK_NONE;
+ break;
+
+ case LOW_PRIO_TASK_PARAM_SAVE:
+
+ if (0 == param_save_default()) {
+ mavlink_log_info(mavlink_fd, "Param save success");
+ } else {
+ mavlink_log_critical(mavlink_fd, "Param save ERROR");
+ tune_error();
+ }
+ low_prio_task = LOW_PRIO_TASK_NONE;
+ break;
+
+ case LOW_PRIO_TASK_GYRO_CALIBRATION:
+
+ do_gyro_calibration(mavlink_fd);
+
+ low_prio_task = LOW_PRIO_TASK_NONE;
+ break;
+
+ case LOW_PRIO_TASK_MAG_CALIBRATION:
+
+ do_mag_calibration(mavlink_fd);
+
+ low_prio_task = LOW_PRIO_TASK_NONE;
+ break;
+
+ case LOW_PRIO_TASK_ALTITUDE_CALIBRATION:
+
+ // do_baro_calibration(mavlink_fd);
+
+ case LOW_PRIO_TASK_RC_CALIBRATION:
+
+ // do_rc_calibration(mavlink_fd);
+
+ low_prio_task = LOW_PRIO_TASK_NONE;
+ break;
+
+ case LOW_PRIO_TASK_ACCEL_CALIBRATION:
+
+ do_accel_calibration(mavlink_fd);
+
+ low_prio_task = LOW_PRIO_TASK_NONE;
+ break;
+
+ case LOW_PRIO_TASK_AIRSPEED_CALIBRATION:
+
+ do_airspeed_calibration(mavlink_fd);
+
+ low_prio_task = LOW_PRIO_TASK_NONE;
+ break;
+
+ case LOW_PRIO_TASK_NONE:
+ default:
+ /* slow down to 10Hz */
+ usleep(100000);
+ break;
+ }
+
+ }
+
+ return 0;
+}
diff --git a/src/modules/commander/commander.h b/src/modules/commander/commander.h
index 04b4e72ab..6e57c0ba5 100644
--- a/src/modules/commander/commander.h
+++ b/src/modules/commander/commander.h
@@ -49,10 +49,6 @@
#ifndef COMMANDER_H_
#define COMMANDER_H_
-#define LOW_VOLTAGE_BATTERY_HYSTERESIS_TIME_MS 1000.0f
-#define CRITICAL_VOLTAGE_BATTERY_HYSTERESIS_TIME_MS 100.0f
-void tune_confirm(void);
-void tune_error(void);
#endif /* COMMANDER_H_ */
diff --git a/src/modules/commander/commander_helper.c b/src/modules/commander/commander_helper.c
new file mode 100644
index 000000000..a75b5dec3
--- /dev/null
+++ b/src/modules/commander/commander_helper.c
@@ -0,0 +1,129 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Author: Thomas Gubler <thomasgubler@student.ethz.ch>
+ * Julian Oes <joes@student.ethz.ch>
+ *
+ * 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 commander_helper.c
+ * Commander helper functions implementations
+ */
+
+#include <stdio.h>
+#include <unistd.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <fcntl.h>
+
+#include <uORB/uORB.h>
+#include <uORB/topics/vehicle_status.h>
+#include <uORB/topics/actuator_controls.h>
+#include <uORB/topics/vehicle_control_mode.h>
+#include <systemlib/err.h>
+#include <drivers/drv_hrt.h>
+#include <drivers/drv_tone_alarm.h>
+
+#include "commander_helper.h"
+
+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) ||
+ (current_status->system_type == VEHICLE_TYPE_TRICOPTER));
+}
+
+bool is_rotary_wing(const struct vehicle_status_s *current_status)
+{
+ return is_multirotor(current_status) || (current_status->system_type == VEHICLE_TYPE_HELICOPTER)
+ || (current_status->system_type == VEHICLE_TYPE_COAXIAL);
+}
+
+static int buzzer;
+
+int buzzer_init()
+{
+ buzzer = open("/dev/tone_alarm", O_WRONLY);
+
+ if (buzzer < 0) {
+ warnx("Buzzer: open fail\n");
+ return ERROR;
+ }
+
+ return OK;
+}
+
+void buzzer_deinit()
+{
+ close(buzzer);
+}
+
+void tune_error()
+{
+ ioctl(buzzer, TONE_SET_ALARM, 2);
+}
+
+void tune_positive()
+{
+ ioctl(buzzer, TONE_SET_ALARM, 3);
+}
+
+void tune_neutral()
+{
+ ioctl(buzzer, TONE_SET_ALARM, 4);
+}
+
+void tune_negative()
+{
+ ioctl(buzzer, TONE_SET_ALARM, 5);
+}
+
+int tune_arm()
+{
+ return ioctl(buzzer, TONE_SET_ALARM, 12);
+}
+
+int tune_critical_bat()
+{
+ return ioctl(buzzer, TONE_SET_ALARM, 14);
+}
+
+int tune_low_bat()
+{
+ return ioctl(buzzer, TONE_SET_ALARM, 13);
+}
+
+void tune_stop()
+{
+ ioctl(buzzer, TONE_SET_ALARM, 0);
+}
+
diff --git a/src/modules/commander/commander_helper.h b/src/modules/commander/commander_helper.h
new file mode 100644
index 000000000..ea96d72a6
--- /dev/null
+++ b/src/modules/commander/commander_helper.h
@@ -0,0 +1,66 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Author: Thomas Gubler <thomasgubler@student.ethz.ch>
+ * Julian Oes <joes@student.ethz.ch>
+ *
+ * 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 commander_helper.h
+ * Commander helper functions definitions
+ */
+
+#ifndef COMMANDER_HELPER_H_
+#define COMMANDER_HELPER_H_
+
+#include <uORB/uORB.h>
+#include <uORB/topics/vehicle_status.h>
+#include <uORB/topics/actuator_safety.h>
+#include <uORB/topics/vehicle_control_mode.h>
+
+
+bool is_multirotor(const struct vehicle_status_s *current_status);
+bool is_rotary_wing(const struct vehicle_status_s *current_status);
+
+int buzzer_init(void);
+void buzzer_deinit(void);
+
+void tune_error(void);
+void tune_positive(void);
+void tune_neutral(void);
+void tune_negative(void);
+int tune_arm(void);
+int tune_critical_bat(void);
+int tune_low_bat(void);
+
+void tune_stop(void);
+
+#endif /* COMMANDER_HELPER_H_ */
diff --git a/src/modules/commander/gyro_calibration.c b/src/modules/commander/gyro_calibration.c
new file mode 100644
index 000000000..f452910c9
--- /dev/null
+++ b/src/modules/commander/gyro_calibration.c
@@ -0,0 +1,151 @@
+/****************************************************************************
+ *
+ * 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 gyro_calibration.c
+ * Gyroscope calibration routine
+ */
+
+#include "gyro_calibration.h"
+#include "commander_helper.h"
+
+#include <stdio.h>
+#include <fcntl.h>
+#include <poll.h>
+#include <math.h>
+#include <drivers/drv_hrt.h>
+#include <uORB/topics/sensor_combined.h>
+#include <drivers/drv_gyro.h>
+#include <mavlink/mavlink_log.h>
+#include <systemlib/param/param.h>
+#include <systemlib/err.h>
+
+
+void do_gyro_calibration(int mavlink_fd)
+{
+ mavlink_log_info(mavlink_fd, "gyro calibration starting, hold still");
+
+ const int calibration_count = 5000;
+
+ int sub_sensor_combined = orb_subscribe(ORB_ID(sensor_combined));
+ struct sensor_combined_s raw;
+
+ int calibration_counter = 0;
+ float gyro_offset[3] = {0.0f, 0.0f, 0.0f};
+
+ /* set offsets to zero */
+ int fd = open(GYRO_DEVICE_PATH, 0);
+ struct gyro_scale gscale_null = {
+ 0.0f,
+ 1.0f,
+ 0.0f,
+ 1.0f,
+ 0.0f,
+ 1.0f,
+ };
+
+ if (OK != ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gscale_null))
+ warn("WARNING: failed to set scale / offsets for gyro");
+
+ close(fd);
+
+ while (calibration_counter < calibration_count) {
+
+ /* wait blocking for new data */
+ struct pollfd fds[1] = { { .fd = sub_sensor_combined, .events = POLLIN } };
+
+ int poll_ret = poll(fds, 1, 1000);
+
+ if (poll_ret) {
+ orb_copy(ORB_ID(sensor_combined), sub_sensor_combined, &raw);
+ gyro_offset[0] += raw.gyro_rad_s[0];
+ gyro_offset[1] += raw.gyro_rad_s[1];
+ gyro_offset[2] += raw.gyro_rad_s[2];
+ calibration_counter++;
+
+ } else if (poll_ret == 0) {
+ /* any poll failure for 1s is a reason to abort */
+ mavlink_log_info(mavlink_fd, "gyro calibration aborted, retry");
+ return;
+ }
+ }
+
+ gyro_offset[0] = gyro_offset[0] / calibration_count;
+ gyro_offset[1] = gyro_offset[1] / calibration_count;
+ gyro_offset[2] = gyro_offset[2] / calibration_count;
+
+ if (isfinite(gyro_offset[0]) && isfinite(gyro_offset[1]) && isfinite(gyro_offset[2])) {
+
+ if (param_set(param_find("SENS_GYRO_XOFF"), &(gyro_offset[0]))
+ || param_set(param_find("SENS_GYRO_YOFF"), &(gyro_offset[1]))
+ || param_set(param_find("SENS_GYRO_ZOFF"), &(gyro_offset[2]))) {
+ mavlink_log_critical(mavlink_fd, "Setting gyro offsets failed!");
+ }
+
+ /* set offsets to actual value */
+ fd = open(GYRO_DEVICE_PATH, 0);
+ struct gyro_scale gscale = {
+ gyro_offset[0],
+ 1.0f,
+ gyro_offset[1],
+ 1.0f,
+ gyro_offset[2],
+ 1.0f,
+ };
+
+ if (OK != ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gscale))
+ warn("WARNING: failed to set scale / offsets for gyro");
+
+ close(fd);
+
+ /* auto-save to EEPROM */
+ int save_ret = param_save_default();
+
+ if (save_ret != 0) {
+ warn("WARNING: auto-save of params to storage failed");
+ }
+
+ // char buf[50];
+ // sprintf(buf, "cal: x:%8.4f y:%8.4f z:%8.4f", (double)gyro_offset[0], (double)gyro_offset[1], (double)gyro_offset[2]);
+ // mavlink_log_info(mavlink_fd, buf);
+ mavlink_log_info(mavlink_fd, "gyro calibration done");
+
+ tune_positive();
+ /* third beep by cal end routine */
+
+ } else {
+ mavlink_log_info(mavlink_fd, "gyro calibration FAILED (NaN)");
+ }
+
+ close(sub_sensor_combined);
+}
diff --git a/src/modules/commander/gyro_calibration.h b/src/modules/commander/gyro_calibration.h
new file mode 100644
index 000000000..cd262507d
--- /dev/null
+++ b/src/modules/commander/gyro_calibration.h
@@ -0,0 +1,46 @@
+/****************************************************************************
+ *
+ * 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 gyro_calibration.h
+ * Gyroscope calibration routine
+ */
+
+#ifndef GYRO_CALIBRATION_H_
+#define GYRO_CALIBRATION_H_
+
+#include <stdint.h>
+
+void do_gyro_calibration(int mavlink_fd);
+
+#endif /* GYRO_CALIBRATION_H_ */ \ No newline at end of file
diff --git a/src/modules/commander/mag_calibration.c b/src/modules/commander/mag_calibration.c
new file mode 100644
index 000000000..dbd31a7e7
--- /dev/null
+++ b/src/modules/commander/mag_calibration.c
@@ -0,0 +1,278 @@
+/****************************************************************************
+ *
+ * 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 mag_calibration.c
+ * Magnetometer calibration routine
+ */
+
+#include "mag_calibration.h"
+#include "commander_helper.h"
+#include "calibration_routines.h"
+
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include <poll.h>
+#include <math.h>
+#include <fcntl.h>
+#include <drivers/drv_hrt.h>
+#include <uORB/topics/sensor_combined.h>
+#include <drivers/drv_mag.h>
+#include <mavlink/mavlink_log.h>
+#include <systemlib/param/param.h>
+#include <systemlib/err.h>
+
+
+void do_mag_calibration(int mavlink_fd)
+{
+ mavlink_log_info(mavlink_fd, "mag calibration starting, hold still");
+
+ int sub_mag = orb_subscribe(ORB_ID(sensor_mag));
+ struct mag_report mag;
+
+ /* 45 seconds */
+ uint64_t calibration_interval = 45 * 1000 * 1000;
+
+ /* maximum 2000 values */
+ const unsigned int calibration_maxcount = 500;
+ unsigned int calibration_counter = 0;
+
+ /* limit update rate to get equally spaced measurements over time (in ms) */
+ orb_set_interval(sub_mag, (calibration_interval / 1000) / calibration_maxcount);
+
+ int fd = open(MAG_DEVICE_PATH, O_RDONLY);
+
+ /* erase old calibration */
+ struct mag_scale mscale_null = {
+ 0.0f,
+ 1.0f,
+ 0.0f,
+ 1.0f,
+ 0.0f,
+ 1.0f,
+ };
+
+ if (OK != ioctl(fd, MAGIOCSSCALE, (long unsigned int)&mscale_null)) {
+ warn("WARNING: failed to set scale / offsets for mag");
+ mavlink_log_info(mavlink_fd, "failed to set scale / offsets for mag");
+ }
+
+ /* calibrate range */
+ if (OK != ioctl(fd, MAGIOCCALIBRATE, fd)) {
+ warnx("failed to calibrate scale");
+ }
+
+ close(fd);
+
+ /* calibrate offsets */
+
+ // uint64_t calibration_start = hrt_absolute_time();
+
+ uint64_t axis_deadline = hrt_absolute_time();
+ uint64_t calibration_deadline = hrt_absolute_time() + calibration_interval;
+
+ const char axislabels[3] = { 'X', 'Y', 'Z'};
+ int axis_index = -1;
+
+ float *x = (float *)malloc(sizeof(float) * calibration_maxcount);
+ float *y = (float *)malloc(sizeof(float) * calibration_maxcount);
+ float *z = (float *)malloc(sizeof(float) * calibration_maxcount);
+
+ if (x == NULL || y == NULL || z == NULL) {
+ warnx("mag cal failed: out of memory");
+ mavlink_log_info(mavlink_fd, "mag cal failed: out of memory");
+ warnx("x:%p y:%p z:%p\n", x, y, z);
+ return;
+ }
+
+ while (hrt_absolute_time() < calibration_deadline &&
+ calibration_counter < calibration_maxcount) {
+
+ /* wait blocking for new data */
+ struct pollfd fds[1] = { { .fd = sub_mag, .events = POLLIN } };
+
+ /* user guidance */
+ if (hrt_absolute_time() >= axis_deadline &&
+ axis_index < 3) {
+
+ axis_index++;
+
+ char buf[50];
+ sprintf(buf, "please rotate around %c", axislabels[axis_index]);
+ mavlink_log_info(mavlink_fd, buf);
+ tune_neutral();
+
+ axis_deadline += calibration_interval / 3;
+ }
+
+ if (!(axis_index < 3)) {
+ break;
+ }
+
+ // int axis_left = (int64_t)axis_deadline - (int64_t)hrt_absolute_time();
+
+ // if ((axis_left / 1000) == 0 && axis_left > 0) {
+ // char buf[50];
+ // sprintf(buf, "[cmd] %d seconds left for axis %c", axis_left, axislabels[axis_index]);
+ // mavlink_log_info(mavlink_fd, buf);
+ // }
+
+ int poll_ret = poll(fds, 1, 1000);
+
+ if (poll_ret) {
+ orb_copy(ORB_ID(sensor_mag), sub_mag, &mag);
+
+ x[calibration_counter] = mag.x;
+ y[calibration_counter] = mag.y;
+ z[calibration_counter] = mag.z;
+
+ /* get min/max values */
+
+ // if (mag.x < mag_min[0]) {
+ // mag_min[0] = mag.x;
+ // }
+ // else if (mag.x > mag_max[0]) {
+ // mag_max[0] = mag.x;
+ // }
+
+ // if (raw.magnetometer_ga[1] < mag_min[1]) {
+ // mag_min[1] = raw.magnetometer_ga[1];
+ // }
+ // else if (raw.magnetometer_ga[1] > mag_max[1]) {
+ // mag_max[1] = raw.magnetometer_ga[1];
+ // }
+
+ // if (raw.magnetometer_ga[2] < mag_min[2]) {
+ // mag_min[2] = raw.magnetometer_ga[2];
+ // }
+ // else if (raw.magnetometer_ga[2] > mag_max[2]) {
+ // mag_max[2] = raw.magnetometer_ga[2];
+ // }
+
+ calibration_counter++;
+
+ } else if (poll_ret == 0) {
+ /* any poll failure for 1s is a reason to abort */
+ mavlink_log_info(mavlink_fd, "mag cal canceled (timed out)");
+ break;
+ }
+ }
+
+ float sphere_x;
+ float sphere_y;
+ float sphere_z;
+ float sphere_radius;
+
+ sphere_fit_least_squares(x, y, z, calibration_counter, 100, 0.0f, &sphere_x, &sphere_y, &sphere_z, &sphere_radius);
+
+ free(x);
+ free(y);
+ free(z);
+
+ if (isfinite(sphere_x) && isfinite(sphere_y) && isfinite(sphere_z)) {
+
+ fd = open(MAG_DEVICE_PATH, 0);
+
+ struct mag_scale mscale;
+
+ if (OK != ioctl(fd, MAGIOCGSCALE, (long unsigned int)&mscale))
+ warn("WARNING: failed to get scale / offsets for mag");
+
+ mscale.x_offset = sphere_x;
+ mscale.y_offset = sphere_y;
+ mscale.z_offset = sphere_z;
+
+ if (OK != ioctl(fd, MAGIOCSSCALE, (long unsigned int)&mscale))
+ warn("WARNING: failed to set scale / offsets for mag");
+
+ close(fd);
+
+ /* announce and set new offset */
+
+ if (param_set(param_find("SENS_MAG_XOFF"), &(mscale.x_offset))) {
+ warnx("Setting X mag offset failed!\n");
+ }
+
+ if (param_set(param_find("SENS_MAG_YOFF"), &(mscale.y_offset))) {
+ warnx("Setting Y mag offset failed!\n");
+ }
+
+ if (param_set(param_find("SENS_MAG_ZOFF"), &(mscale.z_offset))) {
+ warnx("Setting Z mag offset failed!\n");
+ }
+
+ if (param_set(param_find("SENS_MAG_XSCALE"), &(mscale.x_scale))) {
+ warnx("Setting X mag scale failed!\n");
+ }
+
+ if (param_set(param_find("SENS_MAG_YSCALE"), &(mscale.y_scale))) {
+ warnx("Setting Y mag scale failed!\n");
+ }
+
+ if (param_set(param_find("SENS_MAG_ZSCALE"), &(mscale.z_scale))) {
+ warnx("Setting Z mag scale failed!\n");
+ }
+
+ /* auto-save to EEPROM */
+ int save_ret = param_save_default();
+
+ if (save_ret != 0) {
+ warn("WARNING: auto-save of params to storage failed");
+ mavlink_log_info(mavlink_fd, "FAILED storing calibration");
+ }
+
+ warnx("\tscale: %.6f %.6f %.6f\n \toffset: %.6f %.6f %.6f\nradius: %.6f GA\n",
+ (double)mscale.x_scale, (double)mscale.y_scale, (double)mscale.z_scale,
+ (double)mscale.x_offset, (double)mscale.y_offset, (double)mscale.z_offset, (double)sphere_radius);
+
+ char buf[52];
+ sprintf(buf, "mag off: x:%.2f y:%.2f z:%.2f Ga", (double)mscale.x_offset,
+ (double)mscale.y_offset, (double)mscale.z_offset);
+ mavlink_log_info(mavlink_fd, buf);
+
+ sprintf(buf, "mag scale: x:%.2f y:%.2f z:%.2f", (double)mscale.x_scale,
+ (double)mscale.y_scale, (double)mscale.z_scale);
+ mavlink_log_info(mavlink_fd, buf);
+
+ mavlink_log_info(mavlink_fd, "mag calibration done");
+
+ tune_positive();
+ /* third beep by cal end routine */
+
+ } else {
+ mavlink_log_info(mavlink_fd, "mag calibration FAILED (NaN in sphere fit)");
+ }
+
+ close(sub_mag);
+} \ No newline at end of file
diff --git a/src/modules/commander/mag_calibration.h b/src/modules/commander/mag_calibration.h
new file mode 100644
index 000000000..fd2085f14
--- /dev/null
+++ b/src/modules/commander/mag_calibration.h
@@ -0,0 +1,46 @@
+/****************************************************************************
+ *
+ * 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 mag_calibration.h
+ * Magnetometer calibration routine
+ */
+
+#ifndef MAG_CALIBRATION_H_
+#define MAG_CALIBRATION_H_
+
+#include <stdint.h>
+
+void do_mag_calibration(int mavlink_fd);
+
+#endif /* MAG_CALIBRATION_H_ */ \ No newline at end of file
diff --git a/src/modules/commander/module.mk b/src/modules/commander/module.mk
index fe44e955a..fef8e366b 100644
--- a/src/modules/commander/module.mk
+++ b/src/modules/commander/module.mk
@@ -38,6 +38,12 @@
MODULE_COMMAND = commander
SRCS = commander.c \
state_machine_helper.c \
+ commander_helper.c \
calibration_routines.c \
- accelerometer_calibration.c
+ accelerometer_calibration.c \
+ gyro_calibration.c \
+ mag_calibration.c \
+ baro_calibration.c \
+ rc_calibration.c \
+ airspeed_calibration.c
diff --git a/src/modules/commander/rc_calibration.c b/src/modules/commander/rc_calibration.c
new file mode 100644
index 000000000..9aa6b86fe
--- /dev/null
+++ b/src/modules/commander/rc_calibration.c
@@ -0,0 +1,83 @@
+/****************************************************************************
+ *
+ * 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 rc_calibration.c
+ * Remote Control calibration routine
+ */
+
+#include "rc_calibration.h"
+#include "commander_helper.h"
+
+#include <poll.h>
+#include <uORB/topics/sensor_combined.h>
+#include <uORB/topics/manual_control_setpoint.h>
+#include <mavlink/mavlink_log.h>
+#include <systemlib/param/param.h>
+#include <systemlib/err.h>
+
+
+void do_rc_calibration(int mavlink_fd)
+{
+ mavlink_log_info(mavlink_fd, "trim calibration starting");
+
+ /* XXX fix this */
+ // if (current_status.offboard_control_signal_lost) {
+ // mavlink_log_critical(mavlink_fd, "TRIM CAL: ABORT. No RC signal.");
+ // return;
+ // }
+
+ int sub_man = orb_subscribe(ORB_ID(manual_control_setpoint));
+ struct manual_control_setpoint_s sp;
+ orb_copy(ORB_ID(manual_control_setpoint), sub_man, &sp);
+
+ /* set parameters */
+ float p = sp.roll;
+ param_set(param_find("TRIM_ROLL"), &p);
+ p = sp.pitch;
+ param_set(param_find("TRIM_PITCH"), &p);
+ p = sp.yaw;
+ param_set(param_find("TRIM_YAW"), &p);
+
+ /* store to permanent storage */
+ /* auto-save */
+ int save_ret = param_save_default();
+
+ if (save_ret != 0) {
+ mavlink_log_critical(mavlink_fd, "TRIM CAL: WARN: auto-save of params failed");
+ }
+
+ tune_positive();
+
+ mavlink_log_info(mavlink_fd, "trim calibration done");
+} \ No newline at end of file
diff --git a/src/modules/commander/rc_calibration.h b/src/modules/commander/rc_calibration.h
new file mode 100644
index 000000000..6505c7364
--- /dev/null
+++ b/src/modules/commander/rc_calibration.h
@@ -0,0 +1,46 @@
+/****************************************************************************
+ *
+ * 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 rc_calibration.h
+ * Remote Control calibration routine
+ */
+
+#ifndef RC_CALIBRATION_H_
+#define RC_CALIBRATION_H_
+
+#include <stdint.h>
+
+void do_rc_calibration(int mavlink_fd);
+
+#endif /* RC_CALIBRATION_H_ */ \ No newline at end of file
diff --git a/src/modules/commander/state_machine_helper.c b/src/modules/commander/state_machine_helper.c
index ab728c7bb..c15fc91a0 100644
--- a/src/modules/commander/state_machine_helper.c
+++ b/src/modules/commander/state_machine_helper.c
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
* Author: Thomas Gubler <thomasgubler@student.ethz.ch>
* Julian Oes <joes@student.ethz.ch>
*
@@ -40,257 +40,532 @@
#include <stdio.h>
#include <unistd.h>
+#include <stdint.h>
+#include <stdbool.h>
#include <uORB/uORB.h>
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/actuator_controls.h>
+#include <uORB/topics/vehicle_control_mode.h>
#include <systemlib/systemlib.h>
+#include <systemlib/param/param.h>
+#include <systemlib/err.h>
#include <drivers/drv_hrt.h>
#include <mavlink/mavlink_log.h>
#include "state_machine_helper.h"
+#include "commander_helper.h"
-static const char *system_state_txt[] = {
- "SYSTEM_STATE_PREFLIGHT",
- "SYSTEM_STATE_STANDBY",
- "SYSTEM_STATE_GROUND_READY",
- "SYSTEM_STATE_MANUAL",
- "SYSTEM_STATE_STABILIZED",
- "SYSTEM_STATE_AUTO",
- "SYSTEM_STATE_MISSION_ABORT",
- "SYSTEM_STATE_EMCY_LANDING",
- "SYSTEM_STATE_EMCY_CUTOFF",
- "SYSTEM_STATE_GROUND_ERROR",
- "SYSTEM_STATE_REBOOT",
-
-};
-/**
- * Transition from one state to another
- */
-int do_state_update(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd, commander_state_machine_t new_state)
-{
- int invalid_state = false;
- int ret = ERROR;
-
- commander_state_machine_t old_state = current_status->state_machine;
-
- switch (new_state) {
- case SYSTEM_STATE_MISSION_ABORT: {
- /* Indoor or outdoor */
- // if (flight_environment_parameter == PX4_FLIGHT_ENVIRONMENT_OUTDOOR) {
- ret = do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_EMCY_LANDING);
-
- // } else {
- // ret = do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_EMCY_CUTOFF);
- // }
- }
- break;
-
- case SYSTEM_STATE_EMCY_LANDING:
- /* Tell the controller to land */
-
- /* set system flags according to state */
- current_status->flag_system_armed = true;
-
- warnx("EMERGENCY LANDING!\n");
- mavlink_log_critical(mavlink_fd, "EMERGENCY LANDING!");
- break;
-
- case SYSTEM_STATE_EMCY_CUTOFF:
- /* Tell the controller to cutoff the motors (thrust = 0) */
-
- /* set system flags according to state */
- current_status->flag_system_armed = false;
-
- warnx("EMERGENCY MOTOR CUTOFF!\n");
- mavlink_log_critical(mavlink_fd, "EMERGENCY MOTOR CUTOFF!");
- break;
-
- case SYSTEM_STATE_GROUND_ERROR:
+int arming_state_transition(int status_pub, struct vehicle_status_s *current_state, arming_state_t new_arming_state, int safety_pub, struct actuator_safety_s *safety, const int mavlink_fd) {
- /* set system flags according to state */
- /* prevent actuators from arming */
- current_status->flag_system_armed = false;
-
- warnx("GROUND ERROR, locking down propulsion system\n");
- mavlink_log_critical(mavlink_fd, "GROUND ERROR, locking down system");
- break;
-
- case SYSTEM_STATE_PREFLIGHT:
- if (current_status->state_machine == SYSTEM_STATE_STANDBY
- || current_status->state_machine == SYSTEM_STATE_PREFLIGHT) {
- /* set system flags according to state */
- current_status->flag_system_armed = false;
- mavlink_log_critical(mavlink_fd, "Switched to PREFLIGHT state");
+ int ret = ERROR;
- } else {
- invalid_state = true;
- mavlink_log_critical(mavlink_fd, "REFUSED to switch to PREFLIGHT state");
- }
+ /* only check transition if the new state is actually different from the current one */
+ if (new_arming_state == current_state->arming_state) {
+ ret = OK;
+ } else {
- break;
-
- case SYSTEM_STATE_REBOOT:
- if (current_status->state_machine == SYSTEM_STATE_STANDBY
- || current_status->state_machine == SYSTEM_STATE_PREFLIGHT
- || current_status->flag_hil_enabled) {
- invalid_state = false;
- /* set system flags according to state */
- current_status->flag_system_armed = false;
- mavlink_log_critical(mavlink_fd, "REBOOTING SYSTEM");
- usleep(500000);
- up_systemreset();
- /* SPECIAL CASE: NEVER RETURNS FROM THIS FUNCTION CALL */
-
- } else {
- invalid_state = true;
- mavlink_log_critical(mavlink_fd, "REFUSED to REBOOT");
+ switch (new_arming_state) {
+ case ARMING_STATE_INIT:
+
+ /* allow going back from INIT for calibration */
+ if (current_state->arming_state == ARMING_STATE_STANDBY) {
+ ret = OK;
+ safety->armed = false;
+ safety->ready_to_arm = false;
+ }
+ break;
+ case ARMING_STATE_STANDBY:
+
+ /* allow coming from INIT and disarming from ARMED */
+ if (current_state->arming_state == ARMING_STATE_INIT
+ || current_state->arming_state == ARMING_STATE_ARMED) {
+
+ /* sensors need to be initialized for STANDBY state */
+ if (current_state->condition_system_sensors_initialized) {
+ ret = OK;
+ safety->armed = false;
+ safety->ready_to_arm = true;
+ } else {
+ mavlink_log_critical(mavlink_fd, "Rej. STANDBY state, sensors not initialized");
+ }
+ }
+ break;
+ case ARMING_STATE_ARMED:
+
+ /* allow arming from STANDBY and IN-AIR-RESTORE */
+ if (current_state->arming_state == ARMING_STATE_STANDBY
+ || current_state->arming_state == ARMING_STATE_IN_AIR_RESTORE) {
+
+ /* XXX conditions for arming? */
+ ret = OK;
+ safety->armed = true;
+ }
+ break;
+ case ARMING_STATE_ARMED_ERROR:
+
+ /* an armed error happens when ARMED obviously */
+ if (current_state->arming_state == ARMING_STATE_ARMED) {
+
+ /* XXX conditions for an error state? */
+ ret = OK;
+ safety->armed = true;
+ }
+ break;
+ case ARMING_STATE_STANDBY_ERROR:
+ /* a disarmed error happens when in STANDBY or in INIT or after ARMED_ERROR */
+ if (current_state->arming_state == ARMING_STATE_STANDBY
+ || current_state->arming_state == ARMING_STATE_INIT
+ || current_state->arming_state == ARMING_STATE_ARMED_ERROR) {
+ ret = OK;
+ safety->armed = false;
+ safety->ready_to_arm = false;
+ }
+ break;
+ case ARMING_STATE_REBOOT:
+
+ /* an armed error happens when ARMED obviously */
+ if (current_state->arming_state == ARMING_STATE_INIT
+ || current_state->arming_state == ARMING_STATE_STANDBY
+ || current_state->arming_state == ARMING_STATE_STANDBY_ERROR) {
+
+ ret = OK;
+ safety->armed = false;
+ safety->ready_to_arm = false;
+
+ }
+ break;
+ case ARMING_STATE_IN_AIR_RESTORE:
+
+ /* XXX implement */
+ break;
+ default:
+ break;
}
- break;
-
- case SYSTEM_STATE_STANDBY:
- /* set system flags according to state */
-
- /* standby enforces disarmed */
- current_status->flag_system_armed = false;
-
- mavlink_log_critical(mavlink_fd, "Switched to STANDBY state");
- break;
-
- case SYSTEM_STATE_GROUND_READY:
-
- /* set system flags according to state */
-
- /* ground ready has motors / actuators armed */
- current_status->flag_system_armed = true;
-
- mavlink_log_critical(mavlink_fd, "Switched to GROUND READY state");
- break;
-
- case SYSTEM_STATE_AUTO:
+ if (ret == OK) {
+ current_state->arming_state = new_arming_state;
+ current_state->counter++;
+ current_state->timestamp = hrt_absolute_time();
+ orb_publish(ORB_ID(vehicle_status), status_pub, current_state);
- /* set system flags according to state */
-
- /* auto is airborne and in auto mode, motors armed */
- current_status->flag_system_armed = true;
+ safety->timestamp = hrt_absolute_time();
+ orb_publish(ORB_ID(actuator_safety), safety_pub, safety);
+ }
+ }
- mavlink_log_critical(mavlink_fd, "Switched to FLYING / AUTO mode");
- break;
+ return ret;
+}
- case SYSTEM_STATE_STABILIZED:
- /* set system flags according to state */
- current_status->flag_system_armed = true;
- mavlink_log_critical(mavlink_fd, "Switched to FLYING / STABILIZED mode");
- break;
+/*
+ * This functions does not evaluate any input flags but only checks if the transitions
+ * are valid.
+ */
+int navigation_state_transition(int status_pub, struct vehicle_status_s *current_state, navigation_state_t new_navigation_state, int control_mode_pub, struct vehicle_control_mode_s *control_mode, const int mavlink_fd) {
- case SYSTEM_STATE_MANUAL:
+ int ret = ERROR;
- /* set system flags according to state */
- current_status->flag_system_armed = true;
+ /* only check transition if the new state is actually different from the current one */
+ if (new_navigation_state == current_state->navigation_state) {
+ ret = OK;
+ } else {
- mavlink_log_critical(mavlink_fd, "Switched to FLYING / MANUAL mode");
- break;
+ switch (new_navigation_state) {
+ case NAVIGATION_STATE_INIT:
+
+ /* transitions back to INIT are possible for calibration */
+ if (current_state->navigation_state == NAVIGATION_STATE_MANUAL_STANDBY
+ || current_state->navigation_state == NAVIGATION_STATE_SEATBELT_STANDBY
+ || current_state->navigation_state == NAVIGATION_STATE_AUTO_STANDBY) {
+
+ ret = OK;
+ control_mode->flag_control_rates_enabled = false;
+ control_mode->flag_control_attitude_enabled = false;
+ control_mode->flag_control_velocity_enabled = false;
+ control_mode->flag_control_position_enabled = false;
+ control_mode->flag_control_manual_enabled = false;
+ }
+ break;
+
+ case NAVIGATION_STATE_MANUAL_STANDBY:
+
+ /* transitions from INIT and other STANDBY states as well as MANUAL are possible */
+ if (current_state->navigation_state == NAVIGATION_STATE_INIT
+ || current_state->navigation_state == NAVIGATION_STATE_SEATBELT_STANDBY
+ || current_state->navigation_state == NAVIGATION_STATE_AUTO_STANDBY
+ || current_state->navigation_state == NAVIGATION_STATE_MANUAL) {
+
+ /* need to be disarmed first */
+ if (current_state->arming_state != ARMING_STATE_STANDBY) {
+ mavlink_log_critical(mavlink_fd, "Rej. MANUAL_STANDBY: not disarmed");
+ tune_negative();
+ } else {
+ ret = OK;
+ control_mode->flag_control_rates_enabled = true;
+ control_mode->flag_control_attitude_enabled = true;
+ control_mode->flag_control_velocity_enabled = false;
+ control_mode->flag_control_position_enabled = false;
+ control_mode->flag_control_manual_enabled = true;
+ }
+ }
+ break;
+
+ case NAVIGATION_STATE_MANUAL:
+
+ /* need to be armed first */
+ if (current_state->arming_state != ARMING_STATE_ARMED) {
+ mavlink_log_critical(mavlink_fd, "Rej. MANUAL: not armed");
+ tune_negative();
+ } else {
+ ret = OK;
+ control_mode->flag_control_rates_enabled = true;
+ control_mode->flag_control_attitude_enabled = true;
+ control_mode->flag_control_velocity_enabled = false;
+ control_mode->flag_control_position_enabled = false;
+ control_mode->flag_control_manual_enabled = true;
+ }
+ break;
+
+ case NAVIGATION_STATE_SEATBELT_STANDBY:
+
+ /* transitions from INIT and other STANDBY states as well as SEATBELT and SEATBELT_DESCENT are possible */
+ if (current_state->navigation_state == NAVIGATION_STATE_INIT
+ || current_state->navigation_state == NAVIGATION_STATE_MANUAL_STANDBY
+ || current_state->navigation_state == NAVIGATION_STATE_AUTO_STANDBY
+ || current_state->navigation_state == NAVIGATION_STATE_SEATBELT
+ || current_state->navigation_state == NAVIGATION_STATE_SEATBELT_DESCENT) {
+
+ /* need to be disarmed and have a position estimate */
+ if (current_state->arming_state != ARMING_STATE_STANDBY) {
+ mavlink_log_critical(mavlink_fd, "Rej. SEATBELT_STANDBY: not disarmed");
+ tune_negative();
+ } else if (!current_state->condition_local_position_valid) {
+ mavlink_log_critical(mavlink_fd, "Rej. SEATBELT_STANDBY: no position estimate");
+ tune_negative();
+ } else {
+ ret = OK;
+ control_mode->flag_control_rates_enabled = true;
+ control_mode->flag_control_attitude_enabled = true;
+ control_mode->flag_control_velocity_enabled = true;
+ control_mode->flag_control_position_enabled = false;
+ control_mode->flag_control_manual_enabled = false;
+ }
+ }
+ break;
+
+ case NAVIGATION_STATE_SEATBELT:
+
+ /* transitions from all AUTO modes except AUTO_STANDBY and except MANUAL_STANDBY and INIT*/
+ if (current_state->navigation_state == NAVIGATION_STATE_SEATBELT_STANDBY
+ || current_state->navigation_state == NAVIGATION_STATE_SEATBELT_DESCENT
+ || current_state->navigation_state == NAVIGATION_STATE_MANUAL
+ || current_state->navigation_state == NAVIGATION_STATE_AUTO_LAND
+ || current_state->navigation_state == NAVIGATION_STATE_AUTO_LOITER
+ || current_state->navigation_state == NAVIGATION_STATE_AUTO_MISSION
+ || current_state->navigation_state == NAVIGATION_STATE_AUTO_READY
+ || current_state->navigation_state == NAVIGATION_STATE_AUTO_RTL
+ || current_state->navigation_state == NAVIGATION_STATE_AUTO_TAKEOFF) {
+
+ /* need to be armed and have a position estimate */
+ if (current_state->arming_state != ARMING_STATE_ARMED) {
+ mavlink_log_critical(mavlink_fd, "Rej. SEATBELT: not armed");
+ tune_negative();
+ } else if (!current_state->condition_local_position_valid) {
+ mavlink_log_critical(mavlink_fd, "Rej. SEATBELT: no pos estimate");
+ tune_negative();
+ } else {
+ ret = OK;
+ control_mode->flag_control_rates_enabled = true;
+ control_mode->flag_control_attitude_enabled = true;
+ control_mode->flag_control_velocity_enabled = true;
+ control_mode->flag_control_position_enabled = false;
+ control_mode->flag_control_manual_enabled = false;
+ }
+ }
+ break;
+
+ case NAVIGATION_STATE_SEATBELT_DESCENT:
+
+ /* transitions from all AUTO modes except AUTO_STANDBY and except MANUAL_STANDBY and INIT and SEATBELT_STANDBY */
+ if (current_state->navigation_state == NAVIGATION_STATE_SEATBELT
+ || current_state->navigation_state == NAVIGATION_STATE_MANUAL
+ || current_state->navigation_state == NAVIGATION_STATE_AUTO_LAND
+ || current_state->navigation_state == NAVIGATION_STATE_AUTO_LOITER
+ || current_state->navigation_state == NAVIGATION_STATE_AUTO_MISSION
+ || current_state->navigation_state == NAVIGATION_STATE_AUTO_READY
+ || current_state->navigation_state == NAVIGATION_STATE_AUTO_RTL
+ || current_state->navigation_state == NAVIGATION_STATE_AUTO_TAKEOFF) {
+
+ /* need to be armed and have a position estimate */
+ if (current_state->arming_state != ARMING_STATE_ARMED) {
+ mavlink_log_critical(mavlink_fd, "Rej. SEATBELT_DESCENT: not armed");
+ tune_negative();
+ } else if (!current_state->condition_local_position_valid) {
+ mavlink_log_critical(mavlink_fd, "Rej. SEATBELT_DESCENT: no pos estimate");
+ tune_negative();
+ } else {
+ ret = OK;
+ control_mode->flag_control_rates_enabled = true;
+ control_mode->flag_control_attitude_enabled = true;
+ control_mode->flag_control_velocity_enabled = true;
+ control_mode->flag_control_position_enabled = false;
+ control_mode->flag_control_manual_enabled = false;
+ }
+ }
+ break;
+
+ case NAVIGATION_STATE_AUTO_STANDBY:
+
+ /* transitions from INIT or from other STANDBY modes or from AUTO READY */
+ if (current_state->navigation_state == NAVIGATION_STATE_INIT
+ || current_state->navigation_state == NAVIGATION_STATE_MANUAL_STANDBY
+ || current_state->navigation_state == NAVIGATION_STATE_SEATBELT_STANDBY
+ || current_state->navigation_state == NAVIGATION_STATE_AUTO_READY) {
+
+ /* need to be disarmed and have a position and home lock */
+ if (current_state->arming_state != ARMING_STATE_STANDBY) {
+ mavlink_log_critical(mavlink_fd, "Rej. AUTO_STANDBY: not disarmed");
+ tune_negative();
+ } else if (!current_state->condition_global_position_valid) {
+ mavlink_log_critical(mavlink_fd, "Rej. AUTO_STANDBY: no pos lock");
+ tune_negative();
+ } else if (!current_state->condition_home_position_valid) {
+ mavlink_log_critical(mavlink_fd, "Rej. AUTO_STANDBY: no home pos");
+ tune_negative();
+ } else {
+ ret = OK;
+ control_mode->flag_control_rates_enabled = true;
+ control_mode->flag_control_attitude_enabled = true;
+ control_mode->flag_control_velocity_enabled = true;
+ control_mode->flag_control_position_enabled = true;
+ control_mode->flag_control_manual_enabled = false;
+ }
+ }
+ break;
+
+ case NAVIGATION_STATE_AUTO_READY:
+
+ /* transitions from AUTO_STANDBY or AUTO_LAND */
+ if (current_state->navigation_state == NAVIGATION_STATE_AUTO_STANDBY
+ || current_state->navigation_state == NAVIGATION_STATE_AUTO_LAND) {
+
+ // XXX flag test needed?
+
+ /* need to be armed and have a position and home lock */
+ if (current_state->arming_state != ARMING_STATE_ARMED) {
+ mavlink_log_critical(mavlink_fd, "Rej. AUTO_READY: not armed");
+ tune_negative();
+ } else {
+ ret = OK;
+ control_mode->flag_control_rates_enabled = true;
+ control_mode->flag_control_attitude_enabled = true;
+ control_mode->flag_control_velocity_enabled = true;
+ control_mode->flag_control_position_enabled = true;
+ control_mode->flag_control_manual_enabled = false;
+ }
+ }
+ break;
+
+ case NAVIGATION_STATE_AUTO_TAKEOFF:
+
+ /* only transitions from AUTO_READY */
+ if (current_state->navigation_state == NAVIGATION_STATE_AUTO_READY) {
+
+ ret = OK;
+ control_mode->flag_control_rates_enabled = true;
+ control_mode->flag_control_attitude_enabled = true;
+ control_mode->flag_control_velocity_enabled = true;
+ control_mode->flag_control_position_enabled = true;
+ control_mode->flag_control_manual_enabled = false;
+ }
+ break;
+
+ case NAVIGATION_STATE_AUTO_LOITER:
+
+ /* from everywhere flying except AUTO_LAND and SEATBELT_DESCENT */
+ if (current_state->navigation_state == NAVIGATION_STATE_AUTO_TAKEOFF
+ || current_state->navigation_state == NAVIGATION_STATE_AUTO_MISSION
+ || current_state->navigation_state == NAVIGATION_STATE_AUTO_RTL
+ || current_state->navigation_state == NAVIGATION_STATE_SEATBELT
+ || current_state->navigation_state == NAVIGATION_STATE_MANUAL) {
+
+ /* need to have a position and home lock */
+ if (!current_state->condition_global_position_valid) {
+ mavlink_log_critical(mavlink_fd, "Rej. AUTO_LOITER: no pos lock");
+ tune_negative();
+ } else if (!current_state->condition_home_position_valid) {
+ mavlink_log_critical(mavlink_fd, "Rej. AUTO_LOITER: no home pos");
+ tune_negative();
+ } else {
+ ret = OK;
+ control_mode->flag_control_rates_enabled = true;
+ control_mode->flag_control_attitude_enabled = true;
+ control_mode->flag_control_velocity_enabled = true;
+ control_mode->flag_control_position_enabled = true;
+ control_mode->flag_control_manual_enabled = false;
+ }
+ }
+ break;
+
+ case NAVIGATION_STATE_AUTO_MISSION:
+
+ /* from everywhere flying except AUTO_LAND and SEATBELT_DESCENT */
+ if (current_state->navigation_state == NAVIGATION_STATE_AUTO_TAKEOFF
+ || current_state->navigation_state == NAVIGATION_STATE_AUTO_LOITER
+ || current_state->navigation_state == NAVIGATION_STATE_AUTO_RTL
+ || current_state->navigation_state == NAVIGATION_STATE_SEATBELT
+ || current_state->navigation_state == NAVIGATION_STATE_MANUAL) {
+
+ /* need to have a mission ready */
+ if (!current_state-> condition_auto_mission_available) {
+ mavlink_log_critical(mavlink_fd, "Rej. AUTO_MISSION: no mission available");
+ tune_negative();
+ } else {
+ ret = OK;
+ control_mode->flag_control_rates_enabled = true;
+ control_mode->flag_control_attitude_enabled = true;
+ control_mode->flag_control_velocity_enabled = true;
+ control_mode->flag_control_position_enabled = true;
+ control_mode->flag_control_manual_enabled = false;
+ }
+ }
+ break;
+
+ case NAVIGATION_STATE_AUTO_RTL:
+
+ /* from everywhere flying except AUTO_LAND and SEATBELT_DESCENT */
+ if (current_state->navigation_state == NAVIGATION_STATE_AUTO_TAKEOFF
+ || current_state->navigation_state == NAVIGATION_STATE_AUTO_MISSION
+ || current_state->navigation_state == NAVIGATION_STATE_AUTO_LOITER
+ || current_state->navigation_state == NAVIGATION_STATE_SEATBELT
+ || current_state->navigation_state == NAVIGATION_STATE_MANUAL) {
+
+ /* need to have a position and home lock */
+ if (!current_state->condition_global_position_valid) {
+ mavlink_log_critical(mavlink_fd, "Rej. AUTO_RTL: no pos lock");
+ tune_negative();
+ } else if (!current_state->condition_home_position_valid) {
+ mavlink_log_critical(mavlink_fd, "Rej. AUTO_RTL: no home pos");
+ tune_negative();
+ } else {
+ ret = OK;
+ control_mode->flag_control_rates_enabled = true;
+ control_mode->flag_control_attitude_enabled = true;
+ control_mode->flag_control_velocity_enabled = true;
+ control_mode->flag_control_position_enabled = true;
+ control_mode->flag_control_manual_enabled = false;
+ }
+ }
+ break;
+
+ case NAVIGATION_STATE_AUTO_LAND:
+ /* after AUTO_RTL or when in AUTO_LOITER or AUTO_MISSION */
+ if (current_state->navigation_state == NAVIGATION_STATE_AUTO_RTL
+ || current_state->navigation_state == NAVIGATION_STATE_AUTO_MISSION
+ || current_state->navigation_state == NAVIGATION_STATE_AUTO_LOITER) {
+
+ /* need to have a position and home lock */
+ if (!current_state->condition_global_position_valid) {
+ mavlink_log_critical(mavlink_fd, "Rej. AUTO_LAND: no pos lock");
+ tune_negative();
+ } else if (!current_state->condition_home_position_valid) {
+ mavlink_log_critical(mavlink_fd, "Rej. AUTO_LAND: no home pos");
+ tune_negative();
+ } else {
+ ret = OK;
+ control_mode->flag_control_rates_enabled = true;
+ control_mode->flag_control_attitude_enabled = true;
+ control_mode->flag_control_velocity_enabled = true;
+ control_mode->flag_control_position_enabled = true;
+ control_mode->flag_control_manual_enabled = false;
+ }
+ }
+ break;
+
+ default:
+ break;
+ }
- default:
- invalid_state = true;
- break;
- }
+ if (ret == OK) {
+ current_state->navigation_state = new_navigation_state;
+ current_state->counter++;
+ current_state->timestamp = hrt_absolute_time();
+ orb_publish(ORB_ID(vehicle_status), status_pub, current_state);
- if (invalid_state == false || old_state != new_state) {
- current_status->state_machine = new_state;
- state_machine_publish(status_pub, current_status, mavlink_fd);
- publish_armed_status(current_status);
- ret = OK;
+ control_mode->timestamp = hrt_absolute_time();
+ orb_publish(ORB_ID(vehicle_control_mode), control_mode_pub, control_mode);
+ }
}
- if (invalid_state) {
- mavlink_log_critical(mavlink_fd, "REJECTING invalid state transition");
- ret = ERROR;
- }
+
return ret;
}
-void state_machine_publish(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd)
-{
- /* publish the new state */
- current_status->counter++;
- current_status->timestamp = hrt_absolute_time();
- /* assemble state vector based on flag values */
- if (current_status->flag_control_rates_enabled) {
- current_status->onboard_control_sensors_present |= 0x400;
+/**
+* Transition from one hil state to another
+*/
+int hil_state_transition(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd, hil_state_t new_state)
+{
+ bool valid_transition = false;
+ int ret = ERROR;
- } else {
- current_status->onboard_control_sensors_present &= ~0x400;
- }
+ warnx("Current state: %d, requested state: %d", current_status->hil_state, new_state);
- current_status->onboard_control_sensors_present |= (current_status->flag_control_attitude_enabled) ? 0x800 : 0;
- current_status->onboard_control_sensors_present |= (current_status->flag_control_attitude_enabled) ? 0x1000 : 0;
- current_status->onboard_control_sensors_present |= (current_status->flag_control_velocity_enabled || current_status->flag_control_position_enabled) ? 0x2000 : 0;
- current_status->onboard_control_sensors_present |= (current_status->flag_control_velocity_enabled || current_status->flag_control_position_enabled) ? 0x4000 : 0;
+ if (current_status->hil_state == new_state) {
+ warnx("Hil state not changed");
+ valid_transition = true;
- current_status->onboard_control_sensors_enabled |= (current_status->flag_control_rates_enabled) ? 0x400 : 0;
- current_status->onboard_control_sensors_enabled |= (current_status->flag_control_attitude_enabled) ? 0x800 : 0;
- current_status->onboard_control_sensors_enabled |= (current_status->flag_control_attitude_enabled) ? 0x1000 : 0;
- current_status->onboard_control_sensors_enabled |= (current_status->flag_control_velocity_enabled || current_status->flag_control_position_enabled) ? 0x2000 : 0;
- current_status->onboard_control_sensors_enabled |= (current_status->flag_control_velocity_enabled || current_status->flag_control_position_enabled) ? 0x4000 : 0;
+ } else {
- orb_publish(ORB_ID(vehicle_status), status_pub, current_status);
- printf("[cmd] new state: %s\n", system_state_txt[current_status->state_machine]);
-}
+ switch (new_state) {
-void publish_armed_status(const struct vehicle_status_s *current_status)
-{
- struct actuator_armed_s armed;
- armed.armed = current_status->flag_system_armed;
+ case HIL_STATE_OFF:
- /* XXX allow arming by external components on multicopters only if not yet armed by RC */
- /* XXX allow arming only if core sensors are ok */
- armed.ready_to_arm = true;
+ if (current_status->arming_state == ARMING_STATE_INIT
+ || current_status->arming_state == ARMING_STATE_STANDBY) {
- /* lock down actuators if required, only in HIL */
- armed.lockdown = (current_status->flag_hil_enabled) ? true : false;
- orb_advert_t armed_pub = orb_advertise(ORB_ID(actuator_armed), &armed);
- orb_publish(ORB_ID(actuator_armed), armed_pub, &armed);
-}
+ current_status->flag_hil_enabled = false;
+ mavlink_log_critical(mavlink_fd, "Switched to OFF hil state");
+ valid_transition = true;
+ }
+ break;
+ case HIL_STATE_ON:
-/*
- * Private functions, update the state machine
- */
-void state_machine_emergency_always_critical(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd)
-{
- warnx("EMERGENCY HANDLER\n");
- /* Depending on the current state go to one of the error states */
+ if (current_status->arming_state == ARMING_STATE_INIT
+ || current_status->arming_state == ARMING_STATE_STANDBY) {
- if (current_status->state_machine == SYSTEM_STATE_PREFLIGHT || current_status->state_machine == SYSTEM_STATE_STANDBY || current_status->state_machine == SYSTEM_STATE_GROUND_READY) {
- do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_GROUND_ERROR);
+ current_status->flag_hil_enabled = true;
+ mavlink_log_critical(mavlink_fd, "Switched to ON hil state");
+ valid_transition = true;
+ }
+ break;
- } else if (current_status->state_machine == SYSTEM_STATE_AUTO || current_status->state_machine == SYSTEM_STATE_MANUAL) {
-
- // DO NOT abort mission
- //do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_MISSION_ABORT);
-
- } else {
- warnx("Unknown system state: #%d\n", current_status->state_machine);
+ default:
+ warnx("Unknown hil state");
+ break;
+ }
}
-}
-void state_machine_emergency(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd) //do not call state_machine_emergency_always_critical if we are in manual mode for these errors
-{
- if (current_status->state_machine != SYSTEM_STATE_MANUAL) { //if we are in manual: user can react to errors themself
- state_machine_emergency_always_critical(status_pub, current_status, mavlink_fd);
+ if (valid_transition) {
+ current_status->hil_state = new_state;
+
+ current_status->counter++;
+ current_status->timestamp = hrt_absolute_time();
+ orb_publish(ORB_ID(vehicle_status), status_pub, current_status);
+ ret = OK;
} else {
- //global_data_send_mavlink_statustext_message_out("[cmd] ERROR: take action immediately! (did not switch to error state because the system is in manual mode)", MAV_SEVERITY_CRITICAL);
+ mavlink_log_critical(mavlink_fd, "REJECTING invalid hil state transition");
}
+ return ret;
}
@@ -405,353 +680,76 @@ void state_machine_emergency(int status_pub, struct vehicle_status_s *current_st
// }
-// void update_state_machine_subsystem_healthy(int status_pub, struct vehicle_status_s *current_status, subsystem_type_t *subsystem_type)
-// {
-// current_status->onboard_control_sensors_health |= 1 << *subsystem_type;
-// current_status->counter++;
-// current_status->timestamp = hrt_absolute_time();
-// orb_publish(ORB_ID(vehicle_status), status_pub, current_status);
-
-// switch (*subsystem_type) {
-// case SUBSYSTEM_TYPE_GYRO:
-// //TODO state machine change (recovering)
-// break;
-
-// case SUBSYSTEM_TYPE_ACC:
-// //TODO state machine change
-// break;
-
-// case SUBSYSTEM_TYPE_MAG:
-// //TODO state machine change
-// break;
-
-// case SUBSYSTEM_TYPE_GPS:
-// //TODO state machine change
-// break;
-
-// default:
-// break;
-// }
-
-
-// }
-
-
-// void update_state_machine_subsystem_unhealthy(int status_pub, struct vehicle_status_s *current_status, subsystem_type_t *subsystem_type)
-// {
-// bool previosly_healthy = (bool)(current_status->onboard_control_sensors_health & 1 << *subsystem_type);
-// current_status->onboard_control_sensors_health &= ~(1 << *subsystem_type);
-// current_status->counter++;
-// current_status->timestamp = hrt_absolute_time();
-// orb_publish(ORB_ID(vehicle_status), status_pub, current_status);
-
-// /* if we received unhealthy message more than *_HEALTH_COUNTER_LIMIT, switch to error state */
-
-// switch (*subsystem_type) {
-// case SUBSYSTEM_TYPE_GYRO:
-// //global_data_send_mavlink_statustext_message_out("Commander: gyro unhealthy", MAV_SEVERITY_CRITICAL);
-
-// if (previosly_healthy) //only throw emergency if previously healthy
-// state_machine_emergency_always_critical(status_pub, current_status);
-
-// break;
-
-// case SUBSYSTEM_TYPE_ACC:
-// //global_data_send_mavlink_statustext_message_out("Commander: accelerometer unhealthy", MAV_SEVERITY_CRITICAL);
-
-// if (previosly_healthy) //only throw emergency if previously healthy
-// state_machine_emergency_always_critical(status_pub, current_status);
-
-// break;
-
-// case SUBSYSTEM_TYPE_MAG:
-// //global_data_send_mavlink_statustext_message_out("Commander: magnetometer unhealthy", MAV_SEVERITY_CRITICAL);
-
-// if (previosly_healthy) //only throw emergency if previously healthy
-// state_machine_emergency_always_critical(status_pub, current_status);
-
-// break;
-
-// case SUBSYSTEM_TYPE_GPS:
-// // //TODO: remove this block
-// // break;
-// // ///////////////////
-// //global_data_send_mavlink_statustext_message_out("Commander: GPS unhealthy", MAV_SEVERITY_CRITICAL);
-
-// // printf("previosly_healthy = %u\n", previosly_healthy);
-// if (previosly_healthy) //only throw emergency if previously healthy
-// state_machine_emergency(status_pub, current_status);
-
-// break;
-
-// default:
-// break;
-// }
-
-// }
-
-
-/* END SUBSYSTEM/EMERGENCY FUNCTIONS*/
-
-
-void update_state_machine_got_position_fix(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd)
-{
- /* Depending on the current state switch state */
- if (current_status->state_machine == SYSTEM_STATE_PREFLIGHT) {
- do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_STANDBY);
- }
-}
-
-void update_state_machine_no_position_fix(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd)
-{
- /* Depending on the current state switch state */
- if (current_status->state_machine == SYSTEM_STATE_STANDBY || current_status->state_machine == SYSTEM_STATE_GROUND_READY || current_status->state_machine == SYSTEM_STATE_AUTO) {
- state_machine_emergency(status_pub, current_status, mavlink_fd);
- }
-}
-
-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) {
- printf("[cmd] arming\n");
- do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_GROUND_READY);
- }
-}
-
-void update_state_machine_disarm(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd)
-{
- if (current_status->state_machine == SYSTEM_STATE_GROUND_READY || current_status->state_machine == SYSTEM_STATE_MANUAL || current_status->state_machine == SYSTEM_STATE_PREFLIGHT) {
- printf("[cmd] going standby\n");
- do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_STANDBY);
-
- } else if (current_status->state_machine == SYSTEM_STATE_STABILIZED || current_status->state_machine == SYSTEM_STATE_AUTO) {
- printf("[cmd] MISSION ABORT!\n");
- do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_STANDBY);
- }
-}
-
-void update_state_machine_mode_manual(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd)
-{
- int old_mode = current_status->flight_mode;
- current_status->flight_mode = VEHICLE_FLIGHT_MODE_MANUAL;
-
- 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)) {
-
- /* assuming a rotary wing, set to SAS */
- current_status->manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_SAS;
- current_status->flag_control_attitude_enabled = true;
- current_status->flag_control_rates_enabled = true;
-
- } else {
-
- /* assuming a fixed wing, set to direct pass-through */
- current_status->manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_DIRECT;
- current_status->flag_control_attitude_enabled = false;
- current_status->flag_control_rates_enabled = false;
- }
-
- if (old_mode != current_status->flight_mode) state_machine_publish(status_pub, current_status, mavlink_fd);
-
- if (current_status->state_machine == SYSTEM_STATE_GROUND_READY || current_status->state_machine == SYSTEM_STATE_STABILIZED || current_status->state_machine == SYSTEM_STATE_AUTO) {
- printf("[cmd] manual mode\n");
- do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_MANUAL);
- }
-}
-
-void update_state_machine_mode_stabilized(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd)
-{
- if (current_status->state_machine == SYSTEM_STATE_GROUND_READY || current_status->state_machine == SYSTEM_STATE_STABILIZED || current_status->state_machine == SYSTEM_STATE_MANUAL || current_status->state_machine == SYSTEM_STATE_AUTO) {
- int old_mode = current_status->flight_mode;
- int old_manual_control_mode = current_status->manual_control_mode;
- current_status->flight_mode = VEHICLE_FLIGHT_MODE_MANUAL;
- current_status->manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_SAS;
- current_status->flag_control_attitude_enabled = true;
- current_status->flag_control_rates_enabled = true;
- current_status->flag_control_manual_enabled = true;
-
- if (old_mode != current_status->flight_mode ||
- old_manual_control_mode != current_status->manual_control_mode) {
- printf("[cmd] att stabilized mode\n");
- do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_MANUAL);
- state_machine_publish(status_pub, current_status, mavlink_fd);
- }
-
- }
-}
-
-void update_state_machine_mode_guided(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd)
-{
- if (!current_status->flag_vector_flight_mode_ok) {
- mavlink_log_critical(mavlink_fd, "NO POS LOCK, REJ. GUIDED MODE");
- tune_error();
- return;
- }
-
- if (current_status->state_machine == SYSTEM_STATE_GROUND_READY || current_status->state_machine == SYSTEM_STATE_MANUAL || current_status->state_machine == SYSTEM_STATE_AUTO) {
- printf("[cmd] position guided mode\n");
- int old_mode = current_status->flight_mode;
- current_status->flight_mode = VEHICLE_FLIGHT_MODE_STAB;
- current_status->flag_control_manual_enabled = false;
- current_status->flag_control_attitude_enabled = true;
- current_status->flag_control_rates_enabled = true;
- do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_STABILIZED);
-
- if (old_mode != current_status->flight_mode) state_machine_publish(status_pub, current_status, mavlink_fd);
-
- }
-}
-
-void update_state_machine_mode_auto(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd)
-{
- if (!current_status->flag_vector_flight_mode_ok) {
- mavlink_log_critical(mavlink_fd, "NO POS LOCK, REJ. AUTO MODE");
- return;
- }
-
- if (current_status->state_machine == SYSTEM_STATE_GROUND_READY || current_status->state_machine == SYSTEM_STATE_MANUAL || current_status->state_machine == SYSTEM_STATE_STABILIZED) {
- printf("[cmd] auto mode\n");
- int old_mode = current_status->flight_mode;
- current_status->flight_mode = VEHICLE_FLIGHT_MODE_AUTO;
- current_status->flag_control_manual_enabled = false;
- current_status->flag_control_attitude_enabled = true;
- current_status->flag_control_rates_enabled = true;
- do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_AUTO);
-
- if (old_mode != current_status->flight_mode) state_machine_publish(status_pub, current_status, mavlink_fd);
- }
-}
-
-
-uint8_t update_state_machine_mode_request(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd, uint8_t mode)
-{
- uint8_t ret = 1;
-
- /* Switch on HIL if in standby and not already in HIL mode */
- if ((mode & VEHICLE_MODE_FLAG_HIL_ENABLED)
- && !current_status->flag_hil_enabled) {
- if ((current_status->state_machine == SYSTEM_STATE_STANDBY)) {
- /* Enable HIL on request */
- current_status->flag_hil_enabled = true;
- ret = OK;
- state_machine_publish(status_pub, current_status, mavlink_fd);
- publish_armed_status(current_status);
- printf("[cmd] Enabling HIL, locking down all actuators for safety.\n\t(Arming the system will not activate them while in HIL mode)\n");
-
- } else if (current_status->state_machine != SYSTEM_STATE_STANDBY &&
- current_status->flag_system_armed) {
-
- mavlink_log_critical(mavlink_fd, "REJECTING HIL, disarm first!")
-
- } else {
-
- mavlink_log_critical(mavlink_fd, "REJECTING HIL, not in standby.")
- }
- }
-
- /* switch manual / auto */
- if (mode & VEHICLE_MODE_FLAG_AUTO_ENABLED) {
- update_state_machine_mode_auto(status_pub, current_status, mavlink_fd);
-
- } else if (mode & VEHICLE_MODE_FLAG_STABILIZED_ENABLED) {
- update_state_machine_mode_stabilized(status_pub, current_status, mavlink_fd);
-
- } else if (mode & VEHICLE_MODE_FLAG_GUIDED_ENABLED) {
- update_state_machine_mode_guided(status_pub, current_status, mavlink_fd);
-
- } else if (mode & VEHICLE_MODE_FLAG_MANUAL_INPUT_ENABLED) {
- update_state_machine_mode_manual(status_pub, current_status, mavlink_fd);
- }
-
- /* vehicle is disarmed, mode requests arming */
- if (!(current_status->flag_system_armed) && (mode & VEHICLE_MODE_FLAG_SAFETY_ARMED)) {
- /* only arm in standby state */
- // XXX REMOVE
- if (current_status->state_machine == SYSTEM_STATE_STANDBY || current_status->state_machine == SYSTEM_STATE_PREFLIGHT) {
- do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_GROUND_READY);
- ret = OK;
- printf("[cmd] arming due to command request\n");
- }
- }
-
- /* vehicle is armed, mode requests disarming */
- if (current_status->flag_system_armed && !(mode & VEHICLE_MODE_FLAG_SAFETY_ARMED)) {
- /* only disarm in ground ready */
- if (current_status->state_machine == SYSTEM_STATE_GROUND_READY) {
- do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_STANDBY);
- ret = OK;
- printf("[cmd] disarming due to command request\n");
- }
- }
-
- /* NEVER actually switch off HIL without reboot */
- if (current_status->flag_hil_enabled && !(mode & VEHICLE_MODE_FLAG_HIL_ENABLED)) {
- warnx("DENYING request to switch off HIL. Please power cycle (safety reasons)\n");
- mavlink_log_critical(mavlink_fd, "Power-cycle to exit HIL");
- ret = ERROR;
- }
-
- return ret;
-}
-
-uint8_t update_state_machine_custom_mode_request(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd, uint8_t custom_mode) //TODO: add more checks to avoid state switching in critical situations
-{
- commander_state_machine_t current_system_state = current_status->state_machine;
-
- uint8_t ret = 1;
-
- switch (custom_mode) {
- case SYSTEM_STATE_GROUND_READY:
- break;
-
- case SYSTEM_STATE_STANDBY:
- break;
-
- case SYSTEM_STATE_REBOOT:
- printf("try to reboot\n");
-
- if (current_system_state == SYSTEM_STATE_STANDBY
- || current_system_state == SYSTEM_STATE_PREFLIGHT
- || current_status->flag_hil_enabled) {
- printf("system will reboot\n");
- mavlink_log_critical(mavlink_fd, "Rebooting..");
- usleep(200000);
- do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_REBOOT);
- ret = 0;
- }
-
- break;
-
- case SYSTEM_STATE_AUTO:
- printf("try to switch to auto/takeoff\n");
-
- if (current_system_state == SYSTEM_STATE_GROUND_READY || current_system_state == SYSTEM_STATE_MANUAL) {
- do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_AUTO);
- printf("state: auto\n");
- ret = 0;
- }
-
- break;
-
- case SYSTEM_STATE_MANUAL:
- printf("try to switch to manual\n");
-
- if (current_system_state == SYSTEM_STATE_GROUND_READY || current_system_state == SYSTEM_STATE_AUTO) {
- do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_MANUAL);
- printf("state: manual\n");
- ret = 0;
- }
-
- break;
-
- default:
- break;
- }
-
- return ret;
-}
+///* END SUBSYSTEM/EMERGENCY FUNCTIONS*/
+//
+//int update_state_machine_mode_request(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd, uint8_t mode)
+//{
+// int ret = 1;
+//
+//// /* Switch on HIL if in standby and not already in HIL mode */
+//// if ((mode & VEHICLE_MODE_FLAG_HIL_ENABLED)
+//// && !current_status->flag_hil_enabled) {
+//// if ((current_status->state_machine == SYSTEM_STATE_STANDBY)) {
+//// /* Enable HIL on request */
+//// current_status->flag_hil_enabled = true;
+//// ret = OK;
+//// state_machine_publish(status_pub, current_status, mavlink_fd);
+//// publish_armed_status(current_status);
+//// printf("[cmd] Enabling HIL, locking down all actuators for safety.\n\t(Arming the system will not activate them while in HIL mode)\n");
+////
+//// } else if (current_status->state_machine != SYSTEM_STATE_STANDBY &&
+//// current_status->flag_fmu_armed) {
+////
+//// mavlink_log_critical(mavlink_fd, "REJECTING HIL, disarm first!")
+////
+//// } else {
+////
+//// mavlink_log_critical(mavlink_fd, "REJECTING HIL, not in standby.")
+//// }
+//// }
+//
+// /* switch manual / auto */
+// if (mode & VEHICLE_MODE_FLAG_AUTO_ENABLED) {
+// update_state_machine_mode_auto(status_pub, current_status, mavlink_fd);
+//
+// } else if (mode & VEHICLE_MODE_FLAG_STABILIZED_ENABLED) {
+// update_state_machine_mode_stabilized(status_pub, current_status, mavlink_fd);
+//
+// } else if (mode & VEHICLE_MODE_FLAG_GUIDED_ENABLED) {
+// update_state_machine_mode_guided(status_pub, current_status, mavlink_fd);
+//
+// } else if (mode & VEHICLE_MODE_FLAG_MANUAL_INPUT_ENABLED) {
+// update_state_machine_mode_manual(status_pub, current_status, mavlink_fd);
+// }
+//
+// /* vehicle is disarmed, mode requests arming */
+// if (!(current_status->flag_fmu_armed) && (mode & VEHICLE_MODE_FLAG_SAFETY_ARMED)) {
+// /* only arm in standby state */
+// // XXX REMOVE
+// if (current_status->state_machine == SYSTEM_STATE_STANDBY || current_status->state_machine == SYSTEM_STATE_PREFLIGHT) {
+// do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_GROUND_READY);
+// ret = OK;
+// printf("[cmd] arming due to command request\n");
+// }
+// }
+//
+// /* vehicle is armed, mode requests disarming */
+// if (current_status->flag_fmu_armed && !(mode & VEHICLE_MODE_FLAG_SAFETY_ARMED)) {
+// /* only disarm in ground ready */
+// if (current_status->state_machine == SYSTEM_STATE_GROUND_READY) {
+// do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_STANDBY);
+// ret = OK;
+// printf("[cmd] disarming due to command request\n");
+// }
+// }
+//
+// /* NEVER actually switch off HIL without reboot */
+// if (current_status->flag_hil_enabled && !(mode & VEHICLE_MODE_FLAG_HIL_ENABLED)) {
+// warnx("DENYING request to switch off HIL. Please power cycle (safety reasons)\n");
+// mavlink_log_critical(mavlink_fd, "Power-cycle to exit HIL");
+// ret = ERROR;
+// }
+//
+// return ret;
+//}
diff --git a/src/modules/commander/state_machine_helper.h b/src/modules/commander/state_machine_helper.h
index 2f2ccc729..b553a4b56 100644
--- a/src/modules/commander/state_machine_helper.h
+++ b/src/modules/commander/state_machine_helper.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
* Author: Thomas Gubler <thomasgubler@student.ethz.ch>
* Julian Oes <joes@student.ethz.ch>
*
@@ -46,164 +46,14 @@
#include <uORB/uORB.h>
#include <uORB/topics/vehicle_status.h>
+#include <uORB/topics/actuator_safety.h>
+#include <uORB/topics/vehicle_control_mode.h>
-/**
- * Switch to new state with no checking.
- *
- * do_state_update: this is the functions that all other functions have to call in order to update the state.
- * the function does not question the state change, this must be done before
- * The function performs actions that are connected with the new state (buzzer, reboot, ...)
- *
- * @param status_pub file descriptor for state update topic publication
- * @param current_status pointer to the current state machine to operate on
- * @param mavlink_fd file descriptor for MAVLink statustext messages
- *
- * @return 0 (macro OK) or 1 on error (macro ERROR)
- */
-int do_state_update(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd, commander_state_machine_t new_state);
-
-/* These functions decide if an emergency exits and then switch to SYSTEM_STATE_MISSION_ABORT or SYSTEM_STATE_GROUND_ERROR */
-// void update_state_machine_subsystem_present(int status_pub, struct vehicle_status_s *current_status, subsystem_type_t *subsystem_type);
-// void update_state_machine_subsystem_notpresent(int status_pub, struct vehicle_status_s *current_status, subsystem_type_t *subsystem_type);
-
-// void update_state_machine_subsystem_enabled(int status_pub, struct vehicle_status_s *current_status, subsystem_type_t *subsystem_type);
-// void update_state_machine_subsystem_disabled(int status_pub, struct vehicle_status_s *current_status, subsystem_type_t *subsystem_type);
-
-// void update_state_machine_subsystem_healthy(int status_pub, struct vehicle_status_s *current_status, subsystem_type_t *subsystem_type);
-// void update_state_machine_subsystem_unhealthy(int status_pub, struct vehicle_status_s *current_status, subsystem_type_t *subsystem_type);
-
-
-/**
- * Handle state machine if got position fix
- *
- * @param status_pub file descriptor for state update topic publication
- * @param current_status pointer to the current state machine to operate on
- * @param mavlink_fd file descriptor for MAVLink statustext messages
- */
-void update_state_machine_got_position_fix(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd);
-
-/**
- * Handle state machine if position fix lost
- *
- * @param status_pub file descriptor for state update topic publication
- * @param current_status pointer to the current state machine to operate on
- * @param mavlink_fd file descriptor for MAVLink statustext messages
- */
-void update_state_machine_no_position_fix(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd);
-
-/**
- * Handle state machine if user wants to arm
- *
- * @param status_pub file descriptor for state update topic publication
- * @param current_status pointer to the current state machine to operate on
- * @param mavlink_fd file descriptor for MAVLink statustext messages
- */
-void update_state_machine_arm(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd);
-
-/**
- * Handle state machine if user wants to disarm
- *
- * @param status_pub file descriptor for state update topic publication
- * @param current_status pointer to the current state machine to operate on
- * @param mavlink_fd file descriptor for MAVLink statustext messages
- */
-void update_state_machine_disarm(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd);
-
-/**
- * Handle state machine if mode switch is manual
- *
- * @param status_pub file descriptor for state update topic publication
- * @param current_status pointer to the current state machine to operate on
- * @param mavlink_fd file descriptor for MAVLink statustext messages
- */
-void update_state_machine_mode_manual(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd);
-
-/**
- * Handle state machine if mode switch is stabilized
- *
- * @param status_pub file descriptor for state update topic publication
- * @param current_status pointer to the current state machine to operate on
- * @param mavlink_fd file descriptor for MAVLink statustext messages
- */
-void update_state_machine_mode_stabilized(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd);
-
-/**
- * Handle state machine if mode switch is guided
- *
- * @param status_pub file descriptor for state update topic publication
- * @param current_status pointer to the current state machine to operate on
- * @param mavlink_fd file descriptor for MAVLink statustext messages
- */
-void update_state_machine_mode_guided(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd);
-
-/**
- * Handle state machine if mode switch is auto
- *
- * @param status_pub file descriptor for state update topic publication
- * @param current_status pointer to the current state machine to operate on
- * @param mavlink_fd file descriptor for MAVLink statustext messages
- */
-void update_state_machine_mode_auto(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd);
-
-/**
- * Publish current state information
- *
- * @param status_pub file descriptor for state update topic publication
- * @param current_status pointer to the current state machine to operate on
- * @param mavlink_fd file descriptor for MAVLink statustext messages
- */
-void state_machine_publish(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd);
-
-
-/*
- * Functions that handle incoming requests to change the state machine or a parameter (probably from the mavlink app).
- * If the request is obeyed the functions return 0
- *
- */
-
-/**
- * Handles *incoming request* to switch to a specific state, if state change is successful returns 0
- *
- * @param status_pub file descriptor for state update topic publication
- * @param current_status pointer to the current state machine to operate on
- * @param mavlink_fd file descriptor for MAVLink statustext messages
- */
-uint8_t update_state_machine_mode_request(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd, uint8_t mode);
-/**
- * Handles *incoming request* to switch to a specific custom state, if state change is successful returns 0
- *
- * @param status_pub file descriptor for state update topic publication
- * @param current_status pointer to the current state machine to operate on
- * @param mavlink_fd file descriptor for MAVLink statustext messages
- */
-uint8_t update_state_machine_custom_mode_request(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd, uint8_t custom_mode);
-
-/**
- * Always switches to critical mode under any circumstances.
- *
- * @param status_pub file descriptor for state update topic publication
- * @param current_status pointer to the current state machine to operate on
- * @param mavlink_fd file descriptor for MAVLink statustext messages
- */
-void state_machine_emergency_always_critical(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd);
-
-/**
- * Switches to emergency if required.
- *
- * @param status_pub file descriptor for state update topic publication
- * @param current_status pointer to the current state machine to operate on
- * @param mavlink_fd file descriptor for MAVLink statustext messages
- */
-void state_machine_emergency(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd);
-
-/**
- * Publish the armed state depending on the current system state
- *
- * @param current_status the current system status
- */
-void publish_armed_status(const struct vehicle_status_s *current_status);
+int arming_state_transition(int status_pub, struct vehicle_status_s *current_state, arming_state_t new_arming_state, int safety_pub, struct actuator_safety_s *safety, const int mavlink_fd);
+int navigation_state_transition(int status_pub, struct vehicle_status_s *current_state, navigation_state_t new_navigation_state, int control_mode_pub, struct vehicle_control_mode_s *control_mode, const int mavlink_fd);
+int hil_state_transition(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd, hil_state_t new_state);
#endif /* STATE_MACHINE_HELPER_H_ */
diff --git a/src/modules/controllib/fixedwing.cpp b/src/modules/controllib/fixedwing.cpp
index 77b2ac806..9435959e9 100644
--- a/src/modules/controllib/fixedwing.cpp
+++ b/src/modules/controllib/fixedwing.cpp
@@ -39,6 +39,7 @@
#include "fixedwing.hpp"
+
namespace control
{
@@ -210,8 +211,9 @@ void BlockMultiModeBacksideAutopilot::update()
for (unsigned i = 4; i < NUM_ACTUATOR_CONTROLS; i++)
_actuators.control[i] = 0.0f;
+#warning this if is incomplete, should be based on flags
// only update guidance in auto mode
- if (_status.state_machine == SYSTEM_STATE_AUTO) {
+ if (_status.navigation_state == NAVIGATION_STATE_AUTO_MISSION) {
// update guidance
_guide.update(_pos, _att, _posCmd.current, _lastPosCmd.current);
}
@@ -220,9 +222,10 @@ void BlockMultiModeBacksideAutopilot::update()
// once the system switches from manual or auto to stabilized
// the setpoint should update to loitering around this position
+#warning should be base on flags
// handle autopilot modes
- if (_status.state_machine == SYSTEM_STATE_AUTO ||
- _status.state_machine == SYSTEM_STATE_STABILIZED) {
+ if (_status.navigation_state == NAVIGATION_STATE_AUTO_MISSION ||
+ _status.navigation_state == NAVIGATION_STATE_SEATBELT) {
// update guidance
_guide.update(_pos, _att, _posCmd.current, _lastPosCmd.current);
@@ -280,15 +283,16 @@ void BlockMultiModeBacksideAutopilot::update()
_actuators.control[CH_THR] : _manual.throttle;
}
- } else if (_status.state_machine == SYSTEM_STATE_MANUAL) {
-
- if (_status.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_DIRECT) {
- _actuators.control[CH_AIL] = _manual.roll;
- _actuators.control[CH_ELV] = _manual.pitch;
- _actuators.control[CH_RDR] = _manual.yaw;
- _actuators.control[CH_THR] = _manual.throttle;
+ } else if (_status.navigation_state == NAVIGATION_STATE_MANUAL) {
- } else if (_status.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_SAS) {
+#warning fix here too
+// if (_status.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_DIRECT) {
+// _actuators.control[CH_AIL] = _manual.roll;
+// _actuators.control[CH_ELV] = _manual.pitch;
+// _actuators.control[CH_RDR] = _manual.yaw;
+// _actuators.control[CH_THR] = _manual.throttle;
+//
+// } else if (_status.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_SAS) {
// calculate velocity, XXX should be airspeed, but using ground speed for now
// for the purpose of control we will limit the velocity feedback between
@@ -344,7 +348,8 @@ void BlockMultiModeBacksideAutopilot::update()
_actuators.control[CH_THR] = (_actuators.control[CH_THR] < _manual.throttle) ?
_actuators.control[CH_THR] : _manual.throttle;
}
- }
+#warning fix this
+// }
// body rates controller, disabled for now
else if (0 /*_status.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_SAS*/) {
diff --git a/src/modules/fixedwing_att_control/fixedwing_att_control_att.c b/src/modules/fixedwing_att_control/fixedwing_att_control_att.c
index 2aeca3a98..68c176459 100644
--- a/src/modules/fixedwing_att_control/fixedwing_att_control_att.c
+++ b/src/modules/fixedwing_att_control/fixedwing_att_control_att.c
@@ -142,7 +142,7 @@ int fixedwing_att_control_attitude(const struct vehicle_attitude_setpoint_s *att
}
/* Roll (P) */
- rates_sp->roll = pid_calculate(&roll_controller, att_sp->roll_body, att->roll, 0, 0);
+ rates_sp->roll = pid_calculate(&roll_controller, att_sp->roll_body, att->roll, 0, 0, NULL, NULL, NULL);
/* Pitch (P) */
@@ -152,7 +152,7 @@ int fixedwing_att_control_attitude(const struct vehicle_attitude_setpoint_s *att
/* set pitch plus feedforward roll compensation */
rates_sp->pitch = pid_calculate(&pitch_controller,
att_sp->pitch_body + pitch_sp_rollcompensation,
- att->pitch, 0, 0);
+ att->pitch, 0, 0, NULL, NULL, NULL);
/* Yaw (from coordinated turn constraint or lateral force) */
rates_sp->yaw = (att->rollspeed * rates_sp->roll + 9.81f * sinf(att->roll) * cosf(att->pitch) + speed_body[0] * rates_sp->pitch * sinf(att->roll))
diff --git a/src/modules/fixedwing_att_control/fixedwing_att_control_main.c b/src/modules/fixedwing_att_control/fixedwing_att_control_main.c
index 6c9c137bb..b96fc3e5a 100644
--- a/src/modules/fixedwing_att_control/fixedwing_att_control_main.c
+++ b/src/modules/fixedwing_att_control/fixedwing_att_control_main.c
@@ -186,87 +186,88 @@ int fixedwing_att_control_thread_main(int argc, char *argv[])
/* control */
- if (vstatus.state_machine == SYSTEM_STATE_AUTO ||
- vstatus.state_machine == SYSTEM_STATE_STABILIZED) {
- /* attitude control */
- fixedwing_att_control_attitude(&att_sp, &att, speed_body, &rates_sp);
-
- /* angular rate control */
- fixedwing_att_control_rates(&rates_sp, gyro, &actuators);
-
- /* pass through throttle */
- actuators.control[3] = att_sp.thrust;
-
- /* set flaps to zero */
- actuators.control[4] = 0.0f;
-
- } else if (vstatus.state_machine == SYSTEM_STATE_MANUAL) {
- if (vstatus.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_SAS) {
-
- /* if the RC signal is lost, try to stay level and go slowly back down to ground */
- if (vstatus.rc_signal_lost) {
-
- /* put plane into loiter */
- att_sp.roll_body = 0.3f;
- att_sp.pitch_body = 0.0f;
-
- /* limit throttle to 60 % of last value if sane */
- if (isfinite(manual_sp.throttle) &&
- (manual_sp.throttle >= 0.0f) &&
- (manual_sp.throttle <= 1.0f)) {
- att_sp.thrust = 0.6f * manual_sp.throttle;
-
- } else {
- att_sp.thrust = 0.0f;
- }
-
- att_sp.yaw_body = 0;
-
- // XXX disable yaw control, loiter
-
- } else {
-
- att_sp.roll_body = manual_sp.roll;
- att_sp.pitch_body = manual_sp.pitch;
- att_sp.yaw_body = 0;
- att_sp.thrust = manual_sp.throttle;
- }
-
- att_sp.timestamp = hrt_absolute_time();
-
- /* attitude control */
- fixedwing_att_control_attitude(&att_sp, &att, speed_body, &rates_sp);
-
- /* angular rate control */
- fixedwing_att_control_rates(&rates_sp, gyro, &actuators);
-
- /* pass through throttle */
- actuators.control[3] = att_sp.thrust;
-
- /* pass through flaps */
- if (isfinite(manual_sp.flaps)) {
- actuators.control[4] = manual_sp.flaps;
-
- } else {
- actuators.control[4] = 0.0f;
- }
-
- } else if (vstatus.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_DIRECT) {
- /* directly pass through values */
- actuators.control[0] = manual_sp.roll;
- /* positive pitch means negative actuator -> pull up */
- actuators.control[1] = manual_sp.pitch;
- actuators.control[2] = manual_sp.yaw;
- actuators.control[3] = manual_sp.throttle;
-
- if (isfinite(manual_sp.flaps)) {
- actuators.control[4] = manual_sp.flaps;
-
- } else {
- actuators.control[4] = 0.0f;
- }
- }
- }
+#warning fix this
+// if (vstatus.state_machine == SYSTEM_STATE_AUTO ||
+// vstatus.state_machine == SYSTEM_STATE_STABILIZED) {
+// /* attitude control */
+// fixedwing_att_control_attitude(&att_sp, &att, speed_body, &rates_sp);
+//
+// /* angular rate control */
+// fixedwing_att_control_rates(&rates_sp, gyro, &actuators);
+//
+// /* pass through throttle */
+// actuators.control[3] = att_sp.thrust;
+//
+// /* set flaps to zero */
+// actuators.control[4] = 0.0f;
+//
+// } else if (vstatus.state_machine == SYSTEM_STATE_MANUAL) {
+// if (vstatus.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_SAS) {
+//
+// /* if the RC signal is lost, try to stay level and go slowly back down to ground */
+// if (vstatus.rc_signal_lost) {
+//
+// /* put plane into loiter */
+// att_sp.roll_body = 0.3f;
+// att_sp.pitch_body = 0.0f;
+//
+// /* limit throttle to 60 % of last value if sane */
+// if (isfinite(manual_sp.throttle) &&
+// (manual_sp.throttle >= 0.0f) &&
+// (manual_sp.throttle <= 1.0f)) {
+// att_sp.thrust = 0.6f * manual_sp.throttle;
+//
+// } else {
+// att_sp.thrust = 0.0f;
+// }
+//
+// att_sp.yaw_body = 0;
+//
+// // XXX disable yaw control, loiter
+//
+// } else {
+//
+// att_sp.roll_body = manual_sp.roll;
+// att_sp.pitch_body = manual_sp.pitch;
+// att_sp.yaw_body = 0;
+// att_sp.thrust = manual_sp.throttle;
+// }
+//
+// att_sp.timestamp = hrt_absolute_time();
+//
+// /* attitude control */
+// fixedwing_att_control_attitude(&att_sp, &att, speed_body, &rates_sp);
+//
+// /* angular rate control */
+// fixedwing_att_control_rates(&rates_sp, gyro, &actuators);
+//
+// /* pass through throttle */
+// actuators.control[3] = att_sp.thrust;
+//
+// /* pass through flaps */
+// if (isfinite(manual_sp.flaps)) {
+// actuators.control[4] = manual_sp.flaps;
+//
+// } else {
+// actuators.control[4] = 0.0f;
+// }
+//
+// } else if (vstatus.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_DIRECT) {
+// /* directly pass through values */
+// actuators.control[0] = manual_sp.roll;
+// /* positive pitch means negative actuator -> pull up */
+// actuators.control[1] = manual_sp.pitch;
+// actuators.control[2] = manual_sp.yaw;
+// actuators.control[3] = manual_sp.throttle;
+//
+// if (isfinite(manual_sp.flaps)) {
+// actuators.control[4] = manual_sp.flaps;
+//
+// } else {
+// actuators.control[4] = 0.0f;
+// }
+// }
+// }
/* publish rates */
orb_publish(ORB_ID(vehicle_rates_setpoint), rates_pub, &rates_sp);
diff --git a/src/modules/fixedwing_att_control/fixedwing_att_control_rate.c b/src/modules/fixedwing_att_control/fixedwing_att_control_rate.c
index cdab39edc..66854592a 100644
--- a/src/modules/fixedwing_att_control/fixedwing_att_control_rate.c
+++ b/src/modules/fixedwing_att_control/fixedwing_att_control_rate.c
@@ -196,11 +196,11 @@ int fixedwing_att_control_rates(const struct vehicle_rates_setpoint_s *rate_sp,
/* roll rate (PI) */
- actuators->control[0] = pid_calculate(&roll_rate_controller, rate_sp->roll, rates[0], 0.0f, deltaT);
+ actuators->control[0] = pid_calculate(&roll_rate_controller, rate_sp->roll, rates[0], 0.0f, deltaT, NULL, NULL, NULL);
/* pitch rate (PI) */
- actuators->control[1] = -pid_calculate(&pitch_rate_controller, rate_sp->pitch, rates[1], 0.0f, deltaT);
+ actuators->control[1] = -pid_calculate(&pitch_rate_controller, rate_sp->pitch, rates[1], 0.0f, deltaT, NULL, NULL, NULL);
/* yaw rate (PI) */
- actuators->control[2] = pid_calculate(&yaw_rate_controller, rate_sp->yaw, rates[2], 0.0f, deltaT);
+ actuators->control[2] = pid_calculate(&yaw_rate_controller, rate_sp->yaw, rates[2], 0.0f, deltaT, NULL, NULL, NULL);
counter++;
diff --git a/src/modules/fixedwing_pos_control/fixedwing_pos_control_main.c b/src/modules/fixedwing_pos_control/fixedwing_pos_control_main.c
index 73df3fb9e..87a942ffb 100644
--- a/src/modules/fixedwing_pos_control/fixedwing_pos_control_main.c
+++ b/src/modules/fixedwing_pos_control/fixedwing_pos_control_main.c
@@ -271,7 +271,7 @@ int fixedwing_pos_control_thread_main(int argc, char *argv[])
pid_set_parameters(&heading_controller, p.heading_p, 0, 0, 0, 10000.0f); //arbitrary high limit
pid_set_parameters(&heading_rate_controller, p.headingr_p, p.headingr_i, 0, 0, p.roll_lim);
pid_set_parameters(&altitude_controller, p.altitude_p, 0, 0, 0, p.pitch_lim);
- pid_set_parameters(&offtrack_controller, p.xtrack_p, 0, 0, 0, 60.0f * M_DEG_TO_RAD); //TODO: remove hardcoded value
+ pid_set_parameters(&offtrack_controller, p.xtrack_p, 0, 0, 0, 60.0f * M_DEG_TO_RAD_F); //TODO: remove hardcoded value
}
/* only run controller if attitude changed */
@@ -319,7 +319,7 @@ int fixedwing_pos_control_thread_main(int argc, char *argv[])
// XXX what is xtrack_err.past_end?
if (distance_res == OK /*&& !xtrack_err.past_end*/) {
- float delta_psi_c = pid_calculate(&offtrack_controller, 0, xtrack_err.distance, 0.0f, 0.0f); //p.xtrack_p * xtrack_err.distance
+ float delta_psi_c = pid_calculate(&offtrack_controller, 0, xtrack_err.distance, 0.0f, 0.0f, NULL, NULL, NULL); //p.xtrack_p * xtrack_err.distance
float psi_c = psi_track + delta_psi_c;
float psi_e = psi_c - att.yaw;
@@ -336,7 +336,7 @@ int fixedwing_pos_control_thread_main(int argc, char *argv[])
}
/* calculate roll setpoint, do this artificially around zero */
- float delta_psi_rate_c = pid_calculate(&heading_controller, psi_e, 0.0f, 0.0f, 0.0f);
+ float delta_psi_rate_c = pid_calculate(&heading_controller, psi_e, 0.0f, 0.0f, 0.0f, NULL, NULL, NULL);
float psi_rate_track = 0; //=V_gr/r_track , this will be needed for implementation of arc following
float psi_rate_c = delta_psi_rate_c + psi_rate_track;
@@ -359,7 +359,7 @@ int fixedwing_pos_control_thread_main(int argc, char *argv[])
float psi_rate_e_scaled = psi_rate_e * ground_speed / 9.81f; //* V_gr / g
- attitude_setpoint.roll_body = pid_calculate(&heading_rate_controller, psi_rate_e_scaled, 0.0f, 0.0f, deltaT);
+ attitude_setpoint.roll_body = pid_calculate(&heading_rate_controller, psi_rate_e_scaled, 0.0f, 0.0f, deltaT, NULL, NULL, NULL);
if (verbose) {
printf("psi_rate_c %.4f ", (double)psi_rate_c);
@@ -379,7 +379,7 @@ int fixedwing_pos_control_thread_main(int argc, char *argv[])
if (pos_updated) {
//TODO: take care of relative vs. ab. altitude
- attitude_setpoint.pitch_body = pid_calculate(&altitude_controller, global_setpoint.altitude, global_pos.alt, 0.0f, 0.0f);
+ attitude_setpoint.pitch_body = pid_calculate(&altitude_controller, global_setpoint.altitude, global_pos.alt, 0.0f, 0.0f, NULL, NULL, NULL);
}
diff --git a/src/modules/gpio_led/gpio_led.c b/src/modules/gpio_led/gpio_led.c
index 43cbe74c7..618095d0b 100644
--- a/src/modules/gpio_led/gpio_led.c
+++ b/src/modules/gpio_led/gpio_led.c
@@ -51,6 +51,7 @@
#include <systemlib/err.h>
#include <uORB/uORB.h>
#include <uORB/topics/vehicle_status.h>
+#include <uORB/topics/actuator_safety.h>
#include <poll.h>
#include <drivers/drv_gpio.h>
@@ -60,6 +61,8 @@ struct gpio_led_s {
int pin;
struct vehicle_status_s status;
int vehicle_status_sub;
+ struct actuator_safety_s safety;
+ int actuator_safety_sub;
bool led_state;
int counter;
};
@@ -168,10 +171,15 @@ void gpio_led_cycle(FAR void *arg)
if (status_updated)
orb_copy(ORB_ID(vehicle_status), priv->vehicle_status_sub, &priv->status);
+ orb_check(priv->vehicle_status_sub, &status_updated);
+
+ if (status_updated)
+ orb_copy(ORB_ID(actuator_safety), priv->actuator_safety_sub, &priv->safety);
+
/* select pattern for current status */
int pattern = 0;
- if (priv->status.flag_system_armed) {
+ if (priv->safety.armed) {
if (priv->status.battery_warning == VEHICLE_BATTERY_WARNING_NONE) {
pattern = 0x3f; // ****** solid (armed)
@@ -180,11 +188,10 @@ void gpio_led_cycle(FAR void *arg)
}
} else {
- if (priv->status.state_machine == SYSTEM_STATE_PREFLIGHT) {
+ if (priv->safety.ready_to_arm) {
pattern = 0x00; // ______ off (disarmed, preflight check)
- } else if (priv->status.state_machine == SYSTEM_STATE_STANDBY &&
- priv->status.battery_warning == VEHICLE_BATTERY_WARNING_NONE) {
+ } else if (priv->safety.ready_to_arm && priv->status.battery_warning == VEHICLE_BATTERY_WARNING_NONE) {
pattern = 0x38; // ***___ slow blink (disarmed, ready)
} else {
diff --git a/src/modules/mavlink/mavlink.c b/src/modules/mavlink/mavlink.c
index 5b8345e7e..f6c371c7c 100644
--- a/src/modules/mavlink/mavlink.c
+++ b/src/modules/mavlink/mavlink.c
@@ -187,95 +187,88 @@ get_mavlink_mode_and_state(uint8_t *mavlink_state, uint8_t *mavlink_mode)
/* reset MAVLink mode bitfield */
*mavlink_mode = 0;
- /* set mode flags independent of system state */
+ /**
+ * Set mode flags
+ **/
/* HIL */
if (v_status.flag_hil_enabled) {
*mavlink_mode |= MAV_MODE_FLAG_HIL_ENABLED;
}
- /* manual input */
- if (v_status.flag_control_manual_enabled) {
- *mavlink_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
- }
-
- /* attitude or rate control */
- if (v_status.flag_control_attitude_enabled ||
- v_status.flag_control_rates_enabled) {
- *mavlink_mode |= MAV_MODE_FLAG_STABILIZE_ENABLED;
- }
-
- /* vector control */
- if (v_status.flag_control_velocity_enabled ||
- v_status.flag_control_position_enabled) {
- *mavlink_mode |= MAV_MODE_FLAG_GUIDED_ENABLED;
- }
-
/* autonomous mode */
- if (v_status.state_machine == SYSTEM_STATE_AUTO) {
+ if (v_status.navigation_state == NAVIGATION_STATE_AUTO_LAND
+ || v_status.navigation_state == NAVIGATION_STATE_AUTO_LOITER
+ || v_status.navigation_state == NAVIGATION_STATE_AUTO_MISSION
+ || v_status.navigation_state == NAVIGATION_STATE_AUTO_READY
+ || v_status.navigation_state == NAVIGATION_STATE_AUTO_RTL
+ || v_status.navigation_state == NAVIGATION_STATE_AUTO_STANDBY
+ || v_status.navigation_state == NAVIGATION_STATE_AUTO_TAKEOFF) {
*mavlink_mode |= MAV_MODE_FLAG_AUTO_ENABLED;
}
/* set arming state */
- if (armed.armed) {
+ if (v_status.arming_state == ARMING_STATE_ARMED
+ || v_status.arming_state == ARMING_STATE_ARMED_ERROR) {
*mavlink_mode |= MAV_MODE_FLAG_SAFETY_ARMED;
} else {
*mavlink_mode &= ~MAV_MODE_FLAG_SAFETY_ARMED;
}
- switch (v_status.state_machine) {
- case SYSTEM_STATE_PREFLIGHT:
- if (v_status.flag_preflight_gyro_calibration ||
- v_status.flag_preflight_mag_calibration ||
- v_status.flag_preflight_accel_calibration) {
- *mavlink_state = MAV_STATE_CALIBRATING;
+ if (v_status.navigation_state == NAVIGATION_STATE_MANUAL
+ || v_status.navigation_state == NAVIGATION_STATE_MANUAL_STANDBY) {
- } else {
- *mavlink_state = MAV_STATE_UNINIT;
- }
+ *mavlink_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
+ }
- break;
+ if (v_status.navigation_state == NAVIGATION_STATE_SEATBELT
+ || v_status.navigation_state == NAVIGATION_STATE_SEATBELT_DESCENT
+ || v_status.navigation_state == NAVIGATION_STATE_SEATBELT_STANDBY) {
- case SYSTEM_STATE_STANDBY:
- *mavlink_state = MAV_STATE_STANDBY;
- break;
+ *mavlink_mode |= MAV_MODE_FLAG_GUIDED_ENABLED;
+ }
- case SYSTEM_STATE_GROUND_READY:
- *mavlink_state = MAV_STATE_ACTIVE;
- break;
- case SYSTEM_STATE_MANUAL:
- *mavlink_state = MAV_STATE_ACTIVE;
- break;
+ /**
+ * Set mavlink state
+ **/
- case SYSTEM_STATE_STABILIZED:
- *mavlink_state = MAV_STATE_ACTIVE;
- break;
+ /* set calibration state */
+ if (v_status.flag_preflight_calibration) {
- case SYSTEM_STATE_AUTO:
- *mavlink_state = MAV_STATE_ACTIVE;
- break;
+ *mavlink_state = MAV_STATE_CALIBRATING;
- case SYSTEM_STATE_MISSION_ABORT:
- *mavlink_state = MAV_STATE_EMERGENCY;
- break;
+ } else if (v_status.flag_system_emergency) {
- case SYSTEM_STATE_EMCY_LANDING:
*mavlink_state = MAV_STATE_EMERGENCY;
- break;
- case SYSTEM_STATE_EMCY_CUTOFF:
- *mavlink_state = MAV_STATE_EMERGENCY;
- break;
+ // XXX difference between active and armed? is AUTO_READY active?
+ } else if (v_status.navigation_state == NAVIGATION_STATE_AUTO_LAND
+ || v_status.navigation_state == NAVIGATION_STATE_AUTO_LOITER
+ || v_status.navigation_state == NAVIGATION_STATE_AUTO_MISSION
+ || v_status.navigation_state == NAVIGATION_STATE_AUTO_RTL
+ || v_status.navigation_state == NAVIGATION_STATE_AUTO_TAKEOFF
+ || v_status.navigation_state == NAVIGATION_STATE_SEATBELT
+ || v_status.navigation_state == NAVIGATION_STATE_SEATBELT_DESCENT
+ || v_status.navigation_state == NAVIGATION_STATE_MANUAL) {
- case SYSTEM_STATE_GROUND_ERROR:
- *mavlink_state = MAV_STATE_EMERGENCY;
- break;
+ *mavlink_state = MAV_STATE_ACTIVE;
- case SYSTEM_STATE_REBOOT:
- *mavlink_state = MAV_STATE_POWEROFF;
- break;
+ } else if (v_status.navigation_state == NAVIGATION_STATE_AUTO_STANDBY
+ || v_status.navigation_state == NAVIGATION_STATE_AUTO_READY // XXX correct?
+ || v_status.navigation_state == NAVIGATION_STATE_SEATBELT_STANDBY
+ || v_status.navigation_state == NAVIGATION_STATE_MANUAL_STANDBY) {
+
+ *mavlink_state = MAV_STATE_STANDBY;
+
+ } else if (v_status.navigation_state == NAVIGATION_STATE_INIT) {
+
+ *mavlink_state = MAV_STATE_UNINIT;
+ } else {
+
+ warnx("Unknown mavlink state");
+ *mavlink_state = MAV_STATE_CRITICAL;
}
}
@@ -571,6 +564,7 @@ int mavlink_thread_main(int argc, char *argv[])
default:
usage();
+ break;
}
}
@@ -681,7 +675,7 @@ int mavlink_thread_main(int argc, char *argv[])
get_mavlink_mode_and_state(&mavlink_state, &mavlink_mode);
/* send heartbeat */
- mavlink_msg_heartbeat_send(chan, mavlink_system.type, MAV_AUTOPILOT_PX4, mavlink_mode, v_status.state_machine, mavlink_state);
+ mavlink_msg_heartbeat_send(chan, mavlink_system.type, MAV_AUTOPILOT_PX4, mavlink_mode, v_status.navigation_state, mavlink_state);
/* switch HIL mode if required */
set_hil_on_off(v_status.flag_hil_enabled);
diff --git a/src/modules/mavlink/orb_listener.c b/src/modules/mavlink/orb_listener.c
index 0597555ab..a9a611998 100644
--- a/src/modules/mavlink/orb_listener.c
+++ b/src/modules/mavlink/orb_listener.c
@@ -71,7 +71,7 @@ struct vehicle_local_position_s local_pos;
struct vehicle_status_s v_status;
struct rc_channels_s rc;
struct rc_input_values rc_raw;
-struct actuator_armed_s armed;
+struct actuator_safety_s safety;
struct actuator_controls_effective_s actuators_0;
struct vehicle_attitude_s att;
@@ -111,7 +111,7 @@ static void l_global_position_setpoint(const struct listener *l);
static void l_local_position_setpoint(const struct listener *l);
static void l_attitude_setpoint(const struct listener *l);
static void l_actuator_outputs(const struct listener *l);
-static void l_actuator_armed(const struct listener *l);
+static void l_actuator_safety(const struct listener *l);
static void l_manual_control_setpoint(const struct listener *l);
static void l_vehicle_attitude_controls(const struct listener *l);
static void l_debug_key_value(const struct listener *l);
@@ -136,7 +136,7 @@ static const struct listener listeners[] = {
{l_actuator_outputs, &mavlink_subs.act_1_sub, 1},
{l_actuator_outputs, &mavlink_subs.act_2_sub, 2},
{l_actuator_outputs, &mavlink_subs.act_3_sub, 3},
- {l_actuator_armed, &mavlink_subs.armed_sub, 0},
+ {l_actuator_safety, &mavlink_subs.safety_sub, 0},
{l_manual_control_setpoint, &mavlink_subs.man_control_sp_sub, 0},
{l_vehicle_attitude_controls, &mavlink_subs.actuators_sub, 0},
{l_debug_key_value, &mavlink_subs.debug_key_value, 0},
@@ -270,7 +270,7 @@ l_vehicle_status(const struct listener *l)
{
/* immediately communicate state changes back to user */
orb_copy(ORB_ID(vehicle_status), status_sub, &v_status);
- orb_copy(ORB_ID(actuator_armed), mavlink_subs.armed_sub, &armed);
+ orb_copy(ORB_ID(actuator_safety), mavlink_subs.safety_sub, &safety);
/* enable or disable HIL */
set_hil_on_off(v_status.flag_hil_enabled);
@@ -285,7 +285,7 @@ l_vehicle_status(const struct listener *l)
mavlink_system.type,
MAV_AUTOPILOT_PX4,
mavlink_mode,
- v_status.state_machine,
+ v_status.navigation_state,
mavlink_state);
}
@@ -467,7 +467,7 @@ l_actuator_outputs(const struct listener *l)
act_outputs.output[7]);
/* only send in HIL mode */
- if (mavlink_hil_enabled && armed.armed) {
+ if (mavlink_hil_enabled && safety.armed) {
/* translate the current syste state to mavlink state and mode */
uint8_t mavlink_state = 0;
@@ -539,9 +539,9 @@ l_actuator_outputs(const struct listener *l)
}
void
-l_actuator_armed(const struct listener *l)
+l_actuator_safety(const struct listener *l)
{
- orb_copy(ORB_ID(actuator_armed), mavlink_subs.armed_sub, &armed);
+ orb_copy(ORB_ID(actuator_safety), mavlink_subs.safety_sub, &safety);
}
void
@@ -674,7 +674,7 @@ uorb_receive_thread(void *arg)
/* handle the poll result */
if (poll_ret == 0) {
- mavlink_missionlib_send_gcs_string("[mavlink] No telemetry data for 1 s");
+ /* silent */
} else if (poll_ret < 0) {
mavlink_missionlib_send_gcs_string("[mavlink] ERROR reading uORB data");
@@ -760,8 +760,8 @@ uorb_receive_start(void)
orb_set_interval(mavlink_subs.act_3_sub, 100); /* 10Hz updates */
/* --- ACTUATOR ARMED VALUE --- */
- mavlink_subs.armed_sub = orb_subscribe(ORB_ID(actuator_armed));
- orb_set_interval(mavlink_subs.armed_sub, 100); /* 10Hz updates */
+ mavlink_subs.safety_sub = orb_subscribe(ORB_ID(actuator_safety));
+ orb_set_interval(mavlink_subs.safety_sub, 100); /* 10Hz updates */
/* --- MAPPED MANUAL CONTROL INPUTS --- */
mavlink_subs.man_control_sp_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
diff --git a/src/modules/mavlink/orb_topics.h b/src/modules/mavlink/orb_topics.h
index 73e278dc6..3b968b911 100644
--- a/src/modules/mavlink/orb_topics.h
+++ b/src/modules/mavlink/orb_topics.h
@@ -55,10 +55,12 @@
#include <uORB/topics/vehicle_global_position_set_triplet.h>
#include <uORB/topics/vehicle_attitude_setpoint.h>
#include <uORB/topics/vehicle_rates_setpoint.h>
+#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/optical_flow.h>
#include <uORB/topics/actuator_outputs.h>
#include <uORB/topics/actuator_controls_effective.h>
#include <uORB/topics/actuator_controls.h>
+#include <uORB/topics/actuator_safety.h>
#include <uORB/topics/manual_control_setpoint.h>
#include <uORB/topics/telemetry_status.h>
#include <uORB/topics/debug_key_value.h>
@@ -75,7 +77,7 @@ struct mavlink_subscriptions {
int act_3_sub;
int gps_sub;
int man_control_sp_sub;
- int armed_sub;
+ int safety_sub;
int actuators_sub;
int local_pos_sub;
int spa_sub;
diff --git a/src/modules/mavlink_onboard/mavlink.c b/src/modules/mavlink_onboard/mavlink.c
index cb6d6b16a..35d53b880 100644
--- a/src/modules/mavlink_onboard/mavlink.c
+++ b/src/modules/mavlink_onboard/mavlink.c
@@ -274,83 +274,89 @@ void mavlink_update_system(void)
}
void
-get_mavlink_mode_and_state(const struct vehicle_status_s *v_status, const struct actuator_armed_s *armed,
+get_mavlink_mode_and_state(const struct vehicle_control_mode_s *control_mode, const struct actuator_safety_s *safety,
uint8_t *mavlink_state, uint8_t *mavlink_mode)
{
/* reset MAVLink mode bitfield */
*mavlink_mode = 0;
/* set mode flags independent of system state */
- if (v_status->flag_control_manual_enabled) {
+ if (control_mode->flag_control_manual_enabled) {
*mavlink_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
}
- if (v_status->flag_hil_enabled) {
+ if (safety->hil_enabled) {
*mavlink_mode |= MAV_MODE_FLAG_HIL_ENABLED;
}
/* set arming state */
- if (armed->armed) {
+ if (safety->armed) {
*mavlink_mode |= MAV_MODE_FLAG_SAFETY_ARMED;
} else {
*mavlink_mode &= ~MAV_MODE_FLAG_SAFETY_ARMED;
}
- switch (v_status->state_machine) {
- case SYSTEM_STATE_PREFLIGHT:
- if (v_status->flag_preflight_gyro_calibration ||
- v_status->flag_preflight_mag_calibration ||
- v_status->flag_preflight_accel_calibration) {
- *mavlink_state = MAV_STATE_CALIBRATING;
- } else {
- *mavlink_state = MAV_STATE_UNINIT;
- }
- break;
-
- case SYSTEM_STATE_STANDBY:
- *mavlink_state = MAV_STATE_STANDBY;
- break;
-
- case SYSTEM_STATE_GROUND_READY:
- *mavlink_state = MAV_STATE_ACTIVE;
- break;
-
- case SYSTEM_STATE_MANUAL:
- *mavlink_state = MAV_STATE_ACTIVE;
- *mavlink_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
- break;
-
- case SYSTEM_STATE_STABILIZED:
- *mavlink_state = MAV_STATE_ACTIVE;
- *mavlink_mode |= MAV_MODE_FLAG_STABILIZE_ENABLED;
- break;
-
- case SYSTEM_STATE_AUTO:
- *mavlink_state = MAV_STATE_ACTIVE;
+ if (control_mode->flag_control_velocity_enabled) {
*mavlink_mode |= MAV_MODE_FLAG_GUIDED_ENABLED;
- break;
-
- case SYSTEM_STATE_MISSION_ABORT:
- *mavlink_state = MAV_STATE_EMERGENCY;
- break;
-
- case SYSTEM_STATE_EMCY_LANDING:
- *mavlink_state = MAV_STATE_EMERGENCY;
- break;
-
- case SYSTEM_STATE_EMCY_CUTOFF:
- *mavlink_state = MAV_STATE_EMERGENCY;
- break;
-
- case SYSTEM_STATE_GROUND_ERROR:
- *mavlink_state = MAV_STATE_EMERGENCY;
- break;
-
- case SYSTEM_STATE_REBOOT:
- *mavlink_state = MAV_STATE_POWEROFF;
- break;
+ } else {
+ *mavlink_mode &= ~MAV_MODE_FLAG_GUIDED_ENABLED;
}
+// switch (v_status->state_machine) {
+// case SYSTEM_STATE_PREFLIGHT:
+// if (v_status->flag_preflight_gyro_calibration ||
+// v_status->flag_preflight_mag_calibration ||
+// v_status->flag_preflight_accel_calibration) {
+// *mavlink_state = MAV_STATE_CALIBRATING;
+// } else {
+// *mavlink_state = MAV_STATE_UNINIT;
+// }
+// break;
+//
+// case SYSTEM_STATE_STANDBY:
+// *mavlink_state = MAV_STATE_STANDBY;
+// break;
+//
+// case SYSTEM_STATE_GROUND_READY:
+// *mavlink_state = MAV_STATE_ACTIVE;
+// break;
+//
+// case SYSTEM_STATE_MANUAL:
+// *mavlink_state = MAV_STATE_ACTIVE;
+// *mavlink_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
+// break;
+//
+// case SYSTEM_STATE_STABILIZED:
+// *mavlink_state = MAV_STATE_ACTIVE;
+// *mavlink_mode |= MAV_MODE_FLAG_STABILIZE_ENABLED;
+// break;
+//
+// case SYSTEM_STATE_AUTO:
+// *mavlink_state = MAV_STATE_ACTIVE;
+// *mavlink_mode |= MAV_MODE_FLAG_GUIDED_ENABLED;
+// break;
+//
+// case SYSTEM_STATE_MISSION_ABORT:
+// *mavlink_state = MAV_STATE_EMERGENCY;
+// break;
+//
+// case SYSTEM_STATE_EMCY_LANDING:
+// *mavlink_state = MAV_STATE_EMERGENCY;
+// break;
+//
+// case SYSTEM_STATE_EMCY_CUTOFF:
+// *mavlink_state = MAV_STATE_EMERGENCY;
+// break;
+//
+// case SYSTEM_STATE_GROUND_ERROR:
+// *mavlink_state = MAV_STATE_EMERGENCY;
+// break;
+//
+// case SYSTEM_STATE_REBOOT:
+// *mavlink_state = MAV_STATE_POWEROFF;
+// break;
+// }
+
}
/**
@@ -362,8 +368,10 @@ int mavlink_thread_main(int argc, char *argv[])
char *device_name = "/dev/ttyS1";
baudrate = 57600;
+ /* XXX this is never written? */
struct vehicle_status_s v_status;
- struct actuator_armed_s armed;
+ struct vehicle_control_mode_s control_mode;
+ struct actuator_safety_s safety;
/* work around some stupidity in task_create's argv handling */
argc -= 2;
@@ -431,10 +439,10 @@ int mavlink_thread_main(int argc, char *argv[])
/* translate the current system state to mavlink state and mode */
uint8_t mavlink_state = 0;
uint8_t mavlink_mode = 0;
- get_mavlink_mode_and_state(&v_status, &armed, &mavlink_state, &mavlink_mode);
+ get_mavlink_mode_and_state(&control_mode, &safety, &mavlink_state, &mavlink_mode);
/* send heartbeat */
- mavlink_msg_heartbeat_send(chan, mavlink_system.type, MAV_AUTOPILOT_PX4, mavlink_mode, v_status.state_machine, mavlink_state);
+ mavlink_msg_heartbeat_send(chan, mavlink_system.type, MAV_AUTOPILOT_PX4, mavlink_mode, v_status.navigation_state, mavlink_state);
/* send status (values already copied in the section above) */
mavlink_msg_sys_status_send(chan,
diff --git a/src/modules/mavlink_onboard/mavlink_receiver.c b/src/modules/mavlink_onboard/mavlink_receiver.c
index 0acbea675..2d406fb9f 100644
--- a/src/modules/mavlink_onboard/mavlink_receiver.c
+++ b/src/modules/mavlink_onboard/mavlink_receiver.c
@@ -328,4 +328,4 @@ receive_start(int uart)
pthread_t thread;
pthread_create(&thread, &receiveloop_attr, receive_thread, &uart);
return thread;
-} \ No newline at end of file
+}
diff --git a/src/modules/mavlink_onboard/orb_topics.h b/src/modules/mavlink_onboard/orb_topics.h
index f18f56243..f01f09e12 100644
--- a/src/modules/mavlink_onboard/orb_topics.h
+++ b/src/modules/mavlink_onboard/orb_topics.h
@@ -52,9 +52,11 @@
#include <uORB/topics/vehicle_vicon_position.h>
#include <uORB/topics/vehicle_global_position_setpoint.h>
#include <uORB/topics/vehicle_attitude_setpoint.h>
+#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/optical_flow.h>
#include <uORB/topics/actuator_outputs.h>
#include <uORB/topics/actuator_controls.h>
+#include <uORB/topics/actuator_safety.h>
#include <uORB/topics/manual_control_setpoint.h>
#include <uORB/topics/debug_key_value.h>
#include <drivers/drv_rc_input.h>
@@ -69,7 +71,7 @@ struct mavlink_subscriptions {
int act_3_sub;
int gps_sub;
int man_control_sp_sub;
- int armed_sub;
+ int safety_sub;
int actuators_sub;
int local_pos_sub;
int spa_sub;
diff --git a/src/modules/mavlink_onboard/util.h b/src/modules/mavlink_onboard/util.h
index 38a4db372..c6a2e52bf 100644
--- a/src/modules/mavlink_onboard/util.h
+++ b/src/modules/mavlink_onboard/util.h
@@ -50,5 +50,6 @@ extern volatile bool thread_should_exit;
/**
* Translate the custom state into standard mavlink modes and state.
*/
-extern void get_mavlink_mode_and_state(const struct vehicle_status_s *v_status, const struct actuator_armed_s *armed,
+extern void
+get_mavlink_mode_and_state(const struct vehicle_control_mode_s *control_mode, const struct actuator_safety_s *safety,
uint8_t *mavlink_state, uint8_t *mavlink_mode);
diff --git a/src/modules/multirotor_att_control/multirotor_att_control_main.c b/src/modules/multirotor_att_control/multirotor_att_control_main.c
index 99f25cfe9..70a61fc4e 100644
--- a/src/modules/multirotor_att_control/multirotor_att_control_main.c
+++ b/src/modules/multirotor_att_control/multirotor_att_control_main.c
@@ -57,12 +57,14 @@
#include <drivers/drv_hrt.h>
#include <uORB/uORB.h>
#include <drivers/drv_gyro.h>
-#include <uORB/topics/vehicle_status.h>
+#include <uORB/topics/vehicle_control_mode.h>
+#include <uORB/topics/actuator_safety.h>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_attitude_setpoint.h>
#include <uORB/topics/manual_control_setpoint.h>
#include <uORB/topics/offboard_control_setpoint.h>
#include <uORB/topics/vehicle_rates_setpoint.h>
+#include <uORB/topics/vehicle_control_debug.h>
#include <uORB/topics/sensor_combined.h>
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/parameter_update.h>
@@ -83,14 +85,17 @@ static int mc_task;
static bool motor_test_mode = false;
static orb_advert_t actuator_pub;
+static orb_advert_t control_debug_pub;
-static struct vehicle_status_s state;
static int
mc_thread_main(int argc, char *argv[])
{
/* declare and safely initialize all structs */
- memset(&state, 0, sizeof(state));
+ struct vehicle_control_mode_s control_mode;
+ memset(&control_mode, 0, sizeof(control_mode));
+ struct actuator_safety_s safety;
+ memset(&safety, 0, sizeof(safety));
struct vehicle_attitude_s att;
memset(&att, 0, sizeof(att));
struct vehicle_attitude_setpoint_s att_sp;
@@ -107,12 +112,16 @@ mc_thread_main(int argc, char *argv[])
struct actuator_controls_s actuators;
memset(&actuators, 0, sizeof(actuators));
+ struct vehicle_control_debug_s control_debug;
+ memset(&control_debug, 0, sizeof(control_debug));
+
/* subscribe to attitude, motor setpoints and system state */
int att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
int param_sub = orb_subscribe(ORB_ID(parameter_update));
int att_setpoint_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint));
int setpoint_sub = orb_subscribe(ORB_ID(offboard_control_setpoint));
- int state_sub = orb_subscribe(ORB_ID(vehicle_status));
+ int control_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode));
+ int safety_sub = orb_subscribe(ORB_ID(actuator_safety));
int manual_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
int sensor_sub = orb_subscribe(ORB_ID(sensor_combined));
@@ -133,6 +142,8 @@ mc_thread_main(int argc, char *argv[])
for (unsigned i = 0; i < NUM_ACTUATOR_CONTROLS; i++) {
actuators.control[i] = 0.0f;
}
+
+ control_debug_pub = orb_advertise(ORB_ID(vehicle_control_debug), &control_debug);
actuator_pub = orb_advertise(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, &actuators);
orb_advert_t att_sp_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &att_sp);
@@ -150,7 +161,9 @@ mc_thread_main(int argc, char *argv[])
/* store last control mode to detect mode switches */
bool flag_control_manual_enabled = false;
bool flag_control_attitude_enabled = false;
- bool flag_system_armed = false;
+ bool flag_armed = false;
+ bool flag_control_position_enabled = false;
+ bool flag_control_velocity_enabled = false;
/* store if yaw position or yaw speed has been changed */
bool control_yaw_position = true;
@@ -162,7 +175,6 @@ mc_thread_main(int argc, char *argv[])
param_t failsafe_throttle_handle = param_find("MC_RCLOSS_THR");
float failsafe_throttle = 0.0f;
-
while (!thread_should_exit) {
/* wait for a sensor update, check for exit condition every 500 ms */
@@ -175,7 +187,6 @@ mc_thread_main(int argc, char *argv[])
} else if (ret == 0) {
/* no return value, ignore */
} else {
-
/* only update parameters if they changed */
if (fds[1].revents & POLLIN) {
/* read from param to clear updated flag */
@@ -193,10 +204,16 @@ mc_thread_main(int argc, char *argv[])
/* get a local copy of system state */
bool updated;
- orb_check(state_sub, &updated);
+ orb_check(control_mode_sub, &updated);
+
+ if (updated) {
+ orb_copy(ORB_ID(vehicle_control_mode), control_mode_sub, &control_mode);
+ }
+
+ orb_check(safety_sub, &updated);
if (updated) {
- orb_copy(ORB_ID(vehicle_status), state_sub, &state);
+ orb_copy(ORB_ID(actuator_safety), safety_sub, &safety);
}
/* get a local copy of manual setpoint */
@@ -215,9 +232,8 @@ mc_thread_main(int argc, char *argv[])
/* get a local copy of the current sensor values */
orb_copy(ORB_ID(sensor_combined), sensor_sub, &raw);
-
/** STEP 1: Define which input is the dominating control input */
- if (state.flag_control_offboard_enabled) {
+ if (control_mode.flag_control_offboard_enabled) {
/* offboard inputs */
if (offboard_sp.mode == OFFBOARD_CONTROL_MODE_DIRECT_RATES) {
rates_sp.roll = offboard_sp.p1;
@@ -240,102 +256,51 @@ mc_thread_main(int argc, char *argv[])
}
- } else if (state.flag_control_manual_enabled) {
-
- if (state.flag_control_attitude_enabled) {
-
+ } else if (control_mode.flag_control_manual_enabled) {
+ if (control_mode.flag_control_attitude_enabled) {
/* initialize to current yaw if switching to manual or att control */
- if (state.flag_control_attitude_enabled != flag_control_attitude_enabled ||
- state.flag_control_manual_enabled != flag_control_manual_enabled ||
- state.flag_system_armed != flag_system_armed) {
+ if (control_mode.flag_control_attitude_enabled != flag_control_attitude_enabled ||
+ control_mode.flag_control_manual_enabled != flag_control_manual_enabled ||
+ safety.armed != flag_armed) {
att_sp.yaw_body = att.yaw;
}
static bool rc_loss_first_time = true;
/* if the RC signal is lost, try to stay level and go slowly back down to ground */
- if (state.rc_signal_lost) {
- /* the failsafe throttle is stored as a parameter, as it depends on the copter and the payload */
- param_get(failsafe_throttle_handle, &failsafe_throttle);
- att_sp.roll_body = 0.0f;
- att_sp.pitch_body = 0.0f;
- /*
- * Only go to failsafe throttle if last known throttle was
- * high enough to create some lift to make hovering state likely.
- *
- * This is to prevent that someone landing, but not disarming his
- * multicopter (throttle = 0) does not make it jump up in the air
- * if shutting down his remote.
- */
- if (isfinite(manual.throttle) && manual.throttle > 0.2f) {
- att_sp.thrust = failsafe_throttle;
-
- } else {
- att_sp.thrust = 0.0f;
- }
-
- /* keep current yaw, do not attempt to go to north orientation,
- * since if the pilot regains RC control, he will be lost regarding
- * the current orientation.
- */
- if (rc_loss_first_time)
- att_sp.yaw_body = att.yaw;
+ rc_loss_first_time = true;
- rc_loss_first_time = false;
+ att_sp.roll_body = manual.roll;
+ att_sp.pitch_body = manual.pitch;
- } else {
- rc_loss_first_time = true;
+ /* set attitude if arming */
+ if (!flag_control_attitude_enabled && safety.armed) {
+ att_sp.yaw_body = att.yaw;
+ }
- att_sp.roll_body = manual.roll;
- att_sp.pitch_body = manual.pitch;
+ /* only move setpoint if manual input is != 0 */
+ if ((manual.yaw < -0.01f || 0.01f < manual.yaw) && manual.throttle > 0.1f) {
+ rates_sp.yaw = manual.yaw;
+ control_yaw_position = false;
+ first_time_after_yaw_speed_control = true;
- /* set attitude if arming */
- if (!flag_control_attitude_enabled && state.flag_system_armed) {
+ } else {
+ if (first_time_after_yaw_speed_control) {
att_sp.yaw_body = att.yaw;
+ first_time_after_yaw_speed_control = false;
}
- /* act if stabilization is active or if the (nonsense) direct pass through mode is set */
- if (state.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_SAS ||
- state.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_DIRECT) {
-
- if (state.manual_sas_mode == VEHICLE_MANUAL_SAS_MODE_ROLL_PITCH_ABS_YAW_RATE) {
- rates_sp.yaw = manual.yaw;
- control_yaw_position = false;
-
- } else {
- /*
- * This mode SHOULD be the default mode, which is:
- * VEHICLE_MANUAL_SAS_MODE_ROLL_PITCH_ABS_YAW_ABS
- *
- * However, we fall back to this setting for all other (nonsense)
- * settings as well.
- */
-
- /* only move setpoint if manual input is != 0 */
- if ((manual.yaw < -0.01f || 0.01f < manual.yaw) && manual.throttle > 0.3f) {
- rates_sp.yaw = manual.yaw;
- control_yaw_position = false;
- first_time_after_yaw_speed_control = true;
-
- } else {
- if (first_time_after_yaw_speed_control) {
- att_sp.yaw_body = att.yaw;
- first_time_after_yaw_speed_control = false;
- }
-
- control_yaw_position = true;
- }
- }
- }
-
- att_sp.thrust = manual.throttle;
- att_sp.timestamp = hrt_absolute_time();
+ control_yaw_position = true;
}
+ att_sp.thrust = manual.throttle;
+ att_sp.timestamp = hrt_absolute_time();
+
/* STEP 2: publish the controller output */
orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp);
+
if (motor_test_mode) {
printf("testmode");
att_sp.roll_body = 0.0f;
@@ -348,23 +313,26 @@ mc_thread_main(int argc, char *argv[])
}
} else {
- /* manual rate inputs, from RC control or joystick */
- if (state.flag_control_rates_enabled &&
- state.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_RATES) {
- rates_sp.roll = manual.roll;
- rates_sp.pitch = manual.pitch;
- rates_sp.yaw = manual.yaw;
- rates_sp.thrust = manual.throttle;
- rates_sp.timestamp = hrt_absolute_time();
- }
+ //XXX TODO add acro mode here
+
+ /* manual rate inputs, from RC control or joystick */
+// if (state.flag_control_rates_enabled &&
+// state.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_RATES) {
+// rates_sp.roll = manual.roll;
+//
+// rates_sp.pitch = manual.pitch;
+// rates_sp.yaw = manual.yaw;
+// rates_sp.thrust = manual.throttle;
+// rates_sp.timestamp = hrt_absolute_time();
+// }
}
}
/** STEP 3: Identify the controller setup to run and set up the inputs correctly */
- if (state.flag_control_attitude_enabled) {
- multirotor_control_attitude(&att_sp, &att, &rates_sp, control_yaw_position);
+ if (control_mode.flag_control_attitude_enabled) {
+ multirotor_control_attitude(&att_sp, &att, &rates_sp, control_yaw_position, &control_debug_pub, &control_debug);
orb_publish(ORB_ID(vehicle_rates_setpoint), rates_sp_pub, &rates_sp);
}
@@ -372,7 +340,8 @@ mc_thread_main(int argc, char *argv[])
/* measure in what intervals the controller runs */
perf_count(mc_interval_perf);
- float gyro[3];
+ float rates[3];
+ float rates_acc[3];
/* get current rate setpoint */
bool rates_sp_valid = false;
@@ -383,17 +352,21 @@ mc_thread_main(int argc, char *argv[])
}
/* apply controller */
- gyro[0] = att.rollspeed;
- gyro[1] = att.pitchspeed;
- gyro[2] = att.yawspeed;
+ rates[0] = att.rollspeed;
+ rates[1] = att.pitchspeed;
+ rates[2] = att.yawspeed;
- multirotor_control_rates(&rates_sp, gyro, &actuators);
+ multirotor_control_rates(&rates_sp, rates, &actuators, &control_debug_pub, &control_debug);
orb_publish(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_pub, &actuators);
- /* update state */
- flag_control_attitude_enabled = state.flag_control_attitude_enabled;
- flag_control_manual_enabled = state.flag_control_manual_enabled;
- flag_system_armed = state.flag_system_armed;
+ orb_publish(ORB_ID(vehicle_control_debug), control_debug_pub, &control_debug);
+
+ /* update control_mode */
+ flag_control_attitude_enabled = control_mode.flag_control_attitude_enabled;
+ flag_control_manual_enabled = control_mode.flag_control_manual_enabled;
+ flag_control_position_enabled = control_mode.flag_control_position_enabled;
+ flag_control_velocity_enabled = control_mode.flag_control_velocity_enabled;
+ flag_armed = safety.armed;
perf_end(mc_loop_perf);
} /* end of poll call for attitude updates */
@@ -410,7 +383,7 @@ mc_thread_main(int argc, char *argv[])
close(att_sub);
- close(state_sub);
+ close(control_mode_sub);
close(manual_sub);
close(actuator_pub);
close(att_sp_pub);
diff --git a/src/modules/multirotor_att_control/multirotor_attitude_control.c b/src/modules/multirotor_att_control/multirotor_attitude_control.c
index 8f19c6a4b..083311674 100644
--- a/src/modules/multirotor_att_control/multirotor_attitude_control.c
+++ b/src/modules/multirotor_att_control/multirotor_attitude_control.c
@@ -65,50 +65,29 @@
PARAM_DEFINE_FLOAT(MC_YAWPOS_P, 0.3f);
PARAM_DEFINE_FLOAT(MC_YAWPOS_I, 0.15f);
PARAM_DEFINE_FLOAT(MC_YAWPOS_D, 0.0f);
-//PARAM_DEFINE_FLOAT(MC_YAWPOS_AWU, 1.0f);
-//PARAM_DEFINE_FLOAT(MC_YAWPOS_LIM, 3.0f);
PARAM_DEFINE_FLOAT(MC_ATT_P, 0.2f);
PARAM_DEFINE_FLOAT(MC_ATT_I, 0.0f);
PARAM_DEFINE_FLOAT(MC_ATT_D, 0.05f);
-//PARAM_DEFINE_FLOAT(MC_ATT_AWU, 0.05f);
-//PARAM_DEFINE_FLOAT(MC_ATT_LIM, 0.4f);
-
-//PARAM_DEFINE_FLOAT(MC_ATT_XOFF, 0.0f);
-//PARAM_DEFINE_FLOAT(MC_ATT_YOFF, 0.0f);
struct mc_att_control_params {
float yaw_p;
float yaw_i;
float yaw_d;
- //float yaw_awu;
- //float yaw_lim;
float att_p;
float att_i;
float att_d;
- //float att_awu;
- //float att_lim;
-
- //float att_xoff;
- //float att_yoff;
};
struct mc_att_control_param_handles {
param_t yaw_p;
param_t yaw_i;
param_t yaw_d;
- //param_t yaw_awu;
- //param_t yaw_lim;
param_t att_p;
param_t att_i;
param_t att_d;
- //param_t att_awu;
- //param_t att_lim;
-
- //param_t att_xoff;
- //param_t att_yoff;
};
/**
@@ -130,17 +109,10 @@ static int parameters_init(struct mc_att_control_param_handles *h)
h->yaw_p = param_find("MC_YAWPOS_P");
h->yaw_i = param_find("MC_YAWPOS_I");
h->yaw_d = param_find("MC_YAWPOS_D");
- //h->yaw_awu = param_find("MC_YAWPOS_AWU");
- //h->yaw_lim = param_find("MC_YAWPOS_LIM");
h->att_p = param_find("MC_ATT_P");
h->att_i = param_find("MC_ATT_I");
h->att_d = param_find("MC_ATT_D");
- //h->att_awu = param_find("MC_ATT_AWU");
- //h->att_lim = param_find("MC_ATT_LIM");
-
- //h->att_xoff = param_find("MC_ATT_XOFF");
- //h->att_yoff = param_find("MC_ATT_YOFF");
return OK;
}
@@ -150,23 +122,17 @@ static int parameters_update(const struct mc_att_control_param_handles *h, struc
param_get(h->yaw_p, &(p->yaw_p));
param_get(h->yaw_i, &(p->yaw_i));
param_get(h->yaw_d, &(p->yaw_d));
- //param_get(h->yaw_awu, &(p->yaw_awu));
- //param_get(h->yaw_lim, &(p->yaw_lim));
param_get(h->att_p, &(p->att_p));
param_get(h->att_i, &(p->att_i));
param_get(h->att_d, &(p->att_d));
- //param_get(h->att_awu, &(p->att_awu));
- //param_get(h->att_lim, &(p->att_lim));
-
- //param_get(h->att_xoff, &(p->att_xoff));
- //param_get(h->att_yoff, &(p->att_yoff));
return OK;
}
void multirotor_control_attitude(const struct vehicle_attitude_setpoint_s *att_sp,
- const struct vehicle_attitude_s *att, struct vehicle_rates_setpoint_s *rates_sp, bool control_yaw_position)
+ const struct vehicle_attitude_s *att, struct vehicle_rates_setpoint_s *rates_sp, bool control_yaw_position,
+ const orb_advert_t *control_debug_pub, struct vehicle_control_debug_s *control_debug)
{
static uint64_t last_run = 0;
static uint64_t last_input = 0;
@@ -207,7 +173,7 @@ void multirotor_control_attitude(const struct vehicle_attitude_setpoint_s *att_s
/* apply parameters */
pid_set_parameters(&pitch_controller, p.att_p, p.att_i, p.att_d, 1000.0f, 1000.0f);
- pid_set_parameters(&roll_controller, p.att_p, p.att_i, p.att_d, 1000.0f, 1000.0f);
+ pid_set_parameters(&roll_controller, p.att_p, p.att_i, p.att_d, 1000.0f, 1000.0f);
}
/* reset integral if on ground */
@@ -221,11 +187,13 @@ void multirotor_control_attitude(const struct vehicle_attitude_setpoint_s *att_s
/* control pitch (forward) output */
rates_sp->pitch = pid_calculate(&pitch_controller, att_sp->pitch_body ,
- att->pitch, att->pitchspeed, deltaT);
+ att->pitch, att->pitchspeed, deltaT, &control_debug->pitch_p, &control_debug->pitch_i, &control_debug->pitch_d);
/* control roll (left/right) output */
rates_sp->roll = pid_calculate(&roll_controller, att_sp->roll_body ,
- att->roll, att->rollspeed, deltaT);
+ att->roll, att->rollspeed, deltaT, NULL, NULL, NULL);
+
+ // printf("rates_sp: %4.4f, att setpoint: %4.4f\n, pitch: %4.4f, pitchspeed: %4.4f, dT: %4.4f", rates_sp->pitch, att_sp->pitch_body, att->pitch, att->pitchspeed, deltaT);
if (control_yaw_position) {
/* control yaw rate */
diff --git a/src/modules/multirotor_att_control/multirotor_attitude_control.h b/src/modules/multirotor_att_control/multirotor_attitude_control.h
index e78f45c47..6dd5b39fd 100644
--- a/src/modules/multirotor_att_control/multirotor_attitude_control.h
+++ b/src/modules/multirotor_att_control/multirotor_attitude_control.h
@@ -58,8 +58,11 @@
#include <uORB/topics/vehicle_attitude_setpoint.h>
#include <uORB/topics/vehicle_rates_setpoint.h>
#include <uORB/topics/actuator_controls.h>
+#include <uORB/topics/vehicle_control_debug.h>
+
void multirotor_control_attitude(const struct vehicle_attitude_setpoint_s *att_sp,
- const struct vehicle_attitude_s *att, struct vehicle_rates_setpoint_s *rates_sp, bool control_yaw_position);
+ const struct vehicle_attitude_s *att, struct vehicle_rates_setpoint_s *rates_sp, bool control_yaw_position,
+ const orb_advert_t *control_debug_pub, struct vehicle_control_debug_s *control_debug);
#endif /* MULTIROTOR_ATTITUDE_CONTROL_H_ */
diff --git a/src/modules/multirotor_att_control/multirotor_rate_control.c b/src/modules/multirotor_att_control/multirotor_rate_control.c
index e58d357d5..ee8c37580 100644
--- a/src/modules/multirotor_att_control/multirotor_rate_control.c
+++ b/src/modules/multirotor_att_control/multirotor_rate_control.c
@@ -58,6 +58,9 @@
#include <systemlib/param/param.h>
#include <systemlib/err.h>
#include <drivers/drv_hrt.h>
+#include <uORB/uORB.h>
+
+
PARAM_DEFINE_FLOAT(MC_YAWRATE_P, 0.0f); /* same on Flamewheel */
PARAM_DEFINE_FLOAT(MC_YAWRATE_D, 0.0f);
@@ -152,7 +155,8 @@ static int parameters_update(const struct mc_rate_control_param_handles *h, stru
}
void multirotor_control_rates(const struct vehicle_rates_setpoint_s *rate_sp,
- const float rates[], struct actuator_controls_s *actuators)
+ const float rates[], struct actuator_controls_s *actuators,
+ const orb_advert_t *control_debug_pub, struct vehicle_control_debug_s *control_debug)
{
static uint64_t last_run = 0;
const float deltaT = (hrt_absolute_time() - last_run) / 1000000.0f;
@@ -172,8 +176,13 @@ void multirotor_control_rates(const struct vehicle_rates_setpoint_s *rate_sp,
static struct mc_rate_control_params p;
static struct mc_rate_control_param_handles h;
+ float pitch_control_last = 0.0f;
+ float roll_control_last = 0.0f;
+
static bool initialized = false;
+ float diff_filter_factor = 1.0f;
+
/* initialize the pid controllers when the function is called for the first time */
if (initialized == false) {
parameters_init(&h);
@@ -201,11 +210,13 @@ void multirotor_control_rates(const struct vehicle_rates_setpoint_s *rate_sp,
/* control pitch (forward) output */
float pitch_control = pid_calculate(&pitch_rate_controller, rate_sp->pitch ,
- rates[1], 0.0f, deltaT);
+ rates[1], 0.0f, deltaT,
+ &control_debug->pitch_rate_p, &control_debug->pitch_rate_i, &control_debug->pitch_rate_d);
/* control roll (left/right) output */
float roll_control = pid_calculate(&roll_rate_controller, rate_sp->roll ,
- rates[0], 0.0f, deltaT);
+ rates[0], 0.0f, deltaT,
+ &control_debug->roll_rate_p, &control_debug->roll_rate_i, &control_debug->roll_rate_d);
/* control yaw rate */ //XXX use library here
float yaw_rate_control = p.yawrate_p * (rate_sp->yaw - rates[2]);
diff --git a/src/modules/multirotor_att_control/multirotor_rate_control.h b/src/modules/multirotor_att_control/multirotor_rate_control.h
index 362b5ed86..695ff3e16 100644
--- a/src/modules/multirotor_att_control/multirotor_rate_control.h
+++ b/src/modules/multirotor_att_control/multirotor_rate_control.h
@@ -57,8 +57,10 @@
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_rates_setpoint.h>
#include <uORB/topics/actuator_controls.h>
+#include <uORB/topics/vehicle_control_debug.h>
void multirotor_control_rates(const struct vehicle_rates_setpoint_s *rate_sp,
- const float rates[], struct actuator_controls_s *actuators);
+ const float rates[], struct actuator_controls_s *actuators,
+ const orb_advert_t *control_debug_pub, struct vehicle_control_debug_s *control_debug);
#endif /* MULTIROTOR_RATE_CONTROL_H_ */
diff --git a/src/modules/px4iofirmware/mixer.cpp b/src/modules/px4iofirmware/mixer.cpp
index a2193b526..fe9166779 100644
--- a/src/modules/px4iofirmware/mixer.cpp
+++ b/src/modules/px4iofirmware/mixer.cpp
@@ -59,6 +59,12 @@ extern "C" {
*/
#define FMU_INPUT_DROP_LIMIT_US 200000
+/*
+ * Time that the ESCs need to initialize
+ */
+ #define ESC_INIT_TIME_US 1000000
+ #define ESC_RAMP_TIME_US 2000000
+
/* XXX need to move the RC_CHANNEL_FUNCTION out of rc_channels.h and into systemlib */
#define ROLL 0
#define PITCH 1
@@ -68,6 +74,17 @@ extern "C" {
/* current servo arm/disarm state */
static bool mixer_servos_armed = false;
+static bool should_arm = false;
+static bool should_always_enable_pwm = false;
+static uint64_t esc_init_time;
+
+enum esc_state_e {
+ ESC_OFF,
+ ESC_INIT,
+ ESC_RAMP,
+ ESC_ON
+};
+static esc_state_e esc_state;
/* selected control values and count for mixing */
enum mixer_source {
@@ -98,7 +115,7 @@ mixer_tick(void)
if (r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK) {
isr_debug(1, "AP RX timeout");
}
- r_status_flags &= ~(PX4IO_P_STATUS_FLAGS_FMU_OK | PX4IO_P_STATUS_FLAGS_RAW_PWM);
+ r_status_flags &= ~(PX4IO_P_STATUS_FLAGS_FMU_OK);
r_status_alarms |= PX4IO_P_STATUS_ALARMS_FMU_LOST;
} else {
@@ -112,12 +129,11 @@ mixer_tick(void)
* Decide which set of controls we're using.
*/
- /* do not mix if mixer is invalid or if RAW_PWM mode is on and FMU is good */
+ /* do not mix if RAW_PWM mode is on and FMU is good */
if ((r_status_flags & PX4IO_P_STATUS_FLAGS_RAW_PWM) &&
- !(r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK)) {
+ (r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK)) {
- /* don't actually mix anything - we already have raw PWM values or
- not a valid mixer. */
+ /* don't actually mix anything - we already have raw PWM values */
source = MIX_NONE;
} else {
@@ -167,6 +183,48 @@ mixer_tick(void)
float outputs[IO_SERVO_COUNT];
unsigned mixed;
+ uint16_t ramp_promille;
+
+ /* update esc init state, but only if we are truely armed and not just PWM enabled */
+ if (mixer_servos_armed && should_arm) {
+
+ switch (esc_state) {
+
+ /* after arming, some ESCs need an initalization period, count the time from here */
+ case ESC_OFF:
+ esc_init_time = hrt_absolute_time();
+ esc_state = ESC_INIT;
+ break;
+
+ /* after waiting long enough for the ESC initialization, we can start with the ramp to start the ESCs */
+ case ESC_INIT:
+ if (hrt_elapsed_time(&esc_init_time) > ESC_INIT_TIME_US) {
+ esc_state = ESC_RAMP;
+ }
+ break;
+
+ /* then ramp until the min speed is reached */
+ case ESC_RAMP:
+ if (hrt_elapsed_time(&esc_init_time) > (ESC_INIT_TIME_US + ESC_RAMP_TIME_US)) {
+ esc_state = ESC_ON;
+ }
+ break;
+
+ case ESC_ON:
+ default:
+
+ break;
+ }
+ } else {
+ esc_state = ESC_OFF;
+ }
+
+ /* do the calculations during the ramp for all at once */
+ if(esc_state == ESC_RAMP) {
+ ramp_promille = (1000*(hrt_elapsed_time(&esc_init_time)-ESC_INIT_TIME_US))/ESC_RAMP_TIME_US;
+ }
+
+
/* mix */
mixed = mixer_group.mix(&outputs[0], IO_SERVO_COUNT);
@@ -176,9 +234,27 @@ mixer_tick(void)
/* save actuator values for FMU readback */
r_page_actuators[i] = FLOAT_TO_REG(outputs[i]);
- /* scale to servo output */
- r_page_servos[i] = (outputs[i] * 600.0f) + 1500;
-
+ switch (esc_state) {
+ case ESC_INIT:
+ r_page_servos[i] = (outputs[i] * 600 + 1500);
+ break;
+
+ case ESC_RAMP:
+ r_page_servos[i] = (outputs[i]
+ * (ramp_promille*r_page_servo_control_max[i] + (1000-ramp_promille)*2100 - ramp_promille*r_page_servo_control_min[i] - (1000-ramp_promille)*900)/2/1000
+ + (ramp_promille*r_page_servo_control_max[i] + (1000-ramp_promille)*2100 + ramp_promille*r_page_servo_control_min[i] + (1000-ramp_promille)*900)/2/1000);
+ break;
+
+ case ESC_ON:
+ r_page_servos[i] = (outputs[i]
+ * (r_page_servo_control_max[i] - r_page_servo_control_min[i])/2
+ + (r_page_servo_control_max[i] + r_page_servo_control_min[i])/2);
+ break;
+
+ case ESC_OFF:
+ default:
+ break;
+ }
}
for (unsigned i = mixed; i < IO_SERVO_COUNT; i++)
r_page_servos[i] = 0;
@@ -193,30 +269,46 @@ mixer_tick(void)
* XXX correct behaviour for failsafe may require an additional case
* here.
*/
- bool should_arm = (
- /* FMU is armed */ (r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED) &&
- /* IO is armed */ (r_status_flags & PX4IO_P_STATUS_FLAGS_ARMED) &&
- /* there is valid input via direct PWM or mixer */ (r_status_flags & (PX4IO_P_STATUS_FLAGS_RAW_PWM | PX4IO_P_STATUS_FLAGS_MIXER_OK)) &&
- /* IO initialised without error */ (r_status_flags & PX4IO_P_STATUS_FLAGS_INIT_OK) &&
- /* FMU is available or FMU is not available but override is an option */
- ((r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK) || (!(r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK) && (r_setup_arming & PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK) ))
+ should_arm = (
+ /* IO initialised without error */ (r_status_flags & PX4IO_P_STATUS_FLAGS_INIT_OK)
+ /* and IO is armed */ && (r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF)
+ /* and FMU is armed */ && (
+ ((r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED)
+ /* and there is valid input via or mixer */ && (r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK) )
+ /* or direct PWM is set */ || (r_status_flags & PX4IO_P_STATUS_FLAGS_RAW_PWM)
+ /* or failsafe was set manually */ || (r_setup_arming & PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM)
+ )
);
- if (should_arm && !mixer_servos_armed) {
+ should_always_enable_pwm = (r_setup_arming & PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE)
+ && (r_status_flags & PX4IO_P_STATUS_FLAGS_INIT_OK)
+ && (r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK);
+
+ if ((should_arm || should_always_enable_pwm) && !mixer_servos_armed) {
/* need to arm, but not armed */
up_pwm_servo_arm(true);
mixer_servos_armed = true;
+ r_status_flags |= PX4IO_P_STATUS_FLAGS_OUTPUTS_ARMED;
+ isr_debug(5, "> PWM enabled");
- } else if (!should_arm && mixer_servos_armed) {
+ } else if ((!should_arm && !should_always_enable_pwm) && mixer_servos_armed) {
/* armed but need to disarm */
up_pwm_servo_arm(false);
mixer_servos_armed = false;
+ r_status_flags &= ~(PX4IO_P_STATUS_FLAGS_OUTPUTS_ARMED);
+ isr_debug(5, "> PWM disabled");
+
}
- if (mixer_servos_armed) {
+ if (mixer_servos_armed && should_arm) {
/* update the servo outputs. */
for (unsigned i = 0; i < IO_SERVO_COUNT; i++)
up_pwm_servo_set(i, r_page_servos[i]);
+
+ } else if (mixer_servos_armed && should_always_enable_pwm) {
+ /* set the idle servo outputs. */
+ for (unsigned i = 0; i < IO_SERVO_COUNT; i++)
+ up_pwm_servo_set(i, r_page_servo_idle[i]);
}
}
@@ -265,9 +357,8 @@ static unsigned mixer_text_length = 0;
void
mixer_handle_text(const void *buffer, size_t length)
{
- /* do not allow a mixer change while fully armed */
- if (/* FMU is armed */ (r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED) &&
- /* IO is armed */ (r_status_flags & PX4IO_P_STATUS_FLAGS_ARMED)) {
+ /* do not allow a mixer change while outputs armed */
+ if ((r_status_flags & PX4IO_P_STATUS_FLAGS_OUTPUTS_ARMED)) {
return;
}
@@ -344,6 +435,7 @@ mixer_set_failsafe()
* Check if a custom failsafe value has been written,
* or if the mixer is not ok and bail out.
*/
+
if ((r_setup_arming & PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM) ||
!(r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK))
return;
diff --git a/src/modules/px4iofirmware/protocol.h b/src/modules/px4iofirmware/protocol.h
index 674f9dddd..0e477a200 100644
--- a/src/modules/px4iofirmware/protocol.h
+++ b/src/modules/px4iofirmware/protocol.h
@@ -75,10 +75,13 @@
#define REG_TO_FLOAT(_reg) ((float)REG_TO_SIGNED(_reg) / 10000.0f)
#define FLOAT_TO_REG(_float) SIGNED_TO_REG((int16_t)((_float) * 10000.0f))
+#define PX4IO_P_CONFIG_PROTOCOL_VERSION_MAGIC 2
+#define PX4IO_P_CONFIG_SOFTWARE_VERSION_MAGIC 2
+
/* static configuration page */
#define PX4IO_PAGE_CONFIG 0
-#define PX4IO_P_CONFIG_PROTOCOL_VERSION 0 /* magic numbers TBD */
-#define PX4IO_P_CONFIG_SOFTWARE_VERSION 1 /* magic numbers TBD */
+#define PX4IO_P_CONFIG_PROTOCOL_VERSION 0 /* magic numbers */
+#define PX4IO_P_CONFIG_SOFTWARE_VERSION 1 /* magic numbers */
#define PX4IO_P_CONFIG_BOOTLOADER_VERSION 2 /* get this how? */
#define PX4IO_P_CONFIG_MAX_TRANSFER 3 /* maximum I2C transfer size */
#define PX4IO_P_CONFIG_CONTROL_COUNT 4 /* hardcoded max control count supported */
@@ -93,7 +96,7 @@
#define PX4IO_P_STATUS_CPULOAD 1
#define PX4IO_P_STATUS_FLAGS 2 /* monitoring flags */
-#define PX4IO_P_STATUS_FLAGS_ARMED (1 << 0) /* arm-ok and locally armed */
+#define PX4IO_P_STATUS_FLAGS_OUTPUTS_ARMED (1 << 0) /* arm-ok and locally armed */
#define PX4IO_P_STATUS_FLAGS_OVERRIDE (1 << 1) /* in manual override */
#define PX4IO_P_STATUS_FLAGS_RC_OK (1 << 2) /* RC input is valid */
#define PX4IO_P_STATUS_FLAGS_RC_PPM (1 << 3) /* PPM input is valid */
@@ -105,6 +108,7 @@
#define PX4IO_P_STATUS_FLAGS_ARM_SYNC (1 << 9) /* the arming state between IO and FMU is in sync */
#define PX4IO_P_STATUS_FLAGS_INIT_OK (1 << 10) /* initialisation of the IO completed without error */
#define PX4IO_P_STATUS_FLAGS_FAILSAFE (1 << 11) /* failsafe is active */
+#define PX4IO_P_STATUS_FLAGS_SAFETY_OFF (1 << 12) /* safety is off */
#define PX4IO_P_STATUS_ALARMS 3 /* alarm flags - alarms latch, write 1 to a bit to clear it */
#define PX4IO_P_STATUS_ALARMS_VBATT_LOW (1 << 0) /* VBatt is very close to regulator dropout */
@@ -151,6 +155,7 @@
#define PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK (1 << 2) /* OK to switch to manual override via override RC channel */
#define PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM (1 << 3) /* use custom failsafe values, not 0 values of mixer */
#define PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK (1 << 4) /* OK to try in-air restart */
+#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_PWM_RATES 2 /* bitmask, 0 = low rate, 1 = high rate */
#define PX4IO_P_SETUP_PWM_DEFAULTRATE 3 /* 'low' PWM frame output rate in Hz */
@@ -183,6 +188,15 @@
/* PWM failsafe values - zero disables the output */
#define PX4IO_PAGE_FAILSAFE_PWM 105 /* 0..CONFIG_ACTUATOR_COUNT-1 */
+/* PWM minimum values for certain ESCs */
+#define PX4IO_PAGE_CONTROL_MIN_PWM 106 /* 0..CONFIG_ACTUATOR_COUNT-1 */
+
+/* PWM maximum values for certain ESCs */
+#define PX4IO_PAGE_CONTROL_MAX_PWM 107 /* 0..CONFIG_ACTUATOR_COUNT-1 */
+
+/* PWM idle values that are active, even when SAFETY_SAFE */
+#define PX4IO_PAGE_IDLE_PWM 108 /* 0..CONFIG_ACTUATOR_COUNT-1 */
+
/**
* As-needed mixer data upload.
*
diff --git a/src/modules/px4iofirmware/px4io.h b/src/modules/px4iofirmware/px4io.h
index 272cdb7bf..042e7fe66 100644
--- a/src/modules/px4iofirmware/px4io.h
+++ b/src/modules/px4iofirmware/px4io.h
@@ -77,6 +77,9 @@ extern volatile uint16_t r_page_setup[]; /* PX4IO_PAGE_SETUP */
extern volatile uint16_t r_page_controls[]; /* PX4IO_PAGE_CONTROLS */
extern uint16_t r_page_rc_input_config[]; /* PX4IO_PAGE_RC_INPUT_CONFIG */
extern uint16_t r_page_servo_failsafe[]; /* PX4IO_PAGE_FAILSAFE_PWM */
+extern uint16_t r_page_servo_control_min[]; /* PX4IO_PAGE_CONTROL_MIN_PWM */
+extern uint16_t r_page_servo_control_max[]; /* PX4IO_PAGE_CONTROL_MAX_PWM */
+extern uint16_t r_page_servo_idle[]; /* PX4IO_PAGE_IDLE_PWM */
/*
* Register aliases.
diff --git a/src/modules/px4iofirmware/registers.c b/src/modules/px4iofirmware/registers.c
index df7d6dcd3..bd13f3b7d 100644
--- a/src/modules/px4iofirmware/registers.c
+++ b/src/modules/px4iofirmware/registers.c
@@ -57,8 +57,8 @@ static void pwm_configure_rates(uint16_t map, uint16_t defaultrate, uint16_t alt
* Static configuration parameters.
*/
static const uint16_t r_page_config[] = {
- [PX4IO_P_CONFIG_PROTOCOL_VERSION] = 1, /* XXX hardcoded magic number */
- [PX4IO_P_CONFIG_SOFTWARE_VERSION] = 1, /* XXX hardcoded magic number */
+ [PX4IO_P_CONFIG_PROTOCOL_VERSION] = PX4IO_P_CONFIG_PROTOCOL_VERSION_MAGIC,
+ [PX4IO_P_CONFIG_SOFTWARE_VERSION] = PX4IO_P_CONFIG_SOFTWARE_VERSION_MAGIC,
[PX4IO_P_CONFIG_BOOTLOADER_VERSION] = 3, /* XXX hardcoded magic number */
[PX4IO_P_CONFIG_MAX_TRANSFER] = 64, /* XXX hardcoded magic number */
[PX4IO_P_CONFIG_CONTROL_COUNT] = PX4IO_CONTROL_CHANNELS,
@@ -146,7 +146,9 @@ volatile uint16_t r_page_setup[] =
#define PX4IO_P_SETUP_ARMING_VALID (PX4IO_P_SETUP_ARMING_FMU_ARMED | \
PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK | \
PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK | \
- PX4IO_P_SETUP_ARMING_IO_ARM_OK)
+ PX4IO_P_SETUP_ARMING_IO_ARM_OK) | \
+ PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM | \
+ PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE
#define PX4IO_P_SETUP_RATES_VALID ((1 << IO_SERVO_COUNT) - 1)
#define PX4IO_P_SETUP_RELAYS_VALID ((1 << PX4IO_RELAY_CHANNELS) - 1)
@@ -184,6 +186,30 @@ uint16_t r_page_rc_input_config[MAX_CONTROL_CHANNELS * PX4IO_P_RC_CONFIG_STRIDE
*/
uint16_t r_page_servo_failsafe[IO_SERVO_COUNT] = { 0 };
+/**
+ * PAGE 106
+ *
+ * minimum PWM values when armed
+ *
+ */
+uint16_t r_page_servo_control_min[IO_SERVO_COUNT] = { 900, 900, 900, 900, 900, 900, 900, 900 };
+
+/**
+ * PAGE 107
+ *
+ * maximum PWM values when armed
+ *
+ */
+uint16_t r_page_servo_control_max[IO_SERVO_COUNT] = { 2100, 2100, 2100, 2100, 2100, 2100, 2100, 2100 };
+
+/**
+ * PAGE 108
+ *
+ * idle PWM values for difficult ESCs
+ *
+ */
+uint16_t r_page_servo_idle[IO_SERVO_COUNT] = { 900, 900, 900, 900, 900, 900, 900, 900 };
+
void
registers_set(uint8_t page, uint8_t offset, const uint16_t *values, unsigned num_values)
{
@@ -247,6 +273,75 @@ registers_set(uint8_t page, uint8_t offset, const uint16_t *values, unsigned num
}
break;
+ case PX4IO_PAGE_CONTROL_MIN_PWM:
+
+ /* copy channel data */
+ while ((offset < IO_SERVO_COUNT) && (num_values > 0)) {
+
+ if (*values == 0)
+ /* set to default */
+ r_page_servo_control_min[offset] = 900;
+
+ else if (*values > 1200)
+ r_page_servo_control_min[offset] = 1200;
+ else if (*values < 900)
+ r_page_servo_control_min[offset] = 900;
+ else
+ r_page_servo_control_min[offset] = *values;
+
+ offset++;
+ num_values--;
+ values++;
+ }
+ break;
+
+ case PX4IO_PAGE_CONTROL_MAX_PWM:
+
+ /* copy channel data */
+ while ((offset < IO_SERVO_COUNT) && (num_values > 0)) {
+
+ if (*values == 0)
+ /* set to default */
+ r_page_servo_control_max[offset] = 2100;
+
+ else if (*values > 2100)
+ r_page_servo_control_max[offset] = 2100;
+ else if (*values < 1800)
+ r_page_servo_control_max[offset] = 1800;
+ else
+ r_page_servo_control_max[offset] = *values;
+
+ offset++;
+ num_values--;
+ values++;
+ }
+ break;
+
+ case PX4IO_PAGE_IDLE_PWM:
+
+ /* copy channel data */
+ while ((offset < IO_SERVO_COUNT) && (num_values > 0)) {
+
+ if (*values == 0)
+ /* set to default */
+ r_page_servo_idle[offset] = 0;
+
+ else if (*values < 900)
+ r_page_servo_idle[offset] = 900;
+ else if (*values > 2100)
+ r_page_servo_idle[offset] = 2100;
+ else
+ r_page_servo_idle[offset] = *values;
+
+ /* flag the failsafe values as custom */
+ r_setup_arming |= PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE;
+
+ offset++;
+ num_values--;
+ values++;
+ }
+ break;
+
/* handle text going to the mixer parser */
case PX4IO_PAGE_MIXERLOAD:
mixer_handle_text(values, num_values * sizeof(*values));
@@ -317,9 +412,11 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
* so that an in-air reset of FMU can not lead to a
* lockup of the IO arming state.
*/
- if ((r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED) && !(value & PX4IO_P_SETUP_ARMING_FMU_ARMED)) {
- r_status_flags &= ~PX4IO_P_STATUS_FLAGS_ARMED;
- }
+
+ // XXX do not reset IO's safety state by FMU for now
+ // if ((r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED) && !(value & PX4IO_P_SETUP_ARMING_FMU_ARMED)) {
+ // r_status_flags &= ~PX4IO_P_STATUS_FLAGS_ARMED;
+ // }
r_setup_arming = value;
@@ -367,9 +464,8 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
case PX4IO_PAGE_RC_CONFIG: {
- /* do not allow a RC config change while fully armed */
- if (/* FMU is armed */ (r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED) &&
- /* IO is armed */ (r_status_flags & PX4IO_P_STATUS_FLAGS_ARMED)) {
+ /* do not allow a RC config change while outputs armed */
+ if ((r_status_flags & PX4IO_P_STATUS_FLAGS_OUTPUTS_ARMED)) {
break;
}
@@ -583,6 +679,15 @@ registers_get(uint8_t page, uint8_t offset, uint16_t **values, unsigned *num_val
case PX4IO_PAGE_FAILSAFE_PWM:
SELECT_PAGE(r_page_servo_failsafe);
break;
+ case PX4IO_PAGE_CONTROL_MIN_PWM:
+ SELECT_PAGE(r_page_servo_control_min);
+ break;
+ case PX4IO_PAGE_CONTROL_MAX_PWM:
+ SELECT_PAGE(r_page_servo_control_max);
+ break;
+ case PX4IO_PAGE_IDLE_PWM:
+ SELECT_PAGE(r_page_servo_idle);
+ break;
default:
return -1;
diff --git a/src/modules/px4iofirmware/safety.c b/src/modules/px4iofirmware/safety.c
index 4dbecc274..95335f038 100644
--- a/src/modules/px4iofirmware/safety.c
+++ b/src/modules/px4iofirmware/safety.c
@@ -110,7 +110,7 @@ safety_check_button(void *arg)
* state machine, keep ARM_COUNTER_THRESHOLD the same
* length in all cases of the if/else struct below.
*/
- if (safety_button_pressed && !(r_status_flags & PX4IO_P_STATUS_FLAGS_ARMED) &&
+ if (safety_button_pressed && !(r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) &&
(r_setup_arming & PX4IO_P_SETUP_ARMING_IO_ARM_OK)) {
if (counter < ARM_COUNTER_THRESHOLD) {
@@ -118,18 +118,18 @@ safety_check_button(void *arg)
} else if (counter == ARM_COUNTER_THRESHOLD) {
/* switch to armed state */
- r_status_flags |= PX4IO_P_STATUS_FLAGS_ARMED;
+ r_status_flags |= PX4IO_P_STATUS_FLAGS_SAFETY_OFF;
counter++;
}
- } else if (safety_button_pressed && (r_status_flags & PX4IO_P_STATUS_FLAGS_ARMED)) {
+ } else if (safety_button_pressed && (r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF)) {
if (counter < ARM_COUNTER_THRESHOLD) {
counter++;
} else if (counter == ARM_COUNTER_THRESHOLD) {
/* change to disarmed state and notify the FMU */
- r_status_flags &= ~PX4IO_P_STATUS_FLAGS_ARMED;
+ r_status_flags &= ~PX4IO_P_STATUS_FLAGS_SAFETY_OFF;
counter++;
}
@@ -140,7 +140,7 @@ safety_check_button(void *arg)
/* Select the appropriate LED flash pattern depending on the current IO/FMU arm state */
uint16_t pattern = LED_PATTERN_FMU_REFUSE_TO_ARM;
- if (r_status_flags & PX4IO_P_STATUS_FLAGS_ARMED) {
+ if (r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) {
if (r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED) {
pattern = LED_PATTERN_IO_FMU_ARMED;
diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c
index deac9e20b..31da81f5c 100644
--- a/src/modules/sdlog2/sdlog2.c
+++ b/src/modules/sdlog2/sdlog2.c
@@ -60,6 +60,7 @@
#include <drivers/drv_hrt.h>
#include <uORB/uORB.h>
+#include <uORB/topics/actuator_safety.h>
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/sensor_combined.h>
#include <uORB/topics/vehicle_attitude.h>
@@ -74,6 +75,7 @@
#include <uORB/topics/vehicle_global_position.h>
#include <uORB/topics/vehicle_gps_position.h>
#include <uORB/topics/vehicle_vicon_position.h>
+#include <uORB/topics/vehicle_control_debug.h>
#include <uORB/topics/optical_flow.h>
#include <uORB/topics/battery_status.h>
#include <uORB/topics/differential_pressure.h>
@@ -190,7 +192,7 @@ static int file_copy(const char *file_old, const char *file_new);
static void handle_command(struct vehicle_command_s *cmd);
-static void handle_status(struct vehicle_status_s *cmd);
+static void handle_status(struct actuator_safety_s *safety);
/**
* Create folder for current logging session. Store folder name in 'log_folder'.
@@ -614,7 +616,8 @@ int sdlog2_thread_main(int argc, char *argv[])
/* --- IMPORTANT: DEFINE NUMBER OF ORB STRUCTS TO WAIT FOR HERE --- */
/* number of messages */
- const ssize_t fdsc = 17;
+ const ssize_t fdsc = 20;
+
/* Sanity check variable and index */
ssize_t fdsc_count = 0;
/* file descriptors to wait for */
@@ -623,6 +626,9 @@ int sdlog2_thread_main(int argc, char *argv[])
struct vehicle_status_s buf_status;
memset(&buf_status, 0, sizeof(buf_status));
+ struct actuator_safety_s buf_safety;
+ memset(&buf_safety, 0, sizeof(buf_safety));
+
/* warning! using union here to save memory, elements should be used separately! */
union {
struct vehicle_command_s cmd;
@@ -638,6 +644,7 @@ int sdlog2_thread_main(int argc, char *argv[])
struct vehicle_global_position_s global_pos;
struct vehicle_gps_position_s gps_pos;
struct vehicle_vicon_position_s vicon_pos;
+ struct vehicle_control_debug_s control_debug;
struct optical_flow_s flow;
struct rc_channels_s rc;
struct differential_pressure_s diff_pres;
@@ -648,6 +655,7 @@ int sdlog2_thread_main(int argc, char *argv[])
struct {
int cmd_sub;
int status_sub;
+ int safety_sub;
int sensor_sub;
int att_sub;
int att_sp_sub;
@@ -660,6 +668,7 @@ int sdlog2_thread_main(int argc, char *argv[])
int global_pos_sub;
int gps_pos_sub;
int vicon_pos_sub;
+ int control_debug_sub;
int flow_sub;
int rc_sub;
int airspeed_sub;
@@ -680,6 +689,7 @@ int sdlog2_thread_main(int argc, char *argv[])
struct log_GPS_s log_GPS;
struct log_ATTC_s log_ATTC;
struct log_STAT_s log_STAT;
+ struct log_CTRL_s log_CTRL;
struct log_RC_s log_RC;
struct log_OUT0_s log_OUT0;
struct log_AIRS_s log_AIRS;
@@ -699,6 +709,12 @@ int sdlog2_thread_main(int argc, char *argv[])
fds[fdsc_count].events = POLLIN;
fdsc_count++;
+ /* --- SAFETY --- */
+ subs.safety_sub = orb_subscribe(ORB_ID(actuator_safety));
+ fds[fdsc_count].fd = subs.safety_sub;
+ fds[fdsc_count].events = POLLIN;
+ fdsc_count++;
+
/* --- VEHICLE STATUS --- */
subs.status_sub = orb_subscribe(ORB_ID(vehicle_status));
fds[fdsc_count].fd = subs.status_sub;
@@ -777,6 +793,12 @@ int sdlog2_thread_main(int argc, char *argv[])
fds[fdsc_count].events = POLLIN;
fdsc_count++;
+ /* --- CONTROL DEBUG --- */
+ subs.control_debug_sub = orb_subscribe(ORB_ID(vehicle_control_debug));
+ fds[fdsc_count].fd = subs.control_debug_sub;
+ fds[fdsc_count].events = POLLIN;
+ fdsc_count++;
+
/* --- OPTICAL FLOW --- */
subs.flow_sub = orb_subscribe(ORB_ID(optical_flow));
fds[fdsc_count].fd = subs.flow_sub;
@@ -854,22 +876,33 @@ int sdlog2_thread_main(int argc, char *argv[])
handled_topics++;
}
- /* --- VEHICLE STATUS - LOG MANAGEMENT --- */
+ /* --- SAFETY- LOG MANAGEMENT --- */
if (fds[ifds++].revents & POLLIN) {
- orb_copy(ORB_ID(vehicle_status), subs.status_sub, &buf_status);
+ orb_copy(ORB_ID(actuator_safety), subs.safety_sub, &buf_safety);
if (log_when_armed) {
- handle_status(&buf_status);
+ handle_status(&buf_safety);
}
handled_topics++;
}
+ /* --- VEHICLE STATUS - LOG MANAGEMENT --- */
+ if (fds[ifds++].revents & POLLIN) {
+ orb_copy(ORB_ID(vehicle_status), subs.status_sub, &buf_status);
+
+ //if (log_when_armed) {
+ // handle_status(&buf_safety);
+ //}
+
+ //handled_topics++;
+ }
+
if (!logging_enabled || !check_data || handled_topics >= poll_ret) {
continue;
}
- ifds = 1; // Begin from fds[1] again
+ ifds = 2; // Begin from fds[2] again
pthread_mutex_lock(&logbuffer_mutex);
@@ -882,11 +915,16 @@ int sdlog2_thread_main(int argc, char *argv[])
if (fds[ifds++].revents & POLLIN) {
// Don't orb_copy, it's already done few lines above
log_msg.msg_type = LOG_STAT_MSG;
- log_msg.body.log_STAT.state = (unsigned char) buf_status.state_machine;
- log_msg.body.log_STAT.flight_mode = (unsigned char) buf_status.flight_mode;
- log_msg.body.log_STAT.manual_control_mode = (unsigned char) buf_status.manual_control_mode;
- log_msg.body.log_STAT.manual_sas_mode = (unsigned char) buf_status.manual_sas_mode;
- log_msg.body.log_STAT.armed = (unsigned char) buf_status.flag_system_armed;
+ // XXX fix this
+ // log_msg.body.log_STAT.state = (unsigned char) buf_status.state_machine;
+ // log_msg.body.log_STAT.flight_mode = (unsigned char) buf_status.flight_mode;
+ // log_msg.body.log_STAT.manual_control_mode = (unsigned char) buf_status.manual_control_mode;
+ // log_msg.body.log_STAT.manual_sas_mode = (unsigned char) buf_status.manual_sas_mode;
+ log_msg.body.log_STAT.state = 0;
+ log_msg.body.log_STAT.flight_mode = 0;
+ log_msg.body.log_STAT.manual_control_mode = 0;
+ log_msg.body.log_STAT.manual_sas_mode = 0;
+ log_msg.body.log_STAT.armed = (unsigned char) buf_safety.armed; /* XXX fmu armed correct? */
log_msg.body.log_STAT.battery_voltage = buf_status.voltage_battery;
log_msg.body.log_STAT.battery_current = buf_status.current_battery;
log_msg.body.log_STAT.battery_remaining = buf_status.battery_remaining;
@@ -977,6 +1015,9 @@ int sdlog2_thread_main(int argc, char *argv[])
log_msg.body.log_ATT.roll_rate = buf.att.rollspeed;
log_msg.body.log_ATT.pitch_rate = buf.att.pitchspeed;
log_msg.body.log_ATT.yaw_rate = buf.att.yawspeed;
+ log_msg.body.log_ATT.roll_acc = buf.att.rollacc;
+ log_msg.body.log_ATT.pitch_acc = buf.att.pitchacc;
+ log_msg.body.log_ATT.yaw_acc = buf.att.yawacc;
LOGBUFFER_WRITE_AND_COUNT(ATT);
}
@@ -1073,6 +1114,27 @@ int sdlog2_thread_main(int argc, char *argv[])
// TODO not implemented yet
}
+ /* --- CONTROL DEBUG --- */
+ if (fds[ifds++].revents & POLLIN) {
+ orb_copy(ORB_ID(vehicle_control_debug), subs.control_debug_sub, &buf.control_debug);
+
+ log_msg.msg_type = LOG_CTRL_MSG;
+ log_msg.body.log_CTRL.roll_p = buf.control_debug.roll_p;
+ log_msg.body.log_CTRL.roll_i = buf.control_debug.roll_i;
+ log_msg.body.log_CTRL.roll_d = buf.control_debug.roll_d;
+ log_msg.body.log_CTRL.roll_rate_p = buf.control_debug.roll_rate_p;
+ log_msg.body.log_CTRL.roll_rate_i = buf.control_debug.roll_rate_i;
+ log_msg.body.log_CTRL.roll_rate_d = buf.control_debug.roll_rate_d;
+ log_msg.body.log_CTRL.pitch_p = buf.control_debug.pitch_p;
+ log_msg.body.log_CTRL.pitch_i = buf.control_debug.pitch_i;
+ log_msg.body.log_CTRL.pitch_d = buf.control_debug.pitch_d;
+ log_msg.body.log_CTRL.pitch_rate_p = buf.control_debug.pitch_rate_p;
+ log_msg.body.log_CTRL.pitch_rate_i = buf.control_debug.pitch_rate_i;
+ log_msg.body.log_CTRL.pitch_rate_d = buf.control_debug.pitch_rate_d;
+
+ LOGBUFFER_WRITE_AND_COUNT(CTRL);
+ }
+
/* --- FLOW --- */
if (fds[ifds++].revents & POLLIN) {
orb_copy(ORB_ID(optical_flow), subs.flow_sub, &buf.flow);
@@ -1225,10 +1287,10 @@ void handle_command(struct vehicle_command_s *cmd)
}
}
-void handle_status(struct vehicle_status_s *status)
+void handle_status(struct actuator_safety_s *safety)
{
- if (status->flag_system_armed != flag_system_armed) {
- flag_system_armed = status->flag_system_armed;
+ if (safety->armed != flag_system_armed) {
+ flag_system_armed = safety->armed;
if (flag_system_armed) {
sdlog2_start_log();
diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h
index 4a66fe116..358637f93 100644
--- a/src/modules/sdlog2/sdlog2_messages.h
+++ b/src/modules/sdlog2/sdlog2_messages.h
@@ -63,6 +63,9 @@ struct log_ATT_s {
float roll_rate;
float pitch_rate;
float yaw_rate;
+ float roll_acc;
+ float pitch_acc;
+ float yaw_acc;
};
/* --- ATSP - ATTITUDE SET POINT --- */
@@ -160,27 +163,44 @@ struct log_STAT_s {
unsigned char battery_warning;
};
+/* --- CTRL - CONTROL DEBUG --- */
+#define LOG_CTRL_MSG 11
+struct log_CTRL_s {
+ float roll_p;
+ float roll_i;
+ float roll_d;
+ float roll_rate_p;
+ float roll_rate_i;
+ float roll_rate_d;
+ float pitch_p;
+ float pitch_i;
+ float pitch_d;
+ float pitch_rate_p;
+ float pitch_rate_i;
+ float pitch_rate_d;
+};
+
/* --- RC - RC INPUT CHANNELS --- */
-#define LOG_RC_MSG 11
+#define LOG_RC_MSG 12
struct log_RC_s {
float channel[8];
};
/* --- OUT0 - ACTUATOR_0 OUTPUT --- */
-#define LOG_OUT0_MSG 12
+#define LOG_OUT0_MSG 13
struct log_OUT0_s {
float output[8];
};
/* --- AIRS - AIRSPEED --- */
-#define LOG_AIRS_MSG 13
+#define LOG_AIRS_MSG 14
struct log_AIRS_s {
float indicated_airspeed;
float true_airspeed;
};
/* --- ARSP - ATTITUDE RATE SET POINT --- */
-#define LOG_ARSP_MSG 14
+#define LOG_ARSP_MSG 15
struct log_ARSP_s {
float roll_rate_sp;
float pitch_rate_sp;
@@ -188,7 +208,7 @@ struct log_ARSP_s {
};
/* --- FLOW - OPTICAL FLOW --- */
-#define LOG_FLOW_MSG 15
+#define LOG_FLOW_MSG 16
struct log_FLOW_s {
int16_t flow_raw_x;
int16_t flow_raw_y;
@@ -215,7 +235,7 @@ struct log_GPOS_s {
static const struct log_format_s log_formats[] = {
LOG_FORMAT(TIME, "Q", "StartTime"),
- LOG_FORMAT(ATT, "ffffff", "Roll,Pitch,Yaw,RollRate,PitchRate,YawRate"),
+ LOG_FORMAT(ATT, "fffffffff", "Roll,Pitch,Yaw,RollR,PitchR,YawR,RollA,PitchA,YawA"),
LOG_FORMAT(ATSP, "ffff", "RollSP,PitchSP,YawSP,ThrustSP"),
LOG_FORMAT(IMU, "fffffffff", "AccX,AccY,AccZ,GyroX,GyroY,GyroZ,MagX,MagY,MagZ"),
LOG_FORMAT(SENS, "ffff", "BaroPres,BaroAlt,BaroTemp,DiffPres"),
@@ -224,6 +244,7 @@ static const struct log_format_s log_formats[] = {
LOG_FORMAT(GPS, "QBffLLfffff", "GPSTime,FixType,EPH,EPV,Lat,Lon,Alt,VelN,VelE,VelD,Cog"),
LOG_FORMAT(ATTC, "ffff", "Roll,Pitch,Yaw,Thrust"),
LOG_FORMAT(STAT, "BBBBBfffB", "State,FlightMode,CtlMode,SASMode,Armed,BatV,BatC,BatRem,BatWarn"),
+ LOG_FORMAT(CTRL, "ffffffffffff", "RP,RI,RD,RRP,RRI,RRD,PP,PI,PD,PRP,PRI,PRD"),
LOG_FORMAT(RC, "ffffffff", "Ch0,Ch1,Ch2,Ch3,Ch4,Ch5,Ch6,Ch7"),
LOG_FORMAT(OUT0, "ffffffff", "Out0,Out1,Out2,Out3,Out4,Out5,Out6,Out7"),
LOG_FORMAT(AIRS, "ff", "IndSpeed,TrueSpeed"),
diff --git a/src/modules/sensors/sensor_params.c b/src/modules/sensors/sensor_params.c
index f6f4d60c7..7077972aa 100644
--- a/src/modules/sensors/sensor_params.c
+++ b/src/modules/sensors/sensor_params.c
@@ -164,13 +164,11 @@ PARAM_DEFINE_INT32(RC_MAP_PITCH, 2);
PARAM_DEFINE_INT32(RC_MAP_THROTTLE, 3);
PARAM_DEFINE_INT32(RC_MAP_YAW, 4);
-PARAM_DEFINE_INT32(RC_MAP_OVER_SW, 5);
-PARAM_DEFINE_INT32(RC_MAP_MODE_SW, 6);
+PARAM_DEFINE_INT32(RC_MAP_MODE_SW, 5);
+PARAM_DEFINE_INT32(RC_MAP_RETURN_SW, 6);
+PARAM_DEFINE_INT32(RC_MAP_MISSIO_SW, 0);
-PARAM_DEFINE_INT32(RC_MAP_MAN_SW, 0);
-PARAM_DEFINE_INT32(RC_MAP_SAS_SW, 0);
-PARAM_DEFINE_INT32(RC_MAP_RTL_SW, 0);
-PARAM_DEFINE_INT32(RC_MAP_OFFB_SW, 0);
+//PARAM_DEFINE_INT32(RC_MAP_OFFB_SW, 0);
PARAM_DEFINE_INT32(RC_MAP_FLAPS, 0);
diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp
index 1ded14a91..49a1da83b 100644
--- a/src/modules/sensors/sensors.cpp
+++ b/src/modules/sensors/sensors.cpp
@@ -208,13 +208,11 @@ private:
int rc_map_yaw;
int rc_map_throttle;
- int rc_map_manual_override_sw;
- int rc_map_auto_mode_sw;
+ int rc_map_mode_sw;
+ int rc_map_return_sw;
+ int rc_map_mission_sw;
- int rc_map_manual_mode_sw;
- int rc_map_sas_mode_sw;
- int rc_map_rtl_sw;
- int rc_map_offboard_ctrl_mode_sw;
+// int rc_map_offboard_ctrl_mode_sw;
int rc_map_flaps;
@@ -256,13 +254,11 @@ private:
param_t rc_map_yaw;
param_t rc_map_throttle;
- param_t rc_map_manual_override_sw;
- param_t rc_map_auto_mode_sw;
+ param_t rc_map_mode_sw;
+ param_t rc_map_return_sw;
+ param_t rc_map_mission_sw;
- param_t rc_map_manual_mode_sw;
- param_t rc_map_sas_mode_sw;
- param_t rc_map_rtl_sw;
- param_t rc_map_offboard_ctrl_mode_sw;
+// param_t rc_map_offboard_ctrl_mode_sw;
param_t rc_map_flaps;
@@ -462,16 +458,15 @@ Sensors::Sensors() :
_parameter_handles.rc_map_throttle = param_find("RC_MAP_THROTTLE");
/* mandatory mode switches, mapped to channel 5 and 6 per default */
- _parameter_handles.rc_map_manual_override_sw = param_find("RC_MAP_OVER_SW");
- _parameter_handles.rc_map_auto_mode_sw = param_find("RC_MAP_MODE_SW");
+ _parameter_handles.rc_map_mode_sw = param_find("RC_MAP_MODE_SW");
+ _parameter_handles.rc_map_return_sw = param_find("RC_MAP_RETURN_SW");
_parameter_handles.rc_map_flaps = param_find("RC_MAP_FLAPS");
/* optional mode switches, not mapped per default */
- _parameter_handles.rc_map_manual_mode_sw = param_find("RC_MAP_MAN_SW");
- _parameter_handles.rc_map_sas_mode_sw = param_find("RC_MAP_SAS_SW");
- _parameter_handles.rc_map_rtl_sw = param_find("RC_MAP_RTL_SW");
- _parameter_handles.rc_map_offboard_ctrl_mode_sw = param_find("RC_MAP_OFFB_SW");
+ _parameter_handles.rc_map_mission_sw = param_find("RC_MAP_MISSIO_SW");
+
+// _parameter_handles.rc_map_offboard_ctrl_mode_sw = param_find("RC_MAP_OFFB_SW");
_parameter_handles.rc_map_aux1 = param_find("RC_MAP_AUX1");
_parameter_handles.rc_map_aux2 = param_find("RC_MAP_AUX2");
@@ -611,33 +606,25 @@ Sensors::parameters_update()
warnx("Failed getting throttle chan index");
}
- if (param_get(_parameter_handles.rc_map_manual_override_sw, &(_parameters.rc_map_manual_override_sw)) != OK) {
- warnx("Failed getting override sw chan index");
- }
-
- if (param_get(_parameter_handles.rc_map_auto_mode_sw, &(_parameters.rc_map_auto_mode_sw)) != OK) {
- warnx("Failed getting auto mode sw chan index");
- }
-
- if (param_get(_parameter_handles.rc_map_flaps, &(_parameters.rc_map_flaps)) != OK) {
- warnx("Failed getting flaps chan index");
+ if (param_get(_parameter_handles.rc_map_mode_sw, &(_parameters.rc_map_mode_sw)) != OK) {
+ warnx("Failed getting mode sw chan index");
}
- if (param_get(_parameter_handles.rc_map_manual_mode_sw, &(_parameters.rc_map_manual_mode_sw)) != OK) {
- warnx("Failed getting manual mode sw chan index");
+ if (param_get(_parameter_handles.rc_map_return_sw, &(_parameters.rc_map_return_sw)) != OK) {
+ warnx("Failed getting return sw chan index");
}
- if (param_get(_parameter_handles.rc_map_rtl_sw, &(_parameters.rc_map_rtl_sw)) != OK) {
- warnx("Failed getting rtl sw chan index");
+ if (param_get(_parameter_handles.rc_map_mission_sw, &(_parameters.rc_map_mission_sw)) != OK) {
+ warnx("Failed getting mission sw chan index");
}
- if (param_get(_parameter_handles.rc_map_sas_mode_sw, &(_parameters.rc_map_sas_mode_sw)) != OK) {
- warnx("Failed getting sas mode sw chan index");
+ if (param_get(_parameter_handles.rc_map_flaps, &(_parameters.rc_map_flaps)) != OK) {
+ warnx("Failed getting flaps chan index");
}
- if (param_get(_parameter_handles.rc_map_offboard_ctrl_mode_sw, &(_parameters.rc_map_offboard_ctrl_mode_sw)) != OK) {
- warnx("Failed getting offboard control mode sw chan index");
- }
+// if (param_get(_parameter_handles.rc_map_offboard_ctrl_mode_sw, &(_parameters.rc_map_offboard_ctrl_mode_sw)) != OK) {
+// warnx("Failed getting offboard control mode sw chan index");
+// }
if (param_get(_parameter_handles.rc_map_aux1, &(_parameters.rc_map_aux1)) != OK) {
warnx("Failed getting mode aux 1 index");
@@ -681,15 +668,13 @@ Sensors::parameters_update()
_rc.function[PITCH] = _parameters.rc_map_pitch - 1;
_rc.function[YAW] = _parameters.rc_map_yaw - 1;
- _rc.function[OVERRIDE] = _parameters.rc_map_manual_override_sw - 1;
- _rc.function[AUTO_MODE] = _parameters.rc_map_auto_mode_sw - 1;
+ _rc.function[MODE] = _parameters.rc_map_mode_sw - 1;
+ _rc.function[RETURN] = _parameters.rc_map_return_sw - 1;
+ _rc.function[MISSION] = _parameters.rc_map_mission_sw - 1;
_rc.function[FLAPS] = _parameters.rc_map_flaps - 1;
- _rc.function[MANUAL_MODE] = _parameters.rc_map_manual_mode_sw - 1;
- _rc.function[RTL] = _parameters.rc_map_rtl_sw - 1;
- _rc.function[SAS_MODE] = _parameters.rc_map_sas_mode_sw - 1;
- _rc.function[OFFBOARD_MODE] = _parameters.rc_map_offboard_ctrl_mode_sw - 1;
+// _rc.function[OFFBOARD_MODE] = _parameters.rc_map_offboard_ctrl_mode_sw - 1;
_rc.function[AUX_1] = _parameters.rc_map_aux1 - 1;
_rc.function[AUX_2] = _parameters.rc_map_aux2 - 1;
@@ -1145,10 +1130,10 @@ Sensors::ppm_poll()
manual_control.yaw = NAN;
manual_control.throttle = NAN;
- manual_control.manual_mode_switch = NAN;
- manual_control.manual_sas_switch = NAN;
- manual_control.return_to_launch_switch = NAN;
- manual_control.auto_offboard_input_switch = NAN;
+ manual_control.mode_switch = NAN;
+ manual_control.return_switch = NAN;
+ manual_control.mission_switch = NAN;
+// manual_control.auto_offboard_input_switch = NAN;
manual_control.flaps = NAN;
manual_control.aux1 = NAN;
@@ -1248,11 +1233,14 @@ Sensors::ppm_poll()
manual_control.yaw *= _parameters.rc_scale_yaw;
}
- /* override switch input */
- manual_control.manual_override_switch = limit_minus_one_to_one(_rc.chan[_rc.function[OVERRIDE]].scaled);
-
/* mode switch input */
- manual_control.auto_mode_switch = limit_minus_one_to_one(_rc.chan[_rc.function[AUTO_MODE]].scaled);
+ manual_control.mode_switch = limit_minus_one_to_one(_rc.chan[_rc.function[MODE]].scaled);
+
+ /* land switch input */
+ manual_control.return_switch = limit_minus_one_to_one(_rc.chan[_rc.function[RETURN]].scaled);
+
+ /* land switch input */
+ manual_control.mission_switch = limit_minus_one_to_one(_rc.chan[_rc.function[MISSION]].scaled);
/* flaps */
if (_rc.function[FLAPS] >= 0) {
@@ -1264,21 +1252,17 @@ Sensors::ppm_poll()
}
}
- if (_rc.function[MANUAL_MODE] >= 0) {
- manual_control.manual_mode_switch = limit_minus_one_to_one(_rc.chan[_rc.function[MANUAL_MODE]].scaled);
- }
-
- if (_rc.function[SAS_MODE] >= 0) {
- manual_control.manual_sas_switch = limit_minus_one_to_one(_rc.chan[_rc.function[SAS_MODE]].scaled);
+ if (_rc.function[MODE] >= 0) {
+ manual_control.mode_switch = limit_minus_one_to_one(_rc.chan[_rc.function[MODE]].scaled);
}
- if (_rc.function[RTL] >= 0) {
- manual_control.return_to_launch_switch = limit_minus_one_to_one(_rc.chan[_rc.function[RTL]].scaled);
+ if (_rc.function[MISSION] >= 0) {
+ manual_control.mission_switch = limit_minus_one_to_one(_rc.chan[_rc.function[MISSION]].scaled);
}
- if (_rc.function[OFFBOARD_MODE] >= 0) {
- manual_control.auto_offboard_input_switch = limit_minus_one_to_one(_rc.chan[_rc.function[OFFBOARD_MODE]].scaled);
- }
+// if (_rc.function[OFFBOARD_MODE] >= 0) {
+// manual_control.auto_offboard_input_switch = limit_minus_one_to_one(_rc.chan[_rc.function[OFFBOARD_MODE]].scaled);
+// }
/* aux functions, only assign if valid mapping is present */
if (_rc.function[AUX_1] >= 0) {
diff --git a/src/modules/systemlib/pid/pid.c b/src/modules/systemlib/pid/pid.c
index 4996a8f66..9308100b0 100644
--- a/src/modules/systemlib/pid/pid.c
+++ b/src/modules/systemlib/pid/pid.c
@@ -124,7 +124,7 @@ __EXPORT int pid_set_parameters(PID_t *pid, float kp, float ki, float kd, float
* @param dt
* @return
*/
-__EXPORT float pid_calculate(PID_t *pid, float sp, float val, float val_dot, float dt)
+__EXPORT float pid_calculate(PID_t *pid, float sp, float val, float val_dot, float dt, float *ctrl_p, float *ctrl_i, float *ctrl_d)
{
/* error = setpoint - actual_position
integral = integral + (error*dt)
@@ -196,6 +196,10 @@ __EXPORT float pid_calculate(PID_t *pid, float sp, float val, float val_dot, flo
pid->last_output = output;
}
+ *ctrl_p = (error * pid->kp);
+ *ctrl_i = (i * pid->ki);
+ *ctrl_d = (d * pid->kd);
+
return pid->last_output;
}
diff --git a/src/modules/systemlib/pid/pid.h b/src/modules/systemlib/pid/pid.h
index eca228464..5f2650f69 100644
--- a/src/modules/systemlib/pid/pid.h
+++ b/src/modules/systemlib/pid/pid.h
@@ -85,7 +85,7 @@ typedef struct {
__EXPORT void pid_init(PID_t *pid, float kp, float ki, float kd, float intmax, float limit, uint8_t mode, float dt_min);
__EXPORT int pid_set_parameters(PID_t *pid, float kp, float ki, float kd, float intmax, float limit);
//void pid_set(PID_t *pid, float sp);
-__EXPORT float pid_calculate(PID_t *pid, float sp, float val, float val_dot, float dt);
+__EXPORT float pid_calculate(PID_t *pid, float sp, float val, float val_dot, float dt, float *ctrl_p, float *ctrl_i, float *ctrl_d);
__EXPORT void pid_reset_integral(PID_t *pid);
diff --git a/src/modules/uORB/objects_common.cpp b/src/modules/uORB/objects_common.cpp
index e7d7e7bca..8ae47ba8b 100644
--- a/src/modules/uORB/objects_common.cpp
+++ b/src/modules/uORB/objects_common.cpp
@@ -98,6 +98,9 @@ ORB_DEFINE(rc_channels, struct rc_channels_s);
#include "topics/vehicle_command.h"
ORB_DEFINE(vehicle_command, struct vehicle_command_s);
+#include "topics/vehicle_control_mode.h"
+ORB_DEFINE(vehicle_control_mode, struct vehicle_control_mode_s);
+
#include "topics/vehicle_local_position_setpoint.h"
ORB_DEFINE(vehicle_local_position_setpoint, struct vehicle_local_position_setpoint_s);
@@ -119,6 +122,9 @@ ORB_DEFINE(vehicle_attitude_setpoint, struct vehicle_attitude_setpoint_s);
#include "topics/manual_control_setpoint.h"
ORB_DEFINE(manual_control_setpoint, struct manual_control_setpoint_s);
+#include "topics/vehicle_control_debug.h"
+ORB_DEFINE(vehicle_control_debug, struct vehicle_control_debug_s);
+
#include "topics/offboard_control_setpoint.h"
ORB_DEFINE(offboard_control_setpoint, struct offboard_control_setpoint_s);
@@ -146,7 +152,9 @@ ORB_DEFINE(actuator_controls_0, struct actuator_controls_s);
ORB_DEFINE(actuator_controls_1, struct actuator_controls_s);
ORB_DEFINE(actuator_controls_2, struct actuator_controls_s);
ORB_DEFINE(actuator_controls_3, struct actuator_controls_s);
-ORB_DEFINE(actuator_armed, struct actuator_armed_s);
+
+#include "topics/actuator_safety.h"
+ORB_DEFINE(actuator_safety, struct actuator_safety_s);
/* actuator controls, as set by actuators / mixers after limiting */
#include "topics/actuator_controls_effective.h"
diff --git a/src/modules/uORB/topics/actuator_controls.h b/src/modules/uORB/topics/actuator_controls.h
index b7c4196c0..26b967237 100644
--- a/src/modules/uORB/topics/actuator_controls.h
+++ b/src/modules/uORB/topics/actuator_controls.h
@@ -52,6 +52,9 @@
#define NUM_ACTUATOR_CONTROLS 8
#define NUM_ACTUATOR_CONTROL_GROUPS 4 /**< for sanity checking */
+/* control sets with pre-defined applications */
+#define ORB_ID_VEHICLE_ATTITUDE_CONTROLS ORB_ID(actuator_controls_0)
+
struct actuator_controls_s {
uint64_t timestamp;
float control[NUM_ACTUATOR_CONTROLS];
@@ -63,16 +66,4 @@ ORB_DECLARE(actuator_controls_1);
ORB_DECLARE(actuator_controls_2);
ORB_DECLARE(actuator_controls_3);
-/* control sets with pre-defined applications */
-#define ORB_ID_VEHICLE_ATTITUDE_CONTROLS ORB_ID(actuator_controls_0)
-
-/** 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) */
-};
-
-ORB_DECLARE(actuator_armed);
-
#endif \ No newline at end of file
diff --git a/src/modules/uORB/topics/actuator_safety.h b/src/modules/uORB/topics/actuator_safety.h
new file mode 100644
index 000000000..c431217ab
--- /dev/null
+++ b/src/modules/uORB/topics/actuator_safety.h
@@ -0,0 +1,66 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 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 actuator_controls.h
+ *
+ * Actuator control topics - mixer inputs.
+ *
+ * Values published to these topics are the outputs of the vehicle control
+ * system, and are expected to be mixed and used to drive the actuators
+ * (servos, speed controls, etc.) that operate the vehicle.
+ *
+ * Each topic can be published by a single controller
+ */
+
+#ifndef TOPIC_ACTUATOR_SAFETY_H
+#define TOPIC_ACTUATOR_SAFETY_H
+
+#include <stdint.h>
+#include "../uORB.h"
+
+/** global 'actuator output is live' control. */
+struct actuator_safety_s {
+
+ uint64_t timestamp;
+ bool safety_switch_available; /**< Set to true if a safety switch is connected */
+ bool safety_off; /**< Set to true if safety is off */
+ 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 hil_enabled; /**< Set to true if hardware-in-the-loop (HIL) is enabled */
+};
+
+ORB_DECLARE(actuator_safety);
+
+#endif \ No newline at end of file
diff --git a/src/modules/uORB/topics/manual_control_setpoint.h b/src/modules/uORB/topics/manual_control_setpoint.h
index 261a8a4ad..cfee81ea2 100644
--- a/src/modules/uORB/topics/manual_control_setpoint.h
+++ b/src/modules/uORB/topics/manual_control_setpoint.h
@@ -56,17 +56,17 @@ struct manual_control_setpoint_s {
float yaw; /**< rudder / yaw rate / yaw */
float throttle; /**< throttle / collective thrust / altitude */
- float manual_override_switch; /**< manual override mode (mandatory) */
- float auto_mode_switch; /**< auto mode switch (mandatory) */
+ float mode_switch; /**< mode 3 position switch (mandatory): manual, assisted, auto */
+ float return_switch; /**< land 2 position switch (mandatory): land, no effect */
+ float mission_switch; /**< mission 2 position switch (optional): mission, loiter */
/**
* Any of the channels below may not be available and be set to NaN
* to indicate that it does not contain valid data.
*/
- float manual_mode_switch; /**< manual mode (man, sas, alt) switch (optional) */
- float manual_sas_switch; /**< sas mode (rates / attitude) switch (optional) */
- float return_to_launch_switch; /**< return to launch switch (0 = disabled, 1 = enabled) */
- float auto_offboard_input_switch; /**< controller setpoint source (0 = onboard, 1 = offboard) */
+
+ // XXX needed or parameter?
+ //float auto_offboard_input_switch; /**< controller setpoint source (0 = onboard, 1 = offboard) */
float flaps; /**< flap position */
diff --git a/src/modules/uORB/topics/rc_channels.h b/src/modules/uORB/topics/rc_channels.h
index 9dd54df91..a0bb25af4 100644
--- a/src/modules/uORB/topics/rc_channels.h
+++ b/src/modules/uORB/topics/rc_channels.h
@@ -68,18 +68,16 @@ enum RC_CHANNELS_FUNCTION
ROLL = 1,
PITCH = 2,
YAW = 3,
- OVERRIDE = 4,
- AUTO_MODE = 5,
- MANUAL_MODE = 6,
- SAS_MODE = 7,
- RTL = 8,
- OFFBOARD_MODE = 9,
- FLAPS = 10,
- AUX_1 = 11,
- AUX_2 = 12,
- AUX_3 = 13,
- AUX_4 = 14,
- AUX_5 = 15,
+ MODE = 4,
+ RETURN = 5,
+ MISSION = 6,
+ OFFBOARD_MODE = 7,
+ FLAPS = 8,
+ AUX_1 = 9,
+ AUX_2 = 10,
+ AUX_3 = 11,
+ AUX_4 = 12,
+ AUX_5 = 13,
RC_CHANNELS_FUNCTION_MAX /**< indicates the number of functions. There can be more functions than RC channels. */
};
diff --git a/src/modules/uORB/topics/vehicle_control_debug.h b/src/modules/uORB/topics/vehicle_control_debug.h
new file mode 100644
index 000000000..6184284a4
--- /dev/null
+++ b/src/modules/uORB/topics/vehicle_control_debug.h
@@ -0,0 +1,87 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Author: @author Lorenz Meier <lm@inf.ethz.ch>
+ *
+ * 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 vehicle_control_debug.h
+ * For debugging purposes to log PID parts of controller
+ */
+
+#ifndef TOPIC_VEHICLE_CONTROL_DEBUG_H_
+#define TOPIC_VEHICLE_CONTROL_DEBUG_H_
+
+#include <stdint.h>
+#include "../uORB.h"
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+struct vehicle_control_debug_s
+{
+ uint64_t timestamp; /**< in microseconds since system start */
+
+ float roll_p; /**< roll P control part */
+ float roll_i; /**< roll I control part */
+ float roll_d; /**< roll D control part */
+
+ float roll_rate_p; /**< roll rate P control part */
+ float roll_rate_i; /**< roll rate I control part */
+ float roll_rate_d; /**< roll rate D control part */
+
+ float pitch_p; /**< pitch P control part */
+ float pitch_i; /**< pitch I control part */
+ float pitch_d; /**< pitch D control part */
+
+ float pitch_rate_p; /**< pitch rate P control part */
+ float pitch_rate_i; /**< pitch rate I control part */
+ float pitch_rate_d; /**< pitch rate D control part */
+
+ float yaw_p; /**< yaw P control part */
+ float yaw_i; /**< yaw I control part */
+ float yaw_d; /**< yaw D control part */
+
+ float yaw_rate_p; /**< yaw rate P control part */
+ float yaw_rate_i; /**< yaw rate I control part */
+ float yaw_rate_d; /**< yaw rate D control part */
+
+}; /**< vehicle_control_debug */
+
+ /**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(vehicle_control_debug);
+
+#endif
diff --git a/src/modules/uORB/topics/vehicle_control_mode.h b/src/modules/uORB/topics/vehicle_control_mode.h
new file mode 100644
index 000000000..177e30898
--- /dev/null
+++ b/src/modules/uORB/topics/vehicle_control_mode.h
@@ -0,0 +1,91 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Author: @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Petri Tanskanen <petri.tanskanen@inf.ethz.ch>
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
+ *
+ * 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 vehicle_control_mode.h
+ * Definition of the vehicle_control_mode uORB topic.
+ *
+ * All control apps should depend their actions based on the flags set here.
+ */
+
+#ifndef VEHICLE_CONTROL_MODE
+#define VEHICLE_CONTROL_MODE
+
+#include <stdint.h>
+#include <stdbool.h>
+#include "../uORB.h"
+
+/**
+ * @addtogroup topics @{
+ */
+
+
+/**
+ * state machine / state of vehicle.
+ *
+ * Encodes the complete system state and is set by the commander app.
+ */
+struct vehicle_control_mode_s
+{
+ uint16_t counter; /**< incremented by the writing thread everytime new data is stored */
+ uint64_t timestamp; /**< in microseconds since system start, is set whenever the writing thread stores new data */
+
+ bool flag_external_manual_override_ok; /**< external override non-fatal for system. Only true for fixed wing */
+
+ bool flag_system_emergency;
+ bool flag_preflight_calibration;
+
+ bool flag_control_manual_enabled; /**< true if manual input is mixed in */
+ bool flag_control_offboard_enabled; /**< true if offboard control input is on */
+ bool flag_auto_enabled;
+ bool flag_control_rates_enabled; /**< true if rates are stabilized */
+ bool flag_control_attitude_enabled; /**< true if attitude stabilization is mixed in */
+ bool flag_control_velocity_enabled; /**< true if speed (implies direction) is controlled */
+ bool flag_control_position_enabled; /**< true if position is controlled */
+
+ bool failsave_lowlevel; /**< Set to true if low-level failsafe mode is enabled */
+ bool failsave_highlevel; /**< Set to true if high-level failsafe mode is enabled */
+};
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(vehicle_control_mode);
+
+#endif
diff --git a/src/modules/uORB/topics/vehicle_status.h b/src/modules/uORB/topics/vehicle_status.h
index c7c1048f6..2bcd57f4b 100644
--- a/src/modules/uORB/topics/vehicle_status.h
+++ b/src/modules/uORB/topics/vehicle_status.h
@@ -59,21 +59,58 @@
*/
/* State Machine */
-typedef enum
-{
- SYSTEM_STATE_PREFLIGHT = 0,
- SYSTEM_STATE_STANDBY = 1,
- SYSTEM_STATE_GROUND_READY = 2,
- SYSTEM_STATE_MANUAL = 3,
- SYSTEM_STATE_STABILIZED = 4,
- SYSTEM_STATE_AUTO = 5,
- SYSTEM_STATE_MISSION_ABORT = 6,
- SYSTEM_STATE_EMCY_LANDING = 7,
- SYSTEM_STATE_EMCY_CUTOFF = 8,
- SYSTEM_STATE_GROUND_ERROR = 9,
- SYSTEM_STATE_REBOOT= 10,
-
-} commander_state_machine_t;
+typedef enum {
+ NAVIGATION_STATE_INIT=0,
+ NAVIGATION_STATE_MANUAL_STANDBY,
+ NAVIGATION_STATE_MANUAL,
+ NAVIGATION_STATE_SEATBELT_STANDBY,
+ NAVIGATION_STATE_SEATBELT,
+ NAVIGATION_STATE_SEATBELT_DESCENT,
+ NAVIGATION_STATE_AUTO_STANDBY,
+ NAVIGATION_STATE_AUTO_READY,
+ NAVIGATION_STATE_AUTO_TAKEOFF,
+ NAVIGATION_STATE_AUTO_LOITER,
+ NAVIGATION_STATE_AUTO_MISSION,
+ NAVIGATION_STATE_AUTO_RTL,
+ NAVIGATION_STATE_AUTO_LAND
+} navigation_state_t;
+
+typedef enum {
+ MANUAL_STANDBY = 0,
+ MANUAL_READY,
+ MANUAL_IN_AIR
+} manual_state_t;
+
+typedef enum {
+ ARMING_STATE_INIT = 0,
+ ARMING_STATE_STANDBY,
+ ARMING_STATE_ARMED,
+ ARMING_STATE_ARMED_ERROR,
+ ARMING_STATE_STANDBY_ERROR,
+ ARMING_STATE_REBOOT,
+ ARMING_STATE_IN_AIR_RESTORE
+} arming_state_t;
+
+typedef enum {
+ HIL_STATE_OFF = 0,
+ HIL_STATE_ON
+} hil_state_t;
+
+typedef enum {
+ MODE_SWITCH_MANUAL = 0,
+ MODE_SWITCH_SEATBELT,
+ MODE_SWITCH_AUTO
+} mode_switch_pos_t;
+
+typedef enum {
+ RETURN_SWITCH_NONE = 0,
+ RETURN_SWITCH_RETURN
+} return_switch_pos_t;
+
+typedef enum {
+ MISSION_SWITCH_NONE = 0,
+ MISSION_SWITCH_MISSION
+} mission_switch_pos_t;
enum VEHICLE_MODE_FLAG {
VEHICLE_MODE_FLAG_SAFETY_ARMED = 128,
@@ -86,26 +123,6 @@ enum VEHICLE_MODE_FLAG {
VEHICLE_MODE_FLAG_CUSTOM_MODE_ENABLED = 1
}; /**< Same as MAV_MODE_FLAG of MAVLink 1.0 protocol */
-enum VEHICLE_FLIGHT_MODE {
- VEHICLE_FLIGHT_MODE_MANUAL = 0, /**< direct manual control, exact mode determined by VEHICLE_MANUAL_CONTROL_MODE */
- VEHICLE_FLIGHT_MODE_STAB, /**< attitude or rate stabilization plus velocity or position stabilization */
- VEHICLE_FLIGHT_MODE_HOLD, /**< hold current position (hover or loiter around position when switched) */
- VEHICLE_FLIGHT_MODE_AUTO /**< attitude or rate stabilization plus absolute position control and waypoints */
-};
-
-enum VEHICLE_MANUAL_CONTROL_MODE {
- VEHICLE_MANUAL_CONTROL_MODE_DIRECT = 0, /**< no attitude control, direct stick input mixing (only fixed wing) */
- VEHICLE_MANUAL_CONTROL_MODE_RATES, /**< body rates control mode */
- VEHICLE_MANUAL_CONTROL_MODE_SAS /**< stability augmented system (SAS) mode */
-};
-
-enum VEHICLE_MANUAL_SAS_MODE {
- VEHICLE_MANUAL_SAS_MODE_ROLL_PITCH_ABS_YAW_ABS = 0, /**< roll, pitch and yaw absolute */
- VEHICLE_MANUAL_SAS_MODE_ROLL_PITCH_ABS_YAW_RATE, /**< roll and pitch absolute, yaw rate */
- VEHICLE_MANUAL_SAS_MODE_SIMPLE, /**< simple mode (includes altitude hold) */
- VEHICLE_MANUAL_SAS_MODE_ALTITUDE /**< altitude hold */
-};
-
/**
* Should match 1:1 MAVLink's MAV_TYPE ENUM
*/
@@ -134,7 +151,7 @@ enum VEHICLE_TYPE {
enum VEHICLE_BATTERY_WARNING {
VEHICLE_BATTERY_WARNING_NONE = 0, /**< no battery low voltage warning active */
VEHICLE_BATTERY_WARNING_WARNING, /**< warning of low voltage 1. stage */
- VEHICLE_BATTERY_WARNING_ALERT /**< aleting of low voltage 2. stage */
+ VEHICLE_BATTERY_WARNING_ALERT /**< alerting of low voltage 2. stage */
};
@@ -150,32 +167,55 @@ struct vehicle_status_s
uint16_t counter; /**< incremented by the writing thread everytime new data is stored */
uint64_t timestamp; /**< in microseconds since system start, is set whenever the writing thread stores new data */
uint64_t failsave_lowlevel_start_time; /**< time when the lowlevel failsafe flag was set */
- //uint64_t failsave_highlevel_begin; TO BE COMPLETED
+// uint64_t failsave_highlevel_begin; TO BE COMPLETED
+
+ navigation_state_t navigation_state; /**< current system state */
+ arming_state_t arming_state; /**< current arming state */
+ hil_state_t hil_state; /**< current hil state */
- commander_state_machine_t state_machine; /**< current flight state, main state machine */
- enum VEHICLE_FLIGHT_MODE flight_mode; /**< current flight mode, as defined by mode switch */
- enum VEHICLE_MANUAL_CONTROL_MODE manual_control_mode; /**< current attitude control mode, as defined by VEHICLE_ATTITUDE_MODE enum */
- enum VEHICLE_MANUAL_SAS_MODE manual_sas_mode; /**< current stabilization mode */
int32_t system_type; /**< system type, inspired by MAVLink's VEHICLE_TYPE enum */
int32_t system_id; /**< system id, inspired by MAVLink's system ID field */
int32_t component_id; /**< subsystem / component id, inspired by MAVLink's component ID field */
/* system flags - these represent the state predicates */
- bool flag_system_armed; /**< true is motors / actuators are armed */
- bool flag_control_manual_enabled; /**< true if manual input is mixed in */
- bool flag_control_offboard_enabled; /**< true if offboard control input is on */
+ mode_switch_pos_t mode_switch;
+ return_switch_pos_t return_switch;
+ mission_switch_pos_t mission_switch;
+
+
+ bool condition_system_emergency;
+ bool condition_system_in_air_restore; /**< true if we can restore in mid air */
+ bool condition_system_sensors_initialized;
+ bool condition_system_returned_to_home;
+ bool condition_auto_mission_available;
+ bool condition_global_position_valid; /**< set to true by the commander app if the quality of the gps signal is good enough to use it in the position estimator */
+ bool condition_launch_position_valid; /**< indicates a valid launch position */
+ bool condition_home_position_valid; /**< indicates a valid home position (a valid home position is not always a valid launch) */
+ bool condition_local_position_valid;
+ bool condition_airspeed_valid; /**< set to true by the commander app if there is a valid airspeed measurement available */
+
+ // bool condition_auto_flight_mode_ok; /**< conditions of auto flight mode apply plus a valid takeoff position lock has been aquired */
+ bool flag_external_manual_override_ok; /**< external override non-fatal for system. Only true for fixed wing */
+
bool flag_hil_enabled; /**< true if hardware in the loop simulation is enabled */
+ //bool flag_armed; /**< true is motors / actuators are armed */
+ //bool flag_safety_off; /**< true if safety is off */
+ bool flag_system_emergency;
+ bool flag_preflight_calibration;
- bool flag_control_rates_enabled; /**< true if rates are stabilized */
- bool flag_control_attitude_enabled; /**< true if attitude stabilization is mixed in */
- bool flag_control_velocity_enabled; /**< true if speed (implies direction) is controlled */
- bool flag_control_position_enabled; /**< true if position is controlled */
+ // bool flag_control_manual_enabled; /**< true if manual input is mixed in */
+ // bool flag_control_offboard_enabled; /**< true if offboard control input is on */
+ // bool flag_auto_enabled;
+ // bool flag_control_rates_enabled; /**< true if rates are stabilized */
+ // bool flag_control_attitude_enabled; /**< true if attitude stabilization is mixed in */
+ // bool flag_control_velocity_enabled; /**< true if speed (implies direction) is controlled */
+ // bool flag_control_position_enabled; /**< true if position is controlled */
- bool flag_preflight_gyro_calibration; /**< true if gyro calibration is requested */
- bool flag_preflight_mag_calibration; /**< true if mag calibration is requested */
- bool flag_preflight_accel_calibration;
- bool flag_preflight_airspeed_calibration;
+ // bool flag_preflight_gyro_calibration; /**< true if gyro calibration is requested */
+ // bool flag_preflight_mag_calibration; /**< true if mag calibration is requested */
+ // bool flag_preflight_accel_calibration;
+ // bool flag_preflight_airspeed_calibration;
bool rc_signal_found_once;
bool rc_signal_lost; /**< true if RC reception is terminally lost */
@@ -188,7 +228,7 @@ struct vehicle_status_s
uint64_t offboard_control_signal_lost_interval; /**< interval in microseconds without an offboard control message */
bool failsave_lowlevel; /**< Set to true if low-level failsafe mode is enabled */
- //bool failsave_highlevel;
+ bool failsave_highlevel;
/* see SYS_STATUS mavlink message for the following */
uint32_t onboard_control_sensors_present;
@@ -205,15 +245,6 @@ struct vehicle_status_s
uint16_t errors_count2;
uint16_t errors_count3;
uint16_t errors_count4;
-
- bool flag_global_position_valid; /**< set to true by the commander app if the quality of the gps signal is good enough to use it in the position estimator */
- bool flag_local_position_valid;
- bool flag_vector_flight_mode_ok; /**< position estimation, battery voltage and other critical subsystems are good for autonomous flight */
- bool flag_auto_flight_mode_ok; /**< conditions of vector flight mode apply plus a valid takeoff position lock has been aquired */
- bool flag_external_manual_override_ok; /**< external override non-fatal for system. Only true for fixed wing */
- 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 */
};
/**
diff --git a/src/systemcmds/esc_calib/esc_calib.c b/src/systemcmds/esc_calib/esc_calib.c
new file mode 100644
index 000000000..188fa4e37
--- /dev/null
+++ b/src/systemcmds/esc_calib/esc_calib.c
@@ -0,0 +1,250 @@
+/****************************************************************************
+ *
+ * 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 esc_calib.c
+ *
+ * Tool for ESC calibration
+ */
+
+#include <nuttx/config.h>
+
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include <stdbool.h>
+#include <unistd.h>
+#include <fcntl.h>
+#include <sys/mount.h>
+#include <sys/ioctl.h>
+#include <sys/stat.h>
+
+#include <nuttx/i2c.h>
+#include <nuttx/mtd.h>
+#include <nuttx/fs/nxffs.h>
+#include <nuttx/fs/ioctl.h>
+
+#include <arch/board/board.h>
+
+#include "systemlib/systemlib.h"
+#include "systemlib/err.h"
+#include "drivers/drv_pwm_output.h"
+
+static void usage(const char *reason);
+__EXPORT int esc_calib_main(int argc, char *argv[]);
+
+#define MAX_CHANNELS 8
+
+static void
+usage(const char *reason)
+{
+ if (reason != NULL)
+ warnx("%s", reason);
+ errx(1,
+ "usage:\n"
+ "esc_calib [-d <device>] <channels>\n"
+ " <device> PWM output device (defaults to " PWM_OUTPUT_DEVICE_PATH ")\n"
+ " <channels> Provide channels (e.g.: 1 2 3 4)\n"
+ );
+
+}
+
+int
+esc_calib_main(int argc, char *argv[])
+{
+ const char *dev = PWM_OUTPUT_DEVICE_PATH;
+ char *ep;
+ bool channels_selected[MAX_CHANNELS] = {false};
+ int ch;
+ int ret;
+ char c;
+
+ if (argc < 2)
+ usage(NULL);
+
+ while ((ch = getopt(argc, argv, "d:")) != EOF) {
+ switch (ch) {
+
+ case 'd':
+ dev = optarg;
+ argc--;
+ break;
+
+ default:
+ usage(NULL);
+ }
+ }
+
+ if(argc < 1) {
+ usage("no channels provided");
+ }
+
+ while (--argc) {
+ const char *arg = argv[argc];
+ unsigned channel_number = strtol(arg, &ep, 0);
+
+ if (*ep == '\0') {
+ if (channel_number > MAX_CHANNELS || channel_number <= 0) {
+ err(1, "invalid channel number: %d", channel_number);
+ } else {
+ channels_selected[channel_number-1] = true;
+
+ }
+ }
+ }
+
+ /* Wait for confirmation */
+ int console = open("/dev/console", O_NONBLOCK | O_RDONLY | O_NOCTTY);
+ if (!console)
+ err(1, "failed opening console");
+
+ warnx("ATTENTION, please remove or fix props before starting calibration!\n"
+ "\n"
+ "Also press the arming switch first for safety off\n"
+ "\n"
+ "Do you really want to start calibration: y or n?\n");
+
+ /* wait for user input */
+ while (1) {
+
+ if (read(console, &c, 1) == 1) {
+ if (c == 'y' || c == 'Y') {
+
+ break;
+ } else if (c == 0x03 || c == 0x63 || c == 'q') {
+ warnx("ESC calibration exited");
+ close(console);
+ exit(0);
+ } else if (c == 'n' || c == 'N') {
+ warnx("ESC calibration aborted");
+ close(console);
+ exit(0);
+ } else {
+ warnx("Unknown input, ESC calibration aborted");
+ close(console);
+ exit(0);
+ }
+ }
+ /* rate limit to ~ 20 Hz */
+ usleep(50000);
+ }
+
+ /* open for ioctl only */
+ int fd = open(dev, 0);
+ if (fd < 0)
+ err(1, "can't open %s", dev);
+
+ // XXX arming not necessaire at the moment
+ // /* Then arm */
+ // ret = ioctl(fd, PWM_SERVO_SET_ARM_OK, 0);
+ // if (ret != OK)
+ // err(1, "PWM_SERVO_SET_ARM_OK");
+
+ // ret = ioctl(fd, PWM_SERVO_ARM, 0);
+ // if (ret != OK)
+ // err(1, "PWM_SERVO_ARM");
+
+
+
+
+ /* Wait for user confirmation */
+ warnx("Set high PWM\n"
+ "Connect battery now and hit ENTER after the ESCs confirm the first calibration step");
+
+ while (1) {
+
+ /* First set high PWM */
+ for (unsigned i = 0; i<MAX_CHANNELS; i++) {
+ if(channels_selected[i]) {
+ ret = ioctl(fd, PWM_SERVO_SET(i), 2100);
+ if (ret != OK)
+ err(1, "PWM_SERVO_SET(%d)", i);
+ }
+ }
+
+ if (read(console, &c, 1) == 1) {
+ if (c == 13) {
+
+ break;
+ } else if (c == 0x03 || c == 0x63 || c == 'q') {
+ warnx("ESC calibration exited");
+ close(console);
+ exit(0);
+ }
+ }
+ /* rate limit to ~ 20 Hz */
+ usleep(50000);
+ }
+
+ /* we don't need any more user input */
+
+
+ warnx("Set low PWM, hit ENTER when finished");
+
+ while (1) {
+
+ /* Then set low PWM */
+ for (unsigned i = 0; i<MAX_CHANNELS; i++) {
+ if(channels_selected[i]) {
+ ret = ioctl(fd, PWM_SERVO_SET(i), 900);
+ if (ret != OK)
+ err(1, "PWM_SERVO_SET(%d)", i);
+ }
+ }
+
+ if (read(console, &c, 1) == 1) {
+ if (c == 13) {
+
+ break;
+ } else if (c == 0x03 || c == 0x63 || c == 'q') {
+ warnx("ESC calibration exited");
+ close(console);
+ exit(0);
+ }
+ }
+ /* rate limit to ~ 20 Hz */
+ usleep(50000);
+ }
+
+
+ warnx("ESC calibration finished");
+ close(console);
+
+ // XXX disarming not necessaire at the moment
+ /* Now disarm again */
+ // ret = ioctl(fd, PWM_SERVO_DISARM, 0);
+
+
+
+ exit(0);
+} \ No newline at end of file
diff --git a/src/systemcmds/esc_calib/module.mk b/src/systemcmds/esc_calib/module.mk
new file mode 100644
index 000000000..990c56768
--- /dev/null
+++ b/src/systemcmds/esc_calib/module.mk
@@ -0,0 +1,41 @@
+############################################################################
+#
+# Copyright (c) 2012, 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.
+#
+############################################################################
+
+#
+# Build the esc_calib tool.
+#
+
+MODULE_COMMAND = esc_calib
+SRCS = esc_calib.c
+
+MODULE_STACKSIZE = 4096
diff --git a/src/systemcmds/pwm/pwm.c b/src/systemcmds/pwm/pwm.c
index e150b5a74..c42a36c7f 100644
--- a/src/systemcmds/pwm/pwm.c
+++ b/src/systemcmds/pwm/pwm.c
@@ -180,7 +180,8 @@ pwm_main(int argc, char *argv[])
}
/* iterate remaining arguments */
- unsigned channel = 0;
+ unsigned nchannels = 0;
+ unsigned channel[8] = {0};
while (argc--) {
const char *arg = argv[0];
argv++;
@@ -204,13 +205,15 @@ pwm_main(int argc, char *argv[])
}
unsigned pwm_value = strtol(arg, &ep, 0);
if (*ep == '\0') {
- ret = ioctl(fd, PWM_SERVO_SET(channel), pwm_value);
- if (ret != OK)
- err(1, "PWM_SERVO_SET(%d)", channel);
- channel++;
+ if (nchannels > sizeof(channel) / sizeof(channel[0]))
+ err(1, "too many pwm values (max %d)", sizeof(channel) / sizeof(channel[0]));
+
+ channel[nchannels] = pwm_value;
+ nchannels++;
+
continue;
}
- usage("unrecognised option");
+ usage("unrecognized option");
}
/* print verbose info */
@@ -250,5 +253,38 @@ pwm_main(int argc, char *argv[])
}
fflush(stdout);
}
+
+ /* perform PWM output */
+ if (nchannels) {
+
+ /* Open console directly to grab CTRL-C signal */
+ int console = open("/dev/console", O_NONBLOCK | O_RDONLY | O_NOCTTY);
+ if (!console)
+ err(1, "failed opening console");
+
+ warnx("Press CTRL-C or 'c' to abort.");
+
+ while (1) {
+ for (int i = 0; i < nchannels; i++) {
+ ret = ioctl(fd, PWM_SERVO_SET(i), channel[i]);
+ if (ret != OK)
+ err(1, "PWM_SERVO_SET(%d)", i);
+ }
+
+ /* abort on user request */
+ char c;
+ if (read(console, &c, 1) == 1) {
+ if (c == 0x03 || c == 0x63 || c == 'q') {
+ warnx("User abort\n");
+ close(console);
+ exit(0);
+ }
+ }
+
+ /* rate limit to ~ 20 Hz */
+ usleep(50000);
+ }
+ }
+
exit(0);
} \ No newline at end of file
diff --git a/src/systemcmds/reboot/reboot.c b/src/systemcmds/reboot/reboot.c
index 47d3cd948..cc380f94b 100644
--- a/src/systemcmds/reboot/reboot.c
+++ b/src/systemcmds/reboot/reboot.c
@@ -47,6 +47,9 @@ __EXPORT int reboot_main(int argc, char *argv[]);
int reboot_main(int argc, char *argv[])
{
+ printf("Rebooting now...\n");
+ fflush(stdout);
+ usleep(5000);
up_systemreset();
}