forked from Archive/PX4-Autopilot
mavlink: don't slow mission updates down like this, otherwise we might miss mission results
This commit is contained in:
parent
5bbd0743e0
commit
c9ca61ef5b
|
@ -292,9 +292,6 @@ MavlinkMissionManager::send_mission_item_reached(uint16_t seq)
|
|||
void
|
||||
MavlinkMissionManager::send(const hrt_abstime now)
|
||||
{
|
||||
/* update interval for slow rate limiter */
|
||||
_slow_rate_limiter.set_interval(_interval * 10 / _mavlink->get_rate_mult());
|
||||
|
||||
bool updated = false;
|
||||
orb_check(_mission_result_sub, &updated);
|
||||
|
||||
|
|
Loading…
Reference in New Issue