10 #include <mrpt/opengl/COpenGLScene.h>
11 #include <mrpt/opengl/CPolyhedron.h>
12 #include <mrpt/opengl/CSetOfObjects.h>
13 #include <mrpt/version.h>
27 using namespace mvsim;
33 World* parent,
bool insertCustomVizIntoViz,
bool insertCustomVizIntoPhysical)
35 insertCustomVizIntoViz_(insertCustomVizIntoViz),
36 insertCustomVizIntoPhysical_(insertCustomVizIntoPhysical)
45 const mrpt::optional_ref<mrpt::opengl::COpenGLScene>& viz,
46 const mrpt::optional_ref<mrpt::opengl::COpenGLScene>& physical)
48 using namespace std::string_literals;
50 const auto* meSim =
dynamic_cast<Simulable*
>(
this);
56 const auto objectPoseOrg = viz.has_value() ? meSim->getPose() : meSim->getPoseNoLock();
86 const double height = cs.zMax() - cs.zMin();
87 ASSERT_(height == height);
90 const auto c = cs.getContour();
95 const auto savedMrptGeomEps = mrpt::math::getEpsilon();
97 double smallestEdge = std::abs(height);
98 for (
size_t i = 0; i < c.size(); i++)
100 size_t im1 = i == 0 ? c.size() - 1 : i - 1;
101 const auto Ap = c[i] - c[im1];
102 mrpt::keep_min(smallestEdge, Ap.norm());
104 mrpt::math::setEpsilon(1e-5 * smallestEdge);
106 mrpt::opengl::CPolyhedron::Ptr glCS;
110 glCS = mrpt::opengl::CPolyhedron::CreateCustomPrism(c, height);
112 catch (
const std::exception& e)
115 std::cerr <<
"[mvsim::VisualObject] **WARNING**: Ignoring the "
116 "following error while building the visualization "
117 "of the collision shape for object named '"
119 <<
"' placed by pose=" << meSim->getPose()
120 <<
"). Falling back to rectangular collision shape "
121 "from bounding box:\n"
122 << e.what() << std::endl;
125 mrpt::math::TPoint2D bbMax, bbMin;
126 cs.getContour().getBoundingBox(bbMin, bbMax);
127 mrpt::math::TPolygon2D p;
128 p.emplace_back(bbMin.x, bbMin.y);
129 p.emplace_back(bbMin.x, bbMax.y);
130 p.emplace_back(bbMax.x, bbMax.y);
131 p.emplace_back(bbMax.x, bbMin.y);
132 glCS = mrpt::opengl::CPolyhedron::CreateCustomPrism(p, height);
134 glCS->setWireframe(
true);
136 mrpt::math::setEpsilon(savedMrptGeomEps);
139 glCS->setLocation(0, 0, cs.zMin());
190 bool visualEnabled =
true;
192 auxPar[
"enabled"] =
TParamEntry(
"%bool", &visualEnabled);
201 std::string modelURI;
202 double modelScale = 1.0;
203 mrpt::math::TPose3D modelPose;
204 bool initialShowBoundingBox =
false;
205 std::string objectName =
"group";
210 params[
"model_uri"] =
TParamEntry(
"%s", &modelURI);
211 params[
"model_scale"] =
TParamEntry(
"%lf", &modelScale);
212 params[
"model_offset_x"] =
TParamEntry(
"%lf", &modelPose.x);
213 params[
"model_offset_y"] =
TParamEntry(
"%lf", &modelPose.y);
214 params[
"model_offset_z"] =
TParamEntry(
"%lf", &modelPose.z);
215 params[
"model_yaw"] =
TParamEntry(
"%lf_deg", &modelPose.yaw);
216 params[
"model_pitch"] =
TParamEntry(
"%lf_deg", &modelPose.pitch);
217 params[
"model_roll"] =
TParamEntry(
"%lf_deg", &modelPose.roll);
218 params[
"show_bounding_box"] =
TParamEntry(
"%bool", &initialShowBoundingBox);
227 if (modelURI.empty())
return false;
233 auto glModel = gModelsCache.get(localFileName, opts);
237 glModel, mrpt::poses::CPose3D(modelPose), modelScale, objectName, modelURI);
263 const mrpt::opengl::CRenderizable::Ptr& glModel,
const mrpt::poses::CPose3D& modelPose,
264 const float modelScale,
const std::string& modelName,
265 const std::optional<std::string>& modelURI,
const bool initialShowBoundingBox)
271 float zMin = -std::numeric_limits<float>::max();
272 float zMax = std::numeric_limits<float>::max();
274 if (
const Block* block =
dynamic_cast<const Block*
>(
this);
281 std::cout <<
"MODEL: " << (modelURI ? *modelURI :
"none")
282 <<
" glModel: " << glModel->GetRuntimeClass()->className
283 <<
" modelScale: " << modelScale <<
" zmin=" << zMin
284 <<
" zMax:" << zMax <<
"\n";
288 const auto shape = chc.get(*glModel, zMin, zMax, modelPose, modelScale, modelURI);
290 auto glGroup = mrpt::opengl::CSetOfObjects::Create();
294 glGroup->insert(glModel);
295 glGroup->setScale(modelScale);
296 glGroup->setPose(modelPose);
298 glGroup->setName(modelName);