mirror of https://github.com/ArduPilot/ardupilot
AP_Mission: PLANE to refuse NAV_SPLINE_WAYPOINT missions items
This commit is contained in:
parent
1f28ab0576
commit
684ad39a02
|
@ -962,8 +962,12 @@ MAV_MISSION_RESULT AP_Mission::mavlink_int_to_mission_cmd(const mavlink_mission_
|
|||
break;
|
||||
|
||||
case MAV_CMD_NAV_SPLINE_WAYPOINT: // MAV ID: 82
|
||||
#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
|
||||
return MAV_MISSION_UNSUPPORTED;
|
||||
#else
|
||||
cmd.p1 = packet.param1; // delay at waypoint in seconds
|
||||
break;
|
||||
#endif
|
||||
|
||||
case MAV_CMD_NAV_GUIDED_ENABLE: // MAV ID: 92
|
||||
cmd.p1 = packet.param1; // on/off. >0.5 means "on", hand-over control to external controller
|
||||
|
|
Loading…
Reference in New Issue