15 #include <mrpt/opengl/COpenGLScene.h>    16 #include <mrpt/opengl/CPointCloud.h>    17 #include <mrpt/tfest.h>      21 using namespace mvsim;
    34         std::map<std::string, TParamEntry> params;
    36         std::string sElevationImgFile;
    37         params[
"elevation_image"] = 
TParamEntry(
"%s", &sElevationImgFile);
    38         std::string sTextureImgFile;
    39         params[
"texture_image"] = 
TParamEntry(
"%s", &sTextureImgFile);
    41         double img_min_z = 0.0, img_max_z = 5.0;
    42         params[
"elevation_image_min_z"] = 
TParamEntry(
"%lf", &img_min_z);
    43         params[
"elevation_image_max_z"] = 
TParamEntry(
"%lf", &img_max_z);
    45         TColor mesh_color(0xa0, 0xe0, 0xa0);
    46         params[
"mesh_color"] = 
TParamEntry(
"%color", &mesh_color);
    53         mrpt::math::CMatrixFloat elevation_data;
    54         if (!sElevationImgFile.empty())
    57                 if (!imgElev.loadFromFile(
    58                                 sElevationImgFile, 0 ))
    59                         throw std::runtime_error(mrpt::format(
    60                                 "[ElevationMap] ERROR: Cannot read elevation image '%s'",
    61                                 sElevationImgFile.c_str()));
    66                 ASSERT_(img_min_z != img_max_z);
    67 #if MRPT_VERSION >= 0x199    68                 const double vmin = elevation_data.minCoeff();
    69                 const double vmax = elevation_data.maxCoeff();
    70                 mrpt::math::CMatrixFloat 
f = elevation_data;
    72                 f *= (img_max_z - img_min_z) / (vmax - vmin);
    73                 mrpt::math::CMatrixFloat m(
    74                         elevation_data.rows(), elevation_data.cols());
    75                 m.setConstant(img_min_z);
    79                 elevation_data.adjustRange(img_min_z, img_max_z);
    84                 MRPT_TODO(
"Imgs or txt matrix")
    89         bool has_mesh_image = 
false;
    90         if (!sTextureImgFile.empty())
    92                 if (!mesh_image.loadFromFile(sTextureImgFile))
    93                         throw std::runtime_error(mrpt::format(
    94                                 "[ElevationMap] ERROR: Cannot read texture image '%s'",
    95                                 sTextureImgFile.c_str()));
    96                 has_mesh_image = 
true;
   100         m_gl_mesh = mrpt::opengl::CMesh::Create();
   106                 ASSERT_EQUAL_(mesh_image.getWidth(), (size_t)elevation_data.cols());
   107                 ASSERT_EQUAL_(mesh_image.getHeight(), (size_t)elevation_data.rows());
   122         const double LX = (elevation_data.cols() - 1) * 
m_resolution;
   123         const double LY = (elevation_data.rows() - 1) * 
m_resolution;
   124         m_gl_mesh->setGridLimits(-0.5 * LX, 0.5 * LX, -0.5 * LY, 0.5 * LY);
   133                 "ERROR: Can't render Mesh before loading it! Have you called "   134                 "loadConfigFrom() first?");
   154         for (World::TListVehicles::const_iterator itVeh = lstVehs.begin();
   155                  itVeh != lstVehs.end(); ++itVeh)
   159                 const size_t nWheels = itVeh->second->getNumWheels();
   167                 mrpt::math::TPoint3D dir_down;  
   170                 for (
int iter = 0; iter < 3; iter++)
   172                         const mrpt::math::TPose3D& cur_pose = itVeh->second->getPose();
   173                         const mrpt::poses::CPose3D cur_cpose(cur_pose);  
   178                         mrpt::math::TPose3D new_pose = cur_pose;
   184                         bool out_of_area = 
false;
   185                         for (
size_t iW = 0; !out_of_area && iW < nWheels; iW++)
   187                                 const Wheel& wheel = itVeh->second->getWheelInfo(iW);
   193                                 corr.other_x = wheel.
x;
   194                                 corr.other_y = wheel.
y;
   198                                 mrpt::math::TPoint3D gPt;
   199                                 cur_cpose.composePoint(
   200                                         wheel.
x, wheel.
y, 0.0, gPt.x, gPt.y, gPt.z);
   213                                 corrs.push_back(corr);
   215                         if (out_of_area) 
continue;
   219                         mrpt::poses::CPose3DQuat tmpl;
   222                                 corrs, tmpl, transf_scale, 
true );
   232                         itVeh->second->setPose(new_pose);
   237                         mrpt::poses::CPose3D rot_only;
   239                         rot_only.inverseComposePoint(
   240                                 .0, .0, -1.0, dir_down.x, dir_down.y, dir_down.z);
   247                         const double chassis_weight =
   248                                 itVeh->second->getChassisMass() * gravity;
   249                         const mrpt::math::TPoint2D chassis_com =
   250                                 itVeh->second->getChassisCenterOfMass();
   251                         itVeh->second->apply_force(
   252                                 dir_down.x * chassis_weight, dir_down.y * chassis_weight,
   253                                 chassis_com.x, chassis_com.y);
   256                         for (
size_t iW = 0; iW < nWheels; iW++)
   258                                 const Wheel& wheel = itVeh->second->getWheelInfo(iW);
   259                                 const double wheel_weight = wheel.
mass * gravity;
   260                                 itVeh->second->apply_force(
   261                                         dir_down.x * wheel_weight, dir_down.y * wheel_weight,
   273                 "Save all elements positions in prestep, then here scale their "   274                 "movements * cos(angle)");
   277         const mrpt::math::TPoint3Df& p1, 
const mrpt::math::TPoint3Df& p2,
   278         const mrpt::math::TPoint3Df& p3, 
float x, 
float y)
   281                 (p2.x - p3.x) * (p1.y - p3.y) + (p3.y - p2.y) * (p1.x - p3.x);
   282         ASSERT_(det != 0.0
f);
   285                 ((p2.x - p3.x) * (y - p3.y) + (p3.y - p2.y) * (x - p3.x)) / det;
   287                 ((p3.x - p1.x) * (y - p3.y) + (p1.y - p3.y) * (x - p3.x)) / det;
   288         const float l3 = 1.0f - l1 - l2;
   290         return l1 * p1.z + l2 * p2.z + l3 * p3.z;
   295         const mrpt::opengl::CMesh* mesh = 
m_gl_mesh.get();
   296         const float x0 = mesh->getXMin();
   297         const float y0 = mesh->getYMin();
   304         if (cx00 < 1 || cx00 >= 
int(nCellsX - 1) || cy00 < 1 ||
   305                 cy00 >= 
int(nCellsY - 1))
   319         const mrpt::math::TPoint3Df p00(.0
f, .0
f, z00);
   328                 z = 
calcz(p00, p01, p11, lx, ly);
   330                 z = 
calcz(p00, p10, p11, lx, ly);
 virtual void simul_pre_timestep(const TSimulContext &context)
See docs in base class. 
This file contains rapidxml parser and DOM implementation. 
virtual void gui_update(mrpt::opengl::COpenGLScene &scene)
See docs in base class. 
std::multimap< std::string, VehicleBase * > TListVehicles
virtual void simul_post_timestep(const TSimulContext &context)
See docs in base class. 
virtual void loadConfigFrom(const rapidxml::xml_node< char > *root)
See docs in base class. 
double get_gravity() const 
bool m_first_scene_rendering
CTimeLogger & getTimeLogger()
void parse_xmlnode_children_as_param(const rapidxml::xml_node< char > &xml_node, const std::map< std::string, TParamEntry > ¶ms, const char *function_name_context="")
#define SCENE_INSERT_Z_ORDER(_SCENE, _ZORDER_INDEX, _OBJ_TO_INSERT)
TFSIMD_FORCE_INLINE const tfScalar & z() const 
mrpt::opengl::CMesh::Ptr m_gl_mesh
const TListVehicles & getListOfVehicles() const 
mrpt::math::CMatrixFloat m_mesh_z_cache
bool getElevationAt(double x, double y, float &z) const 
return false if out of bounds 
float calcz(const mrpt::math::TPoint3Df &p1, const mrpt::math::TPoint3Df &p2, const mrpt::math::TPoint3Df &p3, float x, float y)
mrpt::poses::CPose3D m_optimal_transf