aboutsummaryrefslogtreecommitdiff
path: root/src/modules
diff options
context:
space:
mode:
authorAnton Babushkin <anton.babushkin@me.com>2014-06-12 13:11:45 +0200
committerAnton Babushkin <anton.babushkin@me.com>2014-06-12 13:11:45 +0200
commit2951962c2104a0b2a284a7c5208171b257ed9734 (patch)
tree06b0a4ade5fe55fedd37dcea0c5d390380a0627a /src/modules
parent3f1f015fe0998618318c196dc15e245bd4c05675 (diff)
downloadpx4-firmware-2951962c2104a0b2a284a7c5208171b257ed9734.tar.gz
px4-firmware-2951962c2104a0b2a284a7c5208171b257ed9734.tar.bz2
px4-firmware-2951962c2104a0b2a284a7c5208171b257ed9734.zip
dataman: rename SYSTEM_STATE section to MISSION_STATE
Diffstat (limited to 'src/modules')
-rw-r--r--src/modules/dataman/dataman.c6
-rw-r--r--src/modules/dataman/dataman.h4
-rw-r--r--src/modules/mavlink/mavlink_main.cpp18
-rw-r--r--src/modules/navigator/navigator_main.cpp2
4 files changed, 15 insertions, 15 deletions
diff --git a/src/modules/dataman/dataman.c b/src/modules/dataman/dataman.c
index 14fee7c9a..4a89c7d41 100644
--- a/src/modules/dataman/dataman.c
+++ b/src/modules/dataman/dataman.c
@@ -116,7 +116,7 @@ static const unsigned g_per_item_max_index[DM_KEY_NUM_KEYS] = {
DM_KEY_WAYPOINTS_OFFBOARD_0_MAX,
DM_KEY_WAYPOINTS_OFFBOARD_1_MAX,
DM_KEY_WAYPOINTS_ONBOARD_MAX,
- DM_KEY_SYSTEM_STATE_MAX
+ DM_KEY_MISSION_STATE_MAX
};
/* Table of offset for index 0 of each item type */
@@ -642,11 +642,11 @@ task_main(int argc, char *argv[])
for (unsigned i = 0; i < dm_number_of_funcs; i++)
g_func_counts[i] = 0;
- /* Initialize the item type locks, for now only DM_KEY_SYSTEM_STATE supports locking */
+ /* Initialize the item type locks, for now only DM_KEY_MISSION_STATE supports locking */
sem_init(&g_sys_state_mutex, 1, 1); /* Initially unlocked */
for (unsigned i = 0; i < DM_KEY_NUM_KEYS; i++)
g_item_locks[i] = NULL;
- g_item_locks[DM_KEY_SYSTEM_STATE] = &g_sys_state_mutex;
+ g_item_locks[DM_KEY_MISSION_STATE] = &g_sys_state_mutex;
g_task_should_exit = false;
diff --git a/src/modules/dataman/dataman.h b/src/modules/dataman/dataman.h
index b25a2a5ef..215ec4c76 100644
--- a/src/modules/dataman/dataman.h
+++ b/src/modules/dataman/dataman.h
@@ -53,7 +53,7 @@ extern "C" {
DM_KEY_WAYPOINTS_OFFBOARD_0, /* Mission way point coordinates sent over mavlink */
DM_KEY_WAYPOINTS_OFFBOARD_1, /* (alernate between 0 and 1) */
DM_KEY_WAYPOINTS_ONBOARD, /* Mission way point coordinates generated onboard */
- DM_KEY_SYSTEM_STATE, /* Persistent system state storage */
+ DM_KEY_MISSION_STATE, /* Persistent mission state */
DM_KEY_NUM_KEYS /* Total number of item types defined */
} dm_item_t;
@@ -64,7 +64,7 @@ extern "C" {
DM_KEY_WAYPOINTS_OFFBOARD_0_MAX = NUM_MISSIONS_SUPPORTED,
DM_KEY_WAYPOINTS_OFFBOARD_1_MAX = NUM_MISSIONS_SUPPORTED,
DM_KEY_WAYPOINTS_ONBOARD_MAX = NUM_MISSIONS_SUPPORTED,
- DM_KEY_SYSTEM_STATE_MAX = 1
+ DM_KEY_MISSION_STATE_MAX = 1
};
/** Data persistence levels */
diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp
index 9159f5d61..be1fc50a6 100644
--- a/src/modules/mavlink/mavlink_main.cpp
+++ b/src/modules/mavlink/mavlink_main.cpp
@@ -969,7 +969,7 @@ void Mavlink::mavlink_wpm_init(mavlink_wpm_storage *state)
state->action_timeout = MAVLINK_WPM_PROTOCOL_TIMEOUT_DEFAULT;
state->retry_timeout = MAVLINK_WPM_RETRY_TIMEOUT_DEFAULT;
- int sys_state_size = dm_read(DM_KEY_SYSTEM_STATE, 0, &sys_state, sizeof(sys_state));
+ int sys_state_size = dm_read(DM_KEY_MISSION_STATE, 0, &sys_state, sizeof(sys_state));
if (sys_state_size == sizeof(sys_state)) {
if ((sys_state.offboard_waypoint_id >= 0) && (sys_state.offboard_waypoint_id <= 1)) {
state->dataman_id = sys_state.offboard_waypoint_id;
@@ -990,11 +990,11 @@ void Mavlink::mavlink_wpm_init(mavlink_wpm_storage *state)
state->size = seq;
} else {
- if (_verbose) { warnx("WPM init: invalid dataman ID %d stored in SYSTEM_STATE", sys_state.offboard_waypoint_id); }
+ if (_verbose) { warnx("WPM init: invalid dataman ID %d stored in MISSION_STATE", sys_state.offboard_waypoint_id); }
}
} else {
- if (_verbose) { warnx("WPM init: dataman SYSTEM_STATE item has wrong size (%i, should be %u), ignoring", sys_state_size, sizeof(sys_state)); }
+ if (_verbose) { warnx("WPM init: dataman MISSION_STATE item has wrong size (%i, should be %u), ignoring", sys_state_size, sizeof(sys_state)); }
}
/* init mission topic */
@@ -1467,25 +1467,25 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg)
bool dm_result;
/* since we are doing a read-modify-write we must lock the item type */
- dm_lock(DM_KEY_SYSTEM_STATE);
+ dm_lock(DM_KEY_MISSION_STATE);
/* first read in the current state data, there may eventually be data other than the offboard index
* and we must preserve it */
- ssize_t dm_state_size = dm_read(DM_KEY_SYSTEM_STATE, 0, &state, sizeof(state));
+ ssize_t dm_state_size = dm_read(DM_KEY_MISSION_STATE, 0, &state, sizeof(state));
if (dm_state_size != sizeof(state)) {
- warnx("dataman SYSTEM_STATE size invalid: %d, should be %d", dm_state_size, sizeof(state));
+ warnx("dataman MISSION_STATE size invalid: %d, should be %d", dm_state_size, sizeof(state));
}
/* set new dataman storage ID */
state.offboard_waypoint_id = _wpm->current_dataman_id;
/* write back to dataman */
- dm_result = dm_write(DM_KEY_SYSTEM_STATE, 0, DM_PERSIST_POWER_ON_RESET, &state, sizeof(state)) != sizeof(state);
+ dm_result = dm_write(DM_KEY_MISSION_STATE, 0, DM_PERSIST_POWER_ON_RESET, &state, sizeof(state)) != sizeof(state);
- dm_unlock(DM_KEY_SYSTEM_STATE);
+ dm_unlock(DM_KEY_MISSION_STATE);
if (dm_result) {
- if (_verbose) { warnx("WPM: MISSION_ITEM ERROR unable to write storage ID = %d to dataman SYSTEM_STATE", state.offboard_waypoint_id); }
+ if (_verbose) { warnx("WPM: MISSION_ITEM ERROR unable to write storage ID = %d to dataman MISSION_STATE", state.offboard_waypoint_id); }
mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, MAV_MISSION_ERROR);
mavlink_missionlib_send_gcs_string("#audio: Unable to write on micro SD");
diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp
index a3426e65e..c7b39ba93 100644
--- a/src/modules/navigator/navigator_main.cpp
+++ b/src/modules/navigator/navigator_main.cpp
@@ -605,7 +605,7 @@ Navigator::task_main()
/* Get the last offboard mission id */
persistent_system_state_t sys_state;
- if (dm_read(DM_KEY_SYSTEM_STATE, 0, &sys_state, sizeof(sys_state)) == sizeof(sys_state)) {
+ if (dm_read(DM_KEY_MISSION_STATE, 0, &sys_state, sizeof(sys_state)) == sizeof(sys_state)) {
if ((sys_state.offboard_waypoint_id >= 0) && (sys_state.offboard_waypoint_id <= 1))
_mission.set_offboard_dataman_id(sys_state.offboard_waypoint_id);
}