Navigator: allow executing a disarm command during a mission

This commit is contained in:
Mahima Yoga
2025-05-23 11:39:53 +02:00
committed by Silvan Fuhrer
parent e1167f0888
commit 4abe2d1dab
4 changed files with 10 additions and 0 deletions
+6
View File
@@ -1527,6 +1527,11 @@ MavlinkMissionManager::parse_mavlink_mission_item(const mavlink_mission_item_t *
mission_item->nav_cmd = (NAV_CMD)mavlink_mission_item->command;
break;
case MAV_CMD_COMPONENT_ARM_DISARM:
mission_item->nav_cmd = (NAV_CMD)mavlink_mission_item->command;
mission_item->params[0] = (uint16_t)mavlink_mission_item->param1;
break;
default:
mission_item->nav_cmd = NAV_CMD_INVALID;
PX4_DEBUG("Unsupported command %d", mavlink_mission_item->command);
@@ -1616,6 +1621,7 @@ MavlinkMissionManager::parse_mavlink_mission_item(const mavlink_mission_item_t *
case MAV_CMD_CONDITION_DELAY:
case MAV_CMD_CONDITION_DISTANCE:
case MAV_CMD_DO_SET_ACTUATOR:
case MAV_CMD_COMPONENT_ARM_DISARM:
mission_item->nav_cmd = (NAV_CMD)mavlink_mission_item->command;
break;
@@ -263,6 +263,7 @@ bool FeasibilityChecker::checkMissionItemValidity(mission_item_s &mission_item,
mission_item.nav_cmd != NAV_CMD_DO_LAND_START &&
mission_item.nav_cmd != NAV_CMD_DO_TRIGGER_CONTROL &&
mission_item.nav_cmd != NAV_CMD_DO_DIGICAM_CONTROL &&
mission_item.nav_cmd != NAV_CMD_COMPONENT_ARM_DISARM &&
mission_item.nav_cmd != NAV_CMD_IMAGE_START_CAPTURE &&
mission_item.nav_cmd != NAV_CMD_IMAGE_STOP_CAPTURE &&
mission_item.nav_cmd != NAV_CMD_VIDEO_START_CAPTURE &&
+2
View File
@@ -82,6 +82,7 @@ MissionBlock::is_mission_item_reached_or_completed()
case NAV_CMD_DO_MOUNT_CONFIGURE:
case NAV_CMD_DO_MOUNT_CONTROL:
case NAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE:
case NAV_CMD_COMPONENT_ARM_DISARM:
case NAV_CMD_DO_SET_ROI:
case NAV_CMD_DO_SET_ROI_LOCATION:
case NAV_CMD_DO_SET_ROI_WPNEXT_OFFSET:
@@ -95,6 +96,7 @@ MissionBlock::is_mission_item_reached_or_completed()
case NAV_CMD_SET_CAMERA_FOCUS:
case NAV_CMD_DO_CHANGE_SPEED:
case NAV_CMD_DO_SET_HOME:
return true;
// Indefinite Waypoints
+1
View File
@@ -76,6 +76,7 @@ enum NAV_CMD {
NAV_CMD_DO_SET_CAM_TRIGG_INTERVAL = 214,
NAV_CMD_DO_SET_CAM_TRIGG_DIST = 206,
NAV_CMD_OBLIQUE_SURVEY = 260,
NAV_CMD_COMPONENT_ARM_DISARM = 400,
NAV_CMD_SET_CAMERA_MODE = 530,
NAV_CMD_SET_CAMERA_SOURCE = 534,
NAV_CMD_SET_CAMERA_ZOOM = 531,