Block.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/Block.h>
00012 
00013 #include "JointXMLnode.h"
00014 #include "XMLClassesRegistry.h"
00015 #include "xml_utils.h"
00016 
00017 #include <rapidxml.hpp>
00018 #include <rapidxml_utils.hpp>
00019 #include <rapidxml_print.hpp>
00020 #include <mrpt/utils/utils_defs.h>  // mrpt::format()
00021 #include <mrpt/poses/CPose2D.h>
00022 #include <mrpt/opengl/CPolyhedron.h>
00023 
00024 #include <sstream>  // std::stringstream
00025 #include <map>
00026 #include <string>
00027 
00028 using namespace mvsim;
00029 using namespace std;
00030 
00031 XmlClassesRegistry block_classes_registry("block:class");
00032 
00033 // Protected ctor:
00034 Block::Block(World* parent)
00035         : VisualObject(parent),
00036           m_block_index(0),
00037           m_b2d_block_body(NULL),
00038           m_q(0, 0, 0, 0, 0, 0),
00039           m_dq(0, 0, 0),
00040           m_mass(30.0),
00041           m_block_z_min(0.0),
00042           m_block_z_max(1.0),
00043           m_block_color(0x00, 0x00, 0xff),
00044           m_block_com(.0, .0),
00045           m_lateral_friction(0.5),
00046           m_ground_friction(0.5),
00047           m_restitution(0.01)
00048 {
00049         using namespace mrpt::math;
00050         // Default shape:
00051         m_block_poly.push_back(TPoint2D(-0.5, -0.5));
00052         m_block_poly.push_back(TPoint2D(-0.5, 0.5));
00053         m_block_poly.push_back(TPoint2D(0.5, 0.5));
00054         m_block_poly.push_back(TPoint2D(0.5, -0.5));
00055         updateMaxRadiusFromPoly();
00056 }
00057 
00058 void Block::simul_post_timestep_common(const TSimulContext& /*context*/)
00059 {
00060         if (m_b2d_block_body)
00061         {
00062                 // Pos:
00063                 const b2Vec2& pos = m_b2d_block_body->GetPosition();
00064                 const float32 angle = m_b2d_block_body->GetAngle();
00065                 m_q.x = pos(0);
00066                 m_q.y = pos(1);
00067                 m_q.yaw = angle;
00068                 // The rest (z,pitch,roll) will be always 0, unless other world-element
00069                 // modifies them! (e.g. elevation map)
00070 
00071                 // Vel:
00072                 const b2Vec2& vel = m_b2d_block_body->GetLinearVelocity();
00073                 const float32 w = m_b2d_block_body->GetAngularVelocity();
00074                 m_dq.vals[0] = vel(0);
00075                 m_dq.vals[1] = vel(1);
00076                 m_dq.vals[2] = w;
00077         }
00078 }
00079 
00082 void Block::register_block_class(const rapidxml::xml_node<char>* xml_node)
00083 {
00084         // Sanity checks:
00085         if (!xml_node)
00086                 throw runtime_error("[Block::register_vehicle_class] XML node is NULL");
00087         if (0 != strcmp(xml_node->name(), "block:class"))
00088                 throw runtime_error(
00089                         mrpt::format(
00090                                 "[Block::register_block_class] XML element is '%s' "
00091                                 "('block:class' expected)",
00092                                 xml_node->name()));
00093 
00094         // rapidxml doesn't allow making copied of objects.
00095         // So: convert to txt; then re-parse.
00096         std::stringstream ss;
00097         ss << *xml_node;
00098 
00099         block_classes_registry.add(ss.str());
00100 }
00101 
00104 Block* Block::factory(World* parent, const rapidxml::xml_node<char>* root)
00105 {
00106         using namespace std;
00107         using namespace rapidxml;
00108 
00109         if (!root) throw runtime_error("[Block::factory] XML node is NULL");
00110         if (0 != strcmp(root->name(), "block"))
00111                 throw runtime_error(
00112                         mrpt::format(
00113                                 "[Block::factory] XML root element is '%s' ('block' expected)",
00114                                 root->name()));
00115 
00116         // "class": When there is a 'class="XXX"' attribute, look for each parameter
00117         //  in the set of "root" + "class_root" XML nodes:
00118         // --------------------------------------------------------------------------------
00119         JointXMLnode<> block_root_node;
00120         const rapidxml::xml_node<char>* class_root = NULL;
00121         {
00122                 block_root_node.add(
00123                         root);  // Always search in root. Also in the class root, if any:
00124                 const xml_attribute<>* block_class = root->first_attribute("class");
00125                 if (block_class)
00126                 {
00127                         const string sClassName = block_class->value();
00128                         class_root = block_classes_registry.get(sClassName);
00129                         if (!class_root)
00130                                 throw runtime_error(
00131                                         mrpt::format(
00132                                                 "[Block::factory] Block class '%s' undefined",
00133                                                 sClassName.c_str()));
00134                         block_root_node.add(class_root);
00135                 }
00136         }
00137 
00138         // Build object (we don't use class factory for blocks)
00139         // ----------------------------------------------------
00140         Block* block = new Block(parent);
00141 
00142         // Init params
00143         // -------------------------------------------------
00144         // attrib: name
00145         {
00146                 const xml_attribute<>* attrib_name = root->first_attribute("name");
00147                 if (attrib_name && attrib_name->value())
00148                 {
00149                         block->m_name = attrib_name->value();
00150                 }
00151                 else
00152                 {
00153                         // Default name:
00154                         static int cnt = 0;
00155                         block->m_name = mrpt::format("block%i", ++cnt);
00156                 }
00157         }
00158 
00159         // (Mandatory) initial pose:
00160         {
00161                 const xml_node<>* node = block_root_node.first_node("init_pose");
00162                 if (!node)
00163                         throw runtime_error(
00164                                 "[Block::factory] Missing XML node <init_pose>");
00165 
00166                 if (3 != ::sscanf(
00167                                          node->value(), "%lf %lf %lf", &block->m_q.x, &block->m_q.y,
00168                                          &block->m_q.yaw))
00169                         throw runtime_error(
00170                                 "[Block::factory] Error parsing <init_pose>...</init_pose>");
00171                 block->m_q.yaw *= M_PI / 180.0;  // deg->rad
00172         }
00173 
00174         // (Optional) initial vel:
00175         {
00176                 const xml_node<>* node = block_root_node.first_node("init_vel");
00177                 if (node)
00178                 {
00179                         if (3 != ::sscanf(
00180                                                  node->value(), "%lf %lf %lf", &block->m_dq.vals[0],
00181                                                  &block->m_dq.vals[1], &block->m_dq.vals[2]))
00182                                 throw runtime_error(
00183                                         "[Block::factory] Error parsing <init_vel>...</init_vel>");
00184                         block->m_dq.vals[2] *= M_PI / 180.0;  // deg->rad
00185 
00186                         // Convert twist (velocity) from local -> global coords:
00187                         const mrpt::poses::CPose2D pose(
00188                                 0, 0, block->m_q.yaw);  // Only the rotation
00189                         pose.composePoint(
00190                                 block->m_dq.vals[0], block->m_dq.vals[1], block->m_dq.vals[0],
00191                                 block->m_dq.vals[1]);
00192                 }
00193         }
00194 
00195         // Params:
00196         std::map<std::string, TParamEntry> params;
00197         params["mass"] = TParamEntry("%lf", &block->m_mass);
00198         params["zmin"] = TParamEntry("%lf", &block->m_block_z_min);
00199         params["zmax"] = TParamEntry("%lf", &block->m_block_z_max);
00200         params["ground_friction"] = TParamEntry("%lf", &block->m_ground_friction);
00201         params["lateral_friction"] = TParamEntry("%lf", &block->m_lateral_friction);
00202         params["restitution"] = TParamEntry("%lf", &block->m_restitution);
00203         params["color"] = TParamEntry("%color", &block->m_block_color);
00204 
00205         parse_xmlnode_children_as_param(*root, params, "[Block::factory]");
00206         if (class_root)
00207                 parse_xmlnode_children_as_param(
00208                         *class_root, params, "[Block::factory]");
00209 
00210         // Shape node (optional, fallback to default shape if none found)
00211         const rapidxml::xml_node<char>* xml_shape =
00212                 block_root_node.first_node("shape");
00213         if (xml_shape)
00214         {
00215                 mvsim::parse_xmlnode_shape(
00216                         *xml_shape, block->m_block_poly, "[Block::factory]");
00217                 block->updateMaxRadiusFromPoly();
00218         }
00219 
00220         // Register bodies, fixtures, etc. in Box2D simulator:
00221         // ----------------------------------------------------
00222         b2World* b2world = parent->getBox2DWorld();
00223         block->create_multibody_system(b2world);
00224 
00225         if (block->m_b2d_block_body)
00226         {
00227                 // Init pos:
00228                 block->m_b2d_block_body->SetTransform(
00229                         b2Vec2(block->m_q.x, block->m_q.y), block->m_q.yaw);
00230                 // Init vel:
00231                 block->m_b2d_block_body->SetLinearVelocity(
00232                         b2Vec2(block->m_dq.vals[0], block->m_dq.vals[1]));
00233                 block->m_b2d_block_body->SetAngularVelocity(block->m_dq.vals[2]);
00234         }
00235 
00236         return block;
00237 }
00238 
00239 Block* Block::factory(World* parent, const std::string& xml_text)
00240 {
00241         // Parse the string as if it was an XML file:
00242         std::stringstream s;
00243         s.str(xml_text);
00244 
00245         char* input_str = const_cast<char*>(xml_text.c_str());
00246         rapidxml::xml_document<> xml;
00247         try
00248         {
00249                 xml.parse<0>(input_str);
00250         }
00251         catch (rapidxml::parse_error& e)
00252         {
00253                 unsigned int line =
00254                         static_cast<long>(std::count(input_str, e.where<char>(), '\n') + 1);
00255                 throw std::runtime_error(
00256                         mrpt::format(
00257                                 "[Block::factory] XML parse error (Line %u): %s",
00258                                 static_cast<unsigned>(line), e.what()));
00259         }
00260         return Block::factory(parent, xml.first_node());
00261 }
00262 
00263 void Block::simul_pre_timestep(const TSimulContext& context) {}
00266 void Block::simul_post_timestep(const TSimulContext& context) {}
00268 vec3 Block::getVelocityLocal() const
00269 {
00270         vec3 local_vel;
00271         local_vel.vals[2] = m_dq.vals[2];  // omega remains the same.
00272 
00273         const mrpt::poses::CPose2D p(0, 0, -m_q.yaw);  // "-" means inverse pose
00274         p.composePoint(
00275                 m_dq.vals[0], m_dq.vals[1], local_vel.vals[0], local_vel.vals[1]);
00276         return local_vel;
00277 }
00278 
00279 mrpt::poses::CPose2D Block::getCPose2D() const
00280 {
00281         return mrpt::poses::CPose2D(mrpt::math::TPose2D(m_q));
00282 }
00283 
00285 void Block::gui_update(mrpt::opengl::COpenGLScene& scene)
00286 {
00287         // 1st time call?? -> Create objects
00288         // ----------------------------------
00289         if (!m_gl_block)
00290         {
00291                 m_gl_block = mrpt::make_aligned_shared<mrpt::opengl::CSetOfObjects>();
00292 
00293                 // Block shape:
00294                 mrpt::opengl::CPolyhedron::Ptr gl_poly =
00295                         mrpt::opengl::CPolyhedron::CreateCustomPrism(
00296                                 m_block_poly, m_block_z_max - m_block_z_min);
00297                 gl_poly->setLocation(0, 0, m_block_z_min);
00298                 gl_poly->setColor(mrpt::utils::TColorf(m_block_color));
00299                 m_gl_block->insert(gl_poly);
00300 
00301                 SCENE_INSERT_Z_ORDER(scene, 1, m_gl_block);
00302 
00303                 // Visualization of forces:
00304                 m_gl_forces = mrpt::make_aligned_shared<mrpt::opengl::CSetOfLines>();
00305                 m_gl_forces->setLineWidth(3.0);
00306                 m_gl_forces->setColor_u8(mrpt::utils::TColor(0xff, 0xff, 0xff));
00307 
00308                 SCENE_INSERT_Z_ORDER(
00309                         scene, 3, m_gl_forces);  // forces are in global coords
00310         }
00311 
00312         // Update them:
00313         m_gl_block->setPose(m_q);
00314 
00315         // Other common stuff:
00316         internal_gui_update_forces(scene);
00317 }
00318 
00319 void Block::internal_gui_update_forces(mrpt::opengl::COpenGLScene& scene)
00320 {
00321         if (m_world->m_gui_options.show_forces)
00322         {
00323                 std::lock_guard<std::mutex> csl(m_force_segments_for_rendering_cs);
00324                 m_gl_forces->clear();
00325                 m_gl_forces->appendLines(m_force_segments_for_rendering);
00326                 m_gl_forces->setVisibility(true);
00327         }
00328         else
00329         {
00330                 m_gl_forces->setVisibility(false);
00331         }
00332 }
00333 
00334 void Block::updateMaxRadiusFromPoly()
00335 {
00336         using namespace mrpt::math;
00337 
00338         m_max_radius = 0.001f;
00339         for (TPolygon2D::const_iterator it = m_block_poly.begin();
00340                  it != m_block_poly.end(); ++it)
00341         {
00342                 const float n = it->norm();
00343                 mrpt::utils::keep_max(m_max_radius, n);
00344         }
00345 }
00346 
00348 void Block::create_multibody_system(b2World* world)
00349 {
00350         // Define the dynamic body. We set its position and call the body factory.
00351         b2BodyDef bodyDef;
00352         bodyDef.type = b2_dynamicBody;
00353 
00354         m_b2d_block_body = world->CreateBody(&bodyDef);
00355 
00356         // Define shape of block:
00357         // ------------------------------
00358         {
00359                 // Convert shape into Box2D format:
00360                 const size_t nPts = m_block_poly.size();
00361                 ASSERT_(nPts >= 3)
00362                 ASSERT_BELOWEQ_(nPts, (size_t)b2_maxPolygonVertices)
00363                 std::vector<b2Vec2> pts(nPts);
00364                 for (size_t i = 0; i < nPts; i++)
00365                         pts[i] = b2Vec2(m_block_poly[i].x, m_block_poly[i].y);
00366 
00367                 b2PolygonShape blockPoly;
00368                 blockPoly.Set(&pts[0], nPts);
00369                 // blockPoly.m_radius = 1e-3;  // The "skin" depth of the body
00370 
00371                 // Define the dynamic body fixture.
00372                 b2FixtureDef fixtureDef;
00373                 fixtureDef.shape = &blockPoly;
00374                 fixtureDef.restitution = m_restitution;
00375 
00376                 // Set the box density to be non-zero, so it will be dynamic.
00377                 b2MassData mass;
00378                 blockPoly.ComputeMass(&mass, 1);  // Mass with density=1 => compute area
00379                 fixtureDef.density = m_mass / mass.mass;
00380 
00381                 // Override the default friction.
00382                 fixtureDef.friction = m_lateral_friction;  // 0.3f;
00383 
00384                 // Add the shape to the body.
00385                 m_fixture_block = m_b2d_block_body->CreateFixture(&fixtureDef);
00386 
00387                 // Compute center of mass:
00388                 b2MassData vehMass;
00389                 m_fixture_block->GetMassData(&vehMass);
00390                 m_block_com.x = vehMass.center.x;
00391                 m_block_com.y = vehMass.center.y;
00392         }
00393 
00394         // Create "archor points" to simulate friction with the ground:
00395         // -----------------------------------------------------------------
00396         const size_t nContactPoints = 2;
00397         const double weight_per_contact_point =
00398                 m_mass * getWorldObject()->get_gravity() / nContactPoints;
00399         const double mu = m_ground_friction;
00400         const double max_friction = mu * weight_per_contact_point;
00401 
00402         // Location (local coords) of each contact-point:
00403         const vec2 pt_loc[nContactPoints] = {vec2(m_max_radius, 0),
00404                                                                                  vec2(-m_max_radius, 0)};
00405 
00406         b2FrictionJointDef fjd;
00407 
00408         fjd.bodyA = m_world->getBox2DGroundBody();
00409         fjd.bodyB = m_b2d_block_body;
00410 
00411         for (size_t i = 0; i < nContactPoints; i++)
00412         {
00413                 const b2Vec2 local_pt = b2Vec2(pt_loc[i].vals[0], pt_loc[i].vals[1]);
00414 
00415                 fjd.localAnchorA = m_b2d_block_body->GetWorldPoint(local_pt);
00416                 fjd.localAnchorB = local_pt;
00417                 fjd.maxForce = max_friction;
00418                 fjd.maxTorque = 0;
00419 
00420                 b2FrictionJoint* b2_friction = dynamic_cast<b2FrictionJoint*>(
00421                         m_world->getBox2DWorld()->CreateJoint(&fjd));
00422                 m_friction_joints.push_back(b2_friction);
00423         }
00424 }
00425 
00426 void Block::apply_force(
00427         double fx, double fy, double local_ptx, double local_pty)
00428 {
00429         ASSERT_(m_b2d_block_body)
00430         const b2Vec2 wPt = m_b2d_block_body->GetWorldPoint(
00431                 b2Vec2(local_ptx, local_pty));  // Application point -> world coords
00432         m_b2d_block_body->ApplyForce(b2Vec2(fx, fy), wPt, true /*wake up*/);
00433 }


mvsim
Author(s):
autogenerated on Thu Sep 7 2017 09:27:48