test_slam.cc
Go to the documentation of this file.
00001 /*
00002  * This file is part of the rc_dynamics_api package.
00003  *
00004  * Copyright (c) 2017 Roboception GmbH
00005  * All rights reserved
00006  *
00007  * Author: Christian Emmerich
00008  *
00009  * Redistribution and use in source and binary forms, with or without
00010  * modification, are permitted provided that the following conditions are met:
00011  *
00012  * 1. Redistributions of source code must retain the above copyright notice,
00013  * this list of conditions and the following disclaimer.
00014  *
00015  * 2. Redistributions in binary form must reproduce the above copyright notice,
00016  * this list of conditions and the following disclaimer in the documentation
00017  * and/or other materials provided with the distribution.
00018  *
00019  * 3. Neither the name of the copyright holder nor the names of its contributors
00020  * may be used to endorse or promote products derived from this software without
00021  * specific prior written permission.
00022  *
00023  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00024  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00025  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00026  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
00027  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00028  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00029  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00030  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00031  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00032  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  * POSSIBILITY OF SUCH DAMAGE.
00034  */
00035 
00036 #include <rc_dynamics_api/remote_interface.h>
00037 
00038 #include <signal.h>
00039 
00040 #ifdef WIN32
00041 #include <winsock2.h>
00042 #undef min
00043 #undef max
00044 #endif
00045 
00046 using namespace std;
00047 namespace rcdyn = rc::dynamics;
00048 
00052 static bool caught_signal = false;
00053 void signal_callback_handler(int signum)
00054 {
00055   printf("Caught signal %d, stopping program!\n", signum);
00056   caught_signal = true;
00057 }
00058 
00062 void printUsage(char* arg)
00063 {
00064   cout << "\nStarts rc_visard's dynamics and slam modules for a certain time "
00065           "\nperiod, retrieves the Slam trajectory and simply prints it to std out."
00066        << "\n\nUsage: \n"
00067        << arg << " -v <rcVisardIP> [-t <timePeriodSecs>]" << endl;
00068 }
00069 
00070 int main(int argc, char* argv[])
00071 {
00072 #ifdef WIN32
00073   WSADATA wsaData;
00074   WSAStartup(MAKEWORD(2, 2), &wsaData);
00075 #endif
00076 
00077   // Register signals and signal handler for proper program escape
00078   signal(SIGINT, signal_callback_handler);
00079   signal(SIGTERM, signal_callback_handler);
00080 
00084   string visardIP, networkIface = "", streamName = "";
00085   bool userSetIp = false;
00086   unsigned int maxTimeSecs = 5;
00087 
00088   int i = 1;
00089   while (i < argc)
00090   {
00091     std::string p = argv[i++];
00092 
00093     if (p == "-v" && i < argc)
00094     {
00095       visardIP = string(argv[i++]);
00096       userSetIp = true;
00097     }
00098     else if (p == "-t" && i < argc)
00099     {
00100       maxTimeSecs = (unsigned int)std::max(0, atoi(argv[i++]));
00101     }
00102     else if (p == "-h")
00103     {
00104       printUsage(argv[0]);
00105       return EXIT_SUCCESS;
00106     }
00107     else
00108     {
00109       printUsage(argv[0]);
00110       return EXIT_FAILURE;
00111     }
00112   }
00113   if (!userSetIp)
00114   {
00115     cerr << "Please specify rc_visard IP." << endl;
00116     printUsage(argv[0]);
00117     return EXIT_FAILURE;
00118   }
00119 
00123   cout << "connecting rc_visard " << visardIP << "..." << endl;
00124   auto rcvisardDynamics = rcdyn::RemoteInterface::create(visardIP);
00125 
00126   try
00127   {
00128     // start the rc::dynamics module with slam on the rc_visard
00129     cout << "starting rc_dynamics module with slam on rc_visard..." << endl;
00130     rcvisardDynamics->startSlam();
00131   }
00132   catch (exception& e)
00133   {
00134     cout << "ERROR! Could not start rc_dynamics module on rc_visard: " << e.what() << endl;
00135     return EXIT_FAILURE;
00136   }
00137 
00141   cout << "running..." << endl;
00142 
00143 #ifdef WIN32
00144   Sleep(1000 * maxTimeSecs);
00145 #else
00146   usleep(1000 * 1000 * maxTimeSecs);
00147 #endif
00148 
00152   try
00153   {
00154     cout << "stopping rc_dynamics module on rc_visard..." << endl;
00155     rcvisardDynamics->stop();
00156 
00157     // get the full trajectory and print number of recorded poses
00158     roboception::msgs::Trajectory traj = rcvisardDynamics->getSlamTrajectory();
00159     cout << "The full trajectory contains " << traj.poses().size() << " waypoints." << endl;
00160 
00161     // print the last second of the trajectory to cout
00162     traj = rcvisardDynamics->getSlamTrajectory(rc::TrajectoryTime::RelativeToEnd(1));
00163     cout << "The last second of the trajectory contains " << traj.poses().size() << " waypoints and looks like:" << endl
00164          << traj.DebugString() << endl;
00165   }
00166   catch (exception& e)
00167   {
00168     cout << "ERROR! Could not start rc_dynamics module on rc_visard: " << e.what() << endl;
00169   }
00170 
00171 #ifdef WIN32
00172   ::WSACleanup();
00173 #endif
00174 
00175   return EXIT_SUCCESS;
00176 }


rc_dynamics_api
Author(s): Heiko Hirschmueller , Christian Emmerich , Felix Endres
autogenerated on Thu May 9 2019 02:13:50