diff --git a/src/modules/mavlink/mavlink_mission.cpp b/src/modules/mavlink/mavlink_mission.cpp index c823487da2..5c038f0c50 100644 --- a/src/modules/mavlink/mavlink_mission.cpp +++ b/src/modules/mavlink/mavlink_mission.cpp @@ -1338,16 +1338,8 @@ MavlinkMissionManager::parse_mavlink_mission_item(const mavlink_mission_item_t * break; case MAV_CMD_NAV_TAKEOFF: - - // reject takeoff item if minimum pitch (parameter 1) is set - if (PX4_ISFINITE(mavlink_mission_item->param1) && (fabsf(mavlink_mission_item->param1) > FLT_EPSILON)) { - _mavlink->send_statustext_critical("Takeoff rejected, remove deprecated minimum pitch"); - return MAV_MISSION_INVALID_PARAM1; - - } else { - mission_item->nav_cmd = NAV_CMD_TAKEOFF; - mission_item->yaw = wrap_2pi(math::radians(mavlink_mission_item->param4)); - } + mission_item->nav_cmd = NAV_CMD_TAKEOFF; + mission_item->yaw = wrap_2pi(math::radians(mavlink_mission_item->param4)); break;