forked from Archive/PX4-Autopilot
mission: renaming dataman_id to mission_dataman_id
This commit is contained in:
parent
cac858cb24
commit
dfa56d474a
|
@ -1,5 +1,5 @@
|
|||
uint64 timestamp # time since system start (microseconds)
|
||||
uint8 dataman_id # default 0, there are two offboard storage places in the dataman: 0 or 1
|
||||
uint8 mission_dataman_id # default 0, there are two offboard storage places in the dataman: 0 or 1
|
||||
|
||||
uint16 count # count of the missions stored in the dataman
|
||||
int32 current_seq # default -1, start at the one changed latest
|
||||
|
|
|
@ -570,7 +570,7 @@ _file_initialize(unsigned max_offset)
|
|||
|
||||
mission_s mission{};
|
||||
mission.timestamp = hrt_absolute_time();
|
||||
mission.dataman_id = DM_KEY_WAYPOINTS_OFFBOARD_0;
|
||||
mission.mission_dataman_id = DM_KEY_WAYPOINTS_OFFBOARD_0;
|
||||
mission.count = 0;
|
||||
mission.current_seq = 0;
|
||||
mission.mission_id = 0u;
|
||||
|
|
|
@ -57,7 +57,7 @@
|
|||
|
||||
using matrix::wrap_2pi;
|
||||
|
||||
dm_item_t MavlinkMissionManager::_dataman_id = DM_KEY_WAYPOINTS_OFFBOARD_0;
|
||||
dm_item_t MavlinkMissionManager::_mission_dataman_id = DM_KEY_WAYPOINTS_OFFBOARD_0;
|
||||
bool MavlinkMissionManager::_dataman_init = false;
|
||||
uint16_t MavlinkMissionManager::_count[3] = { 0, 0, 0 };
|
||||
uint32_t MavlinkMissionManager::_crc32[3] = { 0, 0, 0 };
|
||||
|
@ -90,13 +90,14 @@ MavlinkMissionManager::MavlinkMissionManager(Mavlink *mavlink) :
|
|||
}
|
||||
}
|
||||
|
||||
_my_dataman_id = _dataman_id;
|
||||
_my_mission_dataman_id = _mission_dataman_id;
|
||||
}
|
||||
|
||||
void
|
||||
MavlinkMissionManager::init_offboard_mission(const mission_s &mission_state)
|
||||
{
|
||||
_dataman_id = (dm_item_t)mission_state.dataman_id;
|
||||
_mission_dataman_id = (dm_item_t)mission_state.mission_dataman_id;
|
||||
_my_mission_dataman_id = _mission_dataman_id;
|
||||
_count[MAV_MISSION_TYPE_MISSION] = mission_state.count;
|
||||
_crc32[MAV_MISSION_TYPE_MISSION] = mission_state.mission_id;
|
||||
_current_seq = mission_state.current_seq;
|
||||
|
@ -140,19 +141,19 @@ MavlinkMissionManager::load_safepoint_stats()
|
|||
* Publish mission topic to notify navigator about changes.
|
||||
*/
|
||||
void
|
||||
MavlinkMissionManager::update_active_mission(dm_item_t dataman_id, uint16_t count, int32_t seq, uint32_t crc32,
|
||||
MavlinkMissionManager::update_active_mission(dm_item_t mission_dataman_id, uint16_t count, int32_t seq, uint32_t crc32,
|
||||
bool write_to_dataman)
|
||||
{
|
||||
/* update active mission state */
|
||||
_dataman_id = dataman_id;
|
||||
_mission_dataman_id = mission_dataman_id;
|
||||
_count[MAV_MISSION_TYPE_MISSION] = count;
|
||||
_crc32[MAV_MISSION_TYPE_MISSION] = crc32;
|
||||
_current_seq = seq;
|
||||
_my_dataman_id = _dataman_id;
|
||||
_my_mission_dataman_id = _mission_dataman_id;
|
||||
|
||||
mission_s mission{};
|
||||
mission.timestamp = hrt_absolute_time();
|
||||
mission.dataman_id = dataman_id;
|
||||
mission.mission_dataman_id = mission_dataman_id;
|
||||
mission.count = count;
|
||||
mission.current_seq = seq;
|
||||
mission.mission_id = _crc32[MAV_MISSION_TYPE_MISSION];
|
||||
|
@ -199,7 +200,8 @@ MavlinkMissionManager::update_geofence_count(unsigned count, uint32_t crc32)
|
|||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
update_active_mission(_dataman_id, _count[MAV_MISSION_TYPE_MISSION], _current_seq, _crc32[MAV_MISSION_TYPE_MISSION],
|
||||
update_active_mission(_mission_dataman_id, _count[MAV_MISSION_TYPE_MISSION], _current_seq,
|
||||
_crc32[MAV_MISSION_TYPE_MISSION],
|
||||
false);
|
||||
return PX4_OK;
|
||||
}
|
||||
|
@ -230,7 +232,8 @@ MavlinkMissionManager::update_safepoint_count(unsigned count, uint32_t crc32)
|
|||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
update_active_mission(_dataman_id, _count[MAV_MISSION_TYPE_MISSION], _current_seq, _crc32[MAV_MISSION_TYPE_MISSION],
|
||||
update_active_mission(_mission_dataman_id, _count[MAV_MISSION_TYPE_MISSION], _current_seq,
|
||||
_crc32[MAV_MISSION_TYPE_MISSION],
|
||||
false);
|
||||
return PX4_OK;
|
||||
}
|
||||
|
@ -293,7 +296,7 @@ MavlinkMissionManager::send_mission_item(uint8_t sysid, uint8_t compid, uint16_t
|
|||
switch (_mission_type) {
|
||||
|
||||
case MAV_MISSION_TYPE_MISSION: {
|
||||
read_success = _dataman_client.readSync(_dataman_id, seq, reinterpret_cast<uint8_t *>(&mission_item),
|
||||
read_success = _dataman_client.readSync(_mission_dataman_id, seq, reinterpret_cast<uint8_t *>(&mission_item),
|
||||
sizeof(mission_item_s));
|
||||
}
|
||||
break;
|
||||
|
@ -375,7 +378,7 @@ MavlinkMissionManager::send_mission_item(uint8_t sysid, uint8_t compid, uint16_t
|
|||
"Mission: Unable to read from storage", _mission_type);
|
||||
}
|
||||
|
||||
PX4_DEBUG("WPM: Send MISSION_ITEM ERROR: could not read seq %u from dataman ID %i", seq, _dataman_id);
|
||||
PX4_DEBUG("WPM: Send MISSION_ITEM ERROR: could not read seq %u from dataman ID %i", seq, _mission_dataman_id);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -670,7 +673,7 @@ MavlinkMissionManager::handle_mission_set_current(const mavlink_message_t *msg)
|
|||
_time_last_recv = hrt_absolute_time();
|
||||
|
||||
if (wpc.seq < _count[MAV_MISSION_TYPE_MISSION]) {
|
||||
update_active_mission(_dataman_id, _count[MAV_MISSION_TYPE_MISSION], wpc.seq, _crc32[MAV_MISSION_TYPE_MISSION]);
|
||||
update_active_mission(_mission_dataman_id, _count[MAV_MISSION_TYPE_MISSION], wpc.seq, _crc32[MAV_MISSION_TYPE_MISSION]);
|
||||
|
||||
} else {
|
||||
PX4_ERR("WPM: MISSION_SET_CURRENT seq=%d ERROR: not in list", wpc.seq);
|
||||
|
@ -904,7 +907,7 @@ MavlinkMissionManager::handle_mission_count(const mavlink_message_t *msg)
|
|||
|
||||
/* alternate dataman ID anyway to let navigator know about changes */
|
||||
|
||||
if (_dataman_id == DM_KEY_WAYPOINTS_OFFBOARD_0) {
|
||||
if (_mission_dataman_id == DM_KEY_WAYPOINTS_OFFBOARD_0) {
|
||||
update_active_mission(DM_KEY_WAYPOINTS_OFFBOARD_1, 0, 0, 0);
|
||||
|
||||
} else {
|
||||
|
@ -938,8 +941,8 @@ MavlinkMissionManager::handle_mission_count(const mavlink_message_t *msg)
|
|||
_transfer_partner_sysid = msg->sysid;
|
||||
_transfer_partner_compid = msg->compid;
|
||||
_transfer_count = wpc.count;
|
||||
_transfer_dataman_id = (_dataman_id == DM_KEY_WAYPOINTS_OFFBOARD_0 ? DM_KEY_WAYPOINTS_OFFBOARD_1 :
|
||||
DM_KEY_WAYPOINTS_OFFBOARD_0); // use inactive storage for transmission
|
||||
_transfer_mission_dataman_id = (_mission_dataman_id == DM_KEY_WAYPOINTS_OFFBOARD_0 ? DM_KEY_WAYPOINTS_OFFBOARD_1 :
|
||||
DM_KEY_WAYPOINTS_OFFBOARD_0); // use inactive storage for transmission
|
||||
_transfer_current_seq = -1;
|
||||
_transfer_land_start_marker = -1;
|
||||
_transfer_land_marker = -1;
|
||||
|
@ -1096,7 +1099,8 @@ MavlinkMissionManager::handle_mission_item_both(const mavlink_message_t *msg)
|
|||
|
||||
} else {
|
||||
|
||||
write_failed = !_dataman_client.writeSync(_transfer_dataman_id, wp.seq, reinterpret_cast<uint8_t *>(&mission_item),
|
||||
write_failed = !_dataman_client.writeSync(_transfer_mission_dataman_id, wp.seq,
|
||||
reinterpret_cast<uint8_t *>(&mission_item),
|
||||
sizeof(struct mission_item_s));
|
||||
|
||||
// Check for land start marker
|
||||
|
@ -1169,7 +1173,7 @@ MavlinkMissionManager::handle_mission_item_both(const mavlink_message_t *msg)
|
|||
}
|
||||
|
||||
if (write_failed || check_failed) {
|
||||
PX4_DEBUG("WPM: MISSION_ITEM ERROR: error writing seq %u to dataman ID %i", wp.seq, _transfer_dataman_id);
|
||||
PX4_DEBUG("WPM: MISSION_ITEM ERROR: error writing seq %u to dataman ID %i", wp.seq, _transfer_mission_dataman_id);
|
||||
|
||||
send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR);
|
||||
|
||||
|
@ -1204,7 +1208,7 @@ MavlinkMissionManager::handle_mission_item_both(const mavlink_message_t *msg)
|
|||
case MAV_MISSION_TYPE_MISSION:
|
||||
_land_start_marker = _transfer_land_start_marker;
|
||||
_land_marker = _transfer_land_marker;
|
||||
update_active_mission(_transfer_dataman_id, _transfer_count, _transfer_current_seq, _transfer_current_crc32);
|
||||
update_active_mission(_transfer_mission_dataman_id, _transfer_count, _transfer_current_seq, _transfer_current_crc32);
|
||||
break;
|
||||
|
||||
case MAV_MISSION_TYPE_FENCE:
|
||||
|
@ -1260,7 +1264,7 @@ MavlinkMissionManager::handle_mission_clear_all(const mavlink_message_t *msg)
|
|||
case MAV_MISSION_TYPE_MISSION:
|
||||
_land_start_marker = -1;
|
||||
_land_marker = -1;
|
||||
update_active_mission(_dataman_id == DM_KEY_WAYPOINTS_OFFBOARD_0 ? DM_KEY_WAYPOINTS_OFFBOARD_1 :
|
||||
update_active_mission(_mission_dataman_id == DM_KEY_WAYPOINTS_OFFBOARD_0 ? DM_KEY_WAYPOINTS_OFFBOARD_1 :
|
||||
DM_KEY_WAYPOINTS_OFFBOARD_0, 0, 0, 0);
|
||||
break;
|
||||
|
||||
|
@ -1275,7 +1279,7 @@ MavlinkMissionManager::handle_mission_clear_all(const mavlink_message_t *msg)
|
|||
case MAV_MISSION_TYPE_ALL:
|
||||
_land_start_marker = -1;
|
||||
_land_marker = -1;
|
||||
update_active_mission(_dataman_id == DM_KEY_WAYPOINTS_OFFBOARD_0 ? DM_KEY_WAYPOINTS_OFFBOARD_1 :
|
||||
update_active_mission(_mission_dataman_id == DM_KEY_WAYPOINTS_OFFBOARD_0 ? DM_KEY_WAYPOINTS_OFFBOARD_1 :
|
||||
DM_KEY_WAYPOINTS_OFFBOARD_0, 0, 0, 0);
|
||||
ret = update_geofence_count(0, 0);
|
||||
ret = update_safepoint_count(0, 0) || ret;
|
||||
|
@ -1790,10 +1794,10 @@ void MavlinkMissionManager::check_active_mission()
|
|||
}
|
||||
|
||||
if ((_mission_sub.get().mission_id != _crc32[MAV_MISSION_TYPE_MISSION])
|
||||
|| (_my_dataman_id != (dm_item_t)_mission_sub.get().dataman_id)) {
|
||||
|| (_my_mission_dataman_id != (dm_item_t)_mission_sub.get().mission_dataman_id)) {
|
||||
PX4_DEBUG("WPM: New mission detected (possibly over different Mavlink instance) Updating");
|
||||
init_offboard_mission(_mission_sub.get());
|
||||
_my_dataman_id = _dataman_id;
|
||||
_my_mission_dataman_id = _mission_dataman_id;
|
||||
send_mission_count(_transfer_partner_sysid, _transfer_partner_compid, _count[MAV_MISSION_TYPE_MISSION],
|
||||
MAV_MISSION_TYPE_MISSION, _crc32[MAV_MISSION_TYPE_MISSION]);
|
||||
}
|
||||
|
|
|
@ -106,8 +106,8 @@ private:
|
|||
|
||||
unsigned _filesystem_errcount{0}; ///< File system error count
|
||||
|
||||
static dm_item_t _dataman_id; ///< Global Dataman storage ID for active mission
|
||||
dm_item_t _my_dataman_id{DM_KEY_WAYPOINTS_OFFBOARD_0}; ///< class Dataman storage ID
|
||||
static dm_item_t _mission_dataman_id; ///< Global Dataman storage ID for active mission
|
||||
dm_item_t _my_mission_dataman_id{DM_KEY_WAYPOINTS_OFFBOARD_0}; ///< class Dataman storage ID for mission
|
||||
|
||||
static bool _dataman_init; ///< Dataman initialized
|
||||
|
||||
|
@ -117,7 +117,7 @@ private:
|
|||
|
||||
int32_t _last_reached{-1}; ///< Last reached waypoint in active mission (-1 means nothing reached)
|
||||
|
||||
dm_item_t _transfer_dataman_id{DM_KEY_WAYPOINTS_OFFBOARD_1}; ///< Dataman storage ID for current transmission
|
||||
dm_item_t _transfer_mission_dataman_id{DM_KEY_WAYPOINTS_OFFBOARD_1}; ///< Dataman storage ID for current mission transmission
|
||||
|
||||
uint16_t _transfer_count{0}; ///< Items count in current transmission
|
||||
uint32_t _transfer_current_crc32{0}; ///< Current CRC32 checksum of current transmission
|
||||
|
@ -168,7 +168,7 @@ private:
|
|||
|
||||
void init_offboard_mission(const mission_s &mission_state);
|
||||
|
||||
void update_active_mission(dm_item_t dataman_id, uint16_t count, int32_t seq, uint32_t crc32,
|
||||
void update_active_mission(dm_item_t mission_dataman_id, uint16_t count, int32_t seq, uint32_t crc32,
|
||||
bool write_to_dataman = true);
|
||||
|
||||
/** store the geofence count to dataman */
|
||||
|
|
|
@ -192,11 +192,11 @@ void Mission::setActiveMissionItems()
|
|||
getNextPositionItems(_mission.current_seq + 1, next_mission_items_index, num_found_items, max_num_next_items);
|
||||
|
||||
mission_item_s next_mission_items[max_num_next_items];
|
||||
const dm_item_t dataman_id = static_cast<dm_item_t>(_mission.dataman_id);
|
||||
const dm_item_t mission_dataman_id = static_cast<dm_item_t>(_mission.mission_dataman_id);
|
||||
|
||||
for (size_t i = 0U; i < num_found_items; i++) {
|
||||
mission_item_s next_mission_item;
|
||||
bool success = _dataman_cache.loadWait(dataman_id, next_mission_items_index[i],
|
||||
bool success = _dataman_cache.loadWait(mission_dataman_id, next_mission_items_index[i],
|
||||
reinterpret_cast<uint8_t *>(&next_mission_item), sizeof(next_mission_item), MAX_DATAMAN_LOAD_WAIT);
|
||||
|
||||
if (success) {
|
||||
|
@ -459,7 +459,7 @@ Mission::save_mission_state()
|
|||
|
||||
if (success) {
|
||||
/* data read successfully, check dataman ID and items count */
|
||||
if (mission_state.dataman_id == _mission.dataman_id && mission_state.count == _mission.count
|
||||
if (mission_state.mission_dataman_id == _mission.mission_dataman_id && mission_state.count == _mission.count
|
||||
&& mission_state.mission_id == _mission.mission_id) {
|
||||
/* navigator may modify only sequence, write modified state only if it changed */
|
||||
if (mission_state.current_seq != _mission.current_seq) {
|
||||
|
|
|
@ -96,7 +96,7 @@ MissionBase::updateDatamanCache()
|
|||
|
||||
for (int32_t index = start_index; index != end_index; index += math::signNoZero(_dataman_cache_size_signed)) {
|
||||
|
||||
_dataman_cache.load(static_cast<dm_item_t>(_mission.dataman_id), index);
|
||||
_dataman_cache.load(static_cast<dm_item_t>(_mission.mission_dataman_id), index);
|
||||
}
|
||||
|
||||
_load_mission_index = _mission.current_seq;
|
||||
|
@ -274,8 +274,8 @@ MissionBase::on_active()
|
|||
|
||||
if (num_found_items == 1U && !PX4_ISFINITE(_mission_item.yaw)) {
|
||||
mission_item_s next_position_mission_item;
|
||||
const dm_item_t dataman_id = static_cast<dm_item_t>(_mission.dataman_id);
|
||||
bool success = _dataman_cache.loadWait(dataman_id, next_mission_item_index,
|
||||
const dm_item_t mission_dataman_id = static_cast<dm_item_t>(_mission.mission_dataman_id);
|
||||
bool success = _dataman_cache.loadWait(mission_dataman_id, next_mission_item_index,
|
||||
reinterpret_cast<uint8_t *>(&next_position_mission_item), sizeof(next_position_mission_item), MAX_DATAMAN_LOAD_WAIT);
|
||||
|
||||
if (success) {
|
||||
|
@ -460,7 +460,7 @@ MissionBase::set_mission_items()
|
|||
|
||||
void MissionBase::loadCurrentMissionItem()
|
||||
{
|
||||
const dm_item_t dm_item = static_cast<dm_item_t>(_mission.dataman_id);
|
||||
const dm_item_t dm_item = static_cast<dm_item_t>(_mission.mission_dataman_id);
|
||||
bool success = _dataman_cache.loadWait(dm_item, _mission.current_seq, reinterpret_cast<uint8_t *>(&_mission_item),
|
||||
sizeof(mission_item_s), MAX_DATAMAN_LOAD_WAIT);
|
||||
|
||||
|
@ -880,7 +880,8 @@ bool MissionBase::isMissionValid(mission_s &mission) const
|
|||
bool ret_val{false};
|
||||
|
||||
if (((mission.current_seq < mission.count) || (mission.count == 0U && mission.current_seq <= 0)) &&
|
||||
(mission.dataman_id == DM_KEY_WAYPOINTS_OFFBOARD_0 || mission.dataman_id == DM_KEY_WAYPOINTS_OFFBOARD_1) &&
|
||||
(mission.mission_dataman_id == DM_KEY_WAYPOINTS_OFFBOARD_0
|
||||
|| mission.mission_dataman_id == DM_KEY_WAYPOINTS_OFFBOARD_1) &&
|
||||
(mission.timestamp != 0u)) {
|
||||
ret_val = true;
|
||||
|
||||
|
@ -896,13 +897,13 @@ int MissionBase::getNonJumpItem(int32_t &mission_index, mission_item_s &mission,
|
|||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
const dm_item_t dataman_id = (dm_item_t)_mission.dataman_id;
|
||||
const dm_item_t mission_dataman_id = (dm_item_t)_mission.mission_dataman_id;
|
||||
int32_t new_mission_index{mission_index};
|
||||
mission_item_s new_mission;
|
||||
|
||||
for (uint16_t jump_count = 0u; jump_count < MAX_JUMP_ITERATION; jump_count++) {
|
||||
/* read mission item from datamanager */
|
||||
bool success = _dataman_cache.loadWait(dataman_id, new_mission_index, reinterpret_cast<uint8_t *>(&new_mission),
|
||||
bool success = _dataman_cache.loadWait(mission_dataman_id, new_mission_index, reinterpret_cast<uint8_t *>(&new_mission),
|
||||
sizeof(mission_item_s), MAX_DATAMAN_LOAD_WAIT);
|
||||
|
||||
if (!success) {
|
||||
|
@ -922,7 +923,7 @@ int MissionBase::getNonJumpItem(int32_t &mission_index, mission_item_s &mission,
|
|||
if ((new_mission.do_jump_current_count < new_mission.do_jump_repeat_count) && execute_jump) {
|
||||
if (write_jumps) {
|
||||
new_mission.do_jump_current_count++;
|
||||
success = _dataman_cache.writeWait(dataman_id, new_mission_index, reinterpret_cast<uint8_t *>(&new_mission),
|
||||
success = _dataman_cache.writeWait(mission_dataman_id, new_mission_index, reinterpret_cast<uint8_t *>(&new_mission),
|
||||
sizeof(struct mission_item_s));
|
||||
|
||||
if (!success) {
|
||||
|
@ -1095,12 +1096,12 @@ int MissionBase::setMissionToClosestItem(double lat, double lon, float alt, floa
|
|||
{
|
||||
int32_t min_dist_index(-1);
|
||||
float min_dist(FLT_MAX), dist_xy(FLT_MAX), dist_z(FLT_MAX);
|
||||
const dm_item_t dataman_id = static_cast<dm_item_t>(_mission.dataman_id);
|
||||
const dm_item_t mission_dataman_id = static_cast<dm_item_t>(_mission.mission_dataman_id);
|
||||
|
||||
for (int32_t mission_item_index = 0; mission_item_index < _mission.count; mission_item_index++) {
|
||||
mission_item_s mission;
|
||||
|
||||
bool success = _dataman_cache.loadWait(dataman_id, mission_item_index, reinterpret_cast<uint8_t *>(&mission),
|
||||
bool success = _dataman_cache.loadWait(mission_dataman_id, mission_item_index, reinterpret_cast<uint8_t *>(&mission),
|
||||
sizeof(mission_item_s), MAX_DATAMAN_LOAD_WAIT);
|
||||
|
||||
if (!success) {
|
||||
|
@ -1151,8 +1152,9 @@ void MissionBase::resetMission()
|
|||
new_mission.land_index = -1;
|
||||
new_mission.count = 0u;
|
||||
new_mission.mission_id = 0u;
|
||||
new_mission.dataman_id = _mission.dataman_id == DM_KEY_WAYPOINTS_OFFBOARD_0 ? DM_KEY_WAYPOINTS_OFFBOARD_1 :
|
||||
DM_KEY_WAYPOINTS_OFFBOARD_0;
|
||||
new_mission.mission_dataman_id = _mission.mission_dataman_id == DM_KEY_WAYPOINTS_OFFBOARD_0 ?
|
||||
DM_KEY_WAYPOINTS_OFFBOARD_1 :
|
||||
DM_KEY_WAYPOINTS_OFFBOARD_0;
|
||||
|
||||
bool success = _dataman_client.writeSync(DM_KEY_MISSION_STATE, 0, reinterpret_cast<uint8_t *>(&new_mission),
|
||||
sizeof(mission_s));
|
||||
|
@ -1168,12 +1170,12 @@ void MissionBase::resetMission()
|
|||
|
||||
void MissionBase::resetMissionJumpCounter()
|
||||
{
|
||||
const dm_item_t dataman_id = static_cast<dm_item_t>(_mission.dataman_id);
|
||||
const dm_item_t mission_dataman_id = static_cast<dm_item_t>(_mission.mission_dataman_id);
|
||||
|
||||
for (size_t mission_index = 0u; mission_index < _mission.count; mission_index++) {
|
||||
mission_item_s mission_item;
|
||||
|
||||
bool success = _dataman_client.readSync(dataman_id, mission_index, reinterpret_cast<uint8_t *>(&mission_item),
|
||||
bool success = _dataman_client.readSync(mission_dataman_id, mission_index, reinterpret_cast<uint8_t *>(&mission_item),
|
||||
sizeof(mission_item_s), MAX_DATAMAN_LOAD_WAIT);
|
||||
|
||||
if (!success) {
|
||||
|
@ -1187,7 +1189,8 @@ void MissionBase::resetMissionJumpCounter()
|
|||
if (mission_item.nav_cmd == NAV_CMD_DO_JUMP) {
|
||||
mission_item.do_jump_current_count = 0u;
|
||||
|
||||
bool write_success = _dataman_cache.writeWait(dataman_id, mission_index, reinterpret_cast<uint8_t *>(&mission_item),
|
||||
bool write_success = _dataman_cache.writeWait(mission_dataman_id, mission_index,
|
||||
reinterpret_cast<uint8_t *>(&mission_item),
|
||||
sizeof(struct mission_item_s));
|
||||
|
||||
if (!write_success) {
|
||||
|
@ -1296,7 +1299,7 @@ void MissionBase::updateCachedItemsUpToIndex(const int end_index)
|
|||
{
|
||||
for (int i = 0; i <= end_index; i++) {
|
||||
mission_item_s mission_item;
|
||||
const dm_item_t dm_current = (dm_item_t)_mission.dataman_id;
|
||||
const dm_item_t dm_current = (dm_item_t)_mission.mission_dataman_id;
|
||||
bool success = _dataman_client.readSync(dm_current, i, reinterpret_cast<uint8_t *>(&mission_item),
|
||||
sizeof(mission_item), 500_ms);
|
||||
|
||||
|
@ -1326,11 +1329,12 @@ void MissionBase::checkClimbRequired(int32_t mission_item_index)
|
|||
|
||||
if (num_found_items > 0U) {
|
||||
|
||||
const dm_item_t dataman_id = static_cast<dm_item_t>(_mission.dataman_id);
|
||||
const dm_item_t mission_dataman_id = static_cast<dm_item_t>(_mission.mission_dataman_id);
|
||||
mission_item_s mission;
|
||||
_mission_init_climb_altitude_amsl = NAN; // default to NAN, overwrite below if applicable
|
||||
|
||||
const bool success = _dataman_cache.loadWait(dataman_id, next_mission_item_index, reinterpret_cast<uint8_t *>(&mission),
|
||||
const bool success = _dataman_cache.loadWait(mission_dataman_id, next_mission_item_index,
|
||||
reinterpret_cast<uint8_t *>(&mission),
|
||||
sizeof(mission), MAX_DATAMAN_LOAD_WAIT);
|
||||
|
||||
const bool is_fw_and_takeoff = mission.nav_cmd == NAV_CMD_TAKEOFF
|
||||
|
@ -1353,7 +1357,7 @@ void MissionBase::checkClimbRequired(int32_t mission_item_index)
|
|||
bool MissionBase::checkMissionDataChanged(mission_s new_mission)
|
||||
{
|
||||
/* count and land_index are the same if the mission_id did not change. We do not care about changes in geofence or rally counters.*/
|
||||
return ((new_mission.dataman_id != _mission.dataman_id) ||
|
||||
return ((new_mission.mission_dataman_id != _mission.mission_dataman_id) ||
|
||||
(new_mission.mission_id != _mission.mission_id) ||
|
||||
(new_mission.current_seq != _mission.current_seq));
|
||||
}
|
||||
|
|
|
@ -79,7 +79,8 @@ MissionFeasibilityChecker::checkMissionFeasible(const mission_s &mission)
|
|||
for (size_t i = 0; i < mission.count; i++) {
|
||||
struct mission_item_s missionitem = {};
|
||||
|
||||
bool success = _dataman_client.readSync((dm_item_t)mission.dataman_id, i, reinterpret_cast<uint8_t *>(&missionitem),
|
||||
bool success = _dataman_client.readSync((dm_item_t)mission.mission_dataman_id, i,
|
||||
reinterpret_cast<uint8_t *>(&missionitem),
|
||||
sizeof(mission_item_s));
|
||||
|
||||
if (!success) {
|
||||
|
@ -119,7 +120,8 @@ MissionFeasibilityChecker::checkMissionAgainstGeofence(const mission_s &mission,
|
|||
for (size_t i = 0; i < mission.count; i++) {
|
||||
struct mission_item_s missionitem = {};
|
||||
|
||||
bool success = _dataman_client.readSync((dm_item_t)mission.dataman_id, i, reinterpret_cast<uint8_t *>(&missionitem),
|
||||
bool success = _dataman_client.readSync((dm_item_t)mission.mission_dataman_id, i,
|
||||
reinterpret_cast<uint8_t *>(&missionitem),
|
||||
sizeof(mission_item_s));
|
||||
|
||||
if (!success) {
|
||||
|
|
|
@ -146,7 +146,7 @@ void RTL::updateDatamanCache()
|
|||
|
||||
if (_mission_id != _mission_sub.get().mission_id) {
|
||||
_mission_id = _mission_sub.get().mission_id;
|
||||
const dm_item_t dm_item = static_cast<dm_item_t>(_mission_sub.get().dataman_id);
|
||||
const dm_item_t dm_item = static_cast<dm_item_t>(_mission_sub.get().mission_dataman_id);
|
||||
_dataman_cache_landItem.invalidate();
|
||||
|
||||
if (_mission_sub.get().land_index > 0) {
|
||||
|
@ -365,7 +365,7 @@ void RTL::findRtlDestination(DestinationType &destination_type, DestinationPosit
|
|||
if (((_param_rtl_type.get() == 1) || (_param_rtl_type.get() == 3) || (fabsf(FLT_MAX - min_dist) < FLT_EPSILON))
|
||||
&& hasMissionLandStart()) {
|
||||
mission_item_s land_mission_item;
|
||||
const dm_item_t dm_item = static_cast<dm_item_t>(_mission_sub.get().dataman_id);
|
||||
const dm_item_t dm_item = static_cast<dm_item_t>(_mission_sub.get().mission_dataman_id);
|
||||
bool success = _dataman_cache_landItem.loadWait(dm_item, _mission_sub.get().land_index,
|
||||
reinterpret_cast<uint8_t *>(&land_mission_item), sizeof(mission_item_s), 500_ms);
|
||||
|
||||
|
|
|
@ -146,11 +146,11 @@ void RtlDirectMissionLand::setActiveMissionItems()
|
|||
getNextPositionItems(_mission.current_seq + 1, next_mission_items_index, num_found_items, max_num_next_items);
|
||||
|
||||
mission_item_s next_mission_items[max_num_next_items];
|
||||
const dm_item_t dataman_id = static_cast<dm_item_t>(_mission.dataman_id);
|
||||
const dm_item_t mission_dataman_id = static_cast<dm_item_t>(_mission.mission_dataman_id);
|
||||
|
||||
for (size_t i = 0U; i < num_found_items; i++) {
|
||||
mission_item_s next_mission_item;
|
||||
bool success = _dataman_cache.loadWait(dataman_id, next_mission_items_index[i],
|
||||
bool success = _dataman_cache.loadWait(mission_dataman_id, next_mission_items_index[i],
|
||||
reinterpret_cast<uint8_t *>(&next_mission_item), sizeof(next_mission_item), MAX_DATAMAN_LOAD_WAIT);
|
||||
|
||||
if (success) {
|
||||
|
|
|
@ -97,11 +97,11 @@ void RtlMissionFast::setActiveMissionItems()
|
|||
getNextPositionItems(_mission.current_seq + 1, next_mission_items_index, num_found_items, max_num_next_items);
|
||||
|
||||
mission_item_s next_mission_items[max_num_next_items];
|
||||
const dm_item_t dataman_id = static_cast<dm_item_t>(_mission.dataman_id);
|
||||
const dm_item_t mission_dataman_id = static_cast<dm_item_t>(_mission.mission_dataman_id);
|
||||
|
||||
for (size_t i = 0U; i < num_found_items; i++) {
|
||||
mission_item_s next_mission_item;
|
||||
bool success = _dataman_cache.loadWait(dataman_id, next_mission_items_index[i],
|
||||
bool success = _dataman_cache.loadWait(mission_dataman_id, next_mission_items_index[i],
|
||||
reinterpret_cast<uint8_t *>(&next_mission_item), sizeof(next_mission_item), MAX_DATAMAN_LOAD_WAIT);
|
||||
|
||||
if (success) {
|
||||
|
|
|
@ -120,9 +120,9 @@ void RtlMissionFastReverse::setActiveMissionItems()
|
|||
|
||||
if (num_found_items > 0) {
|
||||
|
||||
const dm_item_t dataman_id = static_cast<dm_item_t>(_mission.dataman_id);
|
||||
const dm_item_t mission_dataman_id = static_cast<dm_item_t>(_mission.mission_dataman_id);
|
||||
mission_item_s next_mission_item;
|
||||
bool success = _dataman_cache.loadWait(dataman_id, next_mission_item_index,
|
||||
bool success = _dataman_cache.loadWait(mission_dataman_id, next_mission_item_index,
|
||||
reinterpret_cast<uint8_t *>(&next_mission_item), sizeof(mission_item_s), MAX_DATAMAN_LOAD_WAIT);
|
||||
|
||||
if (success) {
|
||||
|
|
|
@ -1076,7 +1076,7 @@ DatamanTest::testResetItems()
|
|||
|
||||
mission_s mission{};
|
||||
mission.timestamp = hrt_absolute_time();
|
||||
mission.dataman_id = DM_KEY_WAYPOINTS_OFFBOARD_0;
|
||||
mission.mission_dataman_id = DM_KEY_WAYPOINTS_OFFBOARD_0;
|
||||
mission.count = 0;
|
||||
mission.current_seq = 0;
|
||||
|
||||
|
|
Loading…
Reference in New Issue