Browse Source

Allow MAV_CMD_DO_SET_HOME as a mission command

sbg
Daniel Agar 7 years ago committed by Sander Smeets
parent
commit
58d1cdc733
  1. 2
      src/modules/mavlink/mavlink_mission.cpp
  2. 1
      src/modules/navigator/mission_block.cpp
  3. 1
      src/modules/navigator/mission_feasibility_checker.cpp
  4. 1
      src/modules/navigator/navigation.h

2
src/modules/mavlink/mavlink_mission.cpp

@ -1406,6 +1406,7 @@ MavlinkMissionManager::parse_mavlink_mission_item(const mavlink_mission_item_t * @@ -1406,6 +1406,7 @@ MavlinkMissionManager::parse_mavlink_mission_item(const mavlink_mission_item_t *
break;
case MAV_CMD_DO_CHANGE_SPEED:
case MAV_CMD_DO_SET_HOME:
case MAV_CMD_DO_SET_SERVO:
case MAV_CMD_DO_LAND_START:
case MAV_CMD_DO_TRIGGER_CONTROL:
@ -1479,6 +1480,7 @@ MavlinkMissionManager::format_mavlink_mission_item(const struct mission_item_s * @@ -1479,6 +1480,7 @@ MavlinkMissionManager::format_mavlink_mission_item(const struct mission_item_s *
break;
case NAV_CMD_DO_CHANGE_SPEED:
case NAV_CMD_DO_SET_HOME:
case NAV_CMD_DO_SET_SERVO:
case NAV_CMD_DO_LAND_START:
case NAV_CMD_DO_TRIGGER_CONTROL:

1
src/modules/navigator/mission_block.cpp

@ -113,6 +113,7 @@ MissionBlock::is_mission_item_reached() @@ -113,6 +113,7 @@ MissionBlock::is_mission_item_reached()
}
case NAV_CMD_DO_CHANGE_SPEED:
case NAV_CMD_DO_SET_HOME:
return true;
default:

1
src/modules/navigator/mission_feasibility_checker.cpp

@ -275,6 +275,7 @@ MissionFeasibilityChecker::checkMissionItemValidity(dm_item_t dm_current, size_t @@ -275,6 +275,7 @@ MissionFeasibilityChecker::checkMissionItemValidity(dm_item_t dm_current, size_t
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 &&

1
src/modules/navigator/navigation.h

@ -71,6 +71,7 @@ enum NAV_CMD { @@ -71,6 +71,7 @@ enum NAV_CMD {
NAV_CMD_DELAY = 93,
NAV_CMD_DO_JUMP = 177,
NAV_CMD_DO_CHANGE_SPEED = 178,
NAV_CMD_DO_SET_HOME = 179,
NAV_CMD_DO_SET_SERVO = 183,
NAV_CMD_DO_LAND_START = 189,
NAV_CMD_DO_SET_ROI = 201,

Loading…
Cancel
Save