From ad58ac34b899d03b9ca1779ef8f52111ae9be61a Mon Sep 17 00:00:00 2001 From: Your Name Date: Thu, 4 Jul 2024 11:24:07 +0300 Subject: [PATCH] Added check how many MAVSDK systems are available. --- src/az_config.h | 1 + src/az_drone_controller.cpp | 8 ++++++++ 2 files changed, 9 insertions(+) diff --git a/src/az_config.h b/src/az_config.h index ddfdd00..0639f2d 100644 --- a/src/az_config.h +++ b/src/az_config.h @@ -1,5 +1,6 @@ #pragma once +// Please check the port name! Also baudrates must match or devices can't communicate with each other. const char *AZ_CONNECTION_SERIAL = "serial:///dev/ttyS0:115200"; const char *AZ_CONNECTION_UDP = "udp://:14550"; const int AZ_RELATIVE_FLY_ALTITUDE = 50; diff --git a/src/az_drone_controller.cpp b/src/az_drone_controller.cpp index f85a167..818e6f9 100644 --- a/src/az_drone_controller.cpp +++ b/src/az_drone_controller.cpp @@ -73,6 +73,14 @@ bool AzDroneController::stateConnect(void) bool AzDroneController::stateAutopilot(void) { + std::vector> systems = mMavsdk.systems(); + qDebug() << "AzDroneController::stateAutopilot() Found" << systems.size() << "systems"; + + if (systems.size() == 0) { + std::cerr << "No system found." << std::endl; + return 1; + } + std::optional> autopilot = mMavsdk.first_autopilot(AZ_GET_AUTOPILOT_TIMEOUT); if (autopilot.has_value()) {