21 using namespace mvsim;
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 mrpt::img::TColor mesh_color(0xa0, 0xe0, 0xa0);
46 params[
"mesh_color"] =
TParamEntry(
"%color", &mesh_color);
54 if (!sElevationImgFile.empty())
58 mrpt::img::CImage imgElev;
59 if (!imgElev.loadFromFile(
60 sElevationImgFile, 0 ))
62 "[ElevationMap] ERROR: Cannot read elevation image '%s'",
63 sElevationImgFile.c_str()));
67 imgElev.getAsMatrix(elevation_data);
68 ASSERT_(img_min_z != img_max_z);
70 const double vmin = elevation_data.minCoeff();
71 const double vmax = elevation_data.maxCoeff();
74 f *= (img_max_z - img_min_z) / (vmax - vmin);
76 elevation_data.rows(), elevation_data.cols());
77 m.setConstant(img_min_z);
79 elevation_data = std::move(f);
87 mrpt::img::CImage mesh_image;
88 bool has_mesh_image =
false;
89 if (!sTextureImgFile.empty())
93 if (!mesh_image.loadFromFile(sTextureImgFile))
95 "[ElevationMap] ERROR: Cannot read texture image '%s'",
96 sTextureImgFile.c_str()));
97 has_mesh_image =
true;
107 ASSERT_EQUAL_(mesh_image.getWidth(), (size_t)elevation_data.cols());
108 ASSERT_EQUAL_(mesh_image.getHeight(), (size_t)elevation_data.rows());
110 m_gl_mesh->assignImageAndZ(mesh_image, elevation_data);
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);
134 "ERROR: Can't render Mesh before loading it! Have you called " 135 "loadConfigFrom() first?");
155 for (World::VehicleList::const_iterator itVeh = lstVehs.begin();
156 itVeh != lstVehs.end(); ++itVeh)
160 const size_t nWheels = itVeh->second->getNumWheels();
171 for (
int iter = 0; iter < 2; iter++)
180 bool out_of_area =
false;
181 for (
size_t iW = 0; !out_of_area && iW < nWheels; iW++)
183 const Wheel& wheel = itVeh->second->getWheelInfo(iW);
186 mrpt::tfest::TMatchingPair corr;
189 corr.other_x = wheel.
x;
190 corr.other_y = wheel.
y;
208 corrs.push_back(corr);
210 if (out_of_area)
continue;
217 corrs, tmpl, transf_scale,
true );
227 itVeh->second->setPose(new_pose);
235 .0, .0, -1.0, dir_down.
x, dir_down.
y, dir_down.
z);
242 const double chassis_weight =
243 itVeh->second->getChassisMass() * gravity;
245 itVeh->second->getChassisCenterOfMass();
246 itVeh->second->apply_force(
247 {dir_down.
x * chassis_weight, dir_down.
y * chassis_weight},
251 for (
size_t iW = 0; iW < nWheels; iW++)
253 const Wheel& wheel = itVeh->second->getWheelInfo(iW);
254 const double wheel_weight = wheel.
mass * gravity;
255 itVeh->second->apply_force(
256 {dir_down.
x * wheel_weight, dir_down.
y * wheel_weight},
270 "Save all elements positions in prestep, then here scale their " 271 "movements * cos(angle)");
279 (p2.
x - p3.
x) * (p1.
y - p3.
y) + (p3.
y - p2.
y) * (p1.
x - p3.
x);
283 ((p2.
x - p3.
x) * (y - p3.
y) + (p3.
y - p2.
y) * (x - p3.
x)) / det;
285 ((p3.
x - p1.
x) * (y - p3.
y) + (p1.
y - p3.
y) * (x - p3.
x)) / det;
286 const float l3 = 1.0f - l1 - l2;
288 return l1 * p1.
z + l2 * p2.
z + l3 * p3.
z;
294 const float x0 = mesh->getxMin();
295 const float y0 = mesh->getyMin();
303 if (cx00 < 1 || cx00 >=
int(nCellsX - 1) || cy00 < 1 ||
304 cy00 >=
int(nCellsY - 1))
327 z =
calcz(p00, p01, p11, lx, ly);
329 z =
calcz(p00, p10, p11, lx, ly);
#define ASSERT_EQUAL_(__A, __B)
This file contains rapidxml parser and DOM implementation.
GLint GLint GLint GLint GLint GLint y
std::map< std::string, TParamEntry > TParameterDefinitions
mrpt::tfest::TMatchingPairList corrs
virtual void loadConfigFrom(const rapidxml::xml_node< char > *root) override
void parse_xmlnode_children_as_param(const rapidxml::xml_node< char > &xml_node, const TParameterDefinitions ¶ms, const std::map< std::string, std::string > &variableNamesValues={}, const char *functionNameContext="")
const VehicleList & getListOfVehicles() const
virtual void simul_pre_timestep(const TSimulContext &context) override
static CMeshPtr Create(bool enableTransparency, float xMin=0.0f, float xMax=0.0f, float yMin=0.0f, float yMax=0.0f)
std::multimap< std::string, VehicleBase::Ptr > VehicleList
void insert(const CRenderizablePtr &newObject, const std::string &viewportName=std::string("main"))
MRPT_TODO("Modify ping to run on Windows + Test this")
double get_gravity() const
bool m_first_scene_rendering
void composePoint(double lx, double ly, double lz, double &gx, double &gy, double &gz, mrpt::math::CMatrixFixedNumeric< double, 3, 3 > *out_jacobian_df_dpoint=NULL, mrpt::math::CMatrixFixedNumeric< double, 3, 6 > *out_jacobian_df_dpose=NULL, mrpt::math::CMatrixFixedNumeric< double, 3, 6 > *out_jacobian_df_dse3=NULL, bool use_small_rot_approx=false) const
virtual void internalGuiUpdate(mrpt::opengl::COpenGLScene &scene, bool childrenOnly) override
std::string resolvePath(const std::string &in_path) const
GLint GLint GLint GLint GLint x
bool TFEST_IMPEXP se3_l2(const mrpt::utils::TMatchingPairList &in_correspondences, mrpt::poses::CPose3DQuat &out_transform, double &out_scale, bool forceScaleToUnity=false)
std::string BASE_IMPEXP format(const char *fmt,...) MRPT_printf_format_check(1
virtual void simul_post_timestep(const TSimulContext &context)
static float calcz(const mrpt::math::TPoint3Df &p1, const mrpt::math::TPoint3Df &p2, const mrpt::math::TPoint3Df &p3, float x, float y)
mrpt::opengl::CMesh::Ptr m_gl_mesh
mrpt::system::CTimeLogger & getTimeLogger()
void getRotationMatrix(mrpt::math::CMatrixDouble33 &ROT) const
mrpt::math::CMatrixFloat m_mesh_z_cache
void inverseComposePoint(const double gx, const double gy, const double gz, double &lx, double &ly, double &lz, mrpt::math::CMatrixFixedNumeric< double, 3, 3 > *out_jacobian_df_dpoint=NULL, mrpt::math::CMatrixFixedNumeric< double, 3, 6 > *out_jacobian_df_dpose=NULL, mrpt::math::CMatrixFixedNumeric< double, 3, 6 > *out_jacobian_df_dse3=NULL) const
bool getElevationAt(double x, double y, float &z) const
return false if out of bounds
#define ASSERTMSG_(f, __ERROR_MSG)
EIGEN_STRONG_INLINE Scalar det() const
virtual void simul_post_timestep(const TSimulContext &context) override
void setRotationMatrix(const mrpt::math::CMatrixDouble33 &ROT)
mrpt::poses::CPose3D m_optimal_transf
GLdouble GLdouble GLdouble GLdouble GLdouble GLdouble f