|
|
|
@ -352,35 +352,29 @@ MissionFeasibilityChecker::checkTakeoff(const mission_s &mission, float home_alt
@@ -352,35 +352,29 @@ MissionFeasibilityChecker::checkTakeoff(const mission_s &mission, float home_alt
|
|
|
|
|
return false; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (missionitem.nav_cmd != NAV_CMD_IDLE && |
|
|
|
|
missionitem.nav_cmd != NAV_CMD_DELAY && |
|
|
|
|
missionitem.nav_cmd != NAV_CMD_DO_JUMP && |
|
|
|
|
missionitem.nav_cmd != NAV_CMD_DO_CHANGE_SPEED && |
|
|
|
|
missionitem.nav_cmd != NAV_CMD_DO_SET_HOME && |
|
|
|
|
missionitem.nav_cmd != NAV_CMD_DO_SET_SERVO && |
|
|
|
|
missionitem.nav_cmd != NAV_CMD_DO_LAND_START && |
|
|
|
|
missionitem.nav_cmd != NAV_CMD_DO_TRIGGER_CONTROL && |
|
|
|
|
missionitem.nav_cmd != NAV_CMD_DO_DIGICAM_CONTROL && |
|
|
|
|
missionitem.nav_cmd != NAV_CMD_IMAGE_START_CAPTURE && |
|
|
|
|
missionitem.nav_cmd != NAV_CMD_IMAGE_STOP_CAPTURE && |
|
|
|
|
missionitem.nav_cmd != NAV_CMD_VIDEO_START_CAPTURE && |
|
|
|
|
missionitem.nav_cmd != NAV_CMD_VIDEO_STOP_CAPTURE && |
|
|
|
|
missionitem.nav_cmd != NAV_CMD_DO_MOUNT_CONFIGURE && |
|
|
|
|
missionitem.nav_cmd != NAV_CMD_DO_MOUNT_CONTROL && |
|
|
|
|
missionitem.nav_cmd != NAV_CMD_DO_SET_ROI && |
|
|
|
|
missionitem.nav_cmd != NAV_CMD_DO_SET_ROI_LOCATION && |
|
|
|
|
missionitem.nav_cmd != NAV_CMD_DO_SET_ROI_WPNEXT_OFFSET && |
|
|
|
|
missionitem.nav_cmd != NAV_CMD_DO_SET_ROI_NONE && |
|
|
|
|
missionitem.nav_cmd != NAV_CMD_DO_SET_CAM_TRIGG_DIST && |
|
|
|
|
missionitem.nav_cmd != NAV_CMD_DO_SET_CAM_TRIGG_INTERVAL && |
|
|
|
|
missionitem.nav_cmd != NAV_CMD_SET_CAMERA_MODE && |
|
|
|
|
missionitem.nav_cmd != NAV_CMD_DO_VTOL_TRANSITION) { |
|
|
|
|
takeoff_first = false; |
|
|
|
|
|
|
|
|
|
} else { |
|
|
|
|
takeoff_first = true; |
|
|
|
|
|
|
|
|
|
} |
|
|
|
|
takeoff_first = !(missionitem.nav_cmd != NAV_CMD_IDLE && |
|
|
|
|
missionitem.nav_cmd != NAV_CMD_DELAY && |
|
|
|
|
missionitem.nav_cmd != NAV_CMD_DO_JUMP && |
|
|
|
|
missionitem.nav_cmd != NAV_CMD_DO_CHANGE_SPEED && |
|
|
|
|
missionitem.nav_cmd != NAV_CMD_DO_SET_HOME && |
|
|
|
|
missionitem.nav_cmd != NAV_CMD_DO_SET_SERVO && |
|
|
|
|
missionitem.nav_cmd != NAV_CMD_DO_LAND_START && |
|
|
|
|
missionitem.nav_cmd != NAV_CMD_DO_TRIGGER_CONTROL && |
|
|
|
|
missionitem.nav_cmd != NAV_CMD_DO_DIGICAM_CONTROL && |
|
|
|
|
missionitem.nav_cmd != NAV_CMD_IMAGE_START_CAPTURE && |
|
|
|
|
missionitem.nav_cmd != NAV_CMD_IMAGE_STOP_CAPTURE && |
|
|
|
|
missionitem.nav_cmd != NAV_CMD_VIDEO_START_CAPTURE && |
|
|
|
|
missionitem.nav_cmd != NAV_CMD_VIDEO_STOP_CAPTURE && |
|
|
|
|
missionitem.nav_cmd != NAV_CMD_DO_MOUNT_CONFIGURE && |
|
|
|
|
missionitem.nav_cmd != NAV_CMD_DO_MOUNT_CONTROL && |
|
|
|
|
missionitem.nav_cmd != NAV_CMD_DO_SET_ROI && |
|
|
|
|
missionitem.nav_cmd != NAV_CMD_DO_SET_ROI_LOCATION && |
|
|
|
|
missionitem.nav_cmd != NAV_CMD_DO_SET_ROI_WPNEXT_OFFSET && |
|
|
|
|
missionitem.nav_cmd != NAV_CMD_DO_SET_ROI_NONE && |
|
|
|
|
missionitem.nav_cmd != NAV_CMD_DO_SET_CAM_TRIGG_DIST && |
|
|
|
|
missionitem.nav_cmd != NAV_CMD_DO_SET_CAM_TRIGG_INTERVAL && |
|
|
|
|
missionitem.nav_cmd != NAV_CMD_SET_CAMERA_MODE && |
|
|
|
|
missionitem.nav_cmd != NAV_CMD_DO_VTOL_TRANSITION); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|