aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mavlink
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2014-12-25 09:48:15 +0100
committerThomas Gubler <thomasgubler@gmail.com>2014-12-25 09:48:15 +0100
commit25af4b266ca48b183a1ad375856396f67d6ab30f (patch)
tree64e031ec3747ab706e5ae8ed9fd052e12ee3248b /src/modules/mavlink
parentad189cf7d69b8de16244b90d398e1d84ed6d0f4b (diff)
parent9b535f6553944f3468bbec9203301623412524ad (diff)
downloadpx4-firmware-25af4b266ca48b183a1ad375856396f67d6ab30f.tar.gz
px4-firmware-25af4b266ca48b183a1ad375856396f67d6ab30f.tar.bz2
px4-firmware-25af4b266ca48b183a1ad375856396f67d6ab30f.zip
Merge remote-tracking branch 'upstream/master' into dev_ros
Conflicts: .gitignore src/lib/uavcan
Diffstat (limited to 'src/modules/mavlink')
-rw-r--r--src/modules/mavlink/mavlink_mission.cpp11
1 files changed, 7 insertions, 4 deletions
diff --git a/src/modules/mavlink/mavlink_mission.cpp b/src/modules/mavlink/mavlink_mission.cpp
index a3c127cdc..859d380fe 100644
--- a/src/modules/mavlink/mavlink_mission.cpp
+++ b/src/modules/mavlink/mavlink_mission.cpp
@@ -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);
@@ -312,6 +309,12 @@ MavlinkMissionManager::send(const hrt_abstime now)
send_mission_current(_current_seq);
+ if (mission_result.item_do_jump_changed) {
+ /* send a mission item again if the remaining DO_JUMPs has changed */
+ send_mission_item(_transfer_partner_sysid, _transfer_partner_compid,
+ (uint16_t)mission_result.item_changed_index);
+ }
+
} else {
if (_slow_rate_limiter.check(now)) {
send_mission_current(_current_seq);
@@ -811,7 +814,7 @@ MavlinkMissionManager::format_mavlink_mission_item(const struct mission_item_s *
case NAV_CMD_DO_JUMP:
mavlink_mission_item->param1 = mission_item->do_jump_mission_index;
- mavlink_mission_item->param2 = mission_item->do_jump_repeat_count;
+ mavlink_mission_item->param2 = mission_item->do_jump_repeat_count - mission_item->do_jump_current_count;
break;
default: