45 #include <visp3/core/vpConfig.h>
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)
54 #include <visp3/robot/vpRobotMavsdk.h>
55 #include <visp3/sensor/vpMocapQualisys.h>
56 #include <visp3/sensor/vpMocapVicon.h>
58 using std::chrono::seconds;
59 using std::this_thread::sleep_for;
61 #ifdef ENABLE_VISP_NAMESPACE
75 void quitHandler(
int sig)
78 std::cout << std::endl <<
"TERMINATING AT USER REQUEST" << std::endl << std::endl;
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> ¤t_body_poses_enu_M_flu,
bool &mocap_failure,
90 bool &mavlink_failure)
92 std::shared_ptr<vpMocap> mocap;
94 #ifdef VISP_HAVE_QUALISYS
95 mocap = std::make_shared<vpMocapQualisys>();
97 std::cout <<
"ERROR : Qualisys not found.";
102 #ifdef VISP_HAVE_VICON
103 mocap = std::make_shared<vpMocapVicon>();
106 std::cout <<
"ERROR : Vicon not found.";
110 mocap->setVerbose(opt_verbose);
111 mocap->setServerAddress(opt_serverAddress);
112 if (mocap->connect() ==
false) {
114 mocap_failure =
true;
116 std::cout <<
"Mocap connexion failure. Check mocap server IP address" << std::endl;
121 bool internal_mavlink_failure =
false;
122 while (!g_quit && !internal_mavlink_failure) {
123 std::map<std::string, vpHomogeneousMatrix> body_poses_enu_M_flu;
125 if (opt_onlyBody ==
"") {
126 if (!mocap->getBodiesPose(body_poses_enu_M_flu, opt_all_bodies)) {
132 if (!mocap->getSpecificBodyPose(opt_onlyBody, enu_M_flu)) {
136 body_poses_enu_M_flu[opt_onlyBody] = enu_M_flu;
141 internal_mavlink_failure = mavlink_failure;
142 current_body_poses_enu_M_flu =
143 body_poses_enu_M_flu;
152 int top(
const std::string &connection_info, std::map<std::string, vpHomogeneousMatrix> ¤t_body_poses_enu_M_flu,
153 std::mutex &lock,
bool &mocap_failure)
155 std::map<std::string, vpHomogeneousMatrix> body_poses_enu_M_flu;
156 bool internal_mocap_failure =
false;
157 const double fps = 100;
159 vpRobotMavsdk drone { connection_info };
161 while (!g_quit && !internal_mocap_failure) {
164 body_poses_enu_M_flu = current_body_poses_enu_M_flu;
165 internal_mocap_failure = mocap_failure;
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)) {
184 void usage(
char *argv[],
int error)
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
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
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
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
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
214 <<
" --verbose, -v" << std::endl
215 <<
" Enable verbose mode." << std::endl
217 <<
" --help, -h" << std::endl
218 <<
" Print this helper message." << std::endl
222 std::cout <<
"Error" << std::endl
224 <<
"Unsupported parameter " << argv[error] << std::endl;
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)
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]);
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") {
247 else if (mode ==
"vicon" || mode ==
"v") {
251 std::cout <<
"ERROR : System not recognized, exiting." << std::endl;
256 else if (std::string(argv[i]) ==
"--device" || std::string(argv[i]) ==
"-d") {
257 connection_info = std::string(argv[i + 1]);
260 else if (std::string(argv[i]) ==
"--server-address" || std::string(argv[i]) ==
"-sa") {
261 server_address = std::string(argv[i + 1]);
264 else if (std::string(argv[i]) ==
"--all-bodies") {
267 else if (std::string(argv[i]) ==
"--verbose" || std::string(argv[i]) ==
"-v") {
270 else if (std::string(argv[i]) ==
"--help" || std::string(argv[i]) ==
"-h") {
286 int main(
int argc,
char **argv)
288 std::map<std::string, vpHomogeneousMatrix> current_body_poses_enu_M_flu;
292 std::string opt_connectionInfo =
"/dev/tty.usbmodem1";
294 std::string opt_connectionInfo =
"udp://127.0.0.1:14550";
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;
304 parse_commandline(argc, argv, opt_qualisys, opt_connectionInfo, opt_serverAddress, opt_onlyBody, opt_all_bodies,
307 if (opt_qualisys && opt_serverAddress ==
"") {
308 opt_serverAddress =
"192.168.30.42";
310 else if (!opt_qualisys && opt_serverAddress ==
"") {
311 opt_serverAddress =
"192.168.30.1";
314 if (opt_onlyBody ==
"") {
315 std::cout <<
"The parameter --only-body MUST be given in the command line." << std::endl;
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 ¤t_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);
329 std::cout <<
"Mocap connexion failure. Check mocap server IP address" << std::endl;
334 std::thread mavlink_thread(
335 [&lock, ¤t_body_poses_enu_M_flu, &opt_connectionInfo, &mocap_failure, &mavlink_failure]() {
337 int result = top(opt_connectionInfo, current_body_poses_enu_M_flu, lock, mocap_failure);
341 fprintf(stderr,
"mavlink_control threw exception %i \n", error);
343 mavlink_failure =
true;
350 mavlink_thread.join();
363 #ifndef VISP_HAVE_MAVSDK
364 std::cout <<
"\nThis example requires mavsdk library. You should install it, configure and rebuid ViSP.\n"
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 "
372 #if !((__cplusplus >= 201703L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201703L)))
374 <<
"\nThis example requires at least cxx17. You should enable cxx17 during ViSP configuration with cmake and "
Implementation of an homogeneous matrix and operations on such kind of matrices.
VISP_EXPORT int wait(double t0, double t)
VISP_EXPORT double measureTimeMs()