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