From 99dd229d719f8b7e1b5587f71d13c8ba23505bf9 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Tue, 13 Aug 2019 16:41:35 +0200 Subject: [PATCH] Rally Point: fix typo of save to safe in mission_safe_point_s Signed-off-by: Silvan Fuhrer --- src/modules/dataman/dataman.cpp | 2 +- src/modules/dataman/dataman.h | 2 +- src/modules/mavlink/mavlink_mission.cpp | 28 ++++++++++++------------- src/modules/mavlink/mavlink_mission.h | 2 +- src/modules/navigator/navigation.h | 4 ++-- 5 files changed, 19 insertions(+), 19 deletions(-) diff --git a/src/modules/dataman/dataman.cpp b/src/modules/dataman/dataman.cpp index 88b2fce59b..7727042903 100644 --- a/src/modules/dataman/dataman.cpp +++ b/src/modules/dataman/dataman.cpp @@ -228,7 +228,7 @@ static const unsigned g_per_item_max_index[DM_KEY_NUM_KEYS] = { /* Table of the len of each item type */ static constexpr size_t g_per_item_size[DM_KEY_NUM_KEYS] = { - sizeof(struct mission_save_point_s) + DM_SECTOR_HDR_SIZE, + sizeof(struct mission_safe_point_s) + DM_SECTOR_HDR_SIZE, sizeof(struct mission_fence_point_s) + DM_SECTOR_HDR_SIZE, sizeof(struct mission_item_s) + DM_SECTOR_HDR_SIZE, sizeof(struct mission_item_s) + DM_SECTOR_HDR_SIZE, diff --git a/src/modules/dataman/dataman.h b/src/modules/dataman/dataman.h index ff732414f6..8d253c82d3 100644 --- a/src/modules/dataman/dataman.h +++ b/src/modules/dataman/dataman.h @@ -103,7 +103,7 @@ struct dataman_compat_s { #define DM_COMPAT_KEY ((DM_COMPAT_VERSION << 32) + (sizeof(struct mission_item_s) << 24) + \ (sizeof(struct mission_s) << 16) + (sizeof(struct mission_stats_entry_s) << 12) + \ - (sizeof(struct mission_fence_point_s) << 8) + (sizeof(struct mission_save_point_s) << 4) + \ + (sizeof(struct mission_fence_point_s) << 8) + (sizeof(struct mission_safe_point_s) << 4) + \ sizeof(struct dataman_compat_s)) /** Retrieve from the data manager store */ diff --git a/src/modules/mavlink/mavlink_mission.cpp b/src/modules/mavlink/mavlink_mission.cpp index 8e59e6fee1..68ec839cd9 100644 --- a/src/modules/mavlink/mavlink_mission.cpp +++ b/src/modules/mavlink/mavlink_mission.cpp @@ -336,15 +336,15 @@ MavlinkMissionManager::send_mission_item(uint8_t sysid, uint8_t compid, uint16_t break; case MAV_MISSION_TYPE_RALLY: { // Read a safe point / rally point - mission_save_point_s mission_save_point; - read_success = dm_read(DM_KEY_SAFE_POINTS, seq + 1, &mission_save_point, sizeof(mission_save_point_s)) == - sizeof(mission_save_point_s); + mission_safe_point_s mission_safe_point; + read_success = dm_read(DM_KEY_SAFE_POINTS, seq + 1, &mission_safe_point, sizeof(mission_safe_point_s)) == + sizeof(mission_safe_point_s); mission_item.nav_cmd = MAV_CMD_NAV_RALLY_POINT; - mission_item.frame = mission_save_point.frame; - mission_item.lat = mission_save_point.lat; - mission_item.lon = mission_save_point.lon; - mission_item.altitude = mission_save_point.alt; + mission_item.frame = mission_safe_point.frame; + mission_item.lat = mission_safe_point.lat; + mission_item.lon = mission_safe_point.lon; + mission_item.altitude = mission_safe_point.alt; } break; @@ -1113,13 +1113,13 @@ MavlinkMissionManager::handle_mission_item_both(const mavlink_message_t *msg) break; case MAV_MISSION_TYPE_RALLY: { // Write a safe point / rally point - mission_save_point_s mission_save_point; - mission_save_point.lat = mission_item.lat; - mission_save_point.lon = mission_item.lon; - mission_save_point.alt = mission_item.altitude; - mission_save_point.frame = mission_item.frame; - write_failed = dm_write(DM_KEY_SAFE_POINTS, wp.seq + 1, DM_PERSIST_POWER_ON_RESET, &mission_save_point, - sizeof(mission_save_point_s)) != sizeof(mission_save_point_s); + mission_safe_point_s mission_safe_point; + mission_safe_point.lat = mission_item.lat; + mission_safe_point.lon = mission_item.lon; + mission_safe_point.alt = mission_item.altitude; + mission_safe_point.frame = mission_item.frame; + write_failed = dm_write(DM_KEY_SAFE_POINTS, wp.seq + 1, DM_PERSIST_POWER_ON_RESET, &mission_safe_point, + sizeof(mission_safe_point_s)) != sizeof(mission_safe_point_s); } break; diff --git a/src/modules/mavlink/mavlink_mission.h b/src/modules/mavlink/mavlink_mission.h index fe3f9bfa7e..aeaff342af 100644 --- a/src/modules/mavlink/mavlink_mission.h +++ b/src/modules/mavlink/mavlink_mission.h @@ -145,7 +145,7 @@ private: DM_KEY_FENCE_POINTS_MAX - 1, DM_KEY_SAFE_POINTS_MAX - 1 }; /**< Maximum number of mission items for each type - (fence & save points use the first item for the stats) */ + (fence & safe points use the first item for the stats) */ /** get the maximum number of item count for the current _mission_type */ uint16_t current_max_item_count(); diff --git a/src/modules/navigator/navigation.h b/src/modules/navigator/navigation.h index 92c4a263f5..d1011e489f 100644 --- a/src/modules/navigator/navigation.h +++ b/src/modules/navigator/navigation.h @@ -217,10 +217,10 @@ struct mission_fence_point_s { }; /** - * Save Point (Rally Point). + * Safe Point (Rally Point). * Corresponds to the DM_KEY_SAFE_POINTS dataman item */ -struct mission_save_point_s { +struct mission_safe_point_s { double lat; double lon; float alt;