|
| 1 | +// |
| 2 | +// Simple example to demonstrate how to get and set params. |
| 3 | +// |
| 4 | + |
| 5 | +#include <mavsdk/mavsdk.h> |
| 6 | +#include <mavsdk/plugins/param/param.h> |
| 7 | +#include <chrono> |
| 8 | +#include <cstdint> |
| 9 | +#include <iostream> |
| 10 | +#include <future> |
| 11 | + |
| 12 | +using namespace mavsdk; |
| 13 | + |
| 14 | +void usage(const std::string& bin_name) |
| 15 | +{ |
| 16 | + std::cerr << "Usage :" << bin_name << '\n' |
| 17 | + << "Connection URL format should be :\n" |
| 18 | + << " For TCP : tcp://[server_host][:server_port]\n" |
| 19 | + << " For UDP : udp://[bind_host][:bind_port]\n" |
| 20 | + << " For Serial : serial:///path/to/serial/dev[:baudrate]\n" |
| 21 | + << "For example, to connect to the simulator use URL: udpin://0.0.0.0:14540\n"; |
| 22 | +} |
| 23 | + |
| 24 | +int main(int argc, char** argv) |
| 25 | +{ |
| 26 | + if (argc != 2) { |
| 27 | + usage(argv[0]); |
| 28 | + return 1; |
| 29 | + } |
| 30 | + |
| 31 | + const std::string connection_url = argv[1]; |
| 32 | + |
| 33 | + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; |
| 34 | + const ConnectionResult connection_result = mavsdk.add_any_connection(connection_url); |
| 35 | + |
| 36 | + if (connection_result != ConnectionResult::Success) { |
| 37 | + std::cerr << "Connection failed: " << connection_result << '\n'; |
| 38 | + return 1; |
| 39 | + } |
| 40 | + |
| 41 | + std::cout << "Waiting to discover system...\n"; |
| 42 | + auto prom = std::promise<std::shared_ptr<System>>{}; |
| 43 | + auto fut = prom.get_future(); |
| 44 | + |
| 45 | + // We wait for new systems to be discovered, once we find one that has an |
| 46 | + // autopilot, we decide to use it. |
| 47 | + Mavsdk::NewSystemHandle handle = mavsdk.subscribe_on_new_system([&mavsdk, &prom, &handle]() { |
| 48 | + auto system = mavsdk.systems().back(); |
| 49 | + |
| 50 | + if (system->has_autopilot()) { |
| 51 | + std::cout << "Discovered autopilot\n"; |
| 52 | + |
| 53 | + // Unsubscribe again as we only want to find one system. |
| 54 | + mavsdk.unsubscribe_on_new_system(handle); |
| 55 | + prom.set_value(system); |
| 56 | + } |
| 57 | + }); |
| 58 | + |
| 59 | + // We usually receive heartbeats at 1Hz, therefore we should find a |
| 60 | + // system after around 3 seconds max, surely. |
| 61 | + if (fut.wait_for(std::chrono::seconds(3)) == std::future_status::timeout) { |
| 62 | + std::cerr << "No autopilot found, exiting.\n"; |
| 63 | + return 1; |
| 64 | + } |
| 65 | + |
| 66 | + // Get discovered system now. |
| 67 | + auto system = fut.get(); |
| 68 | + |
| 69 | + // Instantiate plugins. |
| 70 | + auto param = Param{system}; |
| 71 | + |
| 72 | + // Print params once. |
| 73 | + const auto get_all_result = param.get_all_params(); |
| 74 | + |
| 75 | + std::cout << "Int params: \n"; |
| 76 | + for (auto p : get_all_result.int_params) { |
| 77 | + std::cout << p.name << ": " << p.value << '\n'; |
| 78 | + } |
| 79 | + |
| 80 | + std::cout << "Float params: \n"; |
| 81 | + for (auto p : get_all_result.float_params) { |
| 82 | + std::cout << p.name << ": " << p.value << '\n'; |
| 83 | + } |
| 84 | + |
| 85 | + return 0; |
| 86 | +} |
0 commit comments