diff --git a/src/comm/MAVLinkProtocol.cc b/src/comm/MAVLinkProtocol.cc index 180670b..227e1f0 100644 --- a/src/comm/MAVLinkProtocol.cc +++ b/src/comm/MAVLinkProtocol.cc @@ -187,7 +187,7 @@ void MAVLinkProtocol::linkStatusChanged(bool connected) link->writeBytes(init, sizeof(init)); // Stop any running mavlink instance - char* cmd = "mavlink stop\n"; + const char* cmd = "mavlink stop\n"; link->writeBytes(cmd, strlen(cmd)); link->writeBytes(init, 2); cmd = "uorb start"; diff --git a/src/uas/UASManager.cc b/src/uas/UASManager.cc index 00bb81b..21a6a4d 100644 --- a/src/uas/UASManager.cc +++ b/src/uas/UASManager.cc @@ -232,11 +232,11 @@ void UASManager::uavChangedHomePosition(int uav, double lat, double lon, double **/ UASManager::UASManager() : activeUAS(NULL), + offlineUASWaypointManager(NULL), homeLat(47.3769), homeLon(8.549444), homeAlt(470.0), - homeFrame(MAV_FRAME_GLOBAL), - offlineUASWaypointManager(NULL) + homeFrame(MAV_FRAME_GLOBAL) { loadSettings(); setLocalNEDSafetyBorders(1, -1, 0, -1, 1, -1);