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