Skip to content

Commit

Permalink
Merge branch 'develop'
Browse files Browse the repository at this point in the history
  • Loading branch information
jlblancoc committed Jul 8, 2023
2 parents 93af46d + d7ada4c commit 9abe4e1
Show file tree
Hide file tree
Showing 29 changed files with 218 additions and 45 deletions.
6 changes: 3 additions & 3 deletions appveyor.yml
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
# version format
version: 2.9.4-{branch}-build{build}
version: 2.10.0-{branch}-build{build}

os: Visual Studio 2019

Expand Down Expand Up @@ -41,8 +41,8 @@ install:
- tree c:\tools\opencv\build /F
- set OPENCVDIR=C:\tools\opencv\build\
# This variable is parsed by MRPT/cmakemodules/script_opencv.cmake:
- set OPENCV_DLLS_TO_INSTALL_DIRS=%OPENCVDIR%bin;%OPENCVDIR%x64\vc15\bin
- set PATH=%PATH%;%OPENCVDIR%\bin;%OPENCVDIR%\x64\vc15\bin
- set OPENCV_DLLS_TO_INSTALL_DIRS=%OPENCVDIR%bin;%OPENCVDIR%x64\vc16\bin
- set PATH=%PATH%;%OPENCVDIR%\bin;%OPENCVDIR%\x64\vc16\bin
# ====== Install wxWidgets
- cd c:\
- ps: Start-FileDownload 'https://github.com/wxWidgets/wxWidgets/releases/download/v3.1.3/wxMSW-3.1.3_vc14x_x64_Dev.7z'
Expand Down
10 changes: 10 additions & 0 deletions doc/source/doxygen-docs/changelog.md
Original file line number Diff line number Diff line change
@@ -1,5 +1,15 @@
\page changelog Change Log

# Version 2.10.0: Released July 9th, 2023
- Changes in libraries:
- \ref mrpt_opengl_grp
- Move the parameter eyeDistance2lightShadowExtension from TRenderMatrices to mrpt::opengl::TLightParameters so it can be changed from user code (ABI change).
- New parameter mrpt::opengl::TLightParameters::minimum_shadow_map_extension_ratio
- Python:
- More pymrpt examples.
- BUG FIXES:
- pymrpt was not automatically built when invoking the python tests using `make test_legacy`.

# Version 2.9.4: Released July 1st, 2023
- Python:
- pymrpt now ships stub `.pyi` files, for IDEs to autocomplete MRPT Python programs.
Expand Down
17 changes: 17 additions & 0 deletions doc/source/pymrpt_example_opengl-demo-gui.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
.. _pyexample_opengl-demo-gui:

====================================================
Python example: opengl-demo-gui.py
====================================================

This example illustrates how to create a 3D GUI in MRPT using the Python API
and populate it with different objects, including animating them across the scene.

.. raw:: html

<img src="https://mrpt.github.io/imgs/screenshot_pymrpt_example_opengl1.png" style="width: 90%;" />


.. literalinclude:: ../../python-examples/opengl-demo-gui.py
:language: python
:linenos:
1 change: 1 addition & 0 deletions doc/source/python_examples.rst
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@ C++ examples are `here <examples.html>`_.
pymrpt_example_hwdriver_tao_imu_usb.rst
pymrpt_example_lines-3d-geometry-example.rst
pymrpt_example_matrices.rst
pymrpt_example_opengl-demo-gui.rst
pymrpt_example_rbpf_slam.rst
pymrpt_example_ros-poses-convert.rst
pymrpt_example_se2-poses-example.rst
Expand Down
2 changes: 2 additions & 0 deletions libs/core/include/mrpt/core/common.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,8 @@
#pragma warning(disable : 4275) // DLL export class derived from STL
// Warnings are emited even if a DLL export class contains a *private* STL field
#pragma warning(disable : 4251)
// warning C4305: 'initializing': truncation from 'double' to 'float'
#pragma warning(disable : 4305)

#if (_MSC_VER >= 1400)
// MS believes they have the right to deprecate functions in the C++ Standard
Expand Down
16 changes: 16 additions & 0 deletions libs/opengl/include/mrpt/opengl/TLightParameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,22 @@ struct TLightParameters
float shadow_bias = 1e-5, shadow_bias_cam2frag = 1e-5,
shadow_bias_normal = 1e-4;

/** Multiplier from eye distance to the length size of the squared area in
* which to evaluate shadow casting by unidirectional light.
* Unitless (meter/meter).
* \note (New in MRPT 2.10.0)
*/
double eyeDistance2lightShadowExtension = 2.0;

/** Minimum extension (in [0,1] ratio of the light distance) of the shadow
* map square ortho frustum. Should be roughly the maximum area of the
* largest room for indoor environments to ensure no missing shadows in
* distant areas.
*
* \note (New in MRPT 2.10.0)
*/
float minimum_shadow_map_extension_ratio = 0.03f;

void writeToStream(mrpt::serialization::CArchive& out) const;
void readFromStream(mrpt::serialization::CArchive& in);

Expand Down
8 changes: 2 additions & 6 deletions libs/opengl/include/mrpt/opengl/TRenderMatrices.h
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
#include <mrpt/img/TCamera.h>
#include <mrpt/math/CMatrixFixed.h>
#include <mrpt/math/TPoint3D.h>
#include <mrpt/opengl/opengl_frwds.h>

namespace mrpt::opengl
{
Expand Down Expand Up @@ -84,11 +85,6 @@ struct TRenderMatrices
double azimuth = .0, elev = .0;
double eyeDistance = 1.0f;

/** Multiplier from eye distance to the length size of the squared area in
* which to evaluate shadow casting by unidirectional light.
*/
double eyeDistance2lightShadowExtension = 1.5;

/** In pixels. This may be smaller than the total render window. */
uint32_t viewport_width = 640, viewport_height = 480;

Expand Down Expand Up @@ -121,7 +117,7 @@ struct TRenderMatrices

/** Updates light_pv */
void computeLightProjectionMatrix(
float zmin, float zmax, const mrpt::math::TVector3Df& direction);
float zmin, float zmax, const TLightParameters& lp);

/** Especial case for custom parameters of Orthographic projection.
* Equivalent to `p_matrix = ortho(...);`.
Expand Down
10 changes: 7 additions & 3 deletions libs/opengl/src/TLightParameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,11 +18,13 @@ using namespace std;

void TLightParameters::writeToStream(mrpt::serialization::CArchive& out) const
{
const uint8_t version = 2;
const uint8_t version = 3;
out << version;

out << diffuse << ambient << specular << direction << color;
out << shadow_bias << shadow_bias_cam2frag << shadow_bias_normal; // v2
out << eyeDistance2lightShadowExtension
<< minimum_shadow_map_extension_ratio; // v3
}

void TLightParameters::readFromStream(mrpt::serialization::CArchive& in)
Expand All @@ -44,11 +46,13 @@ void TLightParameters::readFromStream(mrpt::serialization::CArchive& in)
break;
case 1:
case 2:
case 3:
in >> diffuse >> ambient >> specular >> direction >> color;
if (version >= 2)
{
in >> shadow_bias >> shadow_bias_cam2frag >> shadow_bias_normal;
}
if (version >= 3)
in >> eyeDistance2lightShadowExtension >>
minimum_shadow_map_extension_ratio;
break;
default: MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(version);
};
Expand Down
13 changes: 9 additions & 4 deletions libs/opengl/src/TRenderMatrices.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
#include <mrpt/containers/yaml.h>
#include <mrpt/math/geometry.h> // crossProduct3D()
#include <mrpt/math/ops_containers.h> // dotProduct()
#include <mrpt/opengl/TLightParameters.h>
#include <mrpt/opengl/TRenderMatrices.h>

#include <Eigen/Dense>
Expand Down Expand Up @@ -151,26 +152,30 @@ static void azimuthElevationFromDirection(
}

void TRenderMatrices::computeLightProjectionMatrix(
float zmin, float zmax, const mrpt::math::TVector3Df& direction)
float zmin, float zmax, const TLightParameters& lp)
{
m_last_light_z_near = zmin;
m_last_light_z_far = zmax;

float dist = eyeDistance * eyeDistance2lightShadowExtension;
float dist = eyeDistance * lp.eyeDistance2lightShadowExtension;

// Ensure dist is not too small:
mrpt::keep_max(dist, zmax * lp.minimum_shadow_map_extension_ratio);

light_p = OrthoProjectionMatrix(-dist, dist, -dist, dist, zmin, zmax);

// "up" vector from elevation:

float azim = 0, elevation = 0;
azimuthElevationFromDirection(direction, elevation, azim);
azimuthElevationFromDirection(lp.direction, elevation, azim);

const auto lightUp = mrpt::math::TVector3Df(
-cos(azim) * sin(elevation), // x
-sin(azim) * sin(elevation), // y
cos(elevation) // z
);

light_v = LookAt(pointing - direction * zmax * 0.5, pointing, lightUp);
light_v = LookAt(pointing - lp.direction * zmax * 0.5, pointing, lightUp);

light_pv.asEigen() = light_p.asEigen() * light_v.asEigen();

Expand Down
2 changes: 1 addition & 1 deletion libs/opengl/src/Viewport.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1302,7 +1302,7 @@ void Viewport::updateMatricesFromCamera(const CCamera& myCamera) const

// Compute the directional light projection matrix (light_pv)
_.computeLightProjectionMatrix(
m_lightShadowClipMin, m_lightShadowClipMax, m_light.direction);
m_lightShadowClipMin, m_lightShadowClipMax, m_light);

_.initialized = true;
}
Expand Down
2 changes: 1 addition & 1 deletion package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
<package format="3">
<name>mrpt2</name>
<!-- Before updating version number, read [MRPT_ROOT]/version_prefix.txt first -->
<version>2.9.4</version>
<version>2.10.0</version>
<description>Mobile Robot Programming Toolkit (MRPT) version 2.x</description>

<author email="[email protected]">Jose-Luis Blanco-Claraco</author>
Expand Down
4 changes: 1 addition & 3 deletions python-examples/global_localization.py
Original file line number Diff line number Diff line change
Expand Up @@ -10,14 +10,12 @@
#
# ./global_localization.py ../share/mrpt/config_files/pf-localization/localization_demo.ini
#
from mrpt import pymrpt
from mrpt.pymrpt import mrpt
import os
import sys
import argparse
from time import sleep

mrpt = pymrpt.mrpt # namespace shortcut


# args
parser = argparse.ArgumentParser()
Expand Down
3 changes: 1 addition & 2 deletions python-examples/hwdriver-tao-imu-usb.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,7 @@
# export PYTHONPATH=$HOME/code/mrpt/build-Release/:$PYTHONPATH
# ---------------------------------------------------------------------

from mrpt import pymrpt
mrpt = pymrpt.mrpt # namespace shortcut
from mrpt.pymrpt import mrpt

imu = mrpt.hwdrivers.CTaoboticsIMU()

Expand Down
3 changes: 1 addition & 2 deletions python-examples/lines-3d-geometry-example.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,7 @@
# export PYTHONPATH=$HOME/code/mrpt/build-Release/:$PYTHONPATH
# ---------------------------------------------------------------------

from mrpt import pymrpt
mrpt = pymrpt.mrpt
from mrpt.pymrpt import mrpt

# Aliases:
TPoint3D = mrpt.math.TPoint3D_double_t
Expand Down
3 changes: 1 addition & 2 deletions python-examples/matrices.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,9 +8,8 @@
# More matrix classes available in the module mrpt.math.
# See: https://mrpt.github.io/pymrpt-docs/mrpt.pymrpt.mrpt.math.html

from mrpt import pymrpt
from mrpt.pymrpt import mrpt
import numpy as np
mrpt = pymrpt.mrpt

# Create a numpy matrix from a list:
m1_np = np.array([[1, 2, 3], [4, 5, 6], [7, 8, 9]])
Expand Down
82 changes: 82 additions & 0 deletions python-examples/opengl-demo-gui.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,82 @@
#!/usr/bin/env python3

# ---------------------------------------------------------------------
# Install python3-pymrpt, ros-$ROS_DISTRO-mrpt2, or test with a local build with:
# export PYTHONPATH=$HOME/code/mrpt/build-Release/:$PYTHONPATH
# ---------------------------------------------------------------------

from mrpt.pymrpt import mrpt
import time
import math

# Create GUI:
win = mrpt.gui.CDisplayWindow3D('MRPT GUI demo', 800, 600)

# Get and lock 3D scene:
# Lock is required again each time the scene is modified, to prevent
# data race between the main and the rendering threads.
scene = win.get3DSceneAndLock()

# A grid on the XY horizontal plane:
# ctor args: xMin: float, xMax: float, yMin: float, yMax: float, z: float, frequency: float
glGrid = mrpt.opengl.CGridPlaneXY.Create(-3, 3, -3, 3, 0, 1)
scene.insert(glGrid)

# A couple of XYZ "corners":
glCorner = mrpt.opengl.stock_objects.CornerXYZ(2.0)
scene.insert(glCorner)

glCorner2: mrpt.opengl.CSetOfObjects = mrpt.opengl.stock_objects.CornerXYZ(1.0)
glCorner2.setLocation(4.0, 0.0, 0.0)
scene.insert(glCorner2)

# A 3D inverse-depth ellipsoid:
glEllip = mrpt.opengl.CEllipsoidInverseDepth3D()
cov = mrpt.math.CMatrixFixed_double_3UL_3UL_t.Zero()
cov[0, 0] = 0.01
cov[1, 1] = 0.001
cov[2, 2] = 0.002
mean = mrpt.math.CMatrixFixed_double_3UL_1UL_t()
mean[0, 0] = 0.2 # inv_range
mean[1, 0] = 0.5 # yaw
mean[2, 0] = -0.6 # pitch
glEllip.setCovMatrixAndMean(cov, mean)
scene.insert(glEllip)

# A floor "block":
glFloor = mrpt.opengl.CBox()
glFloor.setBoxCorners(mrpt.math.TPoint3D_double_t(-15, -15, 0),
mrpt.math.TPoint3D_double_t(15, 15, 0.1))
glFloor.setLocation(0, 0, -3.0)
glFloor.setColor_u8(mrpt.img.TColor(0x70, 0x70, 0x70))
scene.insert(glFloor)

# A mobile box to illustrate animations:
glBox = mrpt.opengl.CBox()
glBox.setBoxCorners(mrpt.math.TPoint3D_double_t(0, 0, 0),
mrpt.math.TPoint3D_double_t(1, 1, 1))
glBox.setBoxBorderColor(mrpt.img.TColor(0, 0, 0))
glBox.castShadows(True)
scene.insert(glBox)

# Shadows are disabled by default, enable them:
scene.getViewport().enableShadowCasting(True)
print('Shadow casting: ' + str(scene.getViewport().isShadowCastingEnabled()))

# Move camera:
win.setCameraAzimuthDeg(-40.0)
win.setCameraElevationDeg(30.0)

# end of scene lock:
win.unlockAccess3DScene()


print('Close the window to quit the program')
timer = mrpt.system.CTicTac()

while win.isOpen():
y = 5.0*math.sin(1.0*timer.Tac())
glBox.setLocation(4.0, y, 0.0)

win.repaint()
time.sleep(50e-3)
4 changes: 1 addition & 3 deletions python-examples/rbpf_slam.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,11 +14,9 @@
# ./rbpf_slam.py -c ../share/mrpt/config_files/rbpf-slam/gridmapping_optimal_sampling.ini ../share/mrpt/datasets/2006-01ENE-21-SENA_Telecom\ Faculty_one_loop_only.rawlog
#

from mrpt import pymrpt
from mrpt.pymrpt import mrpt
import argparse

mrpt = pymrpt.mrpt

# args
parser = argparse.ArgumentParser()
parser.add_argument('rawlog', help='Rawlog file.')
Expand Down
4 changes: 2 additions & 2 deletions python-examples/ros-poses-convert.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,11 +8,11 @@
# This example shows how to convert back and forth between MRPT poses
# and ROS 1 or ROS 2 (both are compatible with this same code) Pose

from mrpt import pymrpt, ros_bridge
from mrpt.pymrpt import mrpt
from mrpt import ros_bridge
from math import radians
from geometry_msgs.msg import Pose, PoseWithCovariance

mrpt = pymrpt.mrpt

# Example 1: 2D pose
# --------------------------
Expand Down
3 changes: 1 addition & 2 deletions python-examples/se3-poses-example.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,9 +5,8 @@
# export PYTHONPATH=$HOME/code/mrpt/build-Release/:$PYTHONPATH
# ---------------------------------------------------------------------

from mrpt.pymrpt import mrpt
from math import radians
from mrpt import pymrpt
mrpt = pymrpt.mrpt

p1 = mrpt.poses.CPose3D.FromXYZYawPitchRoll(
1.0, 2.0, 0, radians(90), radians(0), radians(0))
Expand Down
Loading

0 comments on commit 9abe4e1

Please sign in to comment.