VehicleBase.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/World.h>
00011 #include <mvsim/VehicleBase.h>
00012 #include <mvsim/VehicleDynamics/VehicleAckermann.h>
00013 #include <mvsim/VehicleDynamics/VehicleAckermann_Drivetrain.h>
00014 #include <mvsim/VehicleDynamics/VehicleDifferential.h>
00015 #include <mvsim/FrictionModels/FrictionBase.h>
00016 #include <mvsim/FrictionModels/DefaultFriction.h>  // For use as default model
00017 
00018 #include "JointXMLnode.h"
00019 #include "XMLClassesRegistry.h"
00020 #include "xml_utils.h"
00021 
00022 #include <rapidxml.hpp>
00023 #include <rapidxml_utils.hpp>
00024 #include <rapidxml_print.hpp>
00025 #include <mrpt/poses/CPose2D.h>
00026 #include <mrpt/opengl/CPolyhedron.h>
00027 
00028 #include <sstream>  // std::stringstream
00029 #include <map>
00030 #include <string>
00031 
00032 using namespace mvsim;
00033 using namespace std;
00034 
00035 XmlClassesRegistry veh_classes_registry("vehicle:class");
00036 
00037 TClassFactory_vehicleDynamics mvsim::classFactory_vehicleDynamics;
00038 
00039 // Explicit registration calls seem to be one (the unique?) way to assure
00040 // registration takes place:
00041 void register_all_veh_dynamics()
00042 {
00043         static bool done = false;
00044         if (done)
00045                 return;
00046         else
00047                 done = true;
00048 
00049         REGISTER_VEHICLE_DYNAMICS("differential", DynamicsDifferential)
00050         REGISTER_VEHICLE_DYNAMICS("ackermann", DynamicsAckermann)
00051         REGISTER_VEHICLE_DYNAMICS(
00052                 "ackermann_drivetrain", DynamicsAckermannDrivetrain)
00053 }
00054 
00055 constexpr char VehicleBase::DL_TIMESTAMP[];
00056 constexpr char VehicleBase::LOGGER_POSE[];
00057 constexpr char VehicleBase::LOGGER_WHEEL[];
00058 
00059 constexpr char VehicleBase::PL_Q_X[];
00060 constexpr char VehicleBase::PL_Q_Y[];
00061 constexpr char VehicleBase::PL_Q_Z[];
00062 constexpr char VehicleBase::PL_Q_YAW[];
00063 constexpr char VehicleBase::PL_Q_PITCH[];
00064 constexpr char VehicleBase::PL_Q_ROLL[];
00065 constexpr char VehicleBase::PL_DQ_X[];
00066 constexpr char VehicleBase::PL_DQ_Y[];
00067 constexpr char VehicleBase::PL_DQ_Z[];
00068 
00069 constexpr char VehicleBase::WL_TORQUE[];
00070 constexpr char VehicleBase::WL_WEIGHT[];
00071 constexpr char VehicleBase::WL_VEL_X[];
00072 constexpr char VehicleBase::WL_VEL_Y[];
00073 constexpr char VehicleBase::WL_FRIC_X[];
00074 constexpr char VehicleBase::WL_FRIC_Y[];
00075 
00076 // Protected ctor:
00077 VehicleBase::VehicleBase(World* parent, size_t nWheels)
00078         : VisualObject(parent),
00079           m_vehicle_index(0),
00080           m_b2d_vehicle_body(NULL),
00081           m_q(0, 0, 0, 0, 0, 0),
00082           m_dq(0, 0, 0),
00083           m_chassis_mass(15.0),
00084           m_chassis_z_min(0.05),
00085           m_chassis_z_max(0.6),
00086           m_chassis_color(0xff, 0x00, 0x00),
00087           m_chassis_com(.0, .0),
00088           m_wheels_info(nWheels),
00089           m_fixture_wheels(nWheels, NULL)
00090 {
00091         using namespace mrpt::math;
00092         // Default shape:
00093         m_chassis_poly.push_back(TPoint2D(-0.4, -0.5));
00094         m_chassis_poly.push_back(TPoint2D(-0.4, 0.5));
00095         m_chassis_poly.push_back(TPoint2D(0.4, 0.5));
00096         m_chassis_poly.push_back(TPoint2D(0.6, 0.3));
00097         m_chassis_poly.push_back(TPoint2D(0.6, -0.3));
00098         m_chassis_poly.push_back(TPoint2D(0.4, -0.5));
00099         updateMaxRadiusFromPoly();
00100 }
00101 
00102 void VehicleBase::simul_post_timestep_common(const TSimulContext& context)
00103 {
00104         if (m_b2d_vehicle_body)
00105         {
00106                 // Pos:
00107                 const b2Vec2& pos = m_b2d_vehicle_body->GetPosition();
00108                 const float32 angle = m_b2d_vehicle_body->GetAngle();
00109                 m_q.x = pos(0);
00110                 m_q.y = pos(1);
00111                 m_q.yaw = angle;
00112                 // The rest (z,pitch,roll) will be always 0, unless other world-element
00113                 // modifies them! (e.g. elevation map)
00114 
00115                 // Vel:
00116                 const b2Vec2& vel = m_b2d_vehicle_body->GetLinearVelocity();
00117                 const float32 w = m_b2d_vehicle_body->GetAngularVelocity();
00118                 m_dq.vals[0] = vel(0);
00119                 m_dq.vals[1] = vel(1);
00120                 m_dq.vals[2] = w;
00121         }
00122 }
00123 
00126 void VehicleBase::register_vehicle_class(
00127         const rapidxml::xml_node<char>* xml_node)
00128 {
00129         // Sanity checks:
00130         if (!xml_node)
00131                 throw runtime_error(
00132                         "[VehicleBase::register_vehicle_class] XML node is NULL");
00133         if (0 != strcmp(xml_node->name(), "vehicle:class"))
00134                 throw runtime_error(
00135                         mrpt::format(
00136                                 "[VehicleBase::register_vehicle_class] XML element is '%s' "
00137                                 "('vehicle:class' expected)",
00138                                 xml_node->name()));
00139 
00140         // rapidxml doesn't allow making copied of objects.
00141         // So: convert to txt; then re-parse.
00142         std::stringstream ss;
00143         ss << *xml_node;
00144 
00145         veh_classes_registry.add(ss.str());
00146 }
00147 
00150 VehicleBase* VehicleBase::factory(
00151         World* parent, const rapidxml::xml_node<char>* root)
00152 {
00153         register_all_veh_dynamics();
00154 
00155         using namespace std;
00156         using namespace rapidxml;
00157 
00158         if (!root) throw runtime_error("[VehicleBase::factory] XML node is NULL");
00159         if (0 != strcmp(root->name(), "vehicle"))
00160                 throw runtime_error(
00161                         mrpt::format(
00162                                 "[VehicleBase::factory] XML root element is '%s' ('vehicle' "
00163                                 "expected)",
00164                                 root->name()));
00165 
00166         // "class": When a vehicle has a 'class="XXX"' attribute, look for each
00167         // parameter
00168         //  in the set of "root" + "class_root" XML nodes:
00169         // --------------------------------------------------------------------------------
00170         JointXMLnode<> veh_root_node;
00171         {
00172                 veh_root_node.add(
00173                         root);  // Always search in root. Also in the class root, if any:
00174 
00175                 const xml_attribute<>* veh_class = root->first_attribute("class");
00176                 if (veh_class)
00177                 {
00178                         const string sClassName = veh_class->value();
00179                         const rapidxml::xml_node<char>* class_root =
00180                                 veh_classes_registry.get(sClassName);
00181                         if (!class_root)
00182                                 throw runtime_error(
00183                                         mrpt::format(
00184                                                 "[VehicleBase::factory] Vehicle class '%s' undefined",
00185                                                 sClassName.c_str()));
00186 
00187                         veh_root_node.add(class_root);
00188                         // cout << *class_root;
00189                 }
00190         }
00191 
00192         // Class factory according to: <dynamics class="XXX">
00193         // -------------------------------------------------
00194         const xml_node<>* dyn_node = veh_root_node.first_node("dynamics");
00195         if (!dyn_node)
00196                 throw runtime_error(
00197                         "[VehicleBase::factory] Missing XML node <dynamics>");
00198 
00199         const xml_attribute<>* dyn_class = dyn_node->first_attribute("class");
00200         if (!dyn_class || !dyn_class->value())
00201                 throw runtime_error(
00202                         "[VehicleBase::factory] Missing mandatory attribute 'class' in "
00203                         "node <dynamics>");
00204 
00205         VehicleBase* veh =
00206                 classFactory_vehicleDynamics.create(dyn_class->value(), parent);
00207         if (!veh)
00208                 throw runtime_error(
00209                         mrpt::format(
00210                                 "[VehicleBase::factory] Unknown vehicle dynamics class '%s'",
00211                                 dyn_class->value()));
00212 
00213         // Initialize here all common params shared by any polymorphic class:
00214         // -------------------------------------------------
00215         // attrib: name
00216         {
00217                 const xml_attribute<>* attrib_name = root->first_attribute("name");
00218                 if (attrib_name && attrib_name->value())
00219                 {
00220                         veh->m_name = attrib_name->value();
00221                 }
00222                 else
00223                 {
00224                         // Default name:
00225                         static int cnt = 0;
00226                         veh->m_name = mrpt::format("veh%i", ++cnt);
00227                 }
00228         }
00229 
00230         // (Mandatory) initial pose:
00231         {
00232                 const xml_node<>* node = veh_root_node.first_node("init_pose");
00233                 if (!node)
00234                         throw runtime_error(
00235                                 "[VehicleBase::factory] Missing XML node <init_pose>");
00236 
00237                 if (3 != ::sscanf(
00238                                          node->value(), "%lf %lf %lf", &veh->m_q.x, &veh->m_q.y,
00239                                          &veh->m_q.yaw))
00240                         throw runtime_error(
00241                                 "[VehicleBase::factory] Error parsing "
00242                                 "<init_pose>...</init_pose>");
00243                 veh->m_q.yaw *= M_PI / 180.0;  // deg->rad
00244         }
00245 
00246         // (Optional) initial vel:
00247         {
00248                 const xml_node<>* node = veh_root_node.first_node("init_vel");
00249                 if (node)
00250                 {
00251                         if (3 != ::sscanf(
00252                                                  node->value(), "%lf %lf %lf", &veh->m_dq.vals[0],
00253                                                  &veh->m_dq.vals[1], &veh->m_dq.vals[2]))
00254                                 throw runtime_error(
00255                                         "[VehicleBase::factory] Error parsing "
00256                                         "<init_vel>...</init_vel>");
00257                         veh->m_dq.vals[2] *= M_PI / 180.0;  // deg->rad
00258 
00259                         // Convert twist (velocity) from local -> global coords:
00260                         const mrpt::poses::CPose2D pose(
00261                                 0, 0, veh->m_q.yaw);  // Only the rotation
00262                         pose.composePoint(
00263                                 veh->m_dq.vals[0], veh->m_dq.vals[1], veh->m_dq.vals[0],
00264                                 veh->m_dq.vals[1]);
00265                 }
00266         }
00267 
00268         // Initialize class-specific params:
00269         // -------------------------------------------------
00270         veh->dynamics_load_params_from_xml(dyn_node);
00271 
00272         // <Optional> Log path. If not specified, app folder will be used
00273         // -----------------------------------------------------------
00274         {
00275                 const xml_node<>* log_path_node = veh_root_node.first_node("log_path");
00276                 if (log_path_node)
00277                 {
00278                         // Parse:
00279                         veh->m_log_path = log_path_node->value();
00280                 }
00281         }
00282 
00283         veh->initLoggers();
00284 
00285         // Register bodies, fixtures, etc. in Box2D simulator:
00286         // ----------------------------------------------------
00287         b2World* b2world = parent->getBox2DWorld();
00288         veh->create_multibody_system(b2world);
00289 
00290         if (veh->m_b2d_vehicle_body)
00291         {
00292                 // Init pos:
00293                 veh->m_b2d_vehicle_body->SetTransform(
00294                         b2Vec2(veh->m_q.x, veh->m_q.y), veh->m_q.yaw);
00295                 // Init vel:
00296                 veh->m_b2d_vehicle_body->SetLinearVelocity(
00297                         b2Vec2(veh->m_dq.vals[0], veh->m_dq.vals[1]));
00298                 veh->m_b2d_vehicle_body->SetAngularVelocity(veh->m_dq.vals[2]);
00299         }
00300 
00301         // Friction model:
00302         // Parse <friction> node, or assume default linear model:
00303         // -----------------------------------------------------------
00304         {
00305                 const xml_node<>* frict_node = veh_root_node.first_node("friction");
00306                 if (!frict_node)
00307                 {
00308                         // Default:
00309                         veh->m_friction = std::shared_ptr<FrictionBase>(
00310                                 new DefaultFriction(*veh, NULL /*default params*/));
00311                 }
00312                 else
00313                 {
00314                         // Parse:
00315                         veh->m_friction = std::shared_ptr<FrictionBase>(
00316                                 FrictionBase::factory(*veh, frict_node));
00317                         ASSERT_(veh->m_friction);
00318                 }
00319         }
00320 
00321         // Sensors: <sensor class='XXX'> entries
00322         // -------------------------------------------------
00323         for (JointXMLnode<>::iterator it = veh_root_node.begin();
00324                  it != veh_root_node.end(); ++it)
00325         {
00326                 if (!strcmp(it->name(), "sensor"))
00327                 {
00328                         SensorBase* se = SensorBase::factory(*veh, *it);
00329                         veh->m_sensors.push_back(SensorBase::Ptr(se));
00330                 }
00331         }
00332 
00333         return veh;
00334 }
00335 
00336 VehicleBase* VehicleBase::factory(World* parent, const std::string& xml_text)
00337 {
00338         // Parse the string as if it was an XML file:
00339         std::stringstream s;
00340         s.str(xml_text);
00341 
00342         char* input_str = const_cast<char*>(xml_text.c_str());
00343         rapidxml::xml_document<> xml;
00344         try
00345         {
00346                 xml.parse<0>(input_str);
00347         }
00348         catch (rapidxml::parse_error& e)
00349         {
00350                 unsigned int line =
00351                         static_cast<long>(std::count(input_str, e.where<char>(), '\n') + 1);
00352                 throw std::runtime_error(
00353                         mrpt::format(
00354                                 "[VehicleBase::factory] XML parse error (Line %u): %s",
00355                                 static_cast<unsigned>(line), e.what()));
00356         }
00357         return VehicleBase::factory(parent, xml.first_node());
00358 }
00359 
00360 void VehicleBase::simul_pre_timestep(const TSimulContext& context)
00361 {
00362         // Update wheels position (they may turn, etc. as in an Ackermann
00363         // configuration)
00364         for (size_t i = 0; i < m_fixture_wheels.size(); i++)
00365         {
00366                 b2PolygonShape* wheelShape =
00367                         dynamic_cast<b2PolygonShape*>(m_fixture_wheels[i]->GetShape());
00368                 wheelShape->SetAsBox(
00369                         m_wheels_info[i].diameter * 0.5, m_wheels_info[i].width * 0.5,
00370                         b2Vec2(m_wheels_info[i].x, m_wheels_info[i].y),
00371                         m_wheels_info[i].yaw);
00372         }
00373 
00374         // Apply motor forces/torques:
00375         this->invoke_motor_controllers(context, m_torque_per_wheel);
00376 
00377         // Apply friction model at each wheel:
00378         const size_t nW = getNumWheels();
00379         ASSERT_EQUAL_(m_torque_per_wheel.size(), nW);
00380 
00381         const double gravity = getWorldObject()->get_gravity();
00382         const double massPerWheel =
00383                 getChassisMass() / nW;  // Part of the vehicle weight on each wheel.
00384         const double weightPerWheel = massPerWheel * gravity;
00385 
00386         std::vector<mrpt::math::TPoint2D> wheels_vels;
00387         getWheelsVelocityLocal(wheels_vels, getVelocityLocal());
00388 
00389         ASSERT_EQUAL_(wheels_vels.size(), nW);
00390 
00391         std::vector<mrpt::math::TSegment3D>
00392                 force_vectors;  // For visualization only
00393 
00394         for (size_t i = 0; i < nW; i++)
00395         {
00396                 // prepare data:
00397                 Wheel& w = getWheelInfo(i);
00398 
00399                 FrictionBase::TFrictionInput fi(context, w);
00400                 fi.motor_torque =
00401                         -m_torque_per_wheel[i];  // "-" => Forwards is negative
00402                 fi.weight = weightPerWheel;
00403                 fi.wheel_speed = wheels_vels[i];
00404 
00405                 m_friction->setLogger(
00406                         getLoggerPtr(LOGGER_WHEEL + std::to_string(i + 1)));
00407                 // eval friction:
00408                 mrpt::math::TPoint2D net_force_;
00409                 m_friction->evaluate_friction(fi, net_force_);
00410 
00411                 // Apply force:
00412                 const b2Vec2 wForce = m_b2d_vehicle_body->GetWorldVector(
00413                         b2Vec2(
00414                                 net_force_.x, net_force_.y));  // Force vector -> world coords
00415                 const b2Vec2 wPt = m_b2d_vehicle_body->GetWorldPoint(
00416                         b2Vec2(w.x, w.y));  // Application point -> world coords
00417                 // printf("w%i: Lx=%6.3f Ly=%6.3f  | Gx=%11.9f
00418                 // Gy=%11.9f\n",(int)i,net_force_.x,net_force_.y,wForce.x,wForce.y);
00419 
00420                 m_b2d_vehicle_body->ApplyForce(wForce, wPt, true /*wake up*/);
00421 
00422                 // log
00423                 {
00424                         m_loggers[LOGGER_WHEEL + std::to_string(i + 1)]->updateColumn(
00425                                 DL_TIMESTAMP, context.simul_time);
00426                         m_loggers[LOGGER_WHEEL + std::to_string(i + 1)]->updateColumn(
00427                                 WL_TORQUE, fi.motor_torque);
00428                         m_loggers[LOGGER_WHEEL + std::to_string(i + 1)]->updateColumn(
00429                                 WL_WEIGHT, fi.weight);
00430                         m_loggers[LOGGER_WHEEL + std::to_string(i + 1)]->updateColumn(
00431                                 WL_VEL_X, fi.wheel_speed.x);
00432                         m_loggers[LOGGER_WHEEL + std::to_string(i + 1)]->updateColumn(
00433                                 WL_VEL_Y, fi.wheel_speed.y);
00434                         m_loggers[LOGGER_WHEEL + std::to_string(i + 1)]->updateColumn(
00435                                 WL_FRIC_X, net_force_.x);
00436                         m_loggers[LOGGER_WHEEL + std::to_string(i + 1)]->updateColumn(
00437                                 WL_FRIC_Y, net_force_.y);
00438                 }
00439 
00440                 // save it for optional rendering:
00441                 if (m_world->m_gui_options.show_forces)
00442                 {
00443                         const double forceScale =
00444                                 m_world->m_gui_options.force_scale;  // [meters/N]
00445                         const mrpt::math::TPoint3D pt1(
00446                                 wPt.x, wPt.y, m_chassis_z_max * 1.1 + m_q.z);
00447                         const mrpt::math::TPoint3D pt2 =
00448                                 pt1 + mrpt::math::TPoint3D(wForce.x, wForce.y, 0) * forceScale;
00449                         force_vectors.push_back(mrpt::math::TSegment3D(pt1, pt2));
00450                 }
00451         }
00452 
00453         // Save forces for optional rendering:
00454         if (m_world->m_gui_options.show_forces)
00455         {
00456                 std::lock_guard<std::mutex> csl(m_force_segments_for_rendering_cs);
00457                 m_force_segments_for_rendering = force_vectors;
00458         }
00459 }
00460 
00463 void VehicleBase::simul_post_timestep(const TSimulContext& context)
00464 {
00465         // Integrate wheels' rotation:
00466         const size_t nW = getNumWheels();
00467 
00468         for (size_t i = 0; i < nW; i++)
00469         {
00470                 // prepare data:
00471                 Wheel& w = getWheelInfo(i);
00472 
00473                 // Explicit Euler:
00474                 w.setPhi(w.getPhi() + w.getW() * context.dt);
00475 
00476                 // Wrap wheel spin position (angle), so it doesn't
00477                 // become excessively large (it's actually unbound, but we don't want to
00478                 // lose 'double' accuracy):
00479                 const double cur_abs_phi = std::abs(w.getPhi());
00480                 if (cur_abs_phi > 1e4)
00481                         w.setPhi(
00482                                 ::fmod(cur_abs_phi, 2 * M_PI) *
00483                                 (w.getPhi() < 0.0 ? -1.0 : 1.0));
00484         }
00485 
00486         m_loggers[LOGGER_POSE]->updateColumn(DL_TIMESTAMP, context.simul_time);
00487         m_loggers[LOGGER_POSE]->updateColumn(PL_Q_X, m_q.x);
00488         m_loggers[LOGGER_POSE]->updateColumn(PL_Q_Y, m_q.y);
00489         m_loggers[LOGGER_POSE]->updateColumn(PL_Q_Z, m_q.z);
00490         m_loggers[LOGGER_POSE]->updateColumn(PL_Q_YAW, m_q.yaw);
00491         m_loggers[LOGGER_POSE]->updateColumn(PL_Q_PITCH, m_q.pitch);
00492         m_loggers[LOGGER_POSE]->updateColumn(PL_Q_ROLL, m_q.roll);
00493         m_loggers[LOGGER_POSE]->updateColumn(PL_DQ_X, m_dq.vals[0]);
00494         m_loggers[LOGGER_POSE]->updateColumn(PL_DQ_Y, m_dq.vals[1]);
00495         m_loggers[LOGGER_POSE]->updateColumn(PL_DQ_Z, m_dq.vals[2]);
00496 
00497         {
00498                 writeLogStrings();
00499         }
00500 }
00501 
00503 void VehicleBase::getWheelsVelocityLocal(
00504         std::vector<mrpt::math::TPoint2D>& vels, const vec3& veh_vel_local) const
00505 {
00506         // Each wheel velocity is:
00507         // v_w = v_veh + \omega \times wheel_pos
00508         // =>
00509         // v_w = v_veh + ( -w*y, w*x )
00510 
00511         const double w = veh_vel_local.vals[2];  // vehicle w
00512 
00513         const size_t nW = this->getNumWheels();
00514         vels.resize(nW);
00515         for (size_t i = 0; i < nW; i++)
00516         {
00517                 const Wheel& wheel = getWheelInfo(i);
00518 
00519                 vels[i].x = veh_vel_local.vals[0] - w * wheel.y;
00520                 vels[i].y = veh_vel_local.vals[1] + w * wheel.x;
00521         }
00522 }
00523 
00525 vec3 VehicleBase::getVelocityLocal() const
00526 {
00527         vec3 local_vel;
00528         local_vel.vals[2] = m_dq.vals[2];  // omega remains the same.
00529 
00530         const mrpt::poses::CPose2D p(0, 0, -m_q.yaw);  // "-" means inverse pose
00531         p.composePoint(
00532                 m_dq.vals[0], m_dq.vals[1], local_vel.vals[0], local_vel.vals[1]);
00533         return local_vel;
00534 }
00535 
00536 mrpt::poses::CPose2D VehicleBase::getCPose2D() const
00537 {
00538         return mrpt::poses::CPose2D(mrpt::math::TPose2D(m_q));
00539 }
00540 
00542 void VehicleBase::gui_update_common(
00543         mrpt::opengl::COpenGLScene& scene, bool defaultVehicleBody)
00544 {
00545         // 1st time call?? -> Create objects
00546         // ----------------------------------
00547         if (defaultVehicleBody)
00548         {
00549                 const size_t nWs = this->getNumWheels();
00550                 if (!m_gl_chassis)
00551                 {
00552                         m_gl_chassis = mrpt::opengl::CSetOfObjects::Create();
00553 
00554                         // Wheels shape:
00555                         m_gl_wheels.resize(nWs);
00556                         for (size_t i = 0; i < nWs; i++)
00557                         {
00558                                 m_gl_wheels[i] = mrpt::opengl::CSetOfObjects::Create();
00559                                 this->getWheelInfo(i).getAs3DObject(*m_gl_wheels[i]);
00560                                 m_gl_chassis->insert(m_gl_wheels[i]);
00561                         }
00562                         // Robot shape:
00563                         mrpt::opengl::CPolyhedron::Ptr gl_poly =
00564                                 mrpt::opengl::CPolyhedron::CreateCustomPrism(
00565                                         m_chassis_poly, m_chassis_z_max - m_chassis_z_min);
00566                         gl_poly->setLocation(0, 0, m_chassis_z_min);
00567                         gl_poly->setColor(TColorf(m_chassis_color));
00568                         m_gl_chassis->insert(gl_poly);
00569 
00570                         SCENE_INSERT_Z_ORDER(scene, 1, m_gl_chassis);
00571 
00572                         // Visualization of forces:
00573                         m_gl_forces = mrpt::opengl::CSetOfLines::Create();
00574                         m_gl_forces->setLineWidth(3.0);
00575                         m_gl_forces->setColor_u8(TColor(0xff, 0xff, 0xff));
00576 
00577                         SCENE_INSERT_Z_ORDER(
00578                                 scene, 3, m_gl_forces);  // forces are in global coords
00579                 }
00580 
00581                 // Update them:
00582                 // ----------------------------------
00583                 m_gl_chassis->setPose(m_q);
00584 
00585                 for (size_t i = 0; i < nWs; i++)
00586                 {
00587                         const Wheel& w = getWheelInfo(i);
00588                         m_gl_wheels[i]->setPose(
00589                                 mrpt::math::TPose3D(
00590                                         w.x, w.y, 0.5 * w.diameter, w.yaw, w.getPhi(), 0.0));
00591                 }
00592         }
00593 
00594         // Other common stuff:
00595         internal_gui_update_sensors(scene);
00596         internal_gui_update_forces(scene);
00597 }
00598 
00599 void VehicleBase::internal_gui_update_sensors(mrpt::opengl::COpenGLScene& scene)
00600 {
00601         for (TListSensors::iterator it = m_sensors.begin(); it != m_sensors.end();
00602                  ++it)
00603                 (*it)->gui_update(scene);
00604 }
00605 
00606 void VehicleBase::internal_gui_update_forces(mrpt::opengl::COpenGLScene& scene)
00607 {
00608         if (m_world->m_gui_options.show_forces)
00609         {
00610                 std::lock_guard<std::mutex> csl(m_force_segments_for_rendering_cs);
00611                 m_gl_forces->clear();
00612                 m_gl_forces->appendLines(m_force_segments_for_rendering);
00613                 m_gl_forces->setVisibility(true);
00614         }
00615         else
00616         {
00617                 m_gl_forces->setVisibility(false);
00618         }
00619 }
00620 
00621 void VehicleBase::updateMaxRadiusFromPoly()
00622 {
00623         using namespace mrpt::math;
00624 
00625         m_max_radius = 0.001f;
00626         for (TPolygon2D::const_iterator it = m_chassis_poly.begin();
00627                  it != m_chassis_poly.end(); ++it)
00628         {
00629                 const float n = it->norm();
00630     keep_max(m_max_radius, n);
00631         }
00632 }
00633 
00635 void VehicleBase::create_multibody_system(b2World* world)
00636 {
00637         // Define the dynamic body. We set its position and call the body factory.
00638         b2BodyDef bodyDef;
00639         bodyDef.type = b2_dynamicBody;
00640 
00641         m_b2d_vehicle_body = world->CreateBody(&bodyDef);
00642 
00643         // Define shape of chassis:
00644         // ------------------------------
00645         {
00646                 // Convert shape into Box2D format:
00647                 const size_t nPts = m_chassis_poly.size();
00648                 ASSERT_(nPts >= 3);
00649                 ASSERT_BELOWEQ_(nPts, (size_t)b2_maxPolygonVertices);
00650                 std::vector<b2Vec2> pts(nPts);
00651                 for (size_t i = 0; i < nPts; i++)
00652                         pts[i] = b2Vec2(m_chassis_poly[i].x, m_chassis_poly[i].y);
00653 
00654                 b2PolygonShape chassisPoly;
00655                 chassisPoly.Set(&pts[0], nPts);
00656                 // chassisPoly.m_radius = 1e-3;  // The "skin" depth of the body
00657 
00658                 // Define the dynamic body fixture.
00659                 b2FixtureDef fixtureDef;
00660                 fixtureDef.shape = &chassisPoly;
00661                 fixtureDef.restitution = 0.01;
00662 
00663                 // Set the box density to be non-zero, so it will be dynamic.
00664                 b2MassData mass;
00665                 chassisPoly.ComputeMass(
00666                         &mass, 1);  // Mass with density=1 => compute area
00667                 fixtureDef.density = m_chassis_mass / mass.mass;
00668 
00669                 // Override the default friction.
00670                 fixtureDef.friction = 0.3f;
00671 
00672                 // Add the shape to the body.
00673                 m_fixture_chassis = m_b2d_vehicle_body->CreateFixture(&fixtureDef);
00674 
00675                 // Compute center of mass:
00676                 b2MassData vehMass;
00677                 m_fixture_chassis->GetMassData(&vehMass);
00678                 m_chassis_com.x = vehMass.center.x;
00679                 m_chassis_com.y = vehMass.center.y;
00680         }
00681 
00682         // Define shape of wheels:
00683         // ------------------------------
00684         ASSERT_EQUAL_(m_fixture_wheels.size(), m_wheels_info.size());
00685 
00686         for (size_t i = 0; i < m_wheels_info.size(); i++)
00687         {
00688                 b2PolygonShape wheelShape;
00689                 wheelShape.SetAsBox(
00690                         m_wheels_info[i].diameter * 0.5, m_wheels_info[i].width * 0.5,
00691                         b2Vec2(m_wheels_info[i].x, m_wheels_info[i].y),
00692                         m_wheels_info[i].yaw);
00693 
00694                 // Define the dynamic body fixture.
00695                 b2FixtureDef fixtureDef;
00696                 fixtureDef.shape = &wheelShape;
00697                 fixtureDef.restitution = 0.05;
00698 
00699                 // Set the box density to be non-zero, so it will be dynamic.
00700                 b2MassData mass;
00701                 wheelShape.ComputeMass(
00702                         &mass, 1);  // Mass with density=1 => compute area
00703                 fixtureDef.density = m_wheels_info[i].mass / mass.mass;
00704 
00705                 // Override the default friction.
00706                 fixtureDef.friction = 0.5f;
00707 
00708                 m_fixture_wheels[i] = m_b2d_vehicle_body->CreateFixture(&fixtureDef);
00709         }
00710 }
00711 
00712 void VehicleBase::gui_update(mrpt::opengl::COpenGLScene& scene)
00713 {
00714         this->gui_update_common(scene);  // Common part: update sensors, etc.
00715 }
00716 
00717 void VehicleBase::initLoggers()
00718 {
00719         m_loggers[LOGGER_POSE] = std::make_shared<CSVLogger>();
00720         //  m_loggers[LOGGER_POSE]->addColumn(DL_TIMESTAMP);
00721         //  m_loggers[LOGGER_POSE]->addColumn(PL_Q_X);
00722         //  m_loggers[LOGGER_POSE]->addColumn(PL_Q_Y);
00723         //  m_loggers[LOGGER_POSE]->addColumn(PL_Q_Z);
00724         //  m_loggers[LOGGER_POSE]->addColumn(PL_Q_YAW);
00725         //  m_loggers[LOGGER_POSE]->addColumn(PL_Q_PITCH);
00726         //  m_loggers[LOGGER_POSE]->addColumn(PL_Q_ROLL);
00727         //  m_loggers[LOGGER_POSE]->addColumn(PL_DQ_X);
00728         //  m_loggers[LOGGER_POSE]->addColumn(PL_DQ_Y);
00729         //  m_loggers[LOGGER_POSE]->addColumn(PL_DQ_Z);
00730         m_loggers[LOGGER_POSE]->setFilepath(
00731                 m_log_path + "mvsim_" + m_name + LOGGER_POSE + ".log");
00732 
00733         for (size_t i = 0; i < getNumWheels(); i++)
00734         {
00735                 m_loggers[LOGGER_WHEEL + std::to_string(i + 1)] =
00736                         std::make_shared<CSVLogger>();
00737                 //    m_loggers[LOGGER_WHEEL + std::to_string(i +
00738                 //    1)]->addColumn(DL_TIMESTAMP);
00739                 //    m_loggers[LOGGER_WHEEL + std::to_string(i +
00740                 //    1)]->addColumn(WL_TORQUE);
00741                 //    m_loggers[LOGGER_WHEEL + std::to_string(i +
00742                 //    1)]->addColumn(WL_WEIGHT);
00743                 //    m_loggers[LOGGER_WHEEL + std::to_string(i +
00744                 //    1)]->addColumn(WL_VEL_X);
00745                 //    m_loggers[LOGGER_WHEEL + std::to_string(i +
00746                 //    1)]->addColumn(WL_VEL_Y);
00747                 //    m_loggers[LOGGER_WHEEL + std::to_string(i +
00748                 //    1)]->addColumn(WL_FRIC_X);
00749                 //    m_loggers[LOGGER_WHEEL + std::to_string(i +
00750                 //    1)]->addColumn(WL_FRIC_Y);
00751                 m_loggers[LOGGER_WHEEL + std::to_string(i + 1)]->setFilepath(
00752                         m_log_path + "mvsim_" + m_name + LOGGER_WHEEL +
00753                         std::to_string(i + 1) + ".log");
00754         }
00755 }
00756 
00757 void VehicleBase::writeLogStrings()
00758 {
00759         std::map<std::string, std::shared_ptr<CSVLogger>>::iterator it;
00760         for (it = m_loggers.begin(); it != m_loggers.end(); ++it)
00761         {
00762                 it->second->writeRow();
00763         }
00764 }
00765 
00766 void VehicleBase::apply_force(
00767         double fx, double fy, double local_ptx, double local_pty)
00768 {
00769         ASSERT_(m_b2d_vehicle_body);
00770         const b2Vec2 wPt = m_b2d_vehicle_body->GetWorldPoint(
00771                 b2Vec2(local_ptx, local_pty));  // Application point -> world coords
00772         m_b2d_vehicle_body->ApplyForce(b2Vec2(fx, fy), wPt, true /*wake up*/);
00773 }


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