Visual Servoing Platform version 3.7.0
Loading...
Searching...
No Matches
vpRobotMavsdk.cpp
1/*
2 * ViSP, open source Visual Servoing Platform software.
3 * Copyright (C) 2005 - 2025 by Inria. All rights reserved.
4 *
5 * This software is free software; you can redistribute it and/or modify
6 * it under the terms of the GNU General Public License as published by
7 * the Free Software Foundation; either version 2 of the License, or
8 * (at your option) any later version.
9 * See the file LICENSE.txt at the root directory of this source
10 * distribution for additional information about the GNU GPL.
11 *
12 * For using ViSP with software that can not be combined with the GNU
13 * GPL, please contact Inria about acquiring a ViSP Professional
14 * Edition License.
15 *
16 * See https://visp.inria.fr for more information.
17 *
18 * This software was developed at:
19 * Inria Rennes - Bretagne Atlantique
20 * Campus Universitaire de Beaulieu
21 * 35042 Rennes Cedex
22 * France
23 *
24 * If you have questions regarding the use of this file, please contact
25 * Inria at visp@inria.fr
26 *
27 * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
28 * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
29 *
30 * Description:
31 * Interface to mavlink compatible controller using mavsdk 3rd party
32 */
33
34#include <visp3/core/vpConfig.h>
35
36// Check if std:c++17 or higher
37#if defined(VISP_HAVE_MAVSDK) && ((__cplusplus >= 201703L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201703L))) \
38 && defined(VISP_HAVE_THREADS)
39
40#include <iostream>
41#include <math.h>
42#include <thread>
43
44#include <mavsdk/mavsdk.h>
45#include <mavsdk/plugins/action/action.h>
46#include <mavsdk/plugins/calibration/calibration.h>
47#include <mavsdk/plugins/mavlink_passthrough/mavlink_passthrough.h>
48#include <mavsdk/plugins/mocap/mocap.h>
49#include <mavsdk/plugins/offboard/offboard.h>
50#include <mavsdk/plugins/telemetry/telemetry.h>
51
52#include <visp3/core/vpExponentialMap.h> // For velocity computation
53#include <visp3/robot/vpRobotMavsdk.h>
54
55using std::chrono::milliseconds;
56using std::chrono::seconds;
57using std::this_thread::sleep_for;
58using namespace std::chrono_literals;
59
61#ifndef DOXYGEN_SHOULD_SKIP_THIS
62class vpRobotMavsdk::vpRobotMavsdkImpl
63{
64public:
65 vpRobotMavsdkImpl() : m_takeoffAlt(1.0) { }
66 vpRobotMavsdkImpl(const std::string &connection_info) : m_takeoffAlt(1.0) { connect(connection_info); }
67
68 virtual ~vpRobotMavsdkImpl()
69 {
70 if (m_has_flying_capability && m_auto_land) {
71 land();
72 }
73 }
74
75private:
81 std::shared_ptr<mavsdk::System> getSystem(mavsdk::Mavsdk &mavsdk)
82 {
83 std::cout << "Waiting to discover system..." << std::endl;
84 auto prom = std::promise<std::shared_ptr<mavsdk::System> > {};
85 auto fut = prom.get_future();
86
87 // We wait for new systems to be discovered, once we find one that has an
88 // autopilot, we decide to use it.
89#if (VISP_HAVE_MAVSDK_VERSION > 0x010412)
90 mavsdk::Mavsdk::NewSystemHandle handle = mavsdk.subscribe_on_new_system([&mavsdk, &prom, &handle]() {
91#else
92 mavsdk.subscribe_on_new_system([&mavsdk, &prom]() {
93#endif
94 auto system = mavsdk.systems().back();
95
96 if (system->has_autopilot()) {
97 std::cout << "Discovered autopilot" << std::endl;
98
99 // Unsubscribe again as we only want to find one system.
100#if (VISP_HAVE_MAVSDK_VERSION > 0x010412)
101 mavsdk.unsubscribe_on_new_system(handle);
102#else
103 mavsdk.subscribe_on_new_system(nullptr);
104#endif
105 prom.set_value(system);
106 }
107 });
108
109 // We usually receive heartbeats at 1Hz, therefore we should find a
110 // system after around 3 seconds max, surely.
111 if (fut.wait_for(seconds(3)) == std::future_status::timeout) {
112 std::cerr << "No autopilot found." << std::endl;
113 return {};
114 }
115
116 // Get discovered system now.
117 return fut.get();
118 }
119
120 MAV_TYPE getVehicleType()
121 {
122 auto passthrough = mavsdk::MavlinkPassthrough { m_system };
123
124 auto prom = std::promise<MAV_TYPE> {};
125 auto fut = prom.get_future();
126#if (VISP_HAVE_MAVSDK_VERSION > 0x010412)
127 mavsdk::MavlinkPassthrough::MessageHandle handle = passthrough.subscribe_message(
128 MAVLINK_MSG_ID_HEARTBEAT, [&passthrough, &prom, &handle](const mavlink_message_t &message) {
129#else
130 passthrough.subscribe_message_async(MAVLINK_MSG_ID_HEARTBEAT,
131 [&passthrough, &prom](const mavlink_message_t &message) {
132#endif
133 // Process only Heartbeat coming from the autopilot
134 if (message.compid != MAV_COMP_ID_AUTOPILOT1) {
135 return;
136 }
137
138 mavlink_heartbeat_t heartbeat;
139 mavlink_msg_heartbeat_decode(&message, &heartbeat);
140
141 // Unsubscribe again as we only want to find one system.
142#if (VISP_HAVE_MAVSDK_VERSION >= 0x020000)
143 passthrough.unsubscribe_message(MAVLINK_MSG_ID_HEARTBEAT, handle);
144#elif (VISP_HAVE_MAVSDK_VERSION > 0x010412)
145 passthrough.unsubscribe_message(handle);
146#else
147 passthrough.subscribe_message_async(MAVLINK_MSG_ID_HEARTBEAT, nullptr);
148#endif
149
150 prom.set_value(static_cast<MAV_TYPE>(heartbeat.type));
151 });
152
153 // We usually receive heartbeats at 1Hz, therefore we should find a
154 // system after around 3 seconds max, surely.
155 if (fut.wait_for(seconds(3)) == std::future_status::timeout) {
156 std::cerr << "No heartbeat received to get vehicle type." << std::endl;
157 return {};
158 }
159
160 // Get discovered system now.
161 return fut.get();
162 }
163
164 void calibrate_accelerometer(mavsdk::Calibration &calibration)
165 {
166 std::cout << "Calibrating accelerometer..." << std::endl;
167
168 std::promise<void> calibration_promise;
169 auto calibration_future = calibration_promise.get_future();
170
171 calibration.calibrate_accelerometer_async(create_calibration_callback(calibration_promise));
172
173 calibration_future.wait();
174 }
175
176 std::function<void(mavsdk::Calibration::Result, mavsdk::Calibration::ProgressData)>
177 create_calibration_callback(std::promise<void> &calibration_promise)
178 {
179 return [&calibration_promise](const mavsdk::Calibration::Result result,
180 const mavsdk::Calibration::ProgressData progress_data) {
181 switch (result) {
182 case mavsdk::Calibration::Result::Success:
183 std::cout << "--- Calibration succeeded!" << std::endl;
184 calibration_promise.set_value();
185 break;
186 case mavsdk::Calibration::Result::Next:
187 if (progress_data.has_progress) {
188 std::cout << " Progress: " << progress_data.progress << std::endl;
189 }
190 if (progress_data.has_status_text) {
191 std::cout << " Instruction: " << progress_data.status_text << std::endl;
192 }
193 break;
194 default:
195 std::cout << "--- Calibration failed with message: " << result << std::endl;
196 calibration_promise.set_value();
197 break;
198 }
199 };
200 }
201
202 void calibrate_gyro(mavsdk::Calibration &calibration)
203 {
204 std::cout << "Calibrating gyro..." << std::endl;
205
206 std::promise<void> calibration_promise;
207 auto calibration_future = calibration_promise.get_future();
208
209 calibration.calibrate_gyro_async(create_calibration_callback(calibration_promise));
210
211 calibration_future.wait();
212 }
213
214public:
215 void connect(const std::string &connectionInfo)
216 {
217 m_address = connectionInfo;
218 mavsdk::ConnectionResult connection_result = m_mavsdk.add_any_connection(connectionInfo);
219
220 if (connection_result != mavsdk::ConnectionResult::Success) {
221 std::cerr << "Connection failed: " << connection_result << std::endl;
222 return;
223 }
224
225 m_system = getSystem(m_mavsdk);
226
227 if (!m_system) {
228 throw vpException(vpException::fatalError, "Unable to connect to: %s", connectionInfo.c_str());
229 }
230
231 m_mav_type = getVehicleType();
232
233 m_has_flying_capability = hasFlyingCapability(m_mav_type);
234
235 std::cout << (m_has_flying_capability ? "Connected to a flying vehicle" : "Connected to a non flying vehicle")
236 << std::endl;
237
238 m_action = std::make_shared<mavsdk::Action>(m_system);
239 m_telemetry = std::make_shared<mavsdk::Telemetry>(m_system);
240 m_offboard = std::make_shared<mavsdk::Offboard>(m_system);
241 }
242
243 bool hasFlyingCapability(MAV_TYPE mav_type)
244 {
245 switch (mav_type) {
246 case MAV_TYPE::MAV_TYPE_GROUND_ROVER:
247 case MAV_TYPE::MAV_TYPE_SURFACE_BOAT:
248 case MAV_TYPE::MAV_TYPE_SUBMARINE:
249 return false;
250 default:
251 return true;
252 }
253 }
254
255 bool isRunning() const
256 {
257 if (m_system == nullptr) {
258 return false;
259 }
260 else {
261 return true;
262 }
263 }
264
265 std::string getAddress() const
266 {
267 std::string sequence;
268 std::stringstream ss(m_address);
269 std::string actual_address;
270 std::getline(ss, sequence, ':');
271 if (sequence == "serial" || sequence == "udp" || sequence == "tcp") {
272 getline(ss, sequence, ':');
273 for (const char &c : sequence) {
274 if (c != '/') {
275 actual_address.append(1, c);
276 }
277 }
278 return actual_address;
279 }
280 else {
281 std::cout << "ERROR : The address parameter must start with \"serial:\" or \"udp:\" or \"tcp:\"." << std::endl;
282 return std::string();
283 }
284 }
285
286 float getBatteryLevel() const
287 {
288 mavsdk::Telemetry::Battery battery = m_telemetry.get()->battery();
289 return battery.voltage_v;
290 }
291
292 void getPosition(vpHomogeneousMatrix &ned_M_frd) const
293 {
294 auto quat = m_telemetry.get()->attitude_quaternion();
295 auto posvel = m_telemetry.get()->position_velocity_ned();
296 vpQuaternionVector q { quat.x, quat.y, quat.z, quat.w };
297 vpTranslationVector t { posvel.position.north_m, posvel.position.east_m, posvel.position.down_m };
298 ned_M_frd.buildFrom(t, q);
299 }
300
301 void getPosition(float &ned_north, float &ned_east, float &ned_down, float &ned_yaw) const
302 {
303 auto odom = m_telemetry.get()->odometry();
304 auto angles = m_telemetry.get()->attitude_euler();
305 ned_north = odom.position_body.x_m;
306 ned_east = odom.position_body.y_m;
307 ned_down = odom.position_body.z_m;
308 ned_yaw = vpMath::rad(angles.yaw_deg);
309 }
310
311 std::tuple<float, float> getHome() const
312 {
313 auto position = m_telemetry.get()->home();
314 return { float(position.latitude_deg), float(position.longitude_deg) };
315 }
316
317 bool sendMocapData(const vpHomogeneousMatrix &enu_M_flu, int display_fps)
318 {
319 static double time_prev = vpTime::measureTimeMs();
320
321 // We suppose here that the body frame which pose is given by the MoCap is FLU (Front Left Up).
322 // Thus we need to transform this frame to FRD (Front Right Down).
323 vpHomogeneousMatrix flu_M_frd;
324 flu_M_frd.eye();
325 flu_M_frd[1][1] = -1;
326 flu_M_frd[2][2] = -1;
327
328 vpHomogeneousMatrix enu_M_frd = enu_M_flu * flu_M_frd;
329 auto mocap = mavsdk::Mocap { m_system };
330 mavsdk::Mocap::VisionPositionEstimate pose_estimate;
331
332 vpHomogeneousMatrix ned_M_frd = vpMath::enu2ned(enu_M_frd);
333 vpRxyzVector ned_rxyz_frd = vpRxyzVector(ned_M_frd.getRotationMatrix());
334 pose_estimate.angle_body.roll_rad = ned_rxyz_frd[0];
335 pose_estimate.angle_body.pitch_rad = ned_rxyz_frd[1];
336 pose_estimate.angle_body.yaw_rad = ned_rxyz_frd[2];
337
338 vpTranslationVector ned_t_frd = ned_M_frd.getTranslationVector();
339 pose_estimate.position_body.x_m = ned_t_frd[0];
340 pose_estimate.position_body.y_m = ned_t_frd[1];
341 pose_estimate.position_body.z_m = ned_t_frd[2];
342
343 pose_estimate.pose_covariance.covariance_matrix.push_back(NAN);
344 pose_estimate.time_usec = 0; // We are using the back end timestamp
345
346 const mavsdk::Mocap::Result set_position_result = mocap.set_vision_position_estimate(pose_estimate);
347 if (set_position_result != mavsdk::Mocap::Result::Success) {
348 std::cerr << "Set position failed: " << set_position_result << '\n';
349 return false;
350 }
351 else {
352 if (display_fps > 0) {
353 double display_time_ms = 1000. / display_fps;
354 if (vpTime::measureTimeMs() - time_prev > display_time_ms) {
355 time_prev = vpTime::measureTimeMs();
356 std::cout << "Send ned_M_frd MoCap data: " << std::endl;
357 std::cout << "Translation [m]: " << pose_estimate.position_body.x_m << " , "
358 << pose_estimate.position_body.y_m << " , " << pose_estimate.position_body.z_m << std::endl;
359 std::cout << "Roll [rad]: " << pose_estimate.angle_body.roll_rad
360 << " , Pitch [rad]: " << pose_estimate.angle_body.pitch_rad
361 << " , Yaw [rad]: " << pose_estimate.angle_body.yaw_rad << " ." << std::endl;
362 }
363 }
364 return true;
365 }
366 }
367
368 void setTakeOffAlt(double altitude)
369 {
370 if (altitude > 0) {
371 m_takeoffAlt = altitude;
372 }
373 else {
374 std::cerr << "ERROR : The take off altitude must be positive." << std::endl;
375 }
376 }
377
378 void doFlatTrim()
379 {
380 // Instantiate plugin.
381 auto calibration = mavsdk::Calibration(m_system);
382
383 // Run calibrations
384 calibrate_accelerometer(calibration);
385 calibrate_gyro(calibration);
386 }
387
388 bool arm()
389 {
390 // Arm vehicle
391 std::cout << "Arming...\n";
392 const mavsdk::Action::Result arm_result = m_action.get()->arm();
393
394 if (arm_result != mavsdk::Action::Result::Success) {
395 std::cerr << "Arming failed: " << arm_result << std::endl;
396 return false;
397 }
398 return true;
399 }
400
401 bool disarm()
402 {
403 // Arm vehicle
404 std::cout << "Disarming...\n";
405 const mavsdk::Action::Result arm_result = m_action.get()->disarm();
406
407 if (arm_result != mavsdk::Action::Result::Success) {
408 std::cerr << "Disarming failed: " << arm_result << std::endl;
409 return false;
410 }
411 return true;
412 }
413
414 bool setGPSGlobalOrigin(double latitude, double longitude, double altitude)
415 {
416 auto passthrough = mavsdk::MavlinkPassthrough { m_system };
417#if (VISP_HAVE_MAVSDK_VERSION >= 0x020000)
418 passthrough.queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
419 (void)channel;
420 mavlink_message_t message;
421 mavlink_set_gps_global_origin_t gps_global_origin;
422 gps_global_origin.latitude = latitude * 1E7; // [deg] Latitude (WGS84)
423 gps_global_origin.longitude = longitude * 1E7; // [deg] Longitude (WGS84)
424 gps_global_origin.altitude = altitude * 1000; // [mm] Altitude (MSL). Positive for up
425 gps_global_origin.target_system = m_system->get_system_id(); // System ID
426 gps_global_origin.time_usec = 0;
427 mavlink_msg_set_gps_global_origin_encode(
428 mavlink_address.system_id,
429 mavlink_address.component_id,
430 &message,
431 &gps_global_origin);
432 return message;
433 });
434#else
435 mavlink_set_gps_global_origin_t gps_global_origin;
436 gps_global_origin.latitude = latitude * 1E7;
437 gps_global_origin.longitude = longitude * 1E7;
438 gps_global_origin.altitude = altitude * 1000; // in mm
439 gps_global_origin.target_system = m_system->get_system_id();
440 mavlink_message_t msg;
441 mavlink_msg_set_gps_global_origin_encode(passthrough.get_our_sysid(), passthrough.get_our_compid(), &msg,
442 &gps_global_origin);
443 auto resp = passthrough.send_message(msg);
444 if (resp != mavsdk::MavlinkPassthrough::Result::Success) {
445 std::cerr << "Set GPS global position failed: " << resp << std::endl;
446 return false;
447 }
448#endif
449 return true;
450 }
451
452 bool takeControl()
453 {
454 if (m_verbose) {
455 std::cout << "Starting offboard mode..." << std::endl;
456 }
457
458 if (m_telemetry.get()->flight_mode() != mavsdk::Telemetry::FlightMode::Offboard) {
459 const mavsdk::Offboard::VelocityBodyYawspeed stay {};
460 m_offboard.get()->set_velocity_body(stay);
461
462 mavsdk::Offboard::Result offboard_result = m_offboard.get()->start();
463 if (offboard_result != mavsdk::Offboard::Result::Success) {
464 std::cerr << "Offboard mode failed: " << offboard_result << std::endl;
465 return false;
466 }
467 }
468 else if (m_verbose) {
469 std::cout << "Already in offboard mode" << std::endl;
470 }
471
472 // Wait to ensure offboard mode active in telemetry
473 double t = vpTime::measureTimeMs();
474 while (m_telemetry.get()->flight_mode() != mavsdk::Telemetry::FlightMode::Offboard) {
475 if (vpTime::measureTimeMs() - t > 3. * 1000.) {
476 std::cout << "Time out received in takeControl()" << std::endl;
477 break;
478 }
479 };
480
481 if (m_verbose) {
482 std::cout << "Offboard mode started" << std::endl;
483 }
484 return true;
485 }
486
487 void setPositioningIncertitude(float position_incertitude, float yaw_incertitude)
488 {
489 m_position_incertitude = position_incertitude;
490 m_yaw_incertitude = yaw_incertitude;
491 }
492
493 bool takeOff(bool interactive, int timeout_sec, bool use_gps)
494 {
495 if (!m_has_flying_capability) {
496 std::cerr << "Warning: Cannot takeoff this non flying vehicle" << std::endl;
497 return true;
498 }
499
500 bool authorize_takeoff = false;
501
502 if (!interactive) {
503 authorize_takeoff = true;
504 }
505 else {
506 if (m_telemetry.get()->flight_mode() == mavsdk::Telemetry::FlightMode::Offboard) {
507 authorize_takeoff = true;
508 }
509 else {
510 std::string answer;
511 while (answer != "Y" && answer != "y" && answer != "N" && answer != "n") {
512 std::cout << "Current flight mode is not the offboard mode. Do you "
513 "want to force offboard mode ? (y/n)"
514 << std::endl;
515 std::cin >> answer;
516 if (answer == "Y" || answer == "y") {
517 authorize_takeoff = true;
518 }
519 }
520 }
521 }
522
523 if (m_telemetry.get()->in_air()) {
524 std::cerr << "Cannot take off as the robot is already flying." << std::endl;
525 return true;
526 }
527 else if (authorize_takeoff) {
528 // Arm vehicle
529 if (!arm()) {
530 return false;
531 }
532
533 vpTime::wait(2000);
534
535 if (interactive) {
536 std::string answer;
537 while (answer != "Y" && answer != "y" && answer != "N" && answer != "n") {
538 std::cout << "If vehicle armed ? (y/n)" << std::endl;
539 std::cin >> answer;
540 if (answer == "N" || answer == "n") {
541 disarm();
542 kill();
543 return false;
544 }
545 }
546 }
547
548 // Takeoff
549 if (m_telemetry.get()->gps_info().fix_type == mavsdk::Telemetry::FixType::NoGps || !use_gps) {
550 // No GPS connected.
551 // When using odometry from MoCap, Action::takeoff() behavior is to takeoff at 0,0,0,alt
552 // that is weird when the drone is not placed at 0,0,0.
553 // That's why here use set_position_ned() to takeoff
554
555 // Start off-board or guided mode
556 takeControl();
557
558 auto in_air_promise = std::promise<void> {};
559 auto in_air_future = in_air_promise.get_future();
560
561 mavsdk::Telemetry::Odometry odom = m_telemetry.get()->odometry();
562 vpQuaternionVector q { odom.q.x, odom.q.y, odom.q.z, odom.q.w };
563 vpRotationMatrix R(q);
564 vpRxyzVector rxyz(R);
565
566 double X_init = odom.position_body.x_m;
567 double Y_init = odom.position_body.y_m;
568 double Z_init = odom.position_body.z_m;
569 double yaw_init = vpMath::deg(rxyz[2]);
570
571 std::cout << "Takeoff using position NED." << std::endl;
572
573 mavsdk::Offboard::PositionNedYaw takeoff {};
574 takeoff.north_m = X_init;
575 takeoff.east_m = Y_init;
576 takeoff.down_m = Z_init - m_takeoffAlt;
577 takeoff.yaw_deg = yaw_init;
578 m_offboard.get()->set_position_ned(takeoff);
579 // Possibility is to use set_position_velocity_ned(); to speed up takeoff
580
581#if (VISP_HAVE_MAVSDK_VERSION > 0x010412)
582 mavsdk::Telemetry::LandedStateHandle handle = m_telemetry.get()->subscribe_landed_state(
583 [this, &in_air_promise, &handle](mavsdk::Telemetry::LandedState state) {
584 if (state == mavsdk::Telemetry::LandedState::InAir) {
585 std::cout << "Drone is taking off\n.";
586 m_telemetry.get()->unsubscribe_landed_state(handle);
587 in_air_promise.set_value();
588 }
589 });
590#else
591 m_telemetry.get()->subscribe_landed_state([this, &in_air_promise](mavsdk::Telemetry::LandedState state) {
592 if (state == mavsdk::Telemetry::LandedState::InAir) {
593 std::cout << "Drone is taking off\n.";
594 m_telemetry.get()->subscribe_landed_state(nullptr);
595 in_air_promise.set_value();
596 }
597 std::cout << "state: " << state << std::endl;
598 });
599#endif
600 if (in_air_future.wait_for(seconds(timeout_sec)) == std::future_status::timeout) {
601 std::cerr << "Takeoff failed: drone not in air.\n";
602#if (VISP_HAVE_MAVSDK_VERSION > 0x010412)
603 m_telemetry.get()->unsubscribe_landed_state(handle);
604#else
605 m_telemetry.get()->subscribe_landed_state(nullptr);
606#endif
607 return false;
608 }
609 // Add check with Altitude
610 auto takeoff_finished_promise = std::promise<void> {};
611 auto takeoff_finished_future = takeoff_finished_promise.get_future();
612
613#if (VISP_HAVE_MAVSDK_VERSION > 0x010412)
614 mavsdk::Telemetry::OdometryHandle handle_odom = m_telemetry.get()->subscribe_odometry(
615 [this, &takeoff_finished_promise, &handle, &Z_init, &handle_odom](mavsdk::Telemetry::Odometry odom) {
616 if (odom.position_body.z_m < 0.90 * (Z_init - m_takeoffAlt) + m_position_incertitude) {
617 std::cout << "Takeoff altitude reached\n.";
618 m_telemetry.get()->unsubscribe_odometry(handle_odom);
619 takeoff_finished_promise.set_value();
620 }
621 });
622#else
623 m_telemetry.get()->subscribe_odometry(
624 [this, &takeoff_finished_promise, &Z_init](mavsdk::Telemetry::Odometry odom) {
625 if (odom.position_body.z_m < 0.90 * (Z_init - m_takeoffAlt) + m_position_incertitude) {
626 std::cout << "Takeoff altitude reached\n.";
627 m_telemetry.get()->subscribe_odometry(nullptr);
628 takeoff_finished_promise.set_value();
629 }
630 });
631#endif
632 if (takeoff_finished_future.wait_for(seconds(timeout_sec)) == std::future_status::timeout) {
633 std::cerr << "Takeoff failed: altitude not reached.\n";
634#if (VISP_HAVE_MAVSDK_VERSION > 0x010412)
635 m_telemetry.get()->unsubscribe_odometry(handle_odom);
636#else
637 m_telemetry.get()->subscribe_odometry(nullptr);
638#endif
639 return false;
640 }
641 }
642 else {
643 // GPS connected, we use Action::takeoff()
644 mavsdk::Telemetry::Odometry odom = m_telemetry.get()->odometry();
645 double Z_init = odom.position_body.z_m;
646
647 m_action.get()->set_takeoff_altitude(m_takeoffAlt);
648 const auto takeoff_result = m_action.get()->takeoff();
649 if (takeoff_result != mavsdk::Action::Result::Success) {
650 std::cerr << "Takeoff failed: " << takeoff_result << '\n';
651 return false;
652 }
653
654 auto in_air_promise = std::promise<void> {};
655 auto in_air_future = in_air_promise.get_future();
656#if (VISP_HAVE_MAVSDK_VERSION > 0x010412)
657 mavsdk::Telemetry::LandedStateHandle handle = m_telemetry.get()->subscribe_landed_state(
658 [this, &in_air_promise, &handle](mavsdk::Telemetry::LandedState state) {
659 if (state == mavsdk::Telemetry::LandedState::InAir) {
660 std::cout << "Taking off has finished\n.";
661 m_telemetry.get()->unsubscribe_landed_state(handle);
662 in_air_promise.set_value();
663 }
664 });
665#else
666 m_telemetry.get()->subscribe_landed_state([this, &in_air_promise](mavsdk::Telemetry::LandedState state) {
667 if (state == mavsdk::Telemetry::LandedState::InAir) {
668 std::cout << "Taking off has finished\n.";
669 m_telemetry.get()->subscribe_landed_state(nullptr);
670 in_air_promise.set_value();
671 }
672 std::cout << "state: " << state << std::endl;
673 });
674#endif
675 if (in_air_future.wait_for(seconds(timeout_sec)) == std::future_status::timeout) {
676 // Add check with Altitude
677 std::cerr << "Takeoff timed out.\n";
678#if (VISP_HAVE_MAVSDK_VERSION > 0x010412)
679 m_telemetry.get()->unsubscribe_landed_state(handle);
680#else
681 m_telemetry.get()->subscribe_landed_state(nullptr);
682#endif
683 }
684 // Add check with Altitude
685 auto takeoff_finished_promise = std::promise<void> {};
686 auto takeoff_finished_future = takeoff_finished_promise.get_future();
687
688#if (VISP_HAVE_MAVSDK_VERSION > 0x010412)
689 mavsdk::Telemetry::OdometryHandle handle_odom = m_telemetry.get()->subscribe_odometry(
690 [this, &takeoff_finished_promise, &handle, &Z_init, &handle_odom](mavsdk::Telemetry::Odometry odom) {
691 if (odom.position_body.z_m < 0.90 * (Z_init - m_takeoffAlt) + m_position_incertitude) {
692 std::cout << "Takeoff altitude reached\n.";
693 m_telemetry.get()->unsubscribe_odometry(handle_odom);
694 takeoff_finished_promise.set_value();
695 }
696 });
697#else
698 m_telemetry.get()->subscribe_odometry(
699 [this, &takeoff_finished_promise, &Z_init](mavsdk::Telemetry::Odometry odom) {
700 if (odom.position_body.z_m < 0.90 * (Z_init - m_takeoffAlt) + m_position_incertitude) {
701 std::cout << "Takeoff altitude reached\n.";
702 m_telemetry.get()->subscribe_odometry(nullptr);
703 takeoff_finished_promise.set_value();
704 }
705 });
706#endif
707 if (takeoff_finished_future.wait_for(seconds(timeout_sec)) == std::future_status::timeout) {
708 std::cerr << "Takeoff failed: altitude not reached.\n";
709#if (VISP_HAVE_MAVSDK_VERSION > 0x010412)
710 m_telemetry.get()->unsubscribe_odometry(handle_odom);
711#else
712 m_telemetry.get()->subscribe_odometry(nullptr);
713#endif
714 return false;
715 }
716 // Start off-board or guided mode
717 takeControl();
718 }
719 }
720 return true;
721 }
722
723 bool land(bool use_buildin = false)
724 {
725 if (!m_has_flying_capability) {
726 std::cerr << "Warning: Cannot land this non flying vehicle" << std::endl;
727 return true;
728 }
729 // Takeoff
730 if (!use_buildin) {
731 // No GPS connected.
732 // When using odometry from MoCap, Action::takeoff() behavior is to
733 // takeoff at 0,0,0,alt that is weird when the drone is not placed at
734 // 0,0,0. That's why here use set_position_ned() to takeoff
735
736 // Start off-board or guided mode
737 takeControl();
738
739 mavsdk::Telemetry::Odometry odom = m_telemetry.get()->odometry();
740 vpQuaternionVector q { odom.q.x, odom.q.y, odom.q.z, odom.q.w };
741 vpRotationMatrix R(q);
742 vpRxyzVector rxyz(R);
743
744 double X_init = odom.position_body.x_m;
745 double Y_init = odom.position_body.y_m;
746 double yaw_init = vpMath::deg(rxyz[2]);
747
748 std::cout << "Landing using position NED." << std::endl;
749
750 mavsdk::Offboard::PositionNedYaw landing {};
751 landing.north_m = X_init;
752 landing.east_m = Y_init;
753 landing.down_m = 0.;
754 landing.yaw_deg = yaw_init;
755 m_offboard.get()->set_position_ned(landing);
756 // Possibility is to use set_position_velocity_ned(); to speed up
757 bool success = false;
758
759 // Add check with Altitude
760 auto landing_finished_promise = std::promise<void> {};
761 auto landing_finished_future = landing_finished_promise.get_future();
762
763#if (VISP_HAVE_MAVSDK_VERSION > 0x010412)
764 mavsdk::Telemetry::OdometryHandle handle_odom = m_telemetry.get()->subscribe_odometry(
765 [this, &landing_finished_promise, &success, &handle_odom](mavsdk::Telemetry::Odometry odom) {
766 if (odom.position_body.z_m > -0.15) {
767 std::cout << "Landing altitude reached \n.";
768
769 success = true;
770 m_telemetry.get()->unsubscribe_odometry(handle_odom);
771 landing_finished_promise.set_value();
772 }
773 });
774#else
775 m_telemetry.get()->subscribe_odometry(
776 [this, &landing_finished_promise, &success](mavsdk::Telemetry::Odometry odom) {
777 if (odom.position_body.z_m > -0.15) {
778 std::cout << "Landing altitude reached\n.";
779
780 success = true;
781 m_telemetry.get()->subscribe_odometry(nullptr);
782 landing_finished_promise.set_value();
783 }
784 });
785#endif
786 if (landing_finished_future.wait_for(seconds(10)) == std::future_status::timeout) {
787 std::cerr << "failed: altitude not reached.\n";
788 success = true; // go to automatic landing
789 }
790
791 while (!success) {
792 std::cout << "Descending\n.";
793 sleep_for(100ms);
794 }
795 }
796
797 if (m_telemetry.get()->flight_mode() != mavsdk::Telemetry::FlightMode::Land) {
798 std::cout << "Landing...\n";
799 const mavsdk::Action::Result land_result = m_action.get()->land();
800 if (land_result != mavsdk::Action::Result::Success) {
801 std::cerr << "Land failed: " << land_result << std::endl;
802 return false;
803 }
804
805 // Check if vehicle is still in air
806 while (m_telemetry.get()->in_air()) {
807 std::cout << "Vehicle is landing..." << std::endl;
808 sleep_for(seconds(1));
809 }
810 }
811
812 std::cout << "Landed!" << std::endl;
813 // We are relying on auto-disarming but let's keep watching the telemetry
814 // for a bit longer.
815 sleep_for(seconds(5));
816 std::cout << "Finished..." << std::endl;
817 return true;
818 }
819
820 bool setPosition(float ned_north, float ned_east, float ned_down, float ned_yaw, bool blocking, int timeout_sec)
821 {
822 mavsdk::Offboard::PositionNedYaw position_target {};
823
824 position_target.north_m = ned_north;
825 position_target.east_m = ned_east;
826 position_target.down_m = ned_down;
827 position_target.yaw_deg = vpMath::deg(ned_yaw);
828
829 std::cout << "NED Pos to reach: " << position_target.north_m << " " << position_target.east_m << " "
830 << position_target.down_m << " " << position_target.yaw_deg << std::endl;
831 m_offboard.get()->set_position_ned(position_target);
832
833 if (m_telemetry.get()->flight_mode() != mavsdk::Telemetry::FlightMode::Offboard) {
834 if (m_verbose) {
835 std::cout << "Cannot set vehicle position: offboard mode not started" << std::endl;
836 }
837 return false;
838 }
839
840 if (blocking) {
841 // Add check with Altitude
842 auto position_reached_promise = std::promise<void> {};
843 auto position_reached_future = position_reached_promise.get_future();
844
845#if (VISP_HAVE_MAVSDK_VERSION > 0x010412)
846 mavsdk::Telemetry::OdometryHandle handle_odom = m_telemetry.get()->subscribe_odometry(
847 [this, &position_reached_promise, &handle_odom, &position_target](mavsdk::Telemetry::Odometry odom) {
848 vpQuaternionVector q { odom.q.x, odom.q.y, odom.q.z, odom.q.w };
849 vpRotationMatrix R(q);
850 vpRxyzVector rxyz(R);
851 double odom_yaw = vpMath::deg(rxyz[2]);
852 double distance_to_target = std::sqrt(vpMath::sqr(odom.position_body.x_m - position_target.north_m) +
853 vpMath::sqr(odom.position_body.y_m - position_target.east_m) +
854 vpMath::sqr(odom.position_body.z_m - position_target.down_m));
855 if (distance_to_target < m_position_incertitude &&
856 std::fabs(odom_yaw - position_target.yaw_deg) < m_yaw_incertitude) {
857 std::cout << "Position reached\n.";
858 m_telemetry.get()->unsubscribe_odometry(handle_odom);
859 position_reached_promise.set_value();
860 }
861 });
862#else
863 m_telemetry.get()->subscribe_odometry(
864 [this, &position_reached_promise, &position_target](mavsdk::Telemetry::Odometry odom) {
865 vpQuaternionVector q { odom.q.x, odom.q.y, odom.q.z, odom.q.w };
866 vpRotationMatrix R(q);
867 vpRxyzVector rxyz(R);
868 double odom_yaw = vpMath::deg(rxyz[2]);
869 double distance_to_target = std::sqrt(vpMath::sqr(odom.position_body.x_m - position_target.north_m) +
870 vpMath::sqr(odom.position_body.y_m - position_target.east_m) +
871 vpMath::sqr(odom.position_body.z_m - position_target.down_m));
872 if (distance_to_target < m_position_incertitude &&
873 std::fabs(odom_yaw - position_target.yaw_deg) < m_yaw_incertitude) {
874 std::cout << "Position reached\n.";
875 m_telemetry.get()->subscribe_odometry(nullptr);
876 position_reached_promise.set_value();
877 }
878 });
879#endif
880 if (position_reached_future.wait_for(seconds(timeout_sec)) == std::future_status::timeout) {
881 std::cerr << "Positioning failed: position not reached.\n";
882 return false;
883 }
884 }
885
886 std::cout << "---- DEBUG timeout: " << timeout_sec << std::endl;
887 return true;
888 }
889
890 bool setPositionRelative(float ned_delta_north, float ned_delta_east, float ned_delta_down, float ned_delta_yaw,
891 bool blocking, int timeout_sec)
892 {
893 mavsdk::Telemetry::Odometry odom;
894 mavsdk::Telemetry::EulerAngle angles;
895 mavsdk::Offboard::PositionNedYaw position_target {};
896
897 position_target.north_m = ned_delta_north;
898 position_target.east_m = ned_delta_east;
899 position_target.down_m = ned_delta_down;
900 position_target.yaw_deg = vpMath::deg(ned_delta_yaw);
901
902 // Set a relative position
903 odom = m_telemetry.get()->odometry();
904 angles = m_telemetry.get()->attitude_euler();
905
906 position_target.north_m += odom.position_body.x_m;
907 position_target.east_m += odom.position_body.y_m;
908 position_target.down_m += odom.position_body.z_m;
909 position_target.yaw_deg += angles.yaw_deg;
910
911 return setPosition(position_target.north_m, position_target.east_m, position_target.down_m,
912 vpMath::rad(position_target.yaw_deg), blocking, timeout_sec);
913 }
914
915 bool setPosition(const vpHomogeneousMatrix &M, bool absolute, int timeout_sec)
916 {
917 auto XYZvec = vpRxyzVector(M.getRotationMatrix());
918 if (XYZvec[0] != 0.0) {
919 std::cerr << "ERROR : Can't move, rotation around X axis should be 0." << std::endl;
920 return false;
921 }
922 if (XYZvec[1] != 0.0) {
923 std::cerr << "ERROR : Can't move, rotation around Y axis should be 0." << std::endl;
924 return false;
925 }
926 return setPosition(M.getTranslationVector()[0], M.getTranslationVector()[1], M.getTranslationVector()[2], XYZvec[2],
927 absolute, timeout_sec);
928 }
929
930 bool setPositionRelative(const vpHomogeneousMatrix &M, bool blocking, int timeout_sec)
931 {
932 auto XYZvec = vpRxyzVector(M.getRotationMatrix());
933 if (XYZvec[0] != 0.0) {
934 std::cerr << "ERROR : Can't move, rotation around X axis should be 0." << std::endl;
935 return false;
936 }
937 if (XYZvec[1] != 0.0) {
938 std::cerr << "ERROR : Can't move, rotation around Y axis should be 0." << std::endl;
939 return false;
940 }
941 return setPositionRelative(M.getTranslationVector()[0], M.getTranslationVector()[1], M.getTranslationVector()[2],
942 XYZvec[2], blocking, timeout_sec);
943 }
944
945 bool setVelocity(const vpColVector &frd_vel_cmd)
946 {
947 if (frd_vel_cmd.size() != 4) {
948 throw(vpException(vpException::dimensionError,
949 "ERROR : Can't set velocity, dimension of the velocity vector %d should be equal to 4.",
950 frd_vel_cmd.size()));
951 }
952
953 if (m_telemetry.get()->flight_mode() != mavsdk::Telemetry::FlightMode::Offboard) {
954 if (m_verbose) {
955 std::cout << "Cannot set vehicle velocity: offboard mode not started" << std::endl;
956 }
957 return false;
958 }
959 mavsdk::Offboard::VelocityBodyYawspeed velocity_comm {};
960 velocity_comm.forward_m_s = frd_vel_cmd[0];
961 velocity_comm.right_m_s = frd_vel_cmd[1];
962 velocity_comm.down_m_s = frd_vel_cmd[2];
963 velocity_comm.yawspeed_deg_s = vpMath::deg(frd_vel_cmd[3]);
964 m_offboard.get()->set_velocity_body(velocity_comm);
965
966 return true;
967 }
968
969 bool kill()
970 {
971 const mavsdk::Action::Result kill_result = m_action.get()->kill();
972 if (kill_result != mavsdk::Action::Result::Success) {
973 std::cerr << "Kill failed: " << kill_result << std::endl;
974 return false;
975 }
976 return true;
977 }
978
979 bool holdPosition()
980 {
981 if (m_telemetry.get()->in_air()) {
982 if (m_telemetry.get()->gps_info().fix_type != mavsdk::Telemetry::FixType::NoGps) {
983 // Action::hold() doesn't work with PX4 when in offboard mode
984 const mavsdk::Action::Result hold_result = m_action.get()->hold();
985 if (hold_result != mavsdk::Action::Result::Success) {
986 std::cerr << "Hold failed: " << hold_result << std::endl;
987 return false;
988 }
989 }
990 else {
991 if (m_telemetry.get()->flight_mode() != mavsdk::Telemetry::FlightMode::Offboard) {
992 if (m_verbose) {
993 std::cout << "Cannot set vehicle velocity: offboard mode not started" << std::endl;
994 }
995 return false;
996 }
997
998 setPositionRelative(0., 0., 0., 0., false, 10.); // timeout not used
999 }
1000 }
1001 return true;
1002 }
1003
1004 bool stopMoving()
1005 {
1006 if (m_telemetry.get()->flight_mode() != mavsdk::Telemetry::FlightMode::Offboard) {
1007 if (m_verbose) {
1008 std::cout << "Cannot stop moving: offboard mode not started" << std::endl;
1009 }
1010 return false;
1011 }
1012
1013 const mavsdk::Offboard::VelocityBodyYawspeed stay {};
1014 m_offboard.get()->set_velocity_body(stay);
1015
1016 return true;
1017 }
1018
1019 bool releaseControl()
1020 {
1021 auto offboard_result = m_offboard.get()->stop();
1022 if (offboard_result != mavsdk::Offboard::Result::Success) {
1023 std::cerr << "Offboard stop failed: " << offboard_result << '\n';
1024 return false;
1025 }
1026 std::cout << "Offboard stopped\n";
1027 return true;
1028 }
1029
1030 void setAutoLand(bool auto_land) { m_auto_land = auto_land; }
1031
1032 bool setYawSpeed(double body_frd_wz)
1033 {
1034 if (m_telemetry.get()->flight_mode() != mavsdk::Telemetry::FlightMode::Offboard) {
1035 if (m_verbose) {
1036 std::cout << "Cannot set vehicle velocity: offboard mode not started" << std::endl;
1037 }
1038 return false;
1039 }
1040 mavsdk::Offboard::VelocityBodyYawspeed velocity_comm {};
1041 velocity_comm.forward_m_s = 0.0;
1042 velocity_comm.right_m_s = 0.0;
1043 velocity_comm.down_m_s = 0.0;
1044 velocity_comm.yawspeed_deg_s = vpMath::deg(body_frd_wz);
1045 m_offboard.get()->set_velocity_body(velocity_comm);
1046
1047 return true;
1048 }
1049
1050 bool setForwardSpeed(double body_frd_vx)
1051 {
1052 if (m_telemetry.get()->flight_mode() != mavsdk::Telemetry::FlightMode::Offboard) {
1053 if (m_verbose) {
1054 std::cout << "Cannot set vehicle velocity: offboard mode not started" << std::endl;
1055 }
1056 return false;
1057 }
1058
1059 mavsdk::Offboard::VelocityBodyYawspeed velocity_comm {};
1060 velocity_comm.forward_m_s = body_frd_vx;
1061 velocity_comm.right_m_s = 0.0;
1062 velocity_comm.down_m_s = 0.0;
1063 velocity_comm.yawspeed_deg_s = 0.0;
1064 m_offboard.get()->set_velocity_body(velocity_comm);
1065
1066 return true;
1067 }
1068
1069 bool setLateralSpeed(double body_frd_vy)
1070 {
1071 if (m_telemetry.get()->flight_mode() != mavsdk::Telemetry::FlightMode::Offboard) {
1072 if (m_verbose) {
1073 std::cout << "Cannot set vehicle velocity: offboard mode not started" << std::endl;
1074 }
1075 return false;
1076 }
1077 mavsdk::Offboard::VelocityBodyYawspeed velocity_comm {};
1078 velocity_comm.forward_m_s = 0.0;
1079 velocity_comm.right_m_s = body_frd_vy;
1080 velocity_comm.down_m_s = 0.0;
1081 velocity_comm.yawspeed_deg_s = 0.0;
1082 m_offboard.get()->set_velocity_body(velocity_comm);
1083
1084 return true;
1085 }
1086
1087 bool setVerticalSpeed(double body_frd_vz)
1088 {
1089 if (m_telemetry.get()->flight_mode() != mavsdk::Telemetry::FlightMode::Offboard) {
1090 if (m_verbose) {
1091 std::cout << "Cannot set vehicle velocity: offboard mode not started" << std::endl;
1092 }
1093 return false;
1094 }
1095 mavsdk::Offboard::VelocityBodyYawspeed velocity_comm {};
1096 velocity_comm.forward_m_s = 0.0;
1097 velocity_comm.right_m_s = 0.0;
1098 velocity_comm.down_m_s = body_frd_vz;
1099 velocity_comm.yawspeed_deg_s = 0.0;
1100 m_offboard.get()->set_velocity_body(velocity_comm);
1101
1102 return true;
1103 }
1104
1105 bool getFlyingCapability() { return m_has_flying_capability; }
1106
1107 void setVerbose(bool verbose) { m_verbose = verbose; }
1108
1109private:
1110 //*** Attributes ***//
1111 std::string m_address {};
1112#if (VISP_HAVE_MAVSDK_VERSION >= 0x020000)
1113 mavsdk::Mavsdk m_mavsdk { mavsdk::Mavsdk::Configuration{mavsdk::ComponentType::GroundStation} };
1114#else
1115 mavsdk::Mavsdk m_mavsdk { };
1116#endif
1117 std::shared_ptr<mavsdk::System> m_system;
1118 std::shared_ptr<mavsdk::Action> m_action;
1119 std::shared_ptr<mavsdk::Telemetry> m_telemetry;
1120 std::shared_ptr<mavsdk::Offboard> m_offboard;
1121
1122 double m_takeoffAlt { 1.0 };
1123
1124 MAV_TYPE m_mav_type {}; // Vehicle type
1125 bool m_has_flying_capability { false };
1126
1127 float m_position_incertitude { 0.05 };
1128 float m_yaw_incertitude { 0.09 }; // 5 deg
1129 bool m_verbose { false };
1130 bool m_auto_land { true };
1131 };
1132#endif // #ifndef DOXYGEN_SHOULD_SKIP_THIS
1133
1170vpRobotMavsdk::vpRobotMavsdk(const std::string &connection_info) : m_impl(new vpRobotMavsdkImpl(connection_info))
1171{
1172 m_impl->setPositioningIncertitude(0.05, vpMath::rad(5));
1173}
1174
1189vpRobotMavsdk::vpRobotMavsdk() : m_impl(new vpRobotMavsdkImpl())
1190{
1191 m_impl->setPositioningIncertitude(0.05, vpMath::rad(5));
1192}
1193
1202
1215void vpRobotMavsdk::connect(const std::string &connection_info) { m_impl->connect(connection_info); }
1216
1220bool vpRobotMavsdk::isRunning() const { return m_impl->isRunning(); }
1221
1242bool vpRobotMavsdk::sendMocapData(const vpHomogeneousMatrix &enu_M_flu, int display_fps)
1243{
1244 return m_impl->sendMocapData(enu_M_flu, display_fps);
1245}
1246
1253std::string vpRobotMavsdk::getAddress() const { return m_impl->getAddress(); }
1254
1260float vpRobotMavsdk::getBatteryLevel() const { return m_impl->getBatteryLevel(); }
1261
1266void vpRobotMavsdk::getPosition(vpHomogeneousMatrix &ned_M_frd) const { m_impl->getPosition(ned_M_frd); }
1267
1275void vpRobotMavsdk::getPosition(float &ned_north, float &ned_east, float &ned_down, float &ned_yaw) const
1276{
1277 m_impl->getPosition(ned_north, ned_east, ned_down, ned_yaw);
1278}
1279
1286std::tuple<float, float> vpRobotMavsdk::getHome() const { return m_impl->getHome(); }
1287
1294
1302void vpRobotMavsdk::setTakeOffAlt(double altitude) { m_impl->setTakeOffAlt(altitude); }
1303
1308bool vpRobotMavsdk::arm() { return m_impl->arm(); }
1309
1314bool vpRobotMavsdk::disarm() { return m_impl->disarm(); }
1315
1330bool vpRobotMavsdk::takeOff(bool interactive, int timeout_sec, bool use_gps)
1331{
1332 return m_impl->takeOff(interactive, timeout_sec, use_gps);
1333}
1334
1349bool vpRobotMavsdk::takeOff(bool interactive, double takeoff_altitude, int timeout_sec, bool use_gps)
1350{
1351 m_impl->setTakeOffAlt(takeoff_altitude);
1352 return m_impl->takeOff(interactive, timeout_sec, use_gps);
1353}
1354
1362bool vpRobotMavsdk::holdPosition() { return m_impl->holdPosition(); }
1363
1369bool vpRobotMavsdk::stopMoving() { return m_impl->stopMoving(); }
1370
1378bool vpRobotMavsdk::land() { return m_impl->land(); }
1379
1394bool vpRobotMavsdk::setPosition(float ned_north, float ned_east, float ned_down, float ned_yaw, bool blocking,
1395 int timeout_sec)
1396{
1397 return m_impl->setPosition(ned_north, ned_east, ned_down, ned_yaw, blocking, timeout_sec);
1398}
1399
1416bool vpRobotMavsdk::setPosition(const vpHomogeneousMatrix &ned_M_frd, bool blocking, int timeout_sec)
1417{
1418 return m_impl->setPosition(ned_M_frd, blocking, timeout_sec);
1419}
1420
1435bool vpRobotMavsdk::setPositionRelative(float ned_delta_north, float ned_delta_east, float ned_delta_down,
1436 float ned_delta_yaw, bool blocking, int timeout_sec)
1437{
1438 return m_impl->setPositionRelative(ned_delta_north, ned_delta_east, ned_delta_down, ned_delta_yaw, blocking,
1439 timeout_sec);
1440}
1441
1457bool vpRobotMavsdk::setPositionRelative(const vpHomogeneousMatrix &delta_frd_M_frd, bool blocking, int timeout_sec)
1458{
1459 return m_impl->setPositionRelative(delta_frd_M_frd, blocking, timeout_sec);
1460}
1461
1471bool vpRobotMavsdk::setVelocity(const vpColVector &frd_vel_cmd) { return m_impl->setVelocity(frd_vel_cmd); }
1472
1478bool vpRobotMavsdk::kill() { return m_impl->kill(); }
1479
1491bool vpRobotMavsdk::setYawSpeed(double body_frd_wz) { return m_impl->setYawSpeed(body_frd_wz); }
1492
1504bool vpRobotMavsdk::setForwardSpeed(double body_frd_vx) { return m_impl->setForwardSpeed(body_frd_vx); }
1505
1517bool vpRobotMavsdk::setLateralSpeed(double body_frd_vy) { return m_impl->setLateralSpeed(body_frd_vy); }
1518
1527bool vpRobotMavsdk::setGPSGlobalOrigin(double latitude, double longitude, double altitude)
1528{
1529 return m_impl->setGPSGlobalOrigin(latitude, longitude, altitude);
1530}
1531
1543bool vpRobotMavsdk::takeControl() { return m_impl->takeControl(); }
1544
1554bool vpRobotMavsdk::releaseControl() { return m_impl->releaseControl(); }
1555
1563void vpRobotMavsdk::setAutoLand(bool auto_land) { m_impl->setAutoLand(auto_land); }
1564
1572void vpRobotMavsdk::setPositioningIncertitude(float position_incertitude, float yaw_incertitude)
1573{
1574 m_impl->setPositioningIncertitude(position_incertitude, yaw_incertitude);
1575}
1576
1588bool vpRobotMavsdk::setVerticalSpeed(double body_frd_vz) { return m_impl->setVerticalSpeed(body_frd_vz); }
1589
1595void vpRobotMavsdk::setVerbose(bool verbose) { m_impl->setVerbose(verbose); }
1596
1602bool vpRobotMavsdk::hasFlyingCapability() { return m_impl->getFlyingCapability(); }
1603#ifdef ENABLE_VISP_NAMESPACE
1604 }
1605#endif
1606#elif !defined(VISP_BUILD_SHARED_LIBS)
1607// Work around to avoid warning: libvisp_robot.a(vpRobotMavsdk.cpp.o) has no symbols
1608void dummy_vpRobotMavsdk() { }
1609#endif
unsigned int size() const
Return the number of elements of the 2D array.
Definition vpArray2D.h:435
Implementation of column vector and the associated operations.
@ dimensionError
Bad dimension.
Definition vpException.h:71
@ fatalError
Fatal error.
Definition vpException.h:72
Implementation of an homogeneous matrix and operations on such kind of matrices.
vpRotationMatrix getRotationMatrix() const
vpHomogeneousMatrix & buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
vpTranslationVector getTranslationVector() const
static double rad(double deg)
Definition vpMath.h:129
static double sqr(double x)
Definition vpMath.h:203
static vpHomogeneousMatrix enu2ned(const vpHomogeneousMatrix &enu_M)
Definition vpMath.cpp:797
static double deg(double rad)
Definition vpMath.h:119
float getBatteryLevel() const
std::string getAddress() const
void setPositioningIncertitude(float position_incertitude, float yaw_incertitude)
std::tuple< float, float > getHome() const
bool sendMocapData(const vpHomogeneousMatrix &enu_M_flu, int display_fps=1)
bool takeOff(bool interactive=true, int timeout_sec=10, bool use_gps=false)
void getPosition(float &ned_north, float &ned_east, float &ned_down, float &ned_yaw) const
bool setLateralSpeed(double body_frd_vy)
bool setPositionRelative(float ned_delta_north, float ned_delta_east, float ned_delta_down, float ned_delta_yaw, bool blocking=true, int timeout_sec=10)
bool setVerticalSpeed(double body_frd_vz)
virtual ~vpRobotMavsdk()
void setAutoLand(bool auto_land)
bool setForwardSpeed(double body_frd_vx)
void setTakeOffAlt(double altitude)
void setVerbose(bool verbose)
bool setVelocity(const vpColVector &frd_vel_cmd)
void connect(const std::string &connection_info)
bool setGPSGlobalOrigin(double latitude, double longitude, double altitude)
bool setPosition(float ned_north, float ned_east, float ned_down, float ned_yaw, bool blocking=true, int timeout_sec=10)
bool setYawSpeed(double body_frd_wz)
bool isRunning() const
VISP_EXPORT double measureTimeMs()
VISP_EXPORT int wait(double t0, double t)