diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc index d5946cb4db1447810c3ea21b37067ec599bb784c..0a4d899544d22a5d03ddb2ab2ed82864b7bf556c 100644 --- a/src/MissionManager/MissionController.cc +++ b/src/MissionManager/MissionController.cc @@ -364,12 +364,12 @@ int MissionController::insertROIMissionItem(QGeoCoordinate coordinate, int i) int sequenceNumber = _nextSequenceNumber(); SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, this); newItem->setSequenceNumber(sequenceNumber); - newItem->setCoordinate(coordinate); newItem->setCommand((MavlinkQmlSingleton::Qml_MAV_CMD)(_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains((MAV_CMD)MAV_CMD_DO_SET_ROI_LOCATION) ? MAV_CMD_DO_SET_ROI_LOCATION : MAV_CMD_DO_SET_ROI)); _initVisualItem(newItem); newItem->setDefaultsForCommand(); + newItem->setCoordinate(coordinate); double prevAltitude; MAV_FRAME prevFrame;