34 #include <visp3/core/vpConfig.h>
37 #if defined(VISP_HAVE_MAVSDK) && ((__cplusplus >= 201703L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201703L))) \
38 && defined(VISP_HAVE_THREADS)
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>
52 #include <visp3/core/vpExponentialMap.h>
53 #include <visp3/robot/vpRobotMavsdk.h>
55 using std::chrono::milliseconds;
56 using std::chrono::seconds;
57 using std::this_thread::sleep_for;
58 using namespace std::chrono_literals;
61 #ifndef DOXYGEN_SHOULD_SKIP_THIS
62 class vpRobotMavsdk::vpRobotMavsdkImpl
65 vpRobotMavsdkImpl() : m_takeoffAlt(1.0) { }
66 vpRobotMavsdkImpl(
const std::string &connection_info) : m_takeoffAlt(1.0) { connect(connection_info); }
68 virtual ~vpRobotMavsdkImpl()
70 if (m_has_flying_capability && m_auto_land) {
81 std::shared_ptr<mavsdk::System> getSystem(mavsdk::Mavsdk &mavsdk)
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();
89 #if (VISP_HAVE_MAVSDK_VERSION > 0x010412)
90 mavsdk::Mavsdk::NewSystemHandle handle = mavsdk.subscribe_on_new_system([&mavsdk, &prom, &handle]() {
92 mavsdk.subscribe_on_new_system([&mavsdk, &prom]() {
94 auto system = mavsdk.systems().back();
96 if (system->has_autopilot()) {
97 std::cout <<
"Discovered autopilot" << std::endl;
100 #if (VISP_HAVE_MAVSDK_VERSION > 0x010412)
101 mavsdk.unsubscribe_on_new_system(handle);
103 mavsdk.subscribe_on_new_system(nullptr);
105 prom.set_value(system);
111 if (fut.wait_for(seconds(3)) == std::future_status::timeout) {
112 std::cerr <<
"No autopilot found." << std::endl;
120 MAV_TYPE getVehicleType()
122 auto passthrough = mavsdk::MavlinkPassthrough { m_system };
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) {
130 passthrough.subscribe_message_async(MAVLINK_MSG_ID_HEARTBEAT,
131 [&passthrough, &prom](
const mavlink_message_t &message) {
134 if (message.compid != MAV_COMP_ID_AUTOPILOT1) {
138 mavlink_heartbeat_t heartbeat;
139 mavlink_msg_heartbeat_decode(&message, &heartbeat);
142 #if (VISP_HAVE_MAVSDK_VERSION > 0x010412)
143 passthrough.unsubscribe_message(handle);
145 passthrough.subscribe_message_async(MAVLINK_MSG_ID_HEARTBEAT,
nullptr);
148 prom.set_value(
static_cast<MAV_TYPE
>(heartbeat.type));
153 if (fut.wait_for(seconds(3)) == std::future_status::timeout) {
154 std::cerr <<
"No heartbeat received to get vehicle type." << std::endl;
162 void calibrate_accelerometer(mavsdk::Calibration &calibration)
164 std::cout <<
"Calibrating accelerometer..." << std::endl;
166 std::promise<void> calibration_promise;
167 auto calibration_future = calibration_promise.get_future();
169 calibration.calibrate_accelerometer_async(create_calibration_callback(calibration_promise));
171 calibration_future.wait();
174 std::function<void(mavsdk::Calibration::Result, mavsdk::Calibration::ProgressData)>
175 create_calibration_callback(std::promise<void> &calibration_promise)
177 return [&calibration_promise](
const mavsdk::Calibration::Result result,
178 const mavsdk::Calibration::ProgressData progress_data) {
180 case mavsdk::Calibration::Result::Success:
181 std::cout <<
"--- Calibration succeeded!" << std::endl;
182 calibration_promise.set_value();
184 case mavsdk::Calibration::Result::Next:
185 if (progress_data.has_progress) {
186 std::cout <<
" Progress: " << progress_data.progress << std::endl;
188 if (progress_data.has_status_text) {
189 std::cout <<
" Instruction: " << progress_data.status_text << std::endl;
193 std::cout <<
"--- Calibration failed with message: " << result << std::endl;
194 calibration_promise.set_value();
200 void calibrate_gyro(mavsdk::Calibration &calibration)
202 std::cout <<
"Calibrating gyro..." << std::endl;
204 std::promise<void> calibration_promise;
205 auto calibration_future = calibration_promise.get_future();
207 calibration.calibrate_gyro_async(create_calibration_callback(calibration_promise));
209 calibration_future.wait();
213 void connect(
const std::string &connectionInfo)
215 m_address = connectionInfo;
216 mavsdk::ConnectionResult connection_result = m_mavsdk.add_any_connection(connectionInfo);
218 if (connection_result != mavsdk::ConnectionResult::Success) {
219 std::cerr <<
"Connection failed: " << connection_result << std::endl;
223 m_system = getSystem(m_mavsdk);
229 m_mav_type = getVehicleType();
231 m_has_flying_capability = hasFlyingCapability(m_mav_type);
233 std::cout << (m_has_flying_capability ?
"Connected to a flying vehicle" :
"Connected to a non flying vehicle")
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);
241 bool hasFlyingCapability(MAV_TYPE 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:
253 bool isRunning()
const
255 if (m_system ==
nullptr) {
263 std::string getAddress()
const
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) {
273 actual_address.append(1, c);
276 return actual_address;
279 std::cout <<
"ERROR : The address parameter must start with \"serial:\" or \"udp:\" or \"tcp:\"." << std::endl;
280 return std::string();
284 float getBatteryLevel()
const
286 mavsdk::Telemetry::Battery battery = m_telemetry.get()->battery();
287 return battery.voltage_v;
292 auto quat = m_telemetry.get()->attitude_quaternion();
293 auto posvel = m_telemetry.get()->position_velocity_ned();
295 vpTranslationVector t { posvel.position.north_m, posvel.position.east_m, posvel.position.down_m };
299 void getPosition(
float &ned_north,
float &ned_east,
float &ned_down,
float &ned_yaw)
const
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;
309 std::tuple<float, float> getHome()
const
311 auto position = m_telemetry.get()->home();
312 return { float(position.latitude_deg), float(position.longitude_deg) };
323 flu_M_frd[1][1] = -1;
324 flu_M_frd[2][2] = -1;
327 auto mocap = mavsdk::Mocap { m_system };
328 mavsdk::Mocap::VisionPositionEstimate pose_estimate;
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];
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];
341 pose_estimate.pose_covariance.covariance_matrix.push_back(NAN);
342 pose_estimate.time_usec = 0;
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';
350 if (display_fps > 0) {
351 double display_time_ms = 1000. / display_fps;
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;
366 void setTakeOffAlt(
double altitude)
369 m_takeoffAlt = altitude;
372 std::cerr <<
"ERROR : The take off altitude must be positive." << std::endl;
379 auto calibration = mavsdk::Calibration(m_system);
382 calibrate_accelerometer(calibration);
383 calibrate_gyro(calibration);
389 std::cout <<
"Arming...\n";
390 const mavsdk::Action::Result arm_result = m_action.get()->arm();
392 if (arm_result != mavsdk::Action::Result::Success) {
393 std::cerr <<
"Arming failed: " << arm_result << std::endl;
402 std::cout <<
"Disarming...\n";
403 const mavsdk::Action::Result arm_result = m_action.get()->disarm();
405 if (arm_result != mavsdk::Action::Result::Success) {
406 std::cerr <<
"Disarming failed: " << arm_result << std::endl;
412 bool setGPSGlobalOrigin(
double latitude,
double longitude,
double altitude)
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;
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,
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;
434 std::cout <<
"Starting offboard mode..." << std::endl;
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);
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;
447 else if (m_verbose) {
448 std::cout <<
"Already in offboard mode" << std::endl;
453 while (m_telemetry.get()->flight_mode() != mavsdk::Telemetry::FlightMode::Offboard) {
455 std::cout <<
"Time out received in takeControl()" << std::endl;
461 std::cout <<
"Offboard mode started" << std::endl;
466 void setPositioningIncertitude(
float position_incertitude,
float yaw_incertitude)
468 m_position_incertitude = position_incertitude;
469 m_yaw_incertitude = yaw_incertitude;
472 bool takeOff(
bool interactive,
int timeout_sec,
bool use_gps)
474 if (!m_has_flying_capability) {
475 std::cerr <<
"Warning: Cannot takeoff this non flying vehicle" << std::endl;
479 bool authorize_takeoff =
false;
482 authorize_takeoff =
true;
485 if (m_telemetry.get()->flight_mode() == mavsdk::Telemetry::FlightMode::Offboard) {
486 authorize_takeoff =
true;
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)"
495 if (answer ==
"Y" || answer ==
"y") {
496 authorize_takeoff =
true;
502 if (m_telemetry.get()->in_air()) {
503 std::cerr <<
"Cannot take off as the robot is already flying." << std::endl;
506 else if (authorize_takeoff) {
516 while (answer !=
"Y" && answer !=
"y" && answer !=
"N" && answer !=
"n") {
517 std::cout <<
"If vehicle armed ? (y/n)" << std::endl;
519 if (answer ==
"N" || answer ==
"n") {
528 if (m_telemetry.get()->gps_info().fix_type == mavsdk::Telemetry::FixType::NoGps || !use_gps) {
537 auto in_air_promise = std::promise<void> {};
538 auto in_air_future = in_air_promise.get_future();
540 mavsdk::Telemetry::Odometry odom = m_telemetry.get()->odometry();
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;
550 std::cout <<
"Takeoff using position NED." << std::endl;
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);
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();
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();
576 std::cout <<
"state: " << state << std::endl;
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);
584 m_telemetry.get()->subscribe_landed_state(
nullptr);
589 auto takeoff_finished_promise = std::promise<void> {};
590 auto takeoff_finished_future = takeoff_finished_promise.get_future();
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();
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();
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);
616 m_telemetry.get()->subscribe_odometry(
nullptr);
623 std::cout <<
"---- DEBUG: GPS detected: use action::takeoff()" << std::endl;
625 mavsdk::Telemetry::Odometry odom = m_telemetry.get()->odometry();
626 double Z_init = odom.position_body.z_m;
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';
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();
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();
653 std::cout <<
"state: " << state << std::endl;
656 if (in_air_future.wait_for(seconds(timeout_sec)) == std::future_status::timeout) {
658 std::cerr <<
"Takeoff timed out.\n";
659 #if (VISP_HAVE_MAVSDK_VERSION > 0x010412)
660 m_telemetry.get()->unsubscribe_landed_state(handle);
662 m_telemetry.get()->subscribe_landed_state(
nullptr);
666 auto takeoff_finished_promise = std::promise<void> {};
667 auto takeoff_finished_future = takeoff_finished_promise.get_future();
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();
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();
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);
693 m_telemetry.get()->subscribe_odometry(
nullptr);
704 bool land(
bool use_buildin =
false)
706 if (!m_has_flying_capability) {
707 std::cerr <<
"Warning: Cannot land this non flying vehicle" << std::endl;
720 mavsdk::Telemetry::Odometry odom = m_telemetry.get()->odometry();
725 double X_init = odom.position_body.x_m;
726 double Y_init = odom.position_body.y_m;
729 std::cout <<
"Landing using position NED." << std::endl;
731 mavsdk::Offboard::PositionNedYaw landing {};
732 landing.north_m = X_init;
733 landing.east_m = Y_init;
735 landing.yaw_deg = yaw_init;
736 m_offboard.get()->set_position_ned(landing);
738 bool success =
false;
741 auto landing_finished_promise = std::promise<void> {};
742 auto landing_finished_future = landing_finished_promise.get_future();
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.";
751 m_telemetry.get()->unsubscribe_odometry(handle_odom);
752 landing_finished_promise.set_value();
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.";
762 m_telemetry.get()->subscribe_odometry(nullptr);
763 landing_finished_promise.set_value();
767 if (landing_finished_future.wait_for(seconds(10)) == std::future_status::timeout) {
768 std::cerr <<
"failed: altitude not reached.\n";
773 std::cout <<
"Descending\n.";
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;
787 while (m_telemetry.get()->in_air()) {
788 std::cout <<
"Vehicle is landing..." << std::endl;
789 sleep_for(seconds(1));
793 std::cout <<
"Landed!" << std::endl;
796 sleep_for(seconds(5));
797 std::cout <<
"Finished..." << std::endl;
801 bool setPosition(
float ned_north,
float ned_east,
float ned_down,
float ned_yaw,
bool blocking,
int timeout_sec)
803 mavsdk::Offboard::PositionNedYaw position_target {};
805 position_target.north_m = ned_north;
806 position_target.east_m = ned_east;
807 position_target.down_m = ned_down;
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);
814 if (m_telemetry.get()->flight_mode() != mavsdk::Telemetry::FlightMode::Offboard) {
816 std::cout <<
"Cannot set vehicle position: offboard mode not started" << std::endl;
823 auto position_reached_promise = std::promise<void> {};
824 auto position_reached_future = position_reached_promise.get_future();
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) {
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();
844 m_telemetry.get()->subscribe_odometry(
845 [
this, &position_reached_promise, &position_target](mavsdk::Telemetry::Odometry odom) {
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();
861 if (position_reached_future.wait_for(seconds(timeout_sec)) == std::future_status::timeout) {
862 std::cerr <<
"Positioning failed: position not reached.\n";
867 std::cout <<
"---- DEBUG timeout: " << timeout_sec << std::endl;
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)
874 mavsdk::Telemetry::Odometry odom;
875 mavsdk::Telemetry::EulerAngle angles;
876 mavsdk::Offboard::PositionNedYaw position_target {};
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);
884 odom = m_telemetry.get()->odometry();
885 angles = m_telemetry.get()->attitude_euler();
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;
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);
899 if (XYZvec[0] != 0.0) {
900 std::cerr <<
"ERROR : Can't move, rotation around X axis should be 0." << std::endl;
903 if (XYZvec[1] != 0.0) {
904 std::cerr <<
"ERROR : Can't move, rotation around Y axis should be 0." << std::endl;
908 absolute, timeout_sec);
914 if (XYZvec[0] != 0.0) {
915 std::cerr <<
"ERROR : Can't move, rotation around X axis should be 0." << std::endl;
918 if (XYZvec[1] != 0.0) {
919 std::cerr <<
"ERROR : Can't move, rotation around Y axis should be 0." << std::endl;
923 XYZvec[2], blocking, timeout_sec);
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()));
934 if (m_telemetry.get()->flight_mode() != mavsdk::Telemetry::FlightMode::Offboard) {
936 std::cout <<
"Cannot set vehicle velocity: offboard mode not started" << std::endl;
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);
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;
962 if (m_telemetry.get()->in_air()) {
963 if (m_telemetry.get()->gps_info().fix_type != mavsdk::Telemetry::FixType::NoGps) {
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;
972 if (m_telemetry.get()->flight_mode() != mavsdk::Telemetry::FlightMode::Offboard) {
974 std::cout <<
"Cannot set vehicle velocity: offboard mode not started" << std::endl;
979 setPositionRelative(0., 0., 0., 0.,
false, 10.);
987 if (m_telemetry.get()->flight_mode() != mavsdk::Telemetry::FlightMode::Offboard) {
989 std::cout <<
"Cannot stop moving: offboard mode not started" << std::endl;
994 const mavsdk::Offboard::VelocityBodyYawspeed stay {};
995 m_offboard.get()->set_velocity_body(stay);
1000 bool releaseControl()
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';
1007 std::cout <<
"Offboard stopped\n";
1011 void setAutoLand(
bool auto_land) { m_auto_land = auto_land; }
1013 bool setYawSpeed(
double body_frd_wz)
1015 if (m_telemetry.get()->flight_mode() != mavsdk::Telemetry::FlightMode::Offboard) {
1017 std::cout <<
"Cannot set vehicle velocity: offboard mode not started" << std::endl;
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);
1031 bool setForwardSpeed(
double body_frd_vx)
1033 if (m_telemetry.get()->flight_mode() != mavsdk::Telemetry::FlightMode::Offboard) {
1035 std::cout <<
"Cannot set vehicle velocity: offboard mode not started" << std::endl;
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);
1050 bool setLateralSpeed(
double body_frd_vy)
1052 if (m_telemetry.get()->flight_mode() != mavsdk::Telemetry::FlightMode::Offboard) {
1054 std::cout <<
"Cannot set vehicle velocity: offboard mode not started" << std::endl;
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);
1068 bool setVerticalSpeed(
double body_frd_vz)
1070 if (m_telemetry.get()->flight_mode() != mavsdk::Telemetry::FlightMode::Offboard) {
1072 std::cout <<
"Cannot set vehicle velocity: offboard mode not started" << std::endl;
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);
1086 bool getFlyingCapability() {
return m_has_flying_capability; }
1088 void setVerbose(
bool verbose) { m_verbose = verbose; }
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;
1099 double m_takeoffAlt { 1.0 };
1101 MAV_TYPE m_mav_type {};
1102 bool m_has_flying_capability {
false };
1104 float m_position_incertitude { 0.05 };
1105 float m_yaw_incertitude { 0.09 };
1106 bool m_verbose {
false };
1107 bool m_auto_land {
true };
1147 vpRobotMavsdk::vpRobotMavsdk(
const std::string &connection_info) : m_impl(new vpRobotMavsdkImpl(connection_info))
1149 m_impl->setPositioningIncertitude(0.05,
vpMath::rad(5));
1166 vpRobotMavsdk::vpRobotMavsdk() : m_impl(new vpRobotMavsdkImpl())
1168 m_impl->setPositioningIncertitude(0.05,
vpMath::rad(5));
1178 vpRobotMavsdk::~vpRobotMavsdk() {
delete m_impl; }
1192 void vpRobotMavsdk::connect(
const std::string &connection_info) { m_impl->connect(connection_info); }
1197 bool vpRobotMavsdk::isRunning()
const {
return m_impl->isRunning(); }
1221 return m_impl->sendMocapData(enu_M_flu, display_fps);
1230 std::string vpRobotMavsdk::getAddress()
const {
return m_impl->getAddress(); }
1237 float vpRobotMavsdk::getBatteryLevel()
const {
return m_impl->getBatteryLevel(); }
1243 void vpRobotMavsdk::getPosition(
vpHomogeneousMatrix &ned_M_frd)
const { m_impl->getPosition(ned_M_frd); }
1252 void vpRobotMavsdk::getPosition(
float &ned_north,
float &ned_east,
float &ned_down,
float &ned_yaw)
const
1254 m_impl->getPosition(ned_north, ned_east, ned_down, ned_yaw);
1263 std::tuple<float, float> vpRobotMavsdk::getHome()
const {
return m_impl->getHome(); }
1270 void vpRobotMavsdk::doFlatTrim() { }
1279 void vpRobotMavsdk::setTakeOffAlt(
double altitude) { m_impl->setTakeOffAlt(altitude); }
1285 bool vpRobotMavsdk::arm() {
return m_impl->arm(); }
1291 bool vpRobotMavsdk::disarm() {
return m_impl->disarm(); }
1307 bool vpRobotMavsdk::takeOff(
bool interactive,
int timeout_sec,
bool use_gps)
1309 return m_impl->takeOff(interactive, timeout_sec, use_gps);
1326 bool vpRobotMavsdk::takeOff(
bool interactive,
double takeoff_altitude,
int timeout_sec,
bool use_gps)
1328 m_impl->setTakeOffAlt(takeoff_altitude);
1329 return m_impl->takeOff(interactive, timeout_sec, use_gps);
1339 bool vpRobotMavsdk::holdPosition() {
return m_impl->holdPosition(); };
1346 bool vpRobotMavsdk::stopMoving() {
return m_impl->stopMoving(); };
1355 bool vpRobotMavsdk::land() {
return m_impl->land(); }
1371 bool vpRobotMavsdk::setPosition(
float ned_north,
float ned_east,
float ned_down,
float ned_yaw,
bool blocking,
1374 return m_impl->setPosition(ned_north, ned_east, ned_down, ned_yaw, blocking, timeout_sec);
1393 bool vpRobotMavsdk::setPosition(
const vpHomogeneousMatrix &ned_M_frd,
bool blocking,
int timeout_sec)
1395 return m_impl->setPosition(ned_M_frd, blocking, timeout_sec);
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)
1415 return m_impl->setPositionRelative(ned_delta_north, ned_delta_east, ned_delta_down, ned_delta_yaw, blocking,
1434 bool vpRobotMavsdk::setPositionRelative(
const vpHomogeneousMatrix &delta_frd_M_frd,
bool blocking,
int timeout_sec)
1436 return m_impl->setPositionRelative(delta_frd_M_frd, blocking, timeout_sec);
1448 bool vpRobotMavsdk::setVelocity(
const vpColVector &frd_vel_cmd) {
return m_impl->setVelocity(frd_vel_cmd); }
1455 bool vpRobotMavsdk::kill() {
return m_impl->kill(); }
1468 bool vpRobotMavsdk::setYawSpeed(
double body_frd_wz) {
return m_impl->setYawSpeed(body_frd_wz); }
1481 bool vpRobotMavsdk::setForwardSpeed(
double body_frd_vx) {
return m_impl->setForwardSpeed(body_frd_vx); }
1494 bool vpRobotMavsdk::setLateralSpeed(
double body_frd_vy) {
return m_impl->setLateralSpeed(body_frd_vy); }
1504 bool vpRobotMavsdk::setGPSGlobalOrigin(
double latitude,
double longitude,
double altitude)
1506 return m_impl->setGPSGlobalOrigin(latitude, longitude, altitude);
1520 bool vpRobotMavsdk::takeControl() {
return m_impl->takeControl(); }
1531 bool vpRobotMavsdk::releaseControl() {
return m_impl->releaseControl(); }
1540 void vpRobotMavsdk::setAutoLand(
bool auto_land) { m_impl->setAutoLand(auto_land); }
1549 void vpRobotMavsdk::setPositioningIncertitude(
float position_incertitude,
float yaw_incertitude)
1551 m_impl->setPositioningIncertitude(position_incertitude, yaw_incertitude);
1565 bool vpRobotMavsdk::setVerticalSpeed(
double body_frd_vz) {
return m_impl->setVerticalSpeed(body_frd_vz); }
1572 void vpRobotMavsdk::setVerbose(
bool verbose) { m_impl->setVerbose(verbose); }
1579 bool vpRobotMavsdk::hasFlyingCapability() {
return m_impl->getFlyingCapability(); }
1580 #ifdef ENABLE_VISP_NAMESPACE
1583 #elif !defined(VISP_BUILD_SHARED_LIBS)
1585 void dummy_vpRobotMavsdk() { };
unsigned int size() const
Return the number of elements of the 2D array.
Implementation of column vector and the associated operations.
error that can be emitted by ViSP classes.
@ dimensionError
Bad dimension.
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)
static double sqr(double x)
static vpHomogeneousMatrix enu2ned(const vpHomogeneousMatrix &enu_M)
static double deg(double rad)
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.
Class that consider the case of a translation vector.
VISP_EXPORT int wait(double t0, double t)
VISP_EXPORT double measureTimeMs()