25 const float resolution = 0.10;
48 scene->insert(gl_grid);
54 gl_map->showGridLines(
false);
57 scene->insert(gl_map);
59 win.unlockAccess3DScene();
62 std::cout <<
"Close the window to exit" << std::endl;
64 bool update_msg =
true;
70 const unsigned int k =
win.getPushedKey();
76 gl_map->showGridLines(!gl_map->areGridLinesVisible());
82 !gl_map->areVoxelsVisible(
89 !gl_map->areVoxelsVisible(
94 gl_map->enableLights(!gl_map->areLightsEnabled());
107 "Commands: 'g' (grids=%s) | 'f' (freespace=%s) | 'o' " 108 "(occupied=%s) | 'l' (lights=%s)",
109 gl_map->areGridLinesVisible() ?
"YES" :
"NO",
116 gl_map->areLightsEnabled() ?
"YES" :
"NO"));
121 using namespace std::chrono_literals;
122 std::this_thread::sleep_for(10ms);
126 int main([[maybe_unused]]
int argc, [[maybe_unused]]
char**
argv)
133 catch (
const std::exception& e)
TRenderingOptions renderingOptions
std::string std::string format(std::string_view fmt, ARGS &&... args)
void example2DRangeScan(mrpt::obs::CObservation2DRangeScan &s, int i=0)
Example 2D lidar scans (form a venerable SICK LMS200).
void setSize(const mrpt::math::TPoint3D &corner_min, const mrpt::math::TPoint3D &corner_max, double resolution, float default_value=0.5f)
Change the size of gridmap, erasing all its previous contents.
static Ptr Create(Args &&... args)
mrpt::gui::CDisplayWindow3D::Ptr win
void getAsOctoMapVoxels(mrpt::opengl::COctoMapVoxels &gl_obj) const
A 3D occupancy grid map with a regular, even distribution of voxels.
A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser sc...
bool generateGridLines
Generate grid lines for all octree nodes, useful to draw the "structure" of the octree, but computationally costly (Default: false)
std::string exception_to_str(const std::exception &e)
Builds a nice textual representation of a nested exception, which if generated using MRPT macros (THR...
static Ptr Create(Args &&... args)
bool insertObservation(const mrpt::obs::CObservation &obs, const mrpt::poses::CPose3D *robotPose=nullptr)
Insert the observation information into this map.
A graphical user interface (GUI) for efficiently rendering 3D scenes in real-time.