mavlink_mission: Send MISSION_CURRENT periodically even when no mission is loaded.

This commit is contained in:
Konrad 2023-09-18 11:26:31 +02:00 committed by Daniel Agar
parent 36f0c0f0bf
commit 42ce9eb692
2 changed files with 4 additions and 4 deletions

View File

@ -256,6 +256,7 @@ MavlinkMissionManager::send_mission_current(uint16_t seq)
{
mavlink_mission_current_t wpc{};
wpc.seq = seq;
wpc.total = _count[MAV_MISSION_TYPE_MISSION] > 0 ? _count[MAV_MISSION_TYPE_MISSION] : UINT16_MAX;
wpc.mission_id = _crc32[MAV_MISSION_TYPE_MISSION];
wpc.fence_id = _crc32[MAV_MISSION_TYPE_FENCE];
wpc.rally_points_id = _crc32[MAV_MISSION_TYPE_RALLY];
@ -516,10 +517,9 @@ MavlinkMissionManager::send()
}
} else if (_slow_rate_limiter.check(hrt_absolute_time())) {
send_mission_current(_current_seq);
if ((_count[MAV_MISSION_TYPE_MISSION] > 0) && (_current_seq >= 0)) {
send_mission_current(_current_seq);
// send the reached message another 10 times
if (_last_reached >= 0 && (_reached_sent_count < 10)) {
send_mission_item_reached((uint16_t)_last_reached);

View File

@ -140,7 +140,7 @@ private:
int32_t _land_start_marker{-1}; ///< index of loaded land start mission item (if unavailable, index of land mission item, -1 otherwise)
int32_t _land_marker{-1}; ///< index of loaded land mission item (-1 if unavailable)
MavlinkRateLimiter _slow_rate_limiter{100 * 1000}; ///< Rate limit sending of the current WP sequence to 10 Hz
MavlinkRateLimiter _slow_rate_limiter{1000 * 1000}; ///< Rate limit sending of the current WP sequence to 1 Hz
Mavlink *_mavlink;