Visual Servoing Platform version 3.7.0
Loading...
Searching...
No Matches
sendMocapToPixhawk.cpp
1/*
2 * ViSP, open source Visual Servoing Platform software.
3 * Copyright (C) 2005 - 2025 by Inria. All rights reserved.
4 *
5 * This software is free software; you can redistribute it and/or modify
6 * it under the terms of the GNU General Public License as published by
7 * the Free Software Foundation; either version 2 of the License, or
8 * (at your option) any later version.
9 * See the file LICENSE.txt at the root directory of this source
10 * distribution for additional information about the GNU GPL.
11 *
12 * For using ViSP with software that can not be combined with the GNU
13 * GPL, please contact Inria about acquiring a ViSP Professional
14 * Edition License.
15 *
16 * See https://visp.inria.fr for more information.
17 *
18 * This software was developed at:
19 * Inria Rennes - Bretagne Atlantique
20 * Campus Universitaire de Beaulieu
21 * 35042 Rennes Cedex
22 * France
23 *
24 * If you have questions regarding the use of this file, please contact
25 * Inria at visp@inria.fr
26 *
27 * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
28 * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
29 *
30 * Description:
31 * Example that shows how to send a pose from a motion capture system through masvsdk.
32 */
33
40
41#include <iostream>
42
43#include <visp3/core/vpConfig.h>
44
45// Check if std:c++17 or higher
46#if defined(VISP_HAVE_MAVSDK) && ((__cplusplus >= 201703L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201703L))) && \
47 (defined(VISP_HAVE_QUALISYS) || defined(VISP_HAVE_VICON)) && defined(VISP_HAVE_THREADS)
48
49#include <chrono>
50#include <thread>
51
52#include <visp3/robot/vpRobotMavsdk.h>
53#include <visp3/sensor/vpMocapQualisys.h>
54#include <visp3/sensor/vpMocapVicon.h>
55
56using std::chrono::seconds;
57using std::this_thread::sleep_for;
58
59#ifdef ENABLE_VISP_NAMESPACE
60using namespace VISP_NAMESPACE_NAME;
61#endif
62
63// ------------------------------------------------------------------------------
64// Modifications Qualisys
65// ------------------------------------------------------------------------------
66
67bool g_quit = false;
68
73void quitHandler(int sig)
74{
75 (void)sig;
76 std::cout << std::endl << "TERMINATING AT USER REQUEST" << std::endl << std::endl;
77
78 g_quit = true;
79}
80
85bool mocap_sdk_loop(std::mutex &lock, bool qualisys, bool opt_verbose, bool opt_all_bodies,
86 std::string &opt_serverAddress, std::string &opt_onlyBody,
87 std::map<std::string, vpHomogeneousMatrix> &current_body_poses_enu_M_flu, bool &mocap_failure,
88 bool &mavlink_failure)
89{
90 std::shared_ptr<vpMocap> mocap;
91 if (qualisys) {
92#ifdef VISP_HAVE_QUALISYS
93 mocap = std::make_shared<vpMocapQualisys>();
94#else
95 std::cout << "ERROR : Qualisys not found.";
96 return false;
97#endif
98 }
99 else {
100#ifdef VISP_HAVE_VICON
101 mocap = std::make_shared<vpMocapVicon>();
102#else
103
104 std::cout << "ERROR : Vicon not found.";
105 return false;
106#endif
107 }
108 mocap->setVerbose(opt_verbose);
109 mocap->setServerAddress(opt_serverAddress);
110 if (mocap->connect() == false) {
111 lock.lock();
112 mocap_failure = true;
113 lock.unlock();
114 std::cout << "Mocap connexion failure. Check mocap server IP address" << std::endl;
115
116 return false;
117 }
118
119 bool internal_mavlink_failure = false;
120 while (!g_quit && !internal_mavlink_failure) {
121 std::map<std::string, vpHomogeneousMatrix> body_poses_enu_M_flu;
122
123 if (opt_onlyBody == "") {
124 if (!mocap->getBodiesPose(body_poses_enu_M_flu, opt_all_bodies)) {
125 g_quit = true;
126 }
127 }
128 else {
129 vpHomogeneousMatrix enu_M_flu;
130 if (!mocap->getSpecificBodyPose(opt_onlyBody, enu_M_flu)) {
131 g_quit = true;
132 }
133 else {
134 body_poses_enu_M_flu[opt_onlyBody] = enu_M_flu;
135 }
136 }
137
138 lock.lock();
139 internal_mavlink_failure = mavlink_failure;
140 current_body_poses_enu_M_flu =
141 body_poses_enu_M_flu; // Now we send directly the poses in the ENU global reference frame.
142 lock.unlock();
143 }
144 return true;
145}
146
147// ------------------------------------------------------------------------------
148// TOP
149// ------------------------------------------------------------------------------
150int top(const std::string &connection_info, std::map<std::string, vpHomogeneousMatrix> &current_body_poses_enu_M_flu,
151 std::mutex &lock, bool &mocap_failure)
152{
153 std::map<std::string, vpHomogeneousMatrix> body_poses_enu_M_flu;
154 bool internal_mocap_failure = false;
155 const double fps = 100;
156
157 vpRobotMavsdk drone { connection_info };
158
159 while (!g_quit && !internal_mocap_failure) {
160 double t = vpTime::measureTimeMs();
161 lock.lock();
162 body_poses_enu_M_flu = current_body_poses_enu_M_flu;
163 internal_mocap_failure = mocap_failure;
164 lock.unlock();
165
166 for (std::map<std::string, vpHomogeneousMatrix>::iterator it = body_poses_enu_M_flu.begin();
167 it != body_poses_enu_M_flu.end(); ++it) {
168 if (!drone.sendMocapData(it->second)) {
169 return 1;
170 }
171 }
172 vpTime::wait(t, 1000./fps); // Stream MoCap at given framerate
173 }
174
175 return 0;
176}
177
178// ------------------------------------------------------------------------------
179// Usage function
180// ------------------------------------------------------------------------------
181
182void usage(char *argv[], int error)
183{
184 std::cout << "SYNOPSIS" << std::endl
185 << " " << argv[0] << " [--only-body <name>] [-ob]"
186 << " [--mocap-system <qualisys>/<vicon>] [-ms <q>/<v>]"
187 << " [--device <device port>] [-d]"
188 << " [--server-address <server address>] [-sa]"
189 << " [--verbose] [-v]"
190 << " [--help] [-h]" << std::endl
191 << std::endl;
192 std::cout << "DESCRIPTION" << std::endl
193 << "MANDATORY PARAMETERS :" << std::endl
194 << " --only-body <name>" << std::endl
195 << " Name of the specific body you want to be displayed." << std::endl
196 << std::endl
197 << "OPTIONAL PARAMETERS (DEFAULT VALUES)" << std::endl
198 << " --mocap-system, -ms" << std::endl
199 << " Specify the name of the mocap system : 'qualisys' / 'q' or 'vicon'/ 'v'." << std::endl
200 << " Default: Qualisys mode." << std::endl
201 << std::endl
202 << " --device <device port>, -d" << std::endl
203 << " String giving us all the informations necessary for connection." << std::endl
204 << " Default: serial:///dev/ttyUSB0 ." << std::endl
205 << " UDP example: udp://192.168.30.111:14540 (udp://IP:Port) ." << std::endl
206 << std::endl
207 << " --server-address <address>, -sa" << std::endl
208 << " Mocap server address." << std::endl
209 << " Default for Qualisys: 192.168.34.42 ." << std::endl
210 << " Default for Vicon: 192.168.34.1 ." << std::endl
211 << std::endl
212 << " --verbose, -v" << std::endl
213 << " Enable verbose mode." << std::endl
214 << std::endl
215 << " --help, -h" << std::endl
216 << " Print this helper message." << std::endl
217 << std::endl;
218
219 if (error) {
220 std::cout << "Error" << std::endl
221 << " "
222 << "Unsupported parameter " << argv[error] << std::endl;
223 }
224}
225
226// ------------------------------------------------------------------------------
227// Parse Command Line
228// ------------------------------------------------------------------------------
229// throws EXIT_FAILURE if could not open the port
230void parse_commandline(int argc, char **argv, bool &qualisys, std::string &connection_info, std::string &server_address,
231 std::string &only_body, bool &all_bodies, bool &verbose)
232{
233
234 // Read input arguments
235 for (int i = 1; i < argc; i++) {
236 if (std::string(argv[i]) == "--only-body" || std::string(argv[i]) == "-ob") {
237 only_body = std::string(argv[i + 1]);
238 i++;
239 }
240 else if (std::string(argv[i]) == "--mocap-system" || std::string(argv[i]) == "-ms") {
241 std::string mode = std::string(argv[i + 1]);
242 if (mode == "qualisys" || mode == "q") {
243 qualisys = true;
244 }
245 else if (mode == "vicon" || mode == "v") {
246 qualisys = false;
247 }
248 else {
249 std::cout << "ERROR : System not recognized, exiting." << std::endl;
250 throw EXIT_FAILURE;
251 }
252 i++;
253 }
254 else if (std::string(argv[i]) == "--device" || std::string(argv[i]) == "-d") {
255 connection_info = std::string(argv[i + 1]);
256 i++;
257 }
258 else if (std::string(argv[i]) == "--server-address" || std::string(argv[i]) == "-sa") {
259 server_address = std::string(argv[i + 1]);
260 i++;
261 }
262 else if (std::string(argv[i]) == "--all-bodies") {
263 all_bodies = true;
264 }
265 else if (std::string(argv[i]) == "--verbose" || std::string(argv[i]) == "-v") {
266 verbose = true;
267 }
268 else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") {
269 usage(argv, 0);
270 throw EXIT_SUCCESS;
271 }
272 else {
273 usage(argv, i);
274 throw EXIT_FAILURE;
275 }
276 }
277
278 return;
279}
280
281// ------------------------------------------------------------------------------
282// Main
283// ------------------------------------------------------------------------------
284int main(int argc, char **argv)
285{
286 std::map<std::string, vpHomogeneousMatrix> current_body_poses_enu_M_flu;
287
288 // Default input arguments
289#ifdef __APPLE__
290 std::string opt_connectionInfo = "/dev/tty.usbmodem1";
291#else
292 std::string opt_connectionInfo = "udp://127.0.0.1:14550";
293#endif
294
295 bool opt_qualisys = false;
296 std::string opt_serverAddress;
297 std::string opt_onlyBody = "";
298 bool opt_all_bodies = false;
299 bool opt_verbose = false;
300
301 // User Input
302 parse_commandline(argc, argv, opt_qualisys, opt_connectionInfo, opt_serverAddress, opt_onlyBody, opt_all_bodies,
303 opt_verbose);
304
305 if (opt_qualisys && opt_serverAddress == "") {
306 opt_serverAddress = "192.168.30.42";
307 }
308 else if (!opt_qualisys && opt_serverAddress == "") {
309 opt_serverAddress = "192.168.30.1";
310 }
311
312 if (opt_onlyBody == "") {
313 std::cout << "The parameter --only-body MUST be given in the command line." << std::endl;
314 return EXIT_FAILURE;
315 }
316
317 // Modifications qualisys ----------------------------------------------------
318 std::mutex lock;
319 bool mocap_failure = false;
320 bool mavlink_failure = false;
321 std::thread mocap_thread([&lock, &opt_qualisys, &opt_verbose, &opt_all_bodies, &opt_serverAddress, &opt_onlyBody,
322 &current_body_poses_enu_M_flu, &mocap_failure, &mavlink_failure]() {
323 mocap_sdk_loop(lock, opt_qualisys, opt_verbose, opt_all_bodies, opt_serverAddress, opt_onlyBody,
324 current_body_poses_enu_M_flu, mocap_failure, mavlink_failure);
325 });
326 if (mocap_failure) {
327 std::cout << "Mocap connexion failure. Check mocap server IP address" << std::endl;
328 return EXIT_FAILURE;
329 }
330
331 // This program uses throw, wrap one big try/catch here
332 std::thread mavlink_thread(
333 [&lock, &current_body_poses_enu_M_flu, &opt_connectionInfo, &mocap_failure, &mavlink_failure]() {
334 try {
335 int result = top(opt_connectionInfo, current_body_poses_enu_M_flu, lock, mocap_failure);
336 return result;
337 }
338 catch (int error) {
339 fprintf(stderr, "mavlink_control threw exception %i \n", error);
340 lock.lock();
341 mavlink_failure = true;
342 lock.unlock();
343 return error;
344 }
345 });
346
347 mocap_thread.join();
348 mavlink_thread.join();
349 if (mocap_failure) {
350 return EXIT_FAILURE;
351 }
352 else {
353 return EXIT_SUCCESS;
354 }
355}
356
357#else
358
359int main()
360{
361#ifndef VISP_HAVE_MAVSDK
362 std::cout << "\nThis example requires mavsdk library. You should install it, configure and rebuild ViSP.\n"
363 << std::endl;
364#endif
365#if !(defined(VISP_HAVE_QUALISYS) || defined(VISP_HAVE_VICON))
366 std::cout << "\nThis example requires data from a Qualisys or Vicon mocap system. You should install it, configure "
367 "and rebuild ViSP.\n"
368 << std::endl;
369#endif
370#if !((__cplusplus >= 201703L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201703L)))
371 std::cout
372 << "\nThis example requires at least cxx17. You should enable cxx17 during ViSP configuration with cmake and "
373 "rebuild ViSP.\n"
374 << std::endl;
375#endif
376 return EXIT_SUCCESS;
377}
378
379#endif // #if defined(VISP_HAVE_MAVSDK)
Implementation of an homogeneous matrix and operations on such kind of matrices.
bool sendMocapData(const vpHomogeneousMatrix &enu_M_flu, int display_fps=1)
VISP_EXPORT double measureTimeMs()
VISP_EXPORT int wait(double t0, double t)