forked from Archive/PX4-Autopilot
MAVLink: Add support for new gate command
This enables the vehicle to be able to wait with executing the next item until a position has been passed.
This commit is contained in:
parent
8842977d80
commit
ed8cb1c5a7
|
@ -1386,6 +1386,10 @@ MavlinkMissionManager::parse_mavlink_mission_item(const mavlink_mission_item_t *
|
|||
mission_item->yaw = wrap_2pi(math::radians(mavlink_mission_item->param4));
|
||||
break;
|
||||
|
||||
case MAV_CMD_CONDITION_GATE:
|
||||
mission_item->nav_cmd = (NAV_CMD)mavlink_mission_item->command;
|
||||
break;
|
||||
|
||||
case MAV_CMD_NAV_FENCE_RETURN_POINT:
|
||||
mission_item->nav_cmd = (NAV_CMD)mavlink_mission_item->command;
|
||||
break;
|
||||
|
@ -1469,6 +1473,8 @@ MavlinkMissionManager::parse_mavlink_mission_item(const mavlink_mission_item_t *
|
|||
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
|
||||
case MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET:
|
||||
case MAV_CMD_DO_SET_ROI_NONE:
|
||||
case MAV_CMD_CONDITION_DELAY:
|
||||
case MAV_CMD_CONDITION_DISTANCE:
|
||||
mission_item->nav_cmd = (NAV_CMD)mavlink_mission_item->command;
|
||||
break;
|
||||
|
||||
|
|
Loading…
Reference in New Issue