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