diff --git a/src/modules/mavlink/mavlink_mission.cpp b/src/modules/mavlink/mavlink_mission.cpp index 073c5afcfc..26384d521e 100644 --- a/src/modules/mavlink/mavlink_mission.cpp +++ b/src/modules/mavlink/mavlink_mission.cpp @@ -856,15 +856,23 @@ MavlinkMissionManager::format_mavlink_mission_item(const struct mission_item_s * break; case NAV_CMD_DO_SET_SERVO: + mavlink_mission_item->frame = MAV_FRAME_MISSION; mavlink_mission_item->param1 = mission_item->actuator_num; mavlink_mission_item->param2 = mission_item->actuator_value; break; case NAV_CMD_DO_JUMP: + mavlink_mission_item->frame = MAV_FRAME_MISSION; mavlink_mission_item->param1 = mission_item->do_jump_mission_index; mavlink_mission_item->param2 = mission_item->do_jump_repeat_count - mission_item->do_jump_current_count; break; + case NAV_CMD_DO_VTOL_TRANSITION: + mavlink_mission_item->frame = MAV_FRAME_MISSION; + mavlink_mission_item->param1 = mission_item->params[0]; + break; + + default: mavlink_mission_item->param2 = mission_item->acceptance_radius; mavlink_mission_item->param1 = mission_item->time_inside; diff --git a/src/modules/navigator/navigation.h b/src/modules/navigator/navigation.h index b768de5ac5..1539e63052 100644 --- a/src/modules/navigator/navigation.h +++ b/src/modules/navigator/navigation.h @@ -64,6 +64,7 @@ enum NAV_CMD { NAV_CMD_DO_JUMP = 177, NAV_CMD_DO_SET_SERVO=183, NAV_CMD_DO_REPEAT_SERVO=184, + NAV_CMD_DO_VTOL_TRANSITION=3000, NAV_CMD_INVALID=UINT16_MAX /* ensure that casting a large number results in a specific error */ };