From 76d3720f6202b2bc5f610c889ddca0bd9c7ad3b2 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Matej=20Fran=C4=8De=C5=A1kin?= Date: Tue, 12 Oct 2021 14:37:52 +0200 Subject: [PATCH] Store all command parameters that are defined in mavlink This makes checksum calculation possible on both sides. --- src/modules/mavlink/mavlink_mission.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/modules/mavlink/mavlink_mission.cpp b/src/modules/mavlink/mavlink_mission.cpp index b4b2ab0b73b9..5e5e5c3f38c8 100644 --- a/src/modules/mavlink/mavlink_mission.cpp +++ b/src/modules/mavlink/mavlink_mission.cpp @@ -1389,8 +1389,8 @@ MavlinkMissionManager::parse_mavlink_mission_item(const mavlink_mission_item_t * case MAV_CMD_NAV_TAKEOFF: mission_item->nav_cmd = NAV_CMD_TAKEOFF; + mission_item->params[0] = mavlink_mission_item->param1; // Pitch mission_item->yaw = wrap_2pi(math::radians(mavlink_mission_item->param4)); - break; case MAV_CMD_NAV_LOITER_TO_ALT: @@ -1426,6 +1426,7 @@ MavlinkMissionManager::parse_mavlink_mission_item(const mavlink_mission_item_t * case MAV_CMD_NAV_VTOL_TAKEOFF: case MAV_CMD_NAV_VTOL_LAND: mission_item->nav_cmd = (NAV_CMD)mavlink_mission_item->command; + mission_item->params[1] = mavlink_mission_item->param2; // Transition heading mission_item->yaw = wrap_2pi(math::radians(mavlink_mission_item->param4)); break;