aboutsummaryrefslogtreecommitdiff
path: root/src/modules/commander
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules/commander')
-rw-r--r--src/modules/commander/commander.cpp35
1 files changed, 30 insertions, 5 deletions
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index 270aa2a1a..4e6b124a4 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -78,6 +78,7 @@
#include <uORB/topics/differential_pressure.h>
#include <uORB/topics/safety.h>
#include <uORB/topics/system_power.h>
+#include <uORB/topics/mission.h>
#include <uORB/topics/mission_result.h>
#include <uORB/topics/telemetry_status.h>
@@ -92,6 +93,7 @@
#include <systemlib/cpuload.h>
#include <systemlib/rc_check.h>
#include <systemlib/state_table.h>
+#include <dataman/dataman.h>
#include "px4_custom_mode.h"
#include "commander_helper.h"
@@ -717,6 +719,11 @@ int commander_thread_main(int argc, char *argv[])
/* publish initial state */
status_pub = orb_advertise(ORB_ID(vehicle_status), &status);
+ if (status_pub < 0) {
+ warnx("ERROR: orb_advertise for topic vehicle_status failed (uorb app running?).\n");
+ warnx("exiting.");
+ exit(ERROR);
+ }
/* armed topic */
orb_advert_t armed_pub;
@@ -734,10 +741,27 @@ int commander_thread_main(int argc, char *argv[])
struct home_position_s home;
memset(&home, 0, sizeof(home));
- if (status_pub < 0) {
- warnx("ERROR: orb_advertise for topic vehicle_status failed (uorb app running?).\n");
- warnx("exiting.");
- exit(ERROR);
+ /* init mission state, do it here to allow navigator to use stored mission even if mavlink failed to start */
+ orb_advert_t mission_pub = -1;
+ mission_s mission;
+ if (dm_read(DM_KEY_MISSION_STATE, 0, &mission, sizeof(mission_s)) == sizeof(mission_s)) {
+ if (mission.dataman_id >= 0 && mission.dataman_id <= 1) {
+ warnx("loaded mission state: dataman_id=%d, count=%u, current=%d", mission.dataman_id, mission.count, mission.current_seq);
+ mavlink_log_info(mavlink_fd, "[cmd] dataman_id=%d, count=%u, current=%d",
+ mission.dataman_id, mission.count, mission.current_seq);
+ } else {
+ warnx("reading mission state failed");
+ mavlink_log_info(mavlink_fd, "[cmd] reading mission state failed");
+
+ /* initialize mission state in dataman */
+ mission.dataman_id = 0;
+ mission.count = 0;
+ mission.current_seq = 0;
+ dm_write(DM_KEY_MISSION_STATE, 0, DM_PERSIST_POWER_ON_RESET, &mission, sizeof(mission_s));
+ }
+
+ mission_pub = orb_advertise(ORB_ID(offboard_mission), &mission);
+ orb_publish(ORB_ID(offboard_mission), mission_pub, &mission);
}
mavlink_log_info(mavlink_fd, "[cmd] started");
@@ -1466,7 +1490,7 @@ int commander_thread_main(int argc, char *argv[])
/* now set navigation state according to failsafe and main state */
bool nav_state_changed = set_nav_state(&status, (bool)datalink_loss_enabled,
- mission_result.mission_finished);
+ mission_result.finished);
// TODO handle mode changes by commands
if (main_state_changed) {
@@ -1570,6 +1594,7 @@ int commander_thread_main(int argc, char *argv[])
close(diff_pres_sub);
close(param_changed_sub);
close(battery_sub);
+ close(mission_pub);
thread_running = false;