mvsim_main.cpp
Go to the documentation of this file.
00001 /*+-------------------------------------------------------------------------+
00002   |                       MultiVehicle simulator (libmvsim)                 |
00003   |                                                                         |
00004   | Copyright (C) 2014  Jose Luis Blanco Claraco (University of Almeria)    |
00005   | Copyright (C) 2017  Borys Tymchenko (Odessa Polytechnic University)     |
00006   | Distributed under GNU General Public License version 3                  |
00007   |   See <http://www.gnu.org/licenses/>                                    |
00008   +-------------------------------------------------------------------------+ */
00009 
00010 #include <mvsim/mvsim.h>
00011 
00012 #include <chrono>
00013 #include <thread>
00014 
00015 #include <mrpt/system/os.h>  // kbhit()
00016 #include <mrpt/utils/CTicTac.h>
00017 #include <rapidxml_utils.hpp>
00018 #include <iostream>
00019 
00020 using namespace mvsim;
00021 
00022 struct TThreadParams
00023 {
00024         World* world;
00025         volatile bool closing;
00026         TThreadParams() : world(NULL), closing(false) {}
00027 };
00028 void usage(const char* argv0);
00029 void thread_update_GUI(TThreadParams& thread_params);
00030 World::TGUIKeyEvent gui_key_events;
00031 std::string msg2gui;
00032 
00033 int main(int argc, char** argv)
00034 {
00035         try
00036         {
00037                 if (argc != 2)
00038                 {
00039                         usage(argv[0]);
00040                         return -1;
00041                 }
00042 
00043                 World world;
00044 
00045                 // Load from XML:
00046                 rapidxml::file<> fil_xml(argv[1]);
00047                 world.load_from_XML(fil_xml.data(), argv[1]);
00048 
00049                 // Launch GUI thread:
00050                 TThreadParams thread_params;
00051                 thread_params.world = &world;
00052                 std::thread thGUI =
00053                         std::thread(thread_update_GUI, std::ref(thread_params));
00054 
00055                 // Run simulation:
00056                 CTicTac tictac;
00057                 double t_old = tictac.Tac();
00058                 double REALTIME_FACTOR = 1.0;
00059                 bool do_exit = false;
00060                 size_t teleop_idx_veh = 0;  // Index of the vehicle to teleop
00061 
00062                 while (!do_exit && !mrpt::system::os::kbhit())
00063                 {
00064                         // Simulation
00065                         // ============================================================
00066                         // Compute how much time has passed to simulate in real-time:
00067                         double t_new = tictac.Tac();
00068                         double incr_time = REALTIME_FACTOR * (t_new - t_old);
00069 
00070                         if (incr_time >= world.get_simul_timestep())  // Just in case the
00071                                                                                                                   // computer is *really
00072                                                                                                                   // fast*...
00073                         {
00074                                 // Simulate:
00075                                 world.run_simulation(incr_time);
00076 
00077                                 // t_old_simul = world.get_simul_time();
00078                                 t_old = t_new;
00079                         }
00080 
00081                         // I could use 10ms here but chono literals are since gcc 4.9.3
00082                         std::this_thread::sleep_for(std::chrono::milliseconds(10));
00083 
00084                         // GUI msgs, teleop, etc.
00085                         // ====================================================
00086 
00087                         std::string txt2gui_tmp;
00088                         World::TGUIKeyEvent keyevent = gui_key_events;
00089 
00090                         // Global keys:
00091                         switch (keyevent.keycode)
00092                         {
00093                                 case 27:
00094                                         do_exit = true;
00095                                         break;
00096                                 case '1':
00097                                 case '2':
00098                                 case '3':
00099                                 case '4':
00100                                 case '5':
00101                                 case '6':
00102                                         teleop_idx_veh = keyevent.keycode - '1';
00103                                         break;
00104                         };
00105 
00106                         {  // Test: Differential drive: Control raw forces
00107                                 const World::TListVehicles& vehs = world.getListOfVehicles();
00108                                 txt2gui_tmp += mrpt::format(
00109                                         "Selected vehicle: %u/%u\n",
00110                                         static_cast<unsigned>(teleop_idx_veh + 1),
00111                                         static_cast<unsigned>(vehs.size()));
00112                                 if (vehs.size() > teleop_idx_veh)
00113                                 {
00114                                         // Get iterator to selected vehicle:
00115                                         World::TListVehicles::const_iterator it_veh = vehs.begin();
00116                                         std::advance(it_veh, teleop_idx_veh);
00117 
00118                                         // Get speed: ground truth
00119                                         {
00120                                                 const vec3& vel = it_veh->second->getVelocityLocal();
00121                                                 txt2gui_tmp += mrpt::format(
00122                                                         "gt. vel: lx=%7.03f, ly=%7.03f, w= %7.03fdeg/s\n",
00123                                                         vel.vals[0], vel.vals[1],
00124                                                     RAD2DEG(vel.vals[2]));
00125                                         }
00126                                         // Get speed: ground truth
00127                                         {
00128                                                 const vec3& vel =
00129                                                         it_veh->second->getVelocityLocalOdoEstimate();
00130                                                 txt2gui_tmp += mrpt::format(
00131                                                         "odo vel: lx=%7.03f, ly=%7.03f, w= %7.03fdeg/s\n",
00132                                                         vel.vals[0], vel.vals[1],
00133                                                     RAD2DEG(vel.vals[2]));
00134                                         }
00135 
00136                                         // Generic teleoperation interface for any controller that
00137                                         // supports it:
00138                                         {
00139                                                 ControllerBaseInterface* controller =
00140                                                         it_veh->second->getControllerInterface();
00141                                                 ControllerBaseInterface::TeleopInput teleop_in;
00142                                                 ControllerBaseInterface::TeleopOutput teleop_out;
00143                                                 teleop_in.keycode = keyevent.keycode;
00144                                                 controller->teleop_interface(teleop_in, teleop_out);
00145                                                 txt2gui_tmp += teleop_out.append_gui_lines;
00146                                         }
00147                                 }
00148                         }
00149 
00150                         // Clear the keystroke buffer
00151                         if (keyevent.keycode != 0) gui_key_events = World::TGUIKeyEvent();
00152 
00153                         msg2gui = txt2gui_tmp;  // send txt msgs to show in the GUI
00154 
00155                 }  // end while()
00156 
00157                 thread_params.closing = true;
00158                 thGUI.join();  // TODO: It could break smth
00159         }
00160         catch (const std::exception& e)
00161         {
00162                 std::cerr << "ERROR: " << e.what() << std::endl;
00163                 return 1;
00164         }
00165         return 0;
00166 }
00167 
00168 void thread_update_GUI(TThreadParams& thread_params)
00169 {
00170         while (!thread_params.closing)
00171         {
00172                 World::TUpdateGUIParams guiparams;
00173                 guiparams.msg_lines = msg2gui;
00174 
00175                 thread_params.world->update_GUI(&guiparams);
00176 
00177                 // Send key-strokes to the main thread:
00178                 if (guiparams.keyevent.keycode != 0)
00179                         gui_key_events = guiparams.keyevent;
00180 
00181                 std::this_thread::sleep_for(std::chrono::milliseconds(25));
00182         }
00183 }
00184 
00185 void usage(const char* argv0)
00186 {
00187         std::cerr << "Usage:\n"
00188                                  " "
00189                           << argv0 << " [WORLD_MODEL.xml]\n";
00190 }


mvsim
Author(s):
autogenerated on Thu Jun 6 2019 22:08:35