diff --git a/ChangeLog.txt b/ChangeLog.txt index 926f81569c..6af835006b 100644 --- a/ChangeLog.txt +++ b/ChangeLog.txt @@ -38,7 +38,8 @@ ViSP 3.x.x (Version in development) . New tutorials in tutorial/segmentation/color folder to show how to use HSV color segmentation to extract the corresponding point cloud . New scene renderer based on Panda3D. See inheritance diagram for vpPanda3DBaseRenderer class and corresponding - tutorial. + tutorial + . New docker image for Ubuntu 24.04 in docker folder - Applications . Migrate eye-to-hand tutorials in apps - Tutorials diff --git a/ci/docker/ubuntu-18.04/Dockerfile b/ci/docker/ubuntu-18.04/Dockerfile index 0e8c23a443..468a3cb008 100644 --- a/ci/docker/ubuntu-18.04/Dockerfile +++ b/ci/docker/ubuntu-18.04/Dockerfile @@ -1,50 +1,88 @@ FROM ubuntu:18.04 -MAINTAINER Fabien Spindler ARG DEBIAN_FRONTEND=noninteractive -ARG VISPCI_USER_UID=1001 -ARG DOCKER_GROUP_GID=130 +ARG USER_UID=1001 ENV TZ=Europe/Paris -# Update aptitude with new repo -RUN apt-get update +# Update aptitude with default packages +RUN apt-get update \ + && apt-get install -y \ + build-essential \ + cmake \ + cmake-curses-gui \ + curl \ + gedit \ + gdb \ + git \ + iputils-ping \ + locales \ + locate \ + lsb-release \ + mercurial \ + nano \ + net-tools \ + python3 \ + python3-dev \ + python3-pip \ + python3-dbg \ + python3-empy \ + python3-numpy \ + python3-pip \ + python3-psutil \ + python3-venv \ + software-properties-common \ + sudo \ + tzdata \ + vim \ + wget \ + && apt-get clean -# Install packages -RUN apt-get install -y \ - sudo \ - build-essential \ - cmake \ - git \ - net-tools \ - iputils-ping \ - # Recommended ViSP 3rd parties - libopencv-dev \ - libx11-dev \ - liblapack-dev \ - libeigen3-dev \ - libdc1394-22-dev \ - libv4l-dev \ - libzbar-dev \ - libpthread-stubs0-dev \ - # Other optional 3rd parties - libpcl-dev \ - libcoin80-dev \ - libjpeg-dev \ - libpng-dev \ - libogre-1.9-dev \ - libois-dev \ - libdmtx-dev \ - libgsl-dev +# Update aptitude with recommended ViSP 3rd parties +RUN apt-get update \ + && apt-get install -y \ + libdc1394-22-dev \ + libeigen3-dev \ + liblapack-dev \ + libopencv-dev \ + libv4l-dev \ + libx11-dev \ + libzbar-dev \ + && apt-get clean -RUN adduser --disabled-password --gecos "" --uid $VISPCI_USER_UID vispci \ - && groupadd docker --gid $DOCKER_GROUP_GID \ - && usermod -aG sudo vispci \ - && usermod -aG docker vispci \ - && echo "%sudo ALL=(ALL:ALL) NOPASSWD:ALL" > /etc/sudoers \ - && echo "Defaults env_keep += \"DEBIAN_FRONTEND\"" >> /etc/sudoers \ - && adduser vispci video +# Update aptitude with other optional ViSP 3rd parties +RUN apt-get update \ + && apt-get install -y \ + libpcl-dev \ + libcoin80-dev \ + libjpeg-dev \ + libpng-dev \ + libogre-1.9-dev \ + libois-dev \ + libdmtx-dev \ + libgsl-dev \ + && apt-get clean -ENV HOME=/home/vispci +# Set Locale +RUN locale-gen en_US en_US.UTF-8 && \ + update-locale LC_ALL=en_US.UTF-8 LANG=en_US.UTF-8 && \ + export LANG=en_US.UTF-8 + +ENV USERNAME vispci + +RUN useradd -U --uid $USER_UID -ms /bin/bash ${USERNAME} \ + && echo "${USERNAME}:${USERNAME}" | chpasswd \ + && adduser ${USERNAME} sudo \ + && echo "$USERNAME ALL=NOPASSWD: ALL" >> /etc/sudoers.d/${USERNAME} \ + && adduser ${USERNAME} video + +# Commands below are now run as normal user +USER ${USERNAME} + +# When running a container start in the home folder +WORKDIR /home/$USERNAME + +# Create visp workspace +ENV VISP_WS /home/$USERNAME/visp-ws # Install visp-images RUN mkdir -p ${HOME}/visp-ws \ @@ -54,16 +92,14 @@ RUN mkdir -p ${HOME}/visp-ws \ && echo "export VISP_INPUT_IMAGE_PATH=${HOME}/visp-ws/visp-images" >> ${HOME}/.bashrc # Get visp -RUN cd ${HOME}/visp-ws \ +RUN cd ${VISP_WS} \ && git clone https://github.com/lagadic/visp # Build visp -RUN cd ${HOME}/visp-ws \ +RUN cd ${VISP_WS} \ && mkdir visp-build \ && cd visp-build \ && cmake ../visp \ - && make -j4 - -USER vispci + && make -j$(nproc) -WORKDIR /home/vispci +CMD ["/bin/bash"] diff --git a/ci/docker/ubuntu-20.04/Dockerfile b/ci/docker/ubuntu-20.04/Dockerfile index d9de38da6f..3a20a67327 100644 --- a/ci/docker/ubuntu-20.04/Dockerfile +++ b/ci/docker/ubuntu-20.04/Dockerfile @@ -1,50 +1,92 @@ FROM ubuntu:20.04 -MAINTAINER Fabien Spindler ARG DEBIAN_FRONTEND=noninteractive -ARG VISPCI_USER_UID=1001 -ARG DOCKER_GROUP_GID=130 +ARG USER_UID=1001 ENV TZ=Europe/Paris -# Update aptitude with new repo -RUN apt-get update +# Update aptitude with default packages +RUN apt-get update \ + && apt-get install -y \ + build-essential \ + cmake \ + cmake-curses-gui \ + curl \ + gedit \ + gdb \ + git \ + iputils-ping \ + locales \ + locate \ + lsb-release \ + mercurial \ + nano \ + net-tools \ + python3 \ + python3-dev \ + python3-pip \ + python3-dbg \ + python3-empy \ + python3-numpy \ + python3-pip \ + python3-psutil \ + python3-venv \ + software-properties-common \ + sudo \ + tzdata \ + vim \ + wget \ + && apt-get clean -# Install packages -RUN apt-get install -y \ - sudo \ - build-essential \ - cmake \ - git \ - net-tools \ - iputils-ping \ - # Recommended ViSP 3rd parties - libopencv-dev \ - libx11-dev \ - liblapack-dev \ - libeigen3-dev \ - libdc1394-22-dev \ - libv4l-dev \ - libzbar-dev \ - libpthread-stubs0-dev \ - # Other optional 3rd parties - libpcl-dev \ - libcoin-dev \ - libjpeg-dev \ - libpng-dev \ - libogre-1.9-dev \ - libois-dev \ - libdmtx-dev \ - libgsl-dev +# Update aptitude with recommended ViSP 3rd parties +RUN apt-get update \ + && apt-get install -y \ + libdc1394-22-dev \ + libeigen3-dev \ + liblapack-dev \ + libopencv-dev \ + libv4l-dev \ + libx11-dev \ + libzbar-dev \ + nlohmann-json3-dev \ + && apt-get clean -RUN adduser --disabled-password --gecos "" --uid $VISPCI_USER_UID vispci \ - && groupadd docker --gid $DOCKER_GROUP_GID \ - && usermod -aG sudo vispci \ - && usermod -aG docker vispci \ - && echo "%sudo ALL=(ALL:ALL) NOPASSWD:ALL" > /etc/sudoers \ - && echo "Defaults env_keep += \"DEBIAN_FRONTEND\"" >> /etc/sudoers \ - && adduser vispci video +# Update aptitude with other optional ViSP 3rd parties +RUN apt-get update \ + && apt-get install -y \ + libcoin-dev \ + libdmtx-dev \ + libgsl-dev \ + libjpeg-dev \ + libogre-1.9-dev \ + libois-dev \ + libpcl-dev \ + libpng-dev \ + && apt-get clean -ENV HOME=/home/vispci +# Set Locale +RUN locale-gen en_US en_US.UTF-8 && \ + update-locale LC_ALL=en_US.UTF-8 LANG=en_US.UTF-8 && \ + export LANG=en_US.UTF-8 + +ENV USERNAME vispci + +RUN useradd -U --uid $USER_UID -ms /bin/bash ${USERNAME} \ + && echo "${USERNAME}:${USERNAME}" | chpasswd \ + && adduser ${USERNAME} sudo \ + && echo "$USERNAME ALL=NOPASSWD: ALL" >> /etc/sudoers.d/${USERNAME} \ + && adduser ${USERNAME} video + +# Commands below are now run as normal user +USER ${USERNAME} + +# When running a container start in the home folder +WORKDIR /home/$USERNAME + +# Some apps don't show controls without this +ENV QT_X11_NO_MITSHM 1 + +# Create visp workspace +ENV VISP_WS /home/$USERNAME/visp-ws # Install visp-images RUN mkdir -p ${HOME}/visp-ws \ @@ -54,16 +96,14 @@ RUN mkdir -p ${HOME}/visp-ws \ && echo "export VISP_INPUT_IMAGE_PATH=${HOME}/visp-ws/visp-images" >> ${HOME}/.bashrc # Get visp -RUN cd ${HOME}/visp-ws \ +RUN cd ${VISP_WS} \ && git clone https://github.com/lagadic/visp # Build visp -RUN cd ${HOME}/visp-ws \ +RUN cd ${VISP_WS} \ && mkdir visp-build \ && cd visp-build \ && cmake ../visp \ - && make -j4 - -USER vispci + && make -j$(nproc) -WORKDIR /home/vispci +CMD ["/bin/bash"] diff --git a/ci/docker/ubuntu-22.04/Dockerfile b/ci/docker/ubuntu-22.04/Dockerfile index dfe5a9da72..e0a12e87fd 100644 --- a/ci/docker/ubuntu-22.04/Dockerfile +++ b/ci/docker/ubuntu-22.04/Dockerfile @@ -1,49 +1,89 @@ FROM ubuntu:22.04 -MAINTAINER Fabien Spindler ARG DEBIAN_FRONTEND=noninteractive -ARG VISPCI_USER_UID=1001 -ARG DOCKER_GROUP_GID=121 +ARG USER_UID=1001 ENV TZ=Europe/Paris -# Update aptitude with new repo -RUN apt-get update +# Update aptitude with default packages +RUN apt-get update \ + && apt-get install -y \ + build-essential \ + cmake \ + cmake-curses-gui \ + curl \ + gedit \ + gdb \ + git \ + iputils-ping \ + locales \ + locate \ + lsb-release \ + mercurial \ + nano \ + net-tools \ + python3 \ + python3-dev \ + python3-pip \ + python3-dbg \ + python3-empy \ + python3-numpy \ + python3-pip \ + python3-psutil \ + python3-venv \ + software-properties-common \ + sudo \ + tzdata \ + vim \ + wget \ + && apt-get clean -# Install packages -RUN apt-get install -y \ - sudo \ - build-essential \ - cmake \ - git \ - net-tools \ - iputils-ping \ - # Recommended ViSP 3rd parties - libopencv-dev \ - libx11-dev \ - liblapack-dev \ - libeigen3-dev \ - libdc1394-dev \ - libv4l-dev \ - libzbar-dev \ - # Other optional 3rd parties - libpcl-dev \ - libcoin-dev \ - libjpeg-turbo8-dev \ - libpng-dev \ - libogre-1.9-dev \ - libois-dev \ - libdmtx-dev \ - libgsl-dev +# Update aptitude with recommended ViSP 3rd parties +RUN apt-get update \ + && apt-get install -y \ + libdc1394-dev \ + libeigen3-dev \ + liblapack-dev \ + libopencv-dev \ + libv4l-dev \ + libx11-dev \ + libzbar-dev \ + nlohmann-json3-dev \ + && apt-get clean -RUN adduser --disabled-password --gecos "" --uid $VISPCI_USER_UID vispci \ - && groupadd docker --gid $DOCKER_GROUP_GID \ - && usermod -aG sudo vispci \ - && usermod -aG docker vispci \ - && echo "%sudo ALL=(ALL:ALL) NOPASSWD:ALL" > /etc/sudoers \ - && echo "Defaults env_keep += \"DEBIAN_FRONTEND\"" >> /etc/sudoers \ - && adduser vispci video +# Update aptitude with other optional ViSP 3rd parties +RUN apt-get update \ + && apt-get install -y \ + libcoin-dev \ + libdmtx-dev \ + libgsl-dev \ + libjpeg-turbo8-dev \ + libpcl-dev \ + libpng-dev \ + libogre-1.9-dev \ + libois-dev \ + && apt-get clean -ENV HOME=/home/vispci +# Set Locale +RUN locale-gen en_US en_US.UTF-8 && \ + update-locale LC_ALL=en_US.UTF-8 LANG=en_US.UTF-8 && \ + export LANG=en_US.UTF-8 + +ENV USERNAME vispci + +RUN useradd -U --uid $USER_UID -ms /bin/bash ${USERNAME} \ + && echo "${USERNAME}:${USERNAME}" | chpasswd \ + && adduser ${USERNAME} sudo \ + && echo "$USERNAME ALL=NOPASSWD: ALL" >> /etc/sudoers.d/${USERNAME} \ + && adduser ${USERNAME} video + +# Commands below are now run as normal user +USER ${USERNAME} + +# When running a container start in the home folder +WORKDIR /home/$USERNAME + +# Some apps don't show controls without this +ENV QT_X11_NO_MITSHM 1 # Install visp-images RUN mkdir -p ${HOME}/visp-ws \ @@ -53,16 +93,14 @@ RUN mkdir -p ${HOME}/visp-ws \ && echo "export VISP_INPUT_IMAGE_PATH=${HOME}/visp-ws/visp-images" >> ${HOME}/.bashrc # Get visp -RUN cd ${HOME}/visp-ws \ +RUN cd ${VISP_WS} \ && git clone https://github.com/lagadic/visp # Build visp -RUN cd ${HOME}/visp-ws \ +RUN cd ${VISP_WS} \ && mkdir visp-build \ && cd visp-build \ && cmake ../visp \ && make -j$(nproc) -USER vispci - -WORKDIR /home/vispci +CMD ["/bin/bash"] diff --git a/ci/docker/ubuntu-24.04/Dockerfile b/ci/docker/ubuntu-24.04/Dockerfile new file mode 100644 index 0000000000..08b76e39db --- /dev/null +++ b/ci/docker/ubuntu-24.04/Dockerfile @@ -0,0 +1,106 @@ +FROM ubuntu:24.04 + +ARG DEBIAN_FRONTEND=noninteractive +ARG USER_UID=1001 +ENV TZ=Europe/Paris + +## Update aptitude with default packages +RUN apt-get update \ + && apt-get install -y \ + build-essential \ + cmake \ + cmake-curses-gui \ + curl \ + gedit \ + gdb \ + git \ + iputils-ping \ + locales \ + locate \ + lsb-release \ + mercurial \ + nano \ + net-tools \ + python3 \ + python3-dev \ + python3-pip \ + python3-dbg \ + python3-empy \ + python3-numpy \ + python3-pip \ + python3-psutil \ + python3-venv \ + software-properties-common \ + sudo \ + tzdata \ + vim \ + wget \ + && apt-get clean + +# Update aptitude with recommended ViSP 3rd parties +RUN apt-get update \ + && apt-get install -y \ + libdc1394-dev \ + libeigen3-dev \ + liblapack-dev \ + libopencv-dev \ + libv4l-dev \ + libx11-dev \ + libzbar-dev \ + nlohmann-json3-dev \ + && apt-get clean + +# Update aptitude with other optional ViSP 3rd parties +RUN apt-get update \ + && apt-get install -y \ + libcoin-dev \ + libdmtx-dev \ + libgsl-dev \ + libjpeg-turbo8-dev \ + libpng-dev \ + libogre-1.9-dev \ + libois-dev \ + libpcl-dev \ + && apt-get clean + +# Set Locale +RUN locale-gen en_US en_US.UTF-8 && \ + update-locale LC_ALL=en_US.UTF-8 LANG=en_US.UTF-8 && \ + export LANG=en_US.UTF-8 + +ENV USERNAME vispci + +RUN useradd -U --uid $USER_UID -ms /bin/bash ${USERNAME} \ + && echo "${USERNAME}:${USERNAME}" | chpasswd \ + && adduser ${USERNAME} sudo \ + && echo "$USERNAME ALL=NOPASSWD: ALL" >> /etc/sudoers.d/${USERNAME} \ + && adduser ${USERNAME} video + +# Commands below are now run as normal user +USER ${USERNAME} + +# When running a container start in the home folder +WORKDIR /home/$USERNAME + +# Some apps don't show controls without this +ENV QT_X11_NO_MITSHM 1 + +# Install visp-images +RUN mkdir -p ${HOME}/visp-ws \ + && cd ${HOME}/visp-ws \ + && git clone https://github.com/lagadic/visp-images.git \ + && echo "export VISP_WS=${HOME}/visp-ws" >> ${HOME}/.bashrc \ + && echo "export VISP_INPUT_IMAGE_PATH=${HOME}/visp-ws/visp-images" >> ${HOME}/.bashrc + +# Get visp +RUN cd ${HOME}/visp-ws \ + && git clone https://github.com/lagadic/visp + +# Build visp +RUN cd ${HOME}/visp-ws \ + && mkdir visp-build \ + && cd visp-build \ + && cmake ../visp \ + && make -j$(nproc) + +CMD ["/bin/bash"] diff --git a/ci/docker/ubuntu-dep-src/Dockerfile b/ci/docker/ubuntu-dep-src/Dockerfile new file mode 100644 index 0000000000..efb2d9aab8 --- /dev/null +++ b/ci/docker/ubuntu-dep-src/Dockerfile @@ -0,0 +1,163 @@ +FROM ubuntu:22.04 + +ARG DEBIAN_FRONTEND=noninteractive +ARG USER_UID=1001 +ENV TZ=Europe/Paris + +## Variable containing the URL of the GIT repository that needs to be tested. +## By default GIT_URL is set to https://githb.com/lagadic/visp and GIT_BRANCH_NAME is set to master branch +## To build this container use : +## +## docker build . -t ubuntu-dep-src:v1 --build-arg GIT_URL="${YOUR_URL}" [--build-arg GIT_BRANCH_NAME="{BRANCH_NAME}"] +## +ARG GIT_URL=https://github.com/lagadic/visp +ARG GIT_BRANCH_NAME=master +RUN ["/bin/bash", "-c", ": ${GIT_URL:?Build argument GIT_URL needs to be set and not null.}"] +ENV GIT_URL="$GIT_URL" +ENV GIT_BRANCH_CMD="${GIT_BRANCH_NAME}" +ENV GIT_BRANCH_CMD=${GIT_BRANCH_CMD:+"--branch $GIT_BRANCH_NAME --depth 1"} + +# Update aptitude with default packages +RUN apt-get update \ + && apt-get install -y \ + build-essential \ + cmake \ + cmake-curses-gui \ + curl \ + gedit \ + git \ + locales \ + lsb-release \ + iputils-ping \ + nano \ + sudo \ + && apt-get clean + +# Install common dependencies +RUN apt update \ + && apt install -y \ + gfortran \ + freeglut3-dev \ + mesa-common-dev \ + mesa-utils \ + nlohmann-json3-dev \ + libboost-all-dev \ + libdc1394-dev \ + libeigen3-dev \ + libflann-dev \ + libgl1-mesa-dev \ + libglfw3-dev \ + libglu1-mesa-dev \ + libgtk-3-dev \ + liblapack-dev \ + libssl-dev \ + libusb-1.0-0-dev \ + libv4l-dev \ + libx11-dev \ + pkg-config \ + && apt-get clean + +# Set Locale +RUN locale-gen en_US en_US.UTF-8 && \ + update-locale LC_ALL=en_US.UTF-8 LANG=en_US.UTF-8 && \ + export LANG=en_US.UTF-8 + +ENV USERNAME vispci + +RUN useradd -U --uid $USER_UID -ms /bin/bash ${USERNAME} \ + && echo "${USERNAME}:${USERNAME}" | chpasswd \ + && adduser ${USERNAME} sudo \ + && echo "$USERNAME ALL=NOPASSWD: ALL" >> /etc/sudoers.d/${USERNAME} \ + && adduser ${USERNAME} video + +# Commands below are now run as normal user +USER ${USERNAME} + +# When running a container start in the home folder +WORKDIR /home/$USERNAME + +# Some apps don't show controls without this +ENV QT_X11_NO_MITSHM 1 + +# Create folder for 3rd parties +RUN mkdir -p ${HOME}/visp-ws/3rdparty + +# Install OpenBLAS from source +RUN cd ${HOME}/visp-ws/3rdparty \ + && git clone --depth 1 https://github.com/xianyi/OpenBLAS.git \ + && cd OpenBLAS \ + && mkdir install \ + && make -j$(nproc) \ + && make -j$(nproc) install PREFIX=$(pwd)/install + +ENV OpenBLAS_HOME=/3rdparty/OpenBLAS/install + +# Install VTK from source +ENV GIT_CLONE_PROTECTION_ACTIVE=false +RUN cd ${HOME}/visp-ws/3rdparty \ + && git clone --recursive --depth 1 --branch v9.3.0 https://github.com/Kitware/VTK.git \ + && cd VTK \ + && mkdir build && cd build && mkdir install \ + && cmake .. -DVTK_ANDROID_BUILD=OFF -DVTK_BUILD_DOCUMENTATION=OFF -DVTK_BUILD_EXAMPLES=OFF -DVTK_BUILD_EXAMPLES=OFF \ + -DCMAKE_BUILD_TYPE=Release -DVTK_GROUP_ENABLE_Imaging=DONT_WANT -DVTK_GROUP_ENABLE_MPI=DONT_WANT \ + -DVTK_GROUP_ENABLE_Web=DONT_WANT -DCMAKE_INSTALL_PREFIX=${HOME}/visp-ws/3rdparty/VTK/build/install \ + && make -j$(nproc) install + +ENV VTK_DIR=${HOME}/visp-ws/3rdparty/VTK/build/install + +# Install OpenCV from source +RUN cd ${HOME}/visp-ws/3rdparty \ + && git clone --depth 1 https://github.com/opencv/opencv.git \ + && mkdir opencv/build \ + && cd opencv/build \ + && mkdir install \ + && cmake .. -DBUILD_EXAMPLES=OFF -DBUILD_PERF_TESTS=OFF -DBUILD_TESTS=OFF -DCMAKE_BUILD_TYPE=Release \ + -DCMAKE_INSTALL_PREFIX=${HOME}/visp-ws/3rdparty/opencv/build/install \ + && make -j$(nproc) install + +ENV OpenCV_DIR=${HOME}/visp-ws/3rdparty/opencv/build/install + +# Install IntelĀ® RealSenseā„¢ SDK +RUN cd ${HOME}/visp-ws/3rdparty \ + && git clone --depth 1 https://github.com/IntelRealSense/librealsense.git \ + && mkdir librealsense/build \ + && cd librealsense/build \ + && mkdir install \ + && cmake .. -DBUILD_EXAMPLES=OFF -DCMAKE_BUILD_TYPE=Release \ + -DCMAKE_INSTALL_PREFIX=${HOME}/visp-ws/3rdparty/librealsense/build/install \ + && make -j$(nproc) install + +ENV REALSENSE2_DIR=${HOME}/visp-ws/3rdparty/librealsense/build/install + +# Build PCL from source +RUN cd ${HOME}/visp-ws/3rdparty \ + && git clone --depth 1 https://github.com/PointCloudLibrary/pcl.git \ + && mkdir pcl/build \ + && cd pcl/build \ + && mkdir install \ + && cmake .. -DBUILD_tools=OFF -DBUILD_global_tests=OFF -DPCL_DISABLE_GPU_TESTS=ON -DCMAKE_BUILD_TYPE=Release \ + -DCMAKE_INSTALL_PREFIX=${HOME}/visp-ws/3rdparty/pcl/build/install \ + && make -j10 install + +ENV PCL_DIR=${HOME}/visp-ws/3rdparty/pcl/build/install + +# Install visp-images +RUN mkdir -p ${HOME}/visp-ws \ + && cd ${HOME}/visp-ws \ + && git clone https://github.com/lagadic/visp-images.git \ + && echo "export VISP_WS=${HOME}/visp-ws" >> ${HOME}/.bashrc \ + && echo "export VISP_INPUT_IMAGE_PATH=${HOME}/visp-ws/visp-images" >> ${HOME}/.bashrc + +# Download ViSP fork +RUN cd ${HOME}/visp-ws \ + && git clone ${GIT_URL} ${GIT_BRANCH_CMD} + +# Build visp +RUN cd ${HOME}/visp-ws \ + && mkdir visp-build \ + && cd visp-build \ + && cmake ../visp -DCMAKE_INSTALL_PREFIX=${HOME}/visp-ws/visp-build/install \ + && make -j$(nproc) developer_scripts \ + && make -j$(nproc) install + +CMD ["/bin/bash"] diff --git a/doc/tutorial/detection_dnn/tutorial-detection-tensorrt.dox b/doc/tutorial/detection_dnn/tutorial-detection-tensorrt.dox index aff7c62955..2660c603e7 100644 --- a/doc/tutorial/detection_dnn/tutorial-detection-tensorrt.dox +++ b/doc/tutorial/detection_dnn/tutorial-detection-tensorrt.dox @@ -201,7 +201,7 @@ Include TensorRT header files. \subsection preprocessing Pre-processing Prepare input image for inference with OpenCV. First, upload image to GPU, resize it to match model's input dimensions, normalize with `meanR` `meanG` `meanB` being -the values used for mean substraction. +the values used for mean subtraction. Transform data to tensor (copy data to channel by channel to `gpu_input`). In the case of `ssd_mobilenet.onnx`, the input dimension is 1x3x300x300. \snippet tutorial-dnn-tensorrt-live.cpp Preprocess image diff --git a/doc/tutorial/docker/tutorial-install-docker.dox b/doc/tutorial/docker/tutorial-install-docker.dox index e7ced95c6f..0faf3f137f 100644 --- a/doc/tutorial/docker/tutorial-install-docker.dox +++ b/doc/tutorial/docker/tutorial-install-docker.dox @@ -77,10 +77,10 @@ In [Docker Hub](https://hub.docker.com/repository/docker/vispci/vispci), we prov images that can be used on an Ubuntu or macOS host with ViSP already built. Instead, there is also the possibility to build docker images from a `Dockerfile` following instruction given in \ref docker_visp_build section. -\subsection docker_visp_pull_ubuntu_18_04 Pull Ubuntu 18.04 image +\subsection docker_visp_pull_ubuntu_22_04 Pull Ubuntu 22.04 image \verbatim -$ docker pull vispci/vispci:ubuntu-18.04 +$ docker pull vispci/vispci:ubuntu-22.04 \endverbatim \subsection docker_visp_pull_ubuntu_20_04 Pull Ubuntu 20.04 image @@ -89,10 +89,10 @@ $ docker pull vispci/vispci:ubuntu-18.04 $ docker pull vispci/vispci:ubuntu-20.04 \endverbatim -\subsection docker_visp_pull_ubuntu_22_04 Pull Ubuntu 22.04 image +\subsection docker_visp_pull_ubuntu_18_04 Pull Ubuntu 18.04 image \verbatim -$ docker pull vispci/vispci:ubuntu-22.04 +$ docker pull vispci/vispci:ubuntu-18.04 \endverbatim \section docker_visp_build Build docker image from Dockerfile @@ -101,25 +101,32 @@ We suppose here that you cloned ViSP from github in your workspace. Change directory to access the `Dockerfile` and build the corresponding docker image -\subsection docker_visp_build_ubuntu_18_04 Build Ubuntu 18.04 image +\subsection docker_visp_build_ubuntu_24_04 Build Ubuntu 24.04 image \verbatim -$ cd $VISP_WS/visp/ci/docker/ubuntu-18.04 -$ docker build -t vispci/vispci:ubuntu-18.04 . +$ cd $VISP_WS/visp/docker/ubuntu-24.04 +$ docker build -t vispci/vispci:ubuntu-24.04 . +\endverbatim + +\subsection docker_visp_build_ubuntu_22_04 Build Ubuntu 22.04 image + +\verbatim +$ cd $VISP_WS/visp/docker/ubuntu-22.04 +$ docker build -t vispci/vispci:ubuntu-22.04 . \endverbatim \subsection docker_visp_build_ubuntu_20_04 Build Ubuntu 20.04 image \verbatim -$ cd $VISP_WS/visp/ci/docker/ubuntu-20.04 +$ cd $VISP_WS/visp/docker/ubuntu-20.04 $ docker build -t vispci/vispci:ubuntu-20.04 . \endverbatim -\subsection docker_visp_build_ubuntu_22_04 Build Ubuntu 22.04 image +\subsection docker_visp_build_ubuntu_18_04 Build Ubuntu 18.04 image \verbatim -$ cd $VISP_WS/visp/ci/docker/ubuntu-22.04 -$ docker build -t vispci/vispci:ubuntu-22.04 . +$ cd $VISP_WS/visp/docker/ubuntu-18.04 +$ docker build -t vispci/vispci:ubuntu-18.04 . \endverbatim \section docker_visp_start Start ViSP container diff --git a/doc/tutorial/imgproc/tutorial-imgproc-count-coins.dox b/doc/tutorial/imgproc/tutorial-imgproc-count-coins.dox index 123dd01bdb..cc8431e3a6 100644 --- a/doc/tutorial/imgproc/tutorial-imgproc-count-coins.dox +++ b/doc/tutorial/imgproc/tutorial-imgproc-count-coins.dox @@ -71,7 +71,7 @@ The fill holes algorithm is basic: \image html img-tutorial-count-coins-mask.png "Left: binary image, right: result of the flood fill operation" -- substract the flood fill image from a white image to get only the holes +- subtract the flood fill image from a white image to get only the holes \image html img-tutorial-count-coins-white-holes.png "Top left: white image, bottom left: flood fill image, right: I_holes = I_white - I_flood_fill" diff --git a/doc/tutorial/misc/tutorial-ukf.dox b/doc/tutorial/misc/tutorial-ukf.dox index f8e0bb1b8e..9725d28c1c 100644 --- a/doc/tutorial/misc/tutorial-ukf.dox +++ b/doc/tutorial/misc/tutorial-ukf.dox @@ -357,17 +357,17 @@ Finally, we create the UKF and initialize its state: \snippet tutorial-ukf.cpp Init_UKF -If the internal state cannot use the standard addition and substraction, it would be necessary to write other methods: +If the internal state cannot use the standard addition and subtraction, it would be necessary to write other methods: - a method permitting to add two state vectors (see vpUnscentedKalman::setStateAddFunction), -- a method permitting to substract two state vectors (see vpUnscentedKalman::setStateResidualFunction), +- a method permitting to subtract two state vectors (see vpUnscentedKalman::setStateResidualFunction), - and a method permitting to compute the mean of several state vectors (see vpUnscentedKalman::setStateMeanFunction). If some commands are known to have an effect on the internal state, it would be necessary to write other methods: - a method for the effects of the commands on the state, without knowing the state (see vpUnscentedKalman::setCommandOnlyFunction), - and/or a method for the effects of the commands on the state, knowing the state (see vpUnscentedKalman::setCommandStateFunction). -If the measurement space cannot use the standard addition and substraction, it would be necessary to write other methods: -- a method permitting to substract two measurement vectors (see vpUnscentedKalman::setMeasurementResidualFunction), +If the measurement space cannot use the standard addition and subtraction, it would be necessary to write other methods: +- a method permitting to subtract two measurement vectors (see vpUnscentedKalman::setMeasurementResidualFunction), - and a method permitting to compute the mean of several measurement vectors (see vpUnscentedKalman::setMeasurementMeanFunction). \subsubsection tuto-ukf-tutorial-explained-initgui Details on the initialization of the Graphical User Interface diff --git a/example/kalman/ukf-nonlinear-complex-example.cpp b/example/kalman/ukf-nonlinear-complex-example.cpp index adbdb4ef2a..4b5d06ee92 100644 --- a/example/kalman/ukf-nonlinear-complex-example.cpp +++ b/example/kalman/ukf-nonlinear-complex-example.cpp @@ -28,7 +28,8 @@ * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. */ -/** \example ukf-nonlinear-complex-example.cpp +/** + * \example ukf-nonlinear-complex-example.cpp * Example of a complex non-linear use-case of the Unscented Kalman Filter (UKF). * The system we are interested in is a 4-wheel robot, moving at a low velocity. * As such, it can be modeled using a bicycle model. @@ -118,7 +119,7 @@ double normalizeAngle(const double &angle) */ vpColVector measurementMean(const std::vector &measurements, const std::vector &wm) { - const unsigned int nbPoints = measurements.size(); + const unsigned int nbPoints = static_cast(measurements.size()); const unsigned int sizeMeasurement = measurements[0].size(); const unsigned int nbLandmarks = sizeMeasurement / 2; vpColVector mean(sizeMeasurement, 0.); @@ -138,16 +139,16 @@ vpColVector measurementMean(const std::vector &measurements, const } /** - * \brief Compute the substraction between two vectors expressed in the measurement space, + * \brief Compute the subtraction between two vectors expressed in the measurement space, * such as v[0] = dist_0 ; v[1] = bearing_0; v[2] = dist_1 ; v[3] = bearing_1 ... * - * \param[in] meas Measurement to which we must substract something. - * \param[in] toSubstract The something we must substract. - * \return vpColVector \b meas - \b toSubstract . + * \param[in] meas Measurement to which we must subtract something. + * \param[in] toSubtract The something we must subtract. + * \return vpColVector \b meas - \b toSubtract . */ -vpColVector measurementResidual(const vpColVector &meas, const vpColVector &toSubstract) +vpColVector measurementResidual(const vpColVector &meas, const vpColVector &toSubtract) { - vpColVector res = meas - toSubstract; + vpColVector res = meas - toSubtract; unsigned int nbMeasures = res.size(); for (unsigned int i = 1; i < nbMeasures; i += 2) { res[i] = normalizeAngle(res[i]); @@ -180,7 +181,7 @@ vpColVector stateAdd(const vpColVector &state, const vpColVector &toAdd) vpColVector stateMean(const std::vector &states, const std::vector &wm) { vpColVector mean(3, 0.); - unsigned int nbPoints = states.size(); + unsigned int nbPoints = static_cast(states.size()); double sumCos = 0.; double sumSin = 0.; for (unsigned int i = 0; i < nbPoints; ++i) { @@ -194,16 +195,16 @@ vpColVector stateMean(const std::vector &states, const std::vector< } /** - * \brief Compute the substraction between two vectors expressed in the state space, + * \brief Compute the subtraction between two vectors expressed in the state space, * such as v[0] = x ; v[1] = y; v[2] = heading . * - * \param[in] state State to which we must substract something. - * \param[in] toSubstract The something we must substract. - * \return vpColVector \b state - \b toSubstract . + * \param[in] state State to which we must subtract something. + * \param[in] toSubtract The something we must subtract. + * \return vpColVector \b state - \b toSubtract . */ -vpColVector stateResidual(const vpColVector &state, const vpColVector &toSubstract) +vpColVector stateResidual(const vpColVector &state, const vpColVector &toSubtract) { - vpColVector res = state - toSubstract; + vpColVector res = state - toSubtract; res[2] = normalizeAngle(res[2]); return res; } @@ -474,7 +475,7 @@ class vpLandmarksGrid */ vpColVector state_to_measurement(const vpColVector &chi) { - unsigned int nbLandmarks = m_landmarks.size(); + unsigned int nbLandmarks = static_cast(m_landmarks.size()); vpColVector measurements(2*nbLandmarks); for (unsigned int i = 0; i < nbLandmarks; ++i) { vpColVector landmarkMeas = m_landmarks[i].state_to_measurement(chi); @@ -494,7 +495,7 @@ class vpLandmarksGrid */ vpColVector measureGT(const vpColVector &pos) { - unsigned int nbLandmarks = m_landmarks.size(); + unsigned int nbLandmarks = static_cast(m_landmarks.size()); vpColVector measurements(2*nbLandmarks); for (unsigned int i = 0; i < nbLandmarks; ++i) { vpColVector landmarkMeas = m_landmarks[i].measureGT(pos); @@ -514,7 +515,7 @@ class vpLandmarksGrid */ vpColVector measureWithNoise(const vpColVector &pos) { - unsigned int nbLandmarks = m_landmarks.size(); + unsigned int nbLandmarks = static_cast(m_landmarks.size()); vpColVector measurements(2*nbLandmarks); for (unsigned int i = 0; i < nbLandmarks; ++i) { vpColVector landmarkMeas = m_landmarks[i].measureWithNoise(pos); @@ -560,10 +561,10 @@ int main(const int argc, const char *argv[]) , vpLandmarkMeasurements(20, 5, sigmaRange, sigmaBearing) , vpLandmarkMeasurements(0, 30, sigmaRange, sigmaBearing) , vpLandmarkMeasurements(50, 30, sigmaRange, sigmaBearing) - , vpLandmarkMeasurements(40, 10, sigmaRange, sigmaBearing) }; // Vector of landmarks constituing the grid - const unsigned int nbLandmarks = landmarks.size(); // Number of landmarks constituing the grid + , vpLandmarkMeasurements(40, 10, sigmaRange, sigmaBearing) }; // Vector of landmarks constituting the grid + const unsigned int nbLandmarks = static_cast(landmarks.size()); // Number of landmarks constituting the grid std::vector cmds = generateCommands(); - const unsigned int nbCmds = cmds.size(); + const unsigned int nbCmds = static_cast(cmds.size()); // Initialize the attributes of the UKF std::shared_ptr drawer = std::make_shared(3, 0.1, 2., 0, stateResidual, stateAdd); diff --git a/example/kalman/ukf-nonlinear-example.cpp b/example/kalman/ukf-nonlinear-example.cpp index 067ad1b6ad..e6dce7377f 100644 --- a/example/kalman/ukf-nonlinear-example.cpp +++ b/example/kalman/ukf-nonlinear-example.cpp @@ -75,7 +75,7 @@ where \f$ w_m^i \f$ is the weight associated to the \f$ i^{th} \f$ measurements for the weighted mean. - Additionnally, the addition and substraction of angles must be carefully done, as the result + Additionnally, the addition and subtraction of angles must be carefully done, as the result must stay in the interval \f$[- \pi ; \pi ]\f$ or \f$[0 ; 2 \pi ]\f$ . We decided to use the interval \f$[- \pi ; \pi ]\f$ . */ @@ -143,7 +143,7 @@ double normalizeAngle(const double &angle) */ vpColVector measurementMean(const std::vector &measurements, const std::vector &wm) { - const unsigned int nbPoints = measurements.size(); + const unsigned int nbPoints = static_cast(measurements.size()); const unsigned int sizeMeasurement = measurements[0].size(); vpColVector mean(sizeMeasurement, 0.); double sumCos(0.); @@ -160,16 +160,16 @@ vpColVector measurementMean(const std::vector &measurements, const } /** - * \brief Compute the substraction between two vectors expressed in the measurement space, + * \brief Compute the subtraction between two vectors expressed in the measurement space, * such as v[0] = range ; v[1] = elevation_angle * - * \param[in] meas Measurement to which we must substract something. - * \param[in] toSubstract The something we must substract. - * \return vpColVector \b meas - \b toSubstract . + * \param[in] meas Measurement to which we must subtract something. + * \param[in] toSubtract The something we must subtract. + * \return vpColVector \b meas - \b toSubtract . */ -vpColVector measurementResidual(const vpColVector &meas, const vpColVector &toSubstract) +vpColVector measurementResidual(const vpColVector &meas, const vpColVector &toSubtract) { - vpColVector res = meas - toSubstract; + vpColVector res = meas - toSubtract; res[1] = normalizeAngle(res[1]); return res; } diff --git a/modules/core/include/visp3/core/vpImageMorphology.h b/modules/core/include/visp3/core/vpImageMorphology.h index dab0ee754b..b73848a3c9 100644 --- a/modules/core/include/visp3/core/vpImageMorphology.h +++ b/modules/core/include/visp3/core/vpImageMorphology.h @@ -137,6 +137,39 @@ class VISP_EXPORT vpImageMorphology #endif private: + template + class vpPixelOperation + { + public: + vpPixelOperation() { } + + virtual T operator()(const T &, const T &) = 0; + }; + + template + class vpPixelOperationMax : public vpPixelOperation + { + public: + vpPixelOperationMax() { } + + virtual T operator()(const T &a, const T &b) VP_OVERRIDE + { + return std::max(a, b); + } + }; + + template + class vpPixelOperationMin : public vpPixelOperation + { + public: + vpPixelOperationMin() { } + + T operator()(const T &a, const T &b) VP_OVERRIDE + { + return std::min(a, b); + } + }; + /** * \brief Modify the image by applying the \b operation on each of its elements on a 3x3 * grid. @@ -149,7 +182,7 @@ class VISP_EXPORT vpImageMorphology * and vertical neighbors, or a 8-connexity, if we want to also take into account the diagonal neighbors. */ template - static void imageOperation(vpImage &I, const T &null_value, const T &(*operation)(const T &, const T &), const vpConnexityType &connexity = CONNEXITY_4); + static void imageOperation(vpImage &I, const T &null_value, vpPixelOperation *operation, const vpConnexityType &connexity = CONNEXITY_4); /** * \brief Modify the image by applying the \b operation on each of its elements on a \b size x \b size @@ -161,7 +194,7 @@ class VISP_EXPORT vpImageMorphology * \param[in] size Size of the kernel of the operation. */ template - static void imageOperation(vpImage &I, const T &(*operation)(const T &, const T &), const int &size = 3); + static void imageOperation(vpImage &I, vpPixelOperation *operation, const int &size = 3); }; @@ -323,7 +356,7 @@ void vpImageMorphology::dilatation(vpImage &I, Type value, Type value_out, } template -void vpImageMorphology::imageOperation(vpImage &I, const T &null_value, const T &(*operation)(const T &, const T &), const vpConnexityType &connexity) +void vpImageMorphology::imageOperation(vpImage &I, const T &null_value, vpPixelOperation *operation, const vpConnexityType &connexity) { const int width_in = I.getWidth(); const int height_in = I.getHeight(); @@ -343,7 +376,7 @@ void vpImageMorphology::imageOperation(vpImage &I, const T &null_value, const for (int j = 0; j < width_in; ++j) { T value = null_value; for (int k = 0; k < nbOffset; ++k) { - value = operation(value, J[i + 1 + offset_y[k]][j + 1 + offset_x[k]]); + value = (*operation)(value, J[i + 1 + offset_y[k]][j + 1 + offset_x[k]]); } I[i][j] = value; @@ -359,7 +392,7 @@ void vpImageMorphology::imageOperation(vpImage &I, const T &null_value, const for (int j = 0; j < width_in; ++j) { T value = null_value; for (int k = 0; k < nbOffset; ++k) { - value = operation(value, J[i + 1 + offset_y[k]][j + 1 + offset_x[k]]); + value = (*operation)(value, J[i + 1 + offset_y[k]][j + 1 + offset_x[k]]); } I[i][j] = value; @@ -394,8 +427,8 @@ void vpImageMorphology::imageOperation(vpImage &I, const T &null_value, const template void vpImageMorphology::erosion(vpImage &I, const vpConnexityType &connexity) { - const T &(*operation)(const T & a, const T & b) = std::min; - vpImageMorphology::imageOperation(I, std::numeric_limits::max(), operation, connexity); + vpPixelOperationMin operation; + vpImageMorphology::imageOperation(I, std::numeric_limits::max(), &operation, connexity); } /*! @@ -424,12 +457,12 @@ void vpImageMorphology::erosion(vpImage &I, const vpConnexityType &connexity) template void vpImageMorphology::dilatation(vpImage &I, const vpConnexityType &connexity) { - const T &(*operation)(const T & a, const T & b) = std::max; - vpImageMorphology::imageOperation(I, std::numeric_limits::min(), operation, connexity); + vpPixelOperationMax operation; + vpImageMorphology::imageOperation(I, std::numeric_limits::min(), &operation, connexity); } template -void vpImageMorphology::imageOperation(vpImage &I, const T &(*operation)(const T &, const T &), const int &size) +void vpImageMorphology::imageOperation(vpImage &I, vpPixelOperation *operation, const int &size) { if ((size % 2) != 1) { throw(vpException(vpException::badValue, "Dilatation/erosion kernel must be odd.")); @@ -461,7 +494,7 @@ void vpImageMorphology::imageOperation(vpImage &I, const T &(*operation)(cons } for (int r_iterator = r_iterator_start; r_iterator < r_iterator_stop; ++r_iterator) { for (int c_iterator = c_iterator_start; c_iterator < c_iterator_stop; ++c_iterator) { - value = operation(value, J[r + r_iterator][c + c_iterator]); + value = (*operation)(value, J[r + r_iterator][c + c_iterator]); } } I[r][c] = value; @@ -498,8 +531,8 @@ void vpImageMorphology::imageOperation(vpImage &I, const T &(*operation)(cons template void vpImageMorphology::erosion(vpImage &I, const int &size) { - const T &(*operation)(const T & a, const T & b) = std::min; - vpImageMorphology::imageOperation(I, operation, size); + vpPixelOperationMin operation; + vpImageMorphology::imageOperation(I, &operation, size); } /** @@ -530,8 +563,8 @@ void vpImageMorphology::erosion(vpImage &I, const int &size) template void vpImageMorphology::dilatation(vpImage &I, const int &size) { - const T &(*operation)(const T & a, const T & b) = std::max; - vpImageMorphology::imageOperation(I, operation, size); + vpPixelOperationMax operation; + vpImageMorphology::imageOperation(I, &operation, size); } END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpMath.h b/modules/core/include/visp3/core/vpMath.h index c4561b5c0b..adb42b7c0f 100644 --- a/modules/core/include/visp3/core/vpMath.h +++ b/modules/core/include/visp3/core/vpMath.h @@ -356,9 +356,11 @@ class VISP_EXPORT vpMath } static std::vector > computeRegularPointsOnSphere(unsigned int maxPoints); + + typedef vpHomogeneousMatrix(*LongLattToHomogeneous)(double lonDeg, double latDeg, double radius); static std::vector getLocalTangentPlaneTransformations(const std::vector > &lonlatVec, double radius, - vpHomogeneousMatrix(*toECEF)(double lonDeg, double latDeg, double radius)); + LongLattToHomogeneous func); static vpHomogeneousMatrix lookAt(const vpColVector &from, const vpColVector &to, vpColVector tmp); diff --git a/modules/core/include/visp3/core/vpMatrix.h b/modules/core/include/visp3/core/vpMatrix.h index bf35979321..f14e76d531 100644 --- a/modules/core/include/visp3/core/vpMatrix.h +++ b/modules/core/include/visp3/core/vpMatrix.h @@ -581,6 +581,8 @@ class VISP_EXPORT vpMatrix : public vpArray2D int pseudoInverseOpenCV(vpMatrix &Ap, vpColVector &sv, int rank_in) const; int pseudoInverseOpenCV(vpMatrix &Ap, vpColVector &sv, int rank_in, vpMatrix &imA, vpMatrix &imAt, vpMatrix &kerAt) const; #endif + + vpMatrix dampedInverse(const double &ratioOfMaxSvd = 1e-4) const; //@} //------------------------------------------------- diff --git a/modules/core/include/visp3/core/vpUnscentedKalman.h b/modules/core/include/visp3/core/vpUnscentedKalman.h index 3003d1b9ec..bbdc7412e0 100644 --- a/modules/core/include/visp3/core/vpUnscentedKalman.h +++ b/modules/core/include/visp3/core/vpUnscentedKalman.h @@ -175,19 +175,19 @@ class VISP_EXPORT vpUnscentedKalman /** * \brief Function that computes either the equivalent of an addition or the equivalent - * of a substraction in the state space or in the measurement space. - * The first argument is the vector to which we must add/substract something - * and the second argument is the thing to be added/substracted. The return is the + * of a subtraction in the state space or in the measurement space. + * The first argument is the vector to which we must add/subtract something + * and the second argument is the thing to be added/subtracted. The return is the * result of this operation. */ typedef std::function vpAddSubFunction; /** - * \brief Residual function, which computes either the equivalent of the substraction in the - * state space or the equivalent of the substraction in the measurement space. - * The first argument is the vector to which we must substract something - * and the second argument is the thing to be substracted. The return is the - * result of this "substraction". + * \brief Residual function, which computes either the equivalent of the subtraction in the + * state space or the equivalent of the subtraction in the measurement space. + * The first argument is the vector to which we must subtract something + * and the second argument is the thing to be subtracted. The return is the + * result of this "subtraction". */ typedef std::function vpAddFunction; @@ -246,7 +246,7 @@ class VISP_EXPORT vpUnscentedKalman } /** - * \brief Set the measurement residual function to use when computing a substraction + * \brief Set the measurement residual function to use when computing a subtraction * in the measurement space. * * \param measResFunc The residual function to use. @@ -279,7 +279,7 @@ class VISP_EXPORT vpUnscentedKalman } /** - * \brief Set the state residual function to use when computing a substraction + * \brief Set the state residual function to use when computing a subtraction * in the state space. * * \param stateResFunc The residual function to use. @@ -393,15 +393,15 @@ class VISP_EXPORT vpUnscentedKalman } /** - * \brief Simple function to compute a residual, which just does \f$ \textbf{res} = \textbf{a} - \textbf{toSubstract} \f$ + * \brief Simple function to compute a residual, which just does \f$ \textbf{res} = \textbf{a} - \textbf{toSubtract} \f$ * - * \param[in] a Vector to which we must substract something. - * \param[in] toSubstract The something we must substract to \b a . - * \return vpColVector \f$ \textbf{res} = \textbf{a} - \textbf{toSubstract} \f$ + * \param[in] a Vector to which we must subtract something. + * \param[in] toSubtract The something we must subtract to \b a . + * \return vpColVector \f$ \textbf{res} = \textbf{a} - \textbf{toSubtract} \f$ */ - inline static vpColVector simpleResidual(const vpColVector &a, const vpColVector &toSubstract) + inline static vpColVector simpleResidual(const vpColVector &a, const vpColVector &toSubtract) { - vpColVector res = a - toSubstract; + vpColVector res = a - toSubtract; return res; } @@ -448,10 +448,10 @@ class VISP_EXPORT vpUnscentedKalman vpCommandOnlyFunction m_b; /*!< Function that permits to compute the effect of the commands on the prior, without knowledge of the state.*/ vpCommandStateFunction m_bx; /*!< Function that permits to compute the effect of the commands on the prior, with knowledge of the state.*/ vpMeanFunction m_measMeanFunc; /*!< Function to compute a weighted mean in the measurement space.*/ - vpAddSubFunction m_measResFunc; /*!< Function to compute a substraction in the measurement space.*/ + vpAddSubFunction m_measResFunc; /*!< Function to compute a subtraction in the measurement space.*/ vpAddSubFunction m_stateAddFunction; /*!< Function to compute an addition in the state space.*/ vpMeanFunction m_stateMeanFunc; /*!< Function to compute a weighted mean in the state space.*/ - vpAddSubFunction m_stateResFunc; /*!< Function to compute a substraction in the state space.*/ + vpAddSubFunction m_stateResFunc; /*!< Function to compute a subtraction in the state space.*/ /** * \brief Structure that stores the results of the unscented transform. diff --git a/modules/core/src/camera/vpXmlParserCamera.cpp b/modules/core/src/camera/vpXmlParserCamera.cpp index b8d0b8751b..094e4cb742 100644 --- a/modules/core/src/camera/vpXmlParserCamera.cpp +++ b/modules/core/src/camera/vpXmlParserCamera.cpp @@ -308,9 +308,10 @@ class vpXmlParserCamera::Impl // if same name && same projection model && same image size camera already exists, we return SEQUENCE_OK // otherwise it is a new camera that need to be updated and we return SEQUENCE_OK bool same_name = (cam_name.empty() || (cam_name == camera_name_tmp)); - bool same_img_size = (abs(static_cast(im_width) - static_cast(image_width_tmp)) < allowedPixelDiffOnImageSize || im_width == 0) && - (abs(static_cast(im_height) - static_cast(image_height_tmp)) < allowedPixelDiffOnImageSize || im_height == 0) && - (test_subsampling_width) && (test_subsampling_height); + bool imWidthOk = (abs(static_cast(im_width) - static_cast(image_width_tmp)) < allowedPixelDiffOnImageSize) || (im_width == 0); + bool imHeightOk = (abs(static_cast(im_height) - static_cast(image_height_tmp)) < allowedPixelDiffOnImageSize) || (im_height == 0); + bool imSizeOk = imWidthOk && imHeightOk; + bool same_img_size = imSizeOk && test_subsampling_width && test_subsampling_height; if (same_name && same_img_size && same_proj_model) { back = SEQUENCE_OK; // Camera exists camera = cam_tmp; @@ -761,10 +762,13 @@ class vpXmlParserCamera::Impl } } } - if (!((cam_name == camera_name_tmp) && (im_width == image_width_tmp || im_width == 0) && - (im_height == image_height_tmp || im_height == 0) && - (subsampl_width == subsampling_width_tmp || subsampl_width == 0) && - (subsampl_height == subsampling_height_tmp || subsampl_height == 0))) { + bool imHeightOK = (im_height == image_height_tmp) || (im_height == 0); + bool imWidthOK = (im_width == image_width_tmp) || (im_width == 0); + bool imSizeEqual = imHeightOK && imWidthOK; + bool subsampleHeightOK = (subsampl_height == subsampling_height_tmp) || (subsampl_height == 0); + bool subsampleWidthOK = (subsampl_width == subsampling_width_tmp) || (subsampl_width == 0); + bool subsampleOK = subsampleHeightOK && subsampleWidthOK; + if (!((cam_name == camera_name_tmp) && imSizeEqual && subsampleOK)) { back = SEQUENCE_ERROR; } return back; diff --git a/modules/core/src/display/vpDisplay_impl.h b/modules/core/src/display/vpDisplay_impl.h index 65f91861f2..6c254a5dcc 100644 --- a/modules/core/src/display/vpDisplay_impl.h +++ b/modules/core/src/display/vpDisplay_impl.h @@ -571,8 +571,9 @@ template void vp_display_display_roi(const vpImage &I, const double roiwidth = floor(roi.getWidth()); double iheight = static_cast(I.getHeight()); double iwidth = static_cast(I.getWidth()); - - if (top < 0 || top > iheight || left < 0 || left > iwidth || top + roiheight > iheight || left + roiwidth > iwidth) { + bool vertNOK = (top < 0) || (top > iheight) || ((top + roiheight) > iheight); + bool horNOK = (left < 0) || (left > iwidth) || ((left + roiwidth) > iwidth); + if (vertNOK || horNOK) { throw(vpException(vpException::dimensionError, "Region of interest outside of the image")); } diff --git a/modules/core/src/image/vpImageCircle.cpp b/modules/core/src/image/vpImageCircle.cpp index 9ea2714dad..1e3ce0d3c7 100644 --- a/modules/core/src/image/vpImageCircle.cpp +++ b/modules/core/src/image/vpImageCircle.cpp @@ -577,11 +577,14 @@ void computeIntersTopRightBottom(const float &u_c, const float &v_c, const float float theta_u_max_bottom = crossing_theta_u_max.first; float u_umin_bottom = crossing_theta_u_min.second; float u_umax_bottom = crossing_theta_u_max.second; + bool crossOnceTopHor = (u_umin_top <= umax_roi) && (u_umax_top > umax_roi); + bool dontCrossVert = (v_vmin <= vmin_roi) && (v_vmax >= vmax_roi); + bool crossOnceBotHor = (u_umin_bottom <= umax_roi) && (u_umax_bottom > umax_roi); if ((u_umax_top <= umax_roi) && (u_umax_bottom <= umax_roi) && (v_vmin >= vmin_roi) && (v_vmax <= vmax_roi)) { // case intersection top + right + bottom twice delta_theta = (2.f * M_PI_FLOAT) - ((theta_u_min_top - theta_u_max_top) + (theta_v_min - theta_v_max) + (theta_u_max_bottom - theta_u_min_bottom)); } - else if ((u_umin_top <= umax_roi) && (u_umax_top > umax_roi) && (v_vmin <= vmin_roi) && (u_umin_bottom <= umax_roi) && (u_umax_bottom > umax_roi) && (v_vmax >= vmax_roi)) { + else if (crossOnceTopHor && crossOnceBotHor && dontCrossVert) { // case intersection top and bottom delta_theta = (theta_u_max_top - theta_u_max_bottom); } diff --git a/modules/core/src/image/vpImageConvert_yuv.cpp b/modules/core/src/image/vpImageConvert_yuv.cpp index 5206a557dc..cea2ebd02a 100644 --- a/modules/core/src/image/vpImageConvert_yuv.cpp +++ b/modules/core/src/image/vpImageConvert_yuv.cpp @@ -44,12 +44,14 @@ namespace { void vpSAT(int &c) { - if (c < 0) { - c = 0; - } - else { - const unsigned int val_255 = 255; - c = val_255; + if (c & (~255)) { + if (c < 0) { + c = 0; + } + else { + const unsigned int val_255 = 255; + c = val_255; + } } } }; @@ -73,13 +75,13 @@ void vpImageConvert::YUYVToRGBa(unsigned char *yuyv, unsigned char *rgba, unsign unsigned char *d; int w, h; int r, g, b, cr, cg, cb, y1, y2; - const unsigned int val_2 = 2; - const unsigned int val_88 = 88; - const unsigned int val_128 = 128; - const unsigned int val_183 = 183; - const unsigned int val_256 = 256; - const unsigned int val_359 = 359; - const unsigned int val_454 = 454; + const int val_2 = 2; + const int val_88 = 88; + const int val_128 = 128; + const int val_183 = 183; + const int val_256 = 256; + const int val_359 = 359; + const int val_454 = 454; h = static_cast(height); w = static_cast(width); @@ -142,13 +144,13 @@ void vpImageConvert::YUYVToRGB(unsigned char *yuyv, unsigned char *rgb, unsigned unsigned char *d; int h, w; int r, g, b, cr, cg, cb, y1, y2; - const unsigned int val_2 = 2; - const unsigned int val_88 = 88; - const unsigned int val_128 = 128; - const unsigned int val_183 = 183; - const unsigned int val_256 = 256; - const unsigned int val_359 = 359; - const unsigned int val_454 = 454; + const int val_2 = 2; + const int val_88 = 88; + const int val_128 = 128; + const int val_183 = 183; + const int val_256 = 256; + const int val_359 = 359; + const int val_454 = 454; h = static_cast(height); w = static_cast(width); diff --git a/modules/core/src/math/matrix/vpColVector.cpp b/modules/core/src/math/matrix/vpColVector.cpp index cd5e66195b..6c9fc1738e 100644 --- a/modules/core/src/math/matrix/vpColVector.cpp +++ b/modules/core/src/math/matrix/vpColVector.cpp @@ -244,16 +244,16 @@ vpColVector::vpColVector(const vpMatrix &M) : vpArray2D(M.getRows(), 1) vpColVector::vpColVector(const std::vector &v) : vpArray2D(static_cast(v.size()), 1) { - size_t v_size = v.size(); - for (size_t i = 0; i < v_size; ++i) { + unsigned int v_size = static_cast(v.size()); + for (unsigned int i = 0; i < v_size; ++i) { (*this)[i] = v[i]; } } vpColVector::vpColVector(const std::vector &v) : vpArray2D(static_cast(v.size()), 1) { - size_t v_size = v.size(); - for (size_t i = 0; i < v_size; ++i) { + unsigned int v_size = static_cast(v.size()); + for (unsigned int i = 0; i < v_size; ++i) { (*this)[i] = static_cast(v[i]); } } @@ -350,9 +350,9 @@ vpColVector &vpColVector::operator=(const vpMatrix &M) vpColVector &vpColVector::operator=(const std::vector &v) { - size_t v_size = v.size(); + unsigned int v_size = static_cast(v.size()); resize(v_size, false); - for (size_t i = 0; i < v_size; ++i) { + for (unsigned int i = 0; i < v_size; ++i) { (*this)[i] = v[i]; } return *this; @@ -360,9 +360,9 @@ vpColVector &vpColVector::operator=(const std::vector &v) vpColVector &vpColVector::operator=(const std::vector &v) { - size_t v_size = v.size(); + unsigned int v_size = static_cast(v.size()); resize(v_size, false); - for (size_t i = 0; i < v_size; ++i) { + for (unsigned int i = 0; i < v_size; ++i) { (*this)[i] = static_cast(v[i]); } return *this; diff --git a/modules/core/src/math/matrix/vpMatrix_pseudo_inverse.cpp b/modules/core/src/math/matrix/vpMatrix_pseudo_inverse.cpp index 4edbd3ed75..d6eee1f0f2 100644 --- a/modules/core/src/math/matrix/vpMatrix_pseudo_inverse.cpp +++ b/modules/core/src/math/matrix/vpMatrix_pseudo_inverse.cpp @@ -1010,4 +1010,29 @@ int vpMatrix::pseudoInverse(vpMatrix &Ap, vpColVector &sv, int rank_in, vpMatrix #endif } +/*! + * Permits to compute an approximated inverse of a matrix that is ill-conditionned. + * If the matrix is well-conditionned, the damped inverse is close to the Moore-Penrose pseudo-inverse. + * + * The corresponding equation is the following, assuming that \f$ \textbf{A} \f$ + * is the matrix we want to compute the damped inverse: + * + * \f$ \textbf{A} \approx ( \lambda \textbf{I} + \textbf{A}^T \textbf{A})^{-1} \textbf{A}^T \f$ + * + * \param[in] ratioOfMaxSvd The ratio of the maximum singular value of \f$ M \f$ we want to set \f$ \lambda \f$. + * @return vpMatrix The damped inverse. + */ +vpMatrix vpMatrix::dampedInverse(const double &ratioOfMaxSvd) const +{ + vpColVector w; + vpMatrix V, Mcpy(*this); + Mcpy.svd(w, V); + double maxSingularValue = w.getMaxValue(); + vpMatrix I; + I.eye(this->colNum); + double lambda = ratioOfMaxSvd * maxSingularValue; + vpMatrix dampedInv = (lambda * I + this->transpose() * *this).inverseByLU()* this->transpose(); + return dampedInv; +} + END_VISP_NAMESPACE diff --git a/modules/core/src/math/matrix/vpRowVector.cpp b/modules/core/src/math/matrix/vpRowVector.cpp index 6b3d9bd6ab..ef1d0bcb67 100644 --- a/modules/core/src/math/matrix/vpRowVector.cpp +++ b/modules/core/src/math/matrix/vpRowVector.cpp @@ -98,9 +98,9 @@ vpRowVector &vpRowVector::operator=(const vpMatrix &M) */ vpRowVector &vpRowVector::operator=(const std::vector &v) { - size_t v_size = v.size(); + unsigned int v_size = static_cast(v.size()); resize(v_size); - for (size_t i = 0; i < v_size; ++i) { + for (unsigned int i = 0; i < v_size; ++i) { (*this)[i] = v[i]; } return *this; @@ -110,9 +110,9 @@ vpRowVector &vpRowVector::operator=(const std::vector &v) */ vpRowVector &vpRowVector::operator=(const std::vector &v) { - size_t v_size = v.size(); + unsigned int v_size = static_cast(v.size()); resize(v_size); - for (size_t i = 0; i < v_size; ++i) { + for (unsigned int i = 0; i < v_size; ++i) { (*this)[i] = static_cast(v[i]); } return *this; @@ -579,18 +579,19 @@ vpRowVector::vpRowVector(const vpMatrix &M) : vpArray2D(1, M.getCols()) */ vpRowVector::vpRowVector(const std::vector &v) : vpArray2D(1, static_cast(v.size())) { - size_t v_size = v.size(); - for (size_t j = 0; j < v_size; ++j) { + unsigned int v_size = static_cast(v.size()); + for (unsigned int j = 0; j < v_size; ++j) { (*this)[j] = v[j]; } } + /*! Constructor that creates a row vector from a std vector of float. */ vpRowVector::vpRowVector(const std::vector &v) : vpArray2D(1, static_cast(v.size())) { - size_t v_size = v.size(); - for (size_t j = 0; j < v_size; ++j) { + unsigned int v_size = static_cast(v.size()); + for (unsigned int j = 0; j < v_size; ++j) { (*this)[j] = static_cast(v[j]); } } diff --git a/modules/core/src/math/misc/vpMath.cpp b/modules/core/src/math/misc/vpMath.cpp index a9a3480042..83be4b418c 100644 --- a/modules/core/src/math/misc/vpMath.cpp +++ b/modules/core/src/math/misc/vpMath.cpp @@ -640,7 +640,7 @@ std::vector > vpMath::computeRegularPointsOnSphere(uns \sa enu2ecef(), ned2ecef() */ std::vector vpMath::getLocalTangentPlaneTransformations(const std::vector > &lonlatVec, double radius, - vpHomogeneousMatrix(*toECEF)(double lonDeg_, double latDeg_, double radius_)) + LongLattToHomogeneous toECEF) { std::vector ecef_M_local_vec; ecef_M_local_vec.reserve(lonlatVec.size()); diff --git a/modules/core/src/math/transformation/vpHomogeneousMatrix.cpp b/modules/core/src/math/transformation/vpHomogeneousMatrix.cpp index f246f9f416..20cfcc6edf 100644 --- a/modules/core/src/math/transformation/vpHomogeneousMatrix.cpp +++ b/modules/core/src/math/transformation/vpHomogeneousMatrix.cpp @@ -995,8 +995,9 @@ bool vpHomogeneousMatrix::isAnHomogeneousMatrix(double threshold) const const unsigned int index_2 = 2; const unsigned int index_3 = 3; const double epsilon = std::numeric_limits::epsilon(); - return R.isARotationMatrix(threshold) && vpMath::nul((*this)[index_3][index_0], epsilon) && vpMath::nul((*this)[index_3][index_1], epsilon) && - vpMath::nul((*this)[index_3][index_2], epsilon) && vpMath::equal((*this)[index_3][index_3], 1.0, epsilon); + bool isLastRowOK = vpMath::nul((*this)[index_3][index_0], epsilon) && vpMath::nul((*this)[index_3][index_1], epsilon) && + vpMath::nul((*this)[index_3][index_2], epsilon); + return R.isARotationMatrix(threshold) && isLastRowOK && vpMath::equal((*this)[index_3][index_3], 1.0, epsilon); } /*! diff --git a/modules/core/src/tools/geometry/vpPolygon.cpp b/modules/core/src/tools/geometry/vpPolygon.cpp index 2283401203..876a1d2a88 100644 --- a/modules/core/src/tools/geometry/vpPolygon.cpp +++ b/modules/core/src/tools/geometry/vpPolygon.cpp @@ -629,7 +629,7 @@ void vpPolygon::updateBoundingBox() std::set setI; std::set setJ; - unsigned int v_corners_size = _corners.size(); + unsigned int v_corners_size = static_cast(_corners.size()); for (unsigned int i = 0; i < v_corners_size; ++i) { setI.insert(_corners[i].get_i()); setJ.insert(_corners[i].get_j()); diff --git a/modules/core/test/tools/io/testNPZ.cpp b/modules/core/test/tools/io/testNPZ.cpp index f8cde42b80..90d9da4ef3 100644 --- a/modules/core/test/tools/io/testNPZ.cpp +++ b/modules/core/test/tools/io/testNPZ.cpp @@ -104,7 +104,7 @@ TEST_CASE("Test visp::cnpy::npy_load/npz_save", "[visp::cnpy I/O]") { std::vector save_vec; save_vec.reserve(height*width*channels); - for (size_t i = 0; i < height*width*channels; i++) { + for (int i = 0; i < static_cast(height*width*channels); ++i) { save_vec.push_back(i); } @@ -120,7 +120,7 @@ TEST_CASE("Test visp::cnpy::npy_load/npz_save", "[visp::cnpy I/O]") std::vector read_vec = arr_vec_data.as_vec(); REQUIRE(save_vec_copy.size() == read_vec.size()); - for (size_t i = 0; i < read_vec.size(); i++) { + for (size_t i = 0; i < read_vec.size(); ++i) { CHECK(save_vec_copy[i] == read_vec[i]); } } @@ -256,7 +256,7 @@ TEST_CASE("Test visp::cnpy::npy_load/npz_save", "[visp::cnpy I/O]") { std::vector vec_cMo_save; for (size_t i = 0; i < 5; i++) { - vpHomogeneousMatrix cMo_save(vpTranslationVector(1+10*i, 2+20*i, 3+30*i), vpThetaUVector(0.1+i, 0.2+i, 0.3+i)); + vpHomogeneousMatrix cMo_save(vpTranslationVector(1. +10.*i, 2. +20.*i, 3. +30.*i), vpThetaUVector(0.1+i, 0.2+i, 0.3+i)); vec_cMo_save_copy.push_back(cMo_save); vec_cMo_save.insert(vec_cMo_save.end(), cMo_save.data, cMo_save.data+cMo_save.size()); // std::cout << "cMo_save:\n" << cMo_save << std::endl; diff --git a/modules/python/examples/ukf-linear-example.py b/modules/python/examples/ukf-linear-example.py index b27b7dd7ef..8f105ccec7 100644 --- a/modules/python/examples/ukf-linear-example.py +++ b/modules/python/examples/ukf-linear-example.py @@ -115,12 +115,12 @@ def add_state_vectors(a, b) -> ColVector: def residual_state_vectors(a, b) -> ColVector: """ - Method that permits to substract a state vector to another. + Method that permits to subtract a state vector to another. - :param a: The first state vector to which another state vector must be substracted. - :param b: The other state vector that must be substracted to a. + :param a: The first state vector to which another state vector must be subtracted. + :param b: The other state vector that must be subtracted to a. - :return ColVector: The substraction a - b. + :return ColVector: The subtraction a - b. """ return a - b diff --git a/modules/python/examples/ukf-nonlinear-complex-example.py b/modules/python/examples/ukf-nonlinear-complex-example.py index 29403ef912..b204a014b3 100644 --- a/modules/python/examples/ukf-nonlinear-complex-example.py +++ b/modules/python/examples/ukf-nonlinear-complex-example.py @@ -73,7 +73,7 @@ where \f$ w_m^i \f$ is the weight associated to the \f$ i^{th} \f$ measurements for the weighted mean. - Additionnally, the addition and substraction of angles must be carefully done, as the result + Additionnally, the addition and subtraction of angles must be carefully done, as the result must stay in the interval \f$[- \pi ; \pi ]\f$ or \f$[0 ; 2 \pi ]\f$ . We decided to use the interval \f$[- \pi ; \pi ]\f$ . """ @@ -126,17 +126,17 @@ def measurement_mean(measurements: List[ColVector], wm: List[float]) -> ColVecto mean[1::2] = orientations return ColVector(mean) -def measurement_residual(meas: ColVector, to_substract: ColVector) -> ColVector: +def measurement_residual(meas: ColVector, to_subtract: ColVector) -> ColVector: """ - Compute the substraction between two vectors expressed in the measurement space, + Compute the subtraction between two vectors expressed in the measurement space, such as v[0] = dist_0 ; v[1] = bearing_0; v[2] = dist_1 ; v[3] = bearing_1 ... - :param meas: Measurement to which we must substract something. - :param toSubstract: The something we must substract. + :param meas: Measurement to which we must subtract something. + :param toSubtract: The something we must subtract. - :return ColVector: \b meas - \b toSubstract . + :return ColVector: \b meas - \b toSubtract . """ - res = meas.numpy() - to_substract.numpy() + res = meas.numpy() - to_subtract.numpy() res[1::2] = [normalize_angle(angle) for angle in res[1::2]] return ColVector(res) @@ -175,13 +175,13 @@ def state_mean_vectors(states: List[ColVector], wm: List[float]) -> ColVector: def state_residual_vectors(a, b) -> ColVector: """ - Compute the substraction between two vectors expressed in the state space, + Compute the subtraction between two vectors expressed in the state space, such as v[0] = x ; v[1] = y; v[2] = heading . - :param a: The first state vector to which another state vector must be substracted. - :param b: The other state vector that must be substracted to a. + :param a: The first state vector to which another state vector must be subtracted. + :param b: The other state vector that must be subtracted to a. - :return ColVector: The substraction a - b. + :return ColVector: The subtraction a - b. """ res = a - b return ColVector([res[0], res[1], normalize_angle(res[2])]) @@ -453,9 +453,9 @@ def measure_with_noise(self, pos: ColVector) -> ColVector: sigma_bearing = Math.rad(0.5) # Standard deviation of the bearing angle: 0.5deg wheelbase = 0.5 # Wheelbase of 0.5m process_variance = 0.0001 - positions = [ (5, 10) , (10, 5), (15, 15), (20, 5), (0, 30), (50, 30), (40, 10)] # Positions of the landmarks constituing the grid - landmarks = [LandmarkMeasurements(x, y, sigma_range, sigma_bearing) for x,y in positions] # Vector of landmarks constituing the grid - nbLandmarks = len(landmarks) # Number of landmarks constituing the grid + positions = [ (5, 10) , (10, 5), (15, 15), (20, 5), (0, 30), (50, 30), (40, 10)] # Positions of the landmarks constituting the grid + landmarks = [LandmarkMeasurements(x, y, sigma_range, sigma_bearing) for x,y in positions] # Vector of landmarks constituting the grid + nbLandmarks = len(landmarks) # Number of landmarks constituting the grid cmds = generate_commands() nb_cmds = len(cmds) diff --git a/modules/python/examples/ukf-nonlinear-example.py b/modules/python/examples/ukf-nonlinear-example.py index bd7062f3a8..d795827069 100644 --- a/modules/python/examples/ukf-nonlinear-example.py +++ b/modules/python/examples/ukf-nonlinear-example.py @@ -107,17 +107,17 @@ def measurement_mean(measurements: List[ColVector], wm: List[float]) -> ColVecto return ColVector([meanRange, mean_angle]) -def measurementResidual(meas: ColVector, to_substract: ColVector) -> ColVector: +def measurementResidual(meas: ColVector, to_subtract: ColVector) -> ColVector: """ - Compute the substraction between two vectors expressed in the measurement space, + Compute the subtraction between two vectors expressed in the measurement space, such as v[0] = range ; v[1] = elevation_angle - :param meas: Measurement to which we must substract something. - :param toSubstract: The something we must substract. + :param meas: Measurement to which we must subtract something. + :param toSubtract: The something we must subtract. - :return vpColVector: \b meas - \b toSubstract . + :return vpColVector: \b meas - \b toSubtract . """ - res_temp = meas - to_substract + res_temp = meas - to_subtract return ColVector([res_temp[0], normalize_angle(res_temp[1])]) def state_add_vectors(a, b) -> ColVector: @@ -133,12 +133,12 @@ def state_add_vectors(a, b) -> ColVector: def state_residual_vectors(a, b) -> ColVector: """ - Method that permits to substract a state vector to another. + Method that permits to subtract a state vector to another. - :param a: The first state vector to which another state vector must be substracted. - :param b: The other state vector that must be substracted to a. + :param a: The first state vector to which another state vector must be subtracted. + :param b: The other state vector that must be subtracted to a. - :return ColVector: The substraction a - b. + :return ColVector: The subtraction a - b. """ return a - b diff --git a/modules/python/examples/yolo-centering-task-afma6.py b/modules/python/examples/yolo-centering-task-afma6.py index 8221727309..4844b185c2 100644 --- a/modules/python/examples/yolo-centering-task-afma6.py +++ b/modules/python/examples/yolo-centering-task-afma6.py @@ -74,12 +74,12 @@ def add_state_vectors(a, b) -> ColVector: def residual_state_vectors(a, b) -> ColVector: """ - @brief Method that permits to substract a state vector to another. + @brief Method that permits to subtract a state vector to another. - @param a The first state vector to which another state vector must be substracted. - @param b The other state vector that must be substracted to a. + @param a The first state vector to which another state vector must be subtracted. + @param b The other state vector that must be subtracted to a. - @return ColVector The substraction a - b. + @return ColVector The subtraction a - b. """ return a - b diff --git a/modules/sensor/src/framegrabber/v4l2/vpV4l2Grabber.cpp b/modules/sensor/src/framegrabber/v4l2/vpV4l2Grabber.cpp index 7d013bc268..ed2657017f 100644 --- a/modules/sensor/src/framegrabber/v4l2/vpV4l2Grabber.cpp +++ b/modules/sensor/src/framegrabber/v4l2/vpV4l2Grabber.cpp @@ -724,8 +724,9 @@ void vpV4l2Grabber::acquire(vpImage &I, struct timeval ×tamp, const vpImageTools::crop(bitmap, width, height, roi, I); break; case V4L2_RGB24_FORMAT: // tested - if (roi == vpRect()) + if (roi == vpRect()) { vpImageConvert::RGBToRGBa((unsigned char *)bitmap, (unsigned char *)I.bitmap, width * height); + } else { vpImage tmp(height, width); vpImageConvert::RGBToRGBa((unsigned char *)bitmap, (unsigned char *)tmp.bitmap, width * height); diff --git a/modules/vision/include/visp3/vision/vpPose.h b/modules/vision/include/visp3/vision/vpPose.h index 8af6989702..752c6f8ce1 100644 --- a/modules/vision/include/visp3/vision/vpPose.h +++ b/modules/vision/include/visp3/vision/vpPose.h @@ -117,7 +117,7 @@ class VISP_EXPORT vpPose public: // Typedef a function that checks if a pose is valid. - typedef bool (*funcCheckValidityPose)(const vpHomogeneousMatrix &); + typedef bool (*FuncCheckValidityPose)(const vpHomogeneousMatrix &); /*! * Default constructor. @@ -183,7 +183,7 @@ class VISP_EXPORT vpPose * has the smallest residual. * - vpPose::RANSAC: Robust Ransac aproach (doesn't need an initialization) */ - bool computePose(vpPoseMethodType method, vpHomogeneousMatrix &cMo, funcCheckValidityPose func = nullptr); + bool computePose(vpPoseMethodType method, vpHomogeneousMatrix &cMo, FuncCheckValidityPose func = nullptr); /*! * @brief Method that first computes the pose \b cMo using the linear approaches of Dementhon and Lagrange @@ -326,7 +326,7 @@ class VISP_EXPORT vpPose * The number of threads used can then be set with setNbParallelRansacThreads(). * Filter flag can be used with setRansacFilterFlag(). */ - bool poseRansac(vpHomogeneousMatrix &cMo, funcCheckValidityPose func = nullptr); + bool poseRansac(vpHomogeneousMatrix &cMo, FuncCheckValidityPose func = nullptr); /*! * Compute the pose using virtual visual servoing approach and @@ -646,7 +646,7 @@ class VISP_EXPORT vpPose const unsigned int &numberOfInlierToReachAConsensus, const double &threshold, unsigned int &ninliers, std::vector &listInliers, vpHomogeneousMatrix &cMo, const int &maxNbTrials = 10000, bool useParallelRansac = true, unsigned int nthreads = 0, - funcCheckValidityPose func = nullptr); + FuncCheckValidityPose func = nullptr); #ifdef VISP_HAVE_HOMOGRAPHY /*! @@ -833,7 +833,7 @@ class VISP_EXPORT vpPose */ vpRansacFunctor(const vpHomogeneousMatrix &cMo_, unsigned int ransacNbInlierConsensus_, const int ransacMaxTrials_, double ransacThreshold_, unsigned int initial_seed_, bool checkDegeneratePoints_, - const std::vector &listOfUniquePoints_, funcCheckValidityPose func_) + const std::vector &listOfUniquePoints_, FuncCheckValidityPose func_) : m_best_consensus(), m_checkDegeneratePoints(checkDegeneratePoints_), m_cMo(cMo_), m_foundSolution(false), m_func(func_), m_listOfUniquePoints(listOfUniquePoints_), m_nbInliers(0), m_ransacMaxTrials(ransacMaxTrials_), m_ransacNbInlierConsensus(ransacNbInlierConsensus_), m_ransacThreshold(ransacThreshold_), @@ -870,7 +870,7 @@ class VISP_EXPORT vpPose bool m_checkDegeneratePoints; //!< Flag to check for degenerate points vpHomogeneousMatrix m_cMo; //!< Estimated pose bool m_foundSolution; //!< Solution found - funcCheckValidityPose m_func; //!< Pointer to ransac function + FuncCheckValidityPose m_func; //!< Pointer to ransac function std::vector m_listOfUniquePoints; //!< List of unique points unsigned int m_nbInliers; //!< Number of inliers int m_ransacMaxTrials; //!< Ransac max trial number diff --git a/modules/vision/src/pose-estimation/private/vpLevenbergMarquartd.cpp b/modules/vision/src/pose-estimation/private/vpLevenbergMarquartd.cpp index 6597e80974..fc9257adde 100644 --- a/modules/vision/src/pose-estimation/private/vpLevenbergMarquartd.cpp +++ b/modules/vision/src/pose-estimation/private/vpLevenbergMarquartd.cpp @@ -643,7 +643,7 @@ int qrsolv(int n, double *r, int ldr, int *ipvt, double *diag, double *qtb, doub return 0; } -bool lmderMostInnerLoop(void (*ptr_fcn)(int m, int n, double *xc, double *fvecc, double *jac, int ldfjac, int iflag), int m, int n, +bool lmderMostInnerLoop(ComputeFunctionAndJacobian ptr_fcn, int m, int n, double *x, double *fvec, double *fjac, int ldfjac, double ftol, double xtol, unsigned int maxfev, double *diag, int nprint, int *info, unsigned int *nfev, int *ipvt, double *qtf, double *wa1, double *wa2, double *wa3, double *wa4, const double &gnorm, int &iter, double &delta, double &par, double &pnorm, @@ -874,7 +874,7 @@ bool lmderMostInnerLoop(void (*ptr_fcn)(int m, int n, double *xc, double *fvecc, return false; } -int lmder(void (*ptr_fcn)(int m, int n, double *xc, double *fvecc, double *jac, int ldfjac, int iflag), int m, int n, +int lmder(ComputeFunctionAndJacobian ptr_fcn, int m, int n, double *x, double *fvec, double *fjac, int ldfjac, double ftol, double xtol, double gtol, unsigned int maxfev, double *diag, int mode, const double factor, int nprint, int *info, unsigned int *nfev, int *njev, int *ipvt, double *qtf, double *wa1, double *wa2, double *wa3, double *wa4) @@ -1183,7 +1183,7 @@ int lmder(void (*ptr_fcn)(int m, int n, double *xc, double *fvecc, double *jac, return 0; } -int lmder1(void (*ptr_fcn)(int m, int n, double *xc, double *fvecc, double *jac, int ldfjac, int iflag), int m, int n, +int lmder1(ComputeFunctionAndJacobian ptr_fcn, int m, int n, double *x, double *fvec, double *fjac, int ldfjac, double tol, int *info, int *ipvt, int lwa, double *wa) { const double factor = 100.0; diff --git a/modules/vision/src/pose-estimation/private/vpLevenbergMarquartd.h b/modules/vision/src/pose-estimation/private/vpLevenbergMarquartd.h index b4a4008373..1a693cd13c 100644 --- a/modules/vision/src/pose-estimation/private/vpLevenbergMarquartd.h +++ b/modules/vision/src/pose-estimation/private/vpLevenbergMarquartd.h @@ -267,6 +267,11 @@ double VISP_EXPORT pythag(double a, double b); int VISP_EXPORT qrfac(int m, int n, double *a, int lda, int *pivot, int *ipvt, int lipvt, double *rdiag, double *acnorm, double *wa); +/** + * \brief Function pointer towards a method that evaluates a function and its Jacobian. + */ +typedef void (*ComputeFunctionAndJacobian)(int m, int n, double *xc, double *fvecc, double *jac, int ldfjac, int iflag); + /* * PROCEDURE : lmder * @@ -372,7 +377,7 @@ int VISP_EXPORT qrfac(int m, int n, double *a, int lda, int *pivot, int *ipvt, i * En cas de succes, la valeur zero est retournee. * Sinon la valeur -1 est retournee. */ -int VISP_EXPORT lmder(void (*ptr_fcn)(int m, int n, double *xc, double *fvecc, double *jac, int ldfjac, int iflag), +int VISP_EXPORT lmder(ComputeFunctionAndJacobian ptr_fcn, int m, int n, double *x, double *fvec, double *fjac, int ldfjac, double ftol, double xtol, double gtol, unsigned int maxfev, double *diag, int mode, const double factor, int nprint, int *info, unsigned int *nfev, int *njev, int *ipvt, double *qtf, double *wa1, double *wa2, @@ -457,7 +462,7 @@ int VISP_EXPORT lmder(void (*ptr_fcn)(int m, int n, double *xc, double *fvecc, d * En cas de succes, la valeur zero est retournee. * Sinon, la valeur -1. */ -int VISP_EXPORT lmder1(void (*ptr_fcn)(int m, int n, double *xc, double *fvecc, double *jac, int ldfjac, int iflag), +int VISP_EXPORT lmder1(ComputeFunctionAndJacobian ptr_fcn, int m, int n, double *x, double *fvec, double *fjac, int ldfjac, double tol, int *info, int *ipvt, int lwa, double *wa); diff --git a/modules/vision/src/pose-estimation/vpPose.cpp b/modules/vision/src/pose-estimation/vpPose.cpp index 6bee3a938f..781d992239 100644 --- a/modules/vision/src/pose-estimation/vpPose.cpp +++ b/modules/vision/src/pose-estimation/vpPose.cpp @@ -381,7 +381,7 @@ void vpPose::callLagrangePose(vpHomogeneousMatrix &cMo) } } -bool vpPose::computePose(vpPoseMethodType method, vpHomogeneousMatrix &cMo, funcCheckValidityPose func) +bool vpPose::computePose(vpPoseMethodType method, vpHomogeneousMatrix &cMo, FuncCheckValidityPose func) { const int minNbPtDementhon = 4; const int minNbPtRansac = 4; diff --git a/modules/vision/src/pose-estimation/vpPoseRansac.cpp b/modules/vision/src/pose-estimation/vpPoseRansac.cpp index a3641e850a..7a529288cf 100644 --- a/modules/vision/src/pose-estimation/vpPoseRansac.cpp +++ b/modules/vision/src/pose-estimation/vpPoseRansac.cpp @@ -323,7 +323,7 @@ bool vpPose::vpRansacFunctor::poseRansacImpl() return foundSolution; } -bool vpPose::poseRansac(vpHomogeneousMatrix &cMo, bool (*func)(const vpHomogeneousMatrix &)) +bool vpPose::poseRansac(vpHomogeneousMatrix &cMo, FuncCheckValidityPose func) { // Check only for adding / removing problem // Do not take into account problem with element modification here @@ -572,7 +572,7 @@ void vpPose::findMatch(std::vector &p2D, std::vector &p3D, const unsigned int &numberOfInlierToReachAConsensus, const double &threshold, unsigned int &ninliers, std::vector &listInliers, vpHomogeneousMatrix &cMo, const int &maxNbTrials, bool useParallelRansac, unsigned int nthreads, - bool (*func)(const vpHomogeneousMatrix &)) + FuncCheckValidityPose func) { vpPose pose;