diff --git a/python-examples/global_localization.py b/python-examples/global_localization.py index 2710b56a3d..8bd748b569 100755 --- a/python-examples/global_localization.py +++ b/python-examples/global_localization.py @@ -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() diff --git a/python-examples/hwdriver-tao-imu-usb.py b/python-examples/hwdriver-tao-imu-usb.py index 09ec6b3c6d..83aca5cd25 100755 --- a/python-examples/hwdriver-tao-imu-usb.py +++ b/python-examples/hwdriver-tao-imu-usb.py @@ -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() diff --git a/python-examples/lines-3d-geometry-example.py b/python-examples/lines-3d-geometry-example.py index d9574c2c5a..2a238a048a 100755 --- a/python-examples/lines-3d-geometry-example.py +++ b/python-examples/lines-3d-geometry-example.py @@ -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 diff --git a/python-examples/matrices.py b/python-examples/matrices.py index fae5280046..c2f3a46ef7 100755 --- a/python-examples/matrices.py +++ b/python-examples/matrices.py @@ -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]]) diff --git a/python-examples/opengl-demo-gui.py b/python-examples/opengl-demo-gui.py new file mode 100755 index 0000000000..5dd6bd9e02 --- /dev/null +++ b/python-examples/opengl-demo-gui.py @@ -0,0 +1,52 @@ +#!/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 + +# 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() + +# ctor args: xMin: float, xMax: float, yMin: float, yMax: float, z: float, frequency: float +glGrid = mrpt.opengl.CGridPlaneXY.Create(-10, 10, -10, 10, 0, 1) +scene.insert(glGrid) + +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) + +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) + + +# end of scene lock: +win.unlockAccess3DScene() + + +print('Close the window to quit the program') + +while win.isOpen(): + + win.repaint() + time.sleep(50e-3) diff --git a/python-examples/rbpf_slam.py b/python-examples/rbpf_slam.py index 8ba4fa32ba..2cc5bb0199 100755 --- a/python-examples/rbpf_slam.py +++ b/python-examples/rbpf_slam.py @@ -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.') diff --git a/python-examples/ros-poses-convert.py b/python-examples/ros-poses-convert.py index dec526e5a3..1ecbd7a237 100755 --- a/python-examples/ros-poses-convert.py +++ b/python-examples/ros-poses-convert.py @@ -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 # -------------------------- diff --git a/python-examples/se3-poses-example.py b/python-examples/se3-poses-example.py index e8b670d502..6ba2b4dffa 100755 --- a/python-examples/se3-poses-example.py +++ b/python-examples/se3-poses-example.py @@ -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)) diff --git a/python/patch-stubs-002.diff b/python/patch-stubs-002.diff new file mode 100644 index 0000000000..ce284b7fa6 --- /dev/null +++ b/python/patch-stubs-002.diff @@ -0,0 +1,24 @@ +diff --git a/python/stubs-out/mrpt/pymrpt/mrpt/opengl/__init__.pyi b/python/stubs-out/mrpt/pymrpt/mrpt/opengl/__init__.pyi +index 8abd014c7..d29cf054a 100644 +--- a/python/stubs-out/mrpt/pymrpt/mrpt/opengl/__init__.pyi ++++ b/python/stubs-out/mrpt/pymrpt/mrpt/opengl/__init__.pyi +@@ -1,5 +1,7 @@ + from typing import Any, ClassVar, Dict, List, Optional, Tuple + ++from . import stock_objects ++ + from typing import overload + import mrpt.pymrpt.mrpt.containers + import mrpt.pymrpt.mrpt.img +diff --git a/python/stubs-out/mrpt/pymrpt/mrpt/poses/__init__.pyi b/python/stubs-out/mrpt/pymrpt/mrpt/poses/__init__.pyi +index 09ba314ee..6d716eb80 100644 +--- a/python/stubs-out/mrpt/pymrpt/mrpt/poses/__init__.pyi ++++ b/python/stubs-out/mrpt/pymrpt/mrpt/poses/__init__.pyi +@@ -1,5 +1,7 @@ + from typing import Any, ClassVar, Dict, Tuple + ++from . import Lie ++ + from typing import overload + import mrpt.pymrpt.mrpt + import mrpt.pymrpt.mrpt.bayes diff --git a/python/stubs-out/mrpt/pymrpt/mrpt/opengl/__init__.pyi b/python/stubs-out/mrpt/pymrpt/mrpt/opengl/__init__.pyi index 8abd014c74..d29cf054a1 100644 --- a/python/stubs-out/mrpt/pymrpt/mrpt/opengl/__init__.pyi +++ b/python/stubs-out/mrpt/pymrpt/mrpt/opengl/__init__.pyi @@ -1,5 +1,7 @@ from typing import Any, ClassVar, Dict, List, Optional, Tuple +from . import stock_objects + from typing import overload import mrpt.pymrpt.mrpt.containers import mrpt.pymrpt.mrpt.img diff --git a/python/stubs-out/mrpt/pymrpt/mrpt/poses/__init__.pyi b/python/stubs-out/mrpt/pymrpt/mrpt/poses/__init__.pyi index 09ba314ee5..6d716eb800 100644 --- a/python/stubs-out/mrpt/pymrpt/mrpt/poses/__init__.pyi +++ b/python/stubs-out/mrpt/pymrpt/mrpt/poses/__init__.pyi @@ -1,5 +1,7 @@ from typing import Any, ClassVar, Dict, Tuple +from . import Lie + from typing import overload import mrpt.pymrpt.mrpt import mrpt.pymrpt.mrpt.bayes