├── .dockerignore
├── .gitignore
├── CMakeLists.txt
├── LICENSE
├── README.md
├── cmake
├── FindGflags.cmake
└── FindGlog.cmake
├── config
├── indoor_test_config.yaml
├── outdoor_test_config.yaml
└── outdoor_test_config_64.yaml
├── docker
├── 1.Dockerfile
├── Dockerfile
├── build_docker.sh
└── run_docker.sh
├── include
├── 3rdparty
│ └── sophus
│ │ ├── LICENSE.txt
│ │ ├── average.hpp
│ │ ├── common.hpp
│ │ ├── example_ensure_handler.cpp
│ │ ├── geometry.hpp
│ │ ├── interpolate.hpp
│ │ ├── interpolate_details.hpp
│ │ ├── num_diff.hpp
│ │ ├── rotation_matrix.hpp
│ │ ├── rxso2.hpp
│ │ ├── rxso3.hpp
│ │ ├── se2.hpp
│ │ ├── se3.hpp
│ │ ├── sim2.hpp
│ │ ├── sim3.hpp
│ │ ├── sim_details.hpp
│ │ ├── so2.hpp
│ │ ├── so3.hpp
│ │ ├── test_macros.hpp
│ │ ├── types.hpp
│ │ └── velocities.hpp
├── factor
│ ├── GravityLocalParameterization.h
│ ├── ImuFactor.h
│ ├── ImuGravityFactor.h
│ ├── MarginalizationFactor.h
│ ├── PivotPointPlaneFactor.h
│ ├── PlaneProjectionFactor.h
│ ├── PlaneToPlaneFactor.h
│ ├── PointDistanceFactor.h
│ ├── PoseLocalParameterization.h
│ └── PriorFactor.h
├── feature_manager
│ └── FeatureManager.h
├── imu_processor
│ ├── Estimator.h
│ ├── ImuInitializer.h
│ ├── ImuInitializer_viorb.h
│ ├── IntegrationBase.h
│ └── MeasurementManager.h
├── map_builder
│ └── MapBuilder.h
├── point_processor
│ ├── PointMapping.h
│ ├── PointOdometry.h
│ ├── PointProcessor.h
│ └── point_types.h
├── utils
│ ├── CircularBuffer.h
│ ├── LoadVirtual.h
│ ├── TicToc.h
│ ├── Twist.h
│ ├── common_ros.h
│ ├── geometry_utils.h
│ └── math_utils.h
└── visualizer
│ └── Visualizer.h
├── launch
├── 16_scans_test.launch
├── 64_scans_test.launch
├── map_4D.launch
├── map_4D_indoor.launch
├── rs32_scans_test.launch
├── test_indoor.launch
├── test_indoor_rs32.launch
├── test_outdoor.launch
└── test_outdoor_64.launch
├── package.xml
├── rviz_cfg
├── lio_baseline.rviz
├── lio_indoor_test.rviz
├── lio_map_builder.rviz
├── lio_map_builder_indoor.rviz
├── lio_map_builder_indoor_without_mapping.rviz
├── lio_outdoor_test.rviz
└── lio_test.rviz
├── scripts
├── debug_plot.sh
└── transform_monitor.py
├── src
├── estimator_node.cc
├── factor
│ ├── GravityLocalParameterization.cc
│ ├── MarginalizationFactor.cc
│ ├── PivotPointPlaneFactor.cc
│ ├── PlaneProjectionFactor.cc
│ ├── PlaneToPlaneFactor.cc
│ ├── PointDistanceFactor.cc
│ ├── PoseLocalParameterization.cc
│ └── PriorFactor.cc
├── feature_manager
│ └── FeatureManager.cc
├── imu_processor
│ ├── Estimator.cc
│ ├── ImuInitializer.cc
│ ├── ImuInitializer_visorb.cc
│ └── MeasurementManager.cc
├── input_filters_node.cc
├── map_builder
│ └── MapBuilder.cc
├── map_builder_node.cc
├── mapping_node.cc
├── odometry_node.cc
├── point_processor
│ ├── PointMapping.cc
│ ├── PointOdometry.cc
│ └── PointProcessor.cc
├── processor_node.cc
├── save_bag_to_pcd.cc
└── visualizer
│ └── Visualizer.cc
└── test
├── data
├── imu_pose_vel.txt
└── imu_pose_vel_noise.txt
├── test_imu_processor
├── test_circular_buffer.cc
├── test_imu_factor.cc
└── test_measurement_manager.cc
├── test_point_processor
├── test_point_mapping.cc
├── test_point_odometry.cc
└── test_point_processor.cc
├── test_rotations.cc
└── test_visualizaer.cc
/.dockerignore:
--------------------------------------------------------------------------------
1 | docker
2 | .git
3 |
--------------------------------------------------------------------------------
/.gitignore:
--------------------------------------------------------------------------------
1 | .idea
2 | .vscode
3 | build
4 | cmake-build-*
5 |
--------------------------------------------------------------------------------
/README.md:
--------------------------------------------------------------------------------
1 | # LIO-mapping
2 | ## A Tightly Coupled 3D Lidar and Inertial Odometry and Mapping Approach
3 | #### Authors: Haoyang Ye, Yuying Chen, and Ming Liu from [RAM-LAB](https://ram-lab.com/).
4 | [[Paper]](https://arxiv.org/abs/1904.06993), [[Project]](https://sites.google.com/view/lio-mapping), [[Bib]](https://ram-lab.com/papers/2019/icra_2019_ye.bib). ICRA 2019.
5 | ## Table of Contents
6 | * [Demo Results](#demo-results)
7 | * [Prerequisites](#prerequisites)
8 | * [Build](#build)
9 | * [Examples](#examples)
10 | * [Docker](#docker)
11 | * [Credits](#credits)
12 | * [Licence](#licence)
13 |
14 | ## Demo Results
15 |
16 |
17 |
18 | Video: [[More indoor and outdoor tests]](https://ram-lab.com/file/hyye/lio-mapping.mp4).
19 |
20 | ## Prerequisites
21 | See [Dockerfile](docker/Dockerfile) as a reference:
22 | 1. [ROS](http://wiki.ros.org/melodic/Installation) with Ubuntu 18.04 or Ubuntu 16.04.
23 | 2. [Ceres-solver](http://ceres-solver.org/installation.html#linux).
24 | 3. [PCL](http://www.pointclouds.org/downloads/), the default version accompanying by ROS.
25 | 4. [OpenCV](https://docs.opencv.org/master/d7/d9f/tutorial_linux_install.html), the default version accompanying by ROS.
26 |
27 | ## Build
28 | 1. `git clone git@github.com:hyye/lio-mapping.git` into the `src` folder of your catkin workspace.
29 | 2. `catkin build -DCMAKE_BUILD_TYPE=Release lio` or `catkin_make -DCMAKE_BUILD_TYPE=Release`.
30 |
31 | ## Examples
32 | Some [sample data](https://drive.google.com/drive/folders/1dPy667dAnJy9wgXmlnRgQZxQF_ESuve3).
33 | 1. `source devel/setup.zsh`, or `setup.bash` if your prefer `bash`.
34 | 2. `roslaunch lio test_indoor.launch &`.
35 | 3. `roslaunch lio map_4D_indoor.launch &`.
36 | 4. `rosbag play fast1.bag`.
37 |
38 | ## Docker
39 | Try it out using docker:
40 | 1. Run `docker/build_docker.sh`.
41 | 2. Run `docker/run_docker.sh`.
42 | 3. Run `rosbag play fast1.bag`, in your host machine or in the running container.
43 |
44 | Note: Visualization (rviz) can run in the running container with [nvidia-docker](https://github.com/NVIDIA/nvidia-docker). The [Dockerfile](docker/Dockerfile) is compatible with [nvidia-docker 2.0](https://github.com/nvidia/nvidia-docker/wiki/Installation-(version-2.0)); [1.Dockerfile](docker/1.Dockerfile) with [nvidia-docker 1.0](https://github.com/nvidia/nvidia-docker/wiki/Installation-(version-1.0)).
45 |
46 | ## Credits
47 | The feature extraction, lidar-only odometry and baseline implemented were heavily derived or taken from the original [LOAM](http://wiki.ros.org/loam_velodyne) and its [modified version](https://github.com/laboshinl/loam_velodyne) (the point_processor in our project), and one of the initialization methods and the optimization pipeline from [VINS-mono](https://github.com/HKUST-Aerial-Robotics/VINS-Mono). The copyright headers are retained for the relevant files.
48 |
49 | ## Licence
50 | The source code is released under [GPL-3.0](https://www.gnu.org/licenses/).
51 |
--------------------------------------------------------------------------------
/config/indoor_test_config.yaml:
--------------------------------------------------------------------------------
1 | %YAML:1.0
2 | # lidar features
3 | min_plane_dis: 0.2
4 |
5 | min_match_sq_dis: 1.0
6 |
7 | corner_filter_size: 0.2
8 | surf_filter_size: 0.4
9 | map_filter_size: 0.6
10 |
11 | # window sizes
12 | window_size: 12 #7
13 | opt_window_size: 7 #5
14 |
15 | init_window_factor: 2
16 |
17 | # Extrinsic parameter between IMU and Camera (adapted from VINS-mono)
18 | estimate_extrinsic: 2 # 0 Have an accurate extrinsic parameters. We will trust the following imu^R_cam, imu^T_cam, don't change it.
19 | # 1 Have an initial guess about extrinsic parameters. We will optimize around your initial guess.
20 | # 2 Don't know anything about extrinsic parameters. You don't need to give R,T. We will try to calibrate it. Do some rotation movement at beginning.
21 | opt_extrinsic: 1
22 |
23 | extrinsic_rotation: !!opencv-matrix
24 | rows: 3
25 | cols: 3
26 | dt: d
27 | data: [1, 0, 0,
28 | 0, 1, 0,
29 | 0, 0, 1]
30 |
31 | #Translation from imu frame to laser frame, laser^T_imu
32 | extrinsic_translation: !!opencv-matrix
33 | rows: 3
34 | cols: 1
35 | dt: d
36 | data: [0.0, 0.0, -0.081939]
37 |
38 | # optimization options
39 | run_optimization: 1
40 |
41 | update_laser_imu: 1
42 | gravity_fix: 1
43 |
44 | plane_projection_factor: 0
45 |
46 | imu_factor: 1
47 | point_distance_factor: 1
48 |
49 | prior_factor: 0
50 |
51 | marginalization_factor: 1
52 |
53 | odom_io: 2
54 |
55 | pcl_viewer: 0
56 |
57 | # IMU noises
58 | acc_n: 0.2
59 | gyr_n: 0.02
60 | acc_w: 0.0002
61 | gyr_w: 2.0e-5
62 | g_norm: 9.805
63 |
64 | # lidar deskew
65 | enable_deskew: 1
66 | cutoff_deskew: 0
67 |
68 | keep_features: 1
69 |
70 | msg_time_delay: 0.05
--------------------------------------------------------------------------------
/config/outdoor_test_config.yaml:
--------------------------------------------------------------------------------
1 | %YAML:1.0
2 | # lidar features
3 | min_plane_dis: 0.2
4 |
5 | min_match_sq_dis: 1.0
6 |
7 | corner_filter_size: 0.2
8 | surf_filter_size: 0.4
9 | map_filter_size: 0.6
10 |
11 | # window sizes
12 | window_size: 7
13 | opt_window_size: 5
14 |
15 | init_window_factor: 1
16 |
17 | # Extrinsic parameter between IMU and Camera (adapted from VINS-mono)
18 | estimate_extrinsic: 1 # 0 Have an accurate extrinsic parameters. We will trust the following imu^R_cam, imu^T_cam, don't change it.
19 | # 1 Have an initial guess about extrinsic parameters. We will optimize around your initial guess.
20 | # 2 Don't know anything about extrinsic parameters. You don't need to give R,T. We will try to calibrate it. Do some rotation movement at beginning.
21 | opt_extrinsic: 1
22 |
23 | extrinsic_rotation: !!opencv-matrix
24 | rows: 3
25 | cols: 3
26 | dt: d
27 | data: [1, 0, 0,
28 | 0, 1, 0,
29 | 0, 0, 1]
30 |
31 | #Translation from imu frame to laser frame, laser^T_imu
32 | extrinsic_translation: !!opencv-matrix
33 | rows: 3
34 | cols: 1
35 | dt: d
36 | data: [-2.4, 0, 0.7]
37 |
38 | # optimization options
39 | run_optimization: 1
40 |
41 | update_laser_imu: 1
42 | gravity_fix: 1
43 |
44 | plane_projection_factor: 0
45 |
46 | imu_factor: 1
47 | point_distance_factor: 1
48 |
49 | prior_factor: 0
50 |
51 | marginalization_factor: 1
52 |
53 | odom_io: 3
54 |
55 | pcl_viewer: 0
56 |
57 | # IMU noises
58 | acc_n: 0.2
59 | gyr_n: 0.02
60 | acc_w: 0.0002
61 | gyr_w: 2.0e-5
62 | g_norm: 9.80
63 |
64 | # lidar deskew
65 | enable_deskew: 1
66 | cutoff_deskew: 0
67 |
68 | keep_features: 0
69 |
70 | msg_time_delay: 0.05
--------------------------------------------------------------------------------
/config/outdoor_test_config_64.yaml:
--------------------------------------------------------------------------------
1 | %YAML:1.0
2 | # lidar features
3 | min_plane_dis: 0.2
4 |
5 | min_match_sq_dis: 1.0
6 |
7 | corner_filter_size: 0.2
8 | surf_filter_size: 0.4
9 | map_filter_size: 0.6
10 |
11 | # window sizes
12 | window_size: 7
13 | opt_window_size: 5
14 |
15 | init_window_factor: 1
16 |
17 | # Extrinsic parameter between IMU and Camera (adapted from VINS-mono)
18 | estimate_extrinsic: 1 # 0 Have an accurate extrinsic parameters. We will trust the following imu^R_cam, imu^T_cam, don't change it.
19 | # 1 Have an initial guess about extrinsic parameters. We will optimize around your initial guess.
20 | # 2 Don't know anything about extrinsic parameters. You don't need to give R,T. We will try to calibrate it. Do some rotation movement at beginning.
21 | opt_extrinsic: 1
22 |
23 | # KITTI 00
24 | extrinsic_rotation: !!opencv-matrix
25 | rows: 3
26 | cols: 3
27 | dt: d
28 | data: [9.999976e-01,7.553071e-04,-2.035826e-03,
29 | -7.854027e-04,9.998898e-01,-1.482298e-02,
30 | 2.024406e-03,1.482454e-02,9.998881e-01]
31 |
32 | #Translation from imu frame to laser frame, laser^T_imu
33 | extrinsic_translation: !!opencv-matrix
34 | rows: 3
35 | cols: 1
36 | dt: d
37 | data: [-8.086759e-01,3.195559e-01,-7.997231e-01]
38 |
39 | # optimization options
40 | run_optimization: 1
41 |
42 | update_laser_imu: 1
43 | gravity_fix: 1
44 |
45 | plane_projection_factor: 0
46 |
47 | imu_factor: 1
48 | point_distance_factor: 1
49 |
50 | prior_factor: 1
51 |
52 | marginalization_factor: 1
53 |
54 | odom_io: 3
55 |
56 | pcl_viewer: 0
57 |
58 | # IMU noises
59 | acc_n: 0.2
60 | gyr_n: 0.02
61 | acc_w: 0.0002
62 | gyr_w: 2.0e-5
63 | g_norm: 9.80
64 |
65 | # lidar deskew
66 | enable_deskew: 1
67 | cutoff_deskew: 1
68 |
69 | keep_features: 0
70 |
71 | msg_time_delay: 0.00
72 |
--------------------------------------------------------------------------------
/docker/1.Dockerfile:
--------------------------------------------------------------------------------
1 | FROM osrf/ros:melodic-desktop-full
2 |
3 | ARG your_name
4 | LABEL com.nvidia.volumes.needed="nvidia_driver"
5 | ENV PATH /usr/local/nvidia/bin:${PATH}
6 | ENV LD_LIBRARY_PATH /usr/local/nvidia/lib:/usr/local/nvidia/lib64:${LD_LIBRARY_PATH}
7 |
8 | RUN apt-get update \
9 | && apt-get install -y \
10 | wget \
11 | lsb-release \
12 | sudo \
13 | mesa-utils \
14 | && apt-get clean
15 | # see: https://gitlab.com/nvidia/opengl/tree/ubuntu18.04
16 | # RUN dpkg --add-architecture i386 && \
17 | # apt-get update && apt-get install -y --no-install-recommends \
18 | # libxau6 libxau6:i386 \
19 | # libxdmcp6 libxdmcp6:i386 \
20 | # libxcb1 libxcb1:i386 \
21 | # libxext6 libxext6:i386 \
22 | # libx11-6 libx11-6:i386 && \
23 | # rm -rf /var/lib/apt/lists/*
24 | #
25 | # # nvidia-container-runtime
26 | # ENV NVIDIA_VISIBLE_DEVICES \
27 | # ${NVIDIA_VISIBLE_DEVICES:-all}
28 | # ENV NVIDIA_DRIVER_CAPABILITIES \
29 | # ${NVIDIA_DRIVER_CAPABILITIES:+$NVIDIA_DRIVER_CAPABILITIES,}graphics,compat32,utility
30 | #
31 | # RUN echo "/usr/local/nvidia/lib" >> /etc/ld.so.conf.d/nvidia.conf && \
32 | # echo "/usr/local/nvidia/lib64" >> /etc/ld.so.conf.d/nvidia.conf
33 | #
34 | # # Required for non-glvnd setups.
35 | # ENV LD_LIBRARY_PATH /usr/lib/x86_64-linux-gnu:/usr/lib/i386-linux-gnu${LD_LIBRARY_PATH:+:${LD_LIBRARY_PATH}}:/usr/local/nvidia/lib:/usr/local/nvidia/lib64
36 | #
37 | # RUN apt-get update && apt-get install -y --no-install-recommends \
38 | # libglvnd0 libglvnd0:i386 \
39 | # libgl1 libgl1:i386 \
40 | # libglx0 libglx0:i386 \
41 | # libegl1 libegl1:i386 \
42 | # libgles2 libgles2:i386 && \
43 | # rm -rf /var/lib/apt/lists/*
44 | #
45 | # COPY --from=nvidia/opengl:1.0-glvnd-runtime-ubuntu18.04 \
46 | # /usr/share/glvnd/egl_vendor.d/10_nvidia.json \
47 | # /usr/share/glvnd/egl_vendor.d/10_nvidia.json
48 | #
49 | # Prerequisites
50 | # ENV USER=$your_name
51 | RUN adduser $your_name
52 | RUN curl http://ceres-solver.org/ceres-solver-1.14.0.tar.gz --output ceres-solver-1.14.0.tar.gz
53 | RUN apt-get update && apt-get install -y --no-install-recommends \
54 | libgoogle-glog-dev libatlas-base-dev libeigen3-dev libsuitesparse-dev
55 | RUN tar zxf ceres-solver-1.14.0.tar.gz && mkdir ceres-bin && cd ceres-bin && cmake ../ceres-solver-1.14.0 && make -j6 && make install
56 | # USER $yourname
57 | # RUN mkdir -p /workspace && chmod -R 777 /workspace
58 | # COPY --chown=1000:1000 . /workspace/src/
59 | COPY . /workspace/src/
60 | RUN /bin/bash -c "source /opt/ros/melodic/setup.bash && cd /workspace && catkin_make -DCMAKE_BUILD_TYPE=Release"
61 |
--------------------------------------------------------------------------------
/docker/Dockerfile:
--------------------------------------------------------------------------------
1 | FROM osrf/ros:melodic-desktop-full
2 |
3 | ARG your_name
4 |
5 | # see: https://gitlab.com/nvidia/opengl/tree/ubuntu18.04
6 |
7 | RUN dpkg --add-architecture i386 && \
8 | apt-get update && apt-get install -y --no-install-recommends \
9 | libxau6 libxau6:i386 \
10 | libxdmcp6 libxdmcp6:i386 \
11 | libxcb1 libxcb1:i386 \
12 | libxext6 libxext6:i386 \
13 | libx11-6 libx11-6:i386 && \
14 | rm -rf /var/lib/apt/lists/*
15 |
16 | # nvidia-container-runtime
17 | ENV NVIDIA_VISIBLE_DEVICES \
18 | ${NVIDIA_VISIBLE_DEVICES:-all}
19 | ENV NVIDIA_DRIVER_CAPABILITIES \
20 | ${NVIDIA_DRIVER_CAPABILITIES:+$NVIDIA_DRIVER_CAPABILITIES,}graphics,compat32,utility
21 |
22 | RUN echo "/usr/local/nvidia/lib" >> /etc/ld.so.conf.d/nvidia.conf && \
23 | echo "/usr/local/nvidia/lib64" >> /etc/ld.so.conf.d/nvidia.conf
24 |
25 | # Required for non-glvnd setups.
26 | ENV LD_LIBRARY_PATH /usr/lib/x86_64-linux-gnu:/usr/lib/i386-linux-gnu${LD_LIBRARY_PATH:+:${LD_LIBRARY_PATH}}:/usr/local/nvidia/lib:/usr/local/nvidia/lib64
27 |
28 | RUN apt-get update && apt-get install -y --no-install-recommends \
29 | libglvnd0 libglvnd0:i386 \
30 | libgl1 libgl1:i386 \
31 | libglx0 libglx0:i386 \
32 | libegl1 libegl1:i386 \
33 | libgles2 libgles2:i386 && \
34 | rm -rf /var/lib/apt/lists/*
35 |
36 | COPY --from=nvidia/opengl:1.0-glvnd-runtime-ubuntu18.04 \
37 | /usr/share/glvnd/egl_vendor.d/10_nvidia.json \
38 | /usr/share/glvnd/egl_vendor.d/10_nvidia.json
39 |
40 | # Prerequisites
41 | # ENV USER=$your_name
42 | RUN adduser $your_name
43 | RUN curl http://ceres-solver.org/ceres-solver-1.14.0.tar.gz --output ceres-solver-1.14.0.tar.gz
44 | RUN apt-get update && apt-get install -y --no-install-recommends \
45 | libgoogle-glog-dev libatlas-base-dev libeigen3-dev libsuitesparse-dev
46 | RUN tar zxf ceres-solver-1.14.0.tar.gz && mkdir ceres-bin && cd ceres-bin && cmake ../ceres-solver-1.14.0 && make -j3 && make install
47 | # USER $yourname
48 | # RUN mkdir -p /workspace && chmod -R 777 /workspace
49 | # COPY --chown=1000:1000 . /workspace/src/
50 | COPY . /workspace/src/
51 | RUN /bin/bash -c "source /opt/ros/melodic/setup.bash && cd /workspace && catkin_make -DCMAKE_BUILD_TYPE=Release"
52 |
--------------------------------------------------------------------------------
/docker/build_docker.sh:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env bash
2 | DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null 2>&1 && pwd )"
3 | docker build --build-arg your_name=${USER} -t hyye/lio -f ${DIR}/Dockerfile ${DIR}/..
--------------------------------------------------------------------------------
/docker/run_docker.sh:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env bash
2 |
3 | until nvidia-docker ps
4 | do
5 | echo "Waiting for docker server"
6 | sleep 1
7 | done
8 |
9 |
10 | # Make sure processes in the container can connect to the x server
11 | # Necessary so rviz can create a context for OpenGL rendering
12 | XAUTH=/tmp/.docker.xauth
13 | if [ ! -f $XAUTH ]
14 | then
15 | xauth_list=$(xauth nlist :0 | sed -e 's/^..../ffff/')
16 | if [ ! -z "$xauth_list" ]
17 | then
18 | echo $xauth_list | xauth -f $XAUTH nmerge -
19 | else
20 | touch $XAUTH
21 | fi
22 | chmod a+r $XAUTH
23 | fi
24 |
25 | # nvidia-docker run -it \
26 | # -e DISPLAY=$DISPLAY \
27 | # -e QT_X11_NO_MITSHM=1 \
28 | # -e XAUTHORITY=$XAUTH \
29 | # -v "$XAUTH:$XAUTH" \
30 | # -v "/tmp/.X11-unix:/tmp/.X11-unix" \
31 | # -v "/etc/localtime:/etc/localtime:ro" \
32 | # -v "/dev/input:/dev/input" \
33 | # --privileged \
34 | # --rm=true \
35 | # --net=host \
36 | # hyye/lio
37 |
38 | nvidia-docker run -it \
39 | -e DISPLAY=$DISPLAY \
40 | -e QT_X11_NO_MITSHM=1 \
41 | -e XAUTHORITY=$XAUTH \
42 | -v "$XAUTH:$XAUTH" \
43 | --user=$USER \
44 | --volume="/etc/group:/etc/group:ro" \
45 | --volume="/etc/passwd:/etc/passwd:ro" \
46 | --volume="/etc/shadow:/etc/shadow:ro" \
47 | --volume="/etc/sudoers.d:/etc/sudoers.d:ro" \
48 | --volume="/tmp/.X11-unix:/tmp/.X11-unix:rw" \
49 | --privileged \
50 | --rm=true \
51 | --net=host \
52 | hyye/lio \
53 | /bin/bash -c "source /workspace/devel/setup.bash; sleep 1; roslaunch lio test_indoor.launch & sleep 1; roslaunch lio map_4D_indoor.launch"
54 |
--------------------------------------------------------------------------------
/include/3rdparty/sophus/LICENSE.txt:
--------------------------------------------------------------------------------
1 | Copyright 2011-2017 Hauke Strasdat
2 | 2012-2017 Steven Lovegrove
3 |
4 | Permission is hereby granted, free of charge, to any person obtaining a copy
5 | of this software and associated documentation files (the "Software"), to
6 | deal in the Software without restriction, including without limitation the
7 | rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
8 | sell copies of the Software, and to permit persons to whom the Software is
9 | furnished to do so, subject to the following conditions:
10 |
11 | The above copyright notice and this permission notice shall be included in
12 | all copies or substantial portions of the Software.
13 |
14 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
15 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
16 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
17 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
18 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
19 | FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
20 | IN THE SOFTWARE.
--------------------------------------------------------------------------------
/include/3rdparty/sophus/common.hpp:
--------------------------------------------------------------------------------
1 | #ifndef SOPHUS_COMMON_HPP
2 | #define SOPHUS_COMMON_HPP
3 |
4 | #include
5 | #include
6 | #include
7 | #include
8 | #include
9 | #include
10 |
11 | #include
12 |
13 | // following boost's assert.hpp
14 | #undef SOPHUS_ENSURE
15 |
16 | // ENSURES are similar to ASSERTS, but they are always checked for (including in
17 | // release builds). At the moment there are no ASSERTS in Sophus which should
18 | // only be used for checks which are performance critical.
19 |
20 | #ifdef __GNUC__
21 | #define SOPHUS_FUNCTION __PRETTY_FUNCTION__
22 | #elif (_MSC_VER >= 1310)
23 | #define SOPHUS_FUNCTION __FUNCTION__
24 | #else
25 | #define SOPHUS_FUNCTION "unknown"
26 | #endif
27 |
28 | // Make sure this compiles with older versions of Eigen which do not have
29 | // EIGEN_DEVICE_FUNC defined.
30 | #ifndef EIGEN_DEVICE_FUNC
31 | #define EIGEN_DEVICE_FUNC
32 | #endif
33 |
34 | #define SOPHUS_FUNC EIGEN_DEVICE_FUNC
35 |
36 | namespace Sophus {
37 | namespace details {
38 |
39 | // Following: http://stackoverflow.com/a/22759544
40 | template
41 | class IsStreamable {
42 | private:
43 | template
44 | static auto test(int)
45 | -> decltype(std::declval() << std::declval(),
46 | std::true_type());
47 |
48 | template
49 | static auto test(...) -> std::false_type;
50 |
51 | public:
52 | static bool const value = decltype(test(0))::value;
53 | };
54 |
55 | template
56 | class ArgToStream {
57 | public:
58 | static void impl(std::stringstream& stream, T&& arg) {
59 | stream << std::forward(arg);
60 | }
61 | };
62 |
63 | inline void FormatStream(std::stringstream& stream, char const* text) {
64 | stream << text;
65 | return;
66 | }
67 |
68 | // Following: http://en.cppreference.com/w/cpp/language/parameter_pack
69 | template
70 | void FormatStream(std::stringstream& stream, char const* text, T&& arg,
71 | Args&&... args) {
72 | static_assert(IsStreamable::value,
73 | "One of the args has no ostream overload!");
74 | for (; *text != '\0'; ++text) {
75 | if (*text == '%') {
76 | ArgToStream::impl(stream, std::forward(arg));
77 | FormatStream(stream, text + 1, std::forward(args)...);
78 | return;
79 | }
80 | stream << *text;
81 | }
82 | stream << "\nFormat-Warning: There are " << sizeof...(Args) + 1
83 | << " args unused.";
84 | return;
85 | }
86 |
87 | template
88 | std::string FormatString(char const* text, Args&&... args) {
89 | std::stringstream stream;
90 | FormatStream(stream, text, std::forward(args)...);
91 | return stream.str();
92 | }
93 |
94 | inline std::string FormatString() { return std::string(); }
95 | } // namespace details
96 | } // namespace Sophus
97 |
98 | #if defined(SOPHUS_DISABLE_ENSURES)
99 |
100 | #define SOPHUS_ENSURE(expr, ...) ((void)0)
101 |
102 | #elif defined(SOPHUS_ENABLE_ENSURE_HANDLER)
103 |
104 | namespace Sophus {
105 | void ensureFailed(char const* function, char const* file, int line,
106 | char const* description);
107 | }
108 |
109 | #define SOPHUS_ENSURE(expr, ...) \
110 | ((expr) ? ((void)0) \
111 | : ::Sophus::ensureFailed( \
112 | SOPHUS_FUNCTION, __FILE__, __LINE__, \
113 | Sophus::details::FormatString(##__VA_ARGS__).c_str()))
114 | #else
115 | // LCOV_EXCL_START
116 |
117 | namespace Sophus {
118 | template
119 | SOPHUS_FUNC void defaultEnsure(char const* function, char const* file, int line,
120 | char const* description, Args&&... args) {
121 | std::printf("Sophus ensure failed in function '%s', file '%s', line %d.\n",
122 | function, file, line);
123 | #ifdef __CUDACC__
124 | std::printf("%s", description);
125 | #else
126 | std::cout << details::FormatString(description, std::forward(args)...)
127 | << std::endl;
128 | std::abort();
129 | #endif
130 | }
131 | } // namespace Sophus
132 |
133 | // LCOV_EXCL_STOP
134 | #define SOPHUS_ENSURE(expr, ...) \
135 | ((expr) ? ((void)0) \
136 | : Sophus::defaultEnsure(SOPHUS_FUNCTION, __FILE__, __LINE__, \
137 | ##__VA_ARGS__))
138 | #endif
139 |
140 | namespace Sophus {
141 |
142 | template
143 | struct Constants {
144 | SOPHUS_FUNC static Scalar epsilon() { return Scalar(1e-10); }
145 |
146 | SOPHUS_FUNC static Scalar epsilonSqrt() {
147 | using std::sqrt;
148 | return sqrt(epsilon());
149 | }
150 |
151 | SOPHUS_FUNC static Scalar pi() { return Scalar(M_PI); }
152 | };
153 |
154 | template <>
155 | struct Constants {
156 | SOPHUS_FUNC static float constexpr epsilon() {
157 | return static_cast(1e-5);
158 | }
159 |
160 | SOPHUS_FUNC static float epsilonSqrt() { return std::sqrt(epsilon()); }
161 |
162 | SOPHUS_FUNC static float constexpr pi() { return static_cast(M_PI); }
163 | };
164 |
165 | // Leightweight optional implementation which require ``T`` to have a
166 | // default constructor.
167 | //
168 | // TODO: Replace with std::optional once Sophus moves to c++17.
169 | //
170 | struct nullopt_t {
171 | explicit constexpr nullopt_t() {}
172 | };
173 |
174 | constexpr nullopt_t nullopt{};
175 | template
176 |
177 | class optional {
178 | public:
179 | optional() : is_valid_(false) {}
180 |
181 | optional(nullopt_t) : is_valid_(false) {}
182 |
183 | optional(T const& type) : type_(type), is_valid_(true) {}
184 |
185 | explicit operator bool() const { return is_valid_; }
186 |
187 | T const* operator->() const {
188 | SOPHUS_ENSURE(is_valid_, "must be valid");
189 | return &type_;
190 | }
191 |
192 | T* operator->() {
193 | SOPHUS_ENSURE(is_valid_, "must be valid");
194 | return &type_;
195 | }
196 |
197 | T const& operator*() const {
198 | SOPHUS_ENSURE(is_valid_, "must be valid");
199 | return type_;
200 | }
201 |
202 | T& operator*() {
203 | SOPHUS_ENSURE(is_valid_, "must be valid");
204 | return type_;
205 | }
206 |
207 | private:
208 | T type_;
209 | bool is_valid_;
210 | };
211 |
212 | template
213 | using enable_if_t = typename std::enable_if::type;
214 |
215 | template
216 | struct IsUniformRandomBitGenerator {
217 | static const bool value = std::is_unsigned::value &&
218 | std::is_unsigned::value &&
219 | std::is_unsigned::value;
220 | };
221 | } // namespace Sophus
222 |
223 | #endif // SOPHUS_COMMON_HPP
224 |
--------------------------------------------------------------------------------
/include/3rdparty/sophus/example_ensure_handler.cpp:
--------------------------------------------------------------------------------
1 | #include "common.hpp"
2 |
3 | #include
4 | #include
5 |
6 | namespace Sophus {
7 | void ensureFailed(char const* function, char const* file, int line,
8 | char const* description) {
9 | std::printf("Sophus ensure failed in function '%s', file '%s', line %d.\n",
10 | file, function, line);
11 | std::printf("Description: %s\n", description);
12 | std::abort();
13 | }
14 | }
15 |
--------------------------------------------------------------------------------
/include/3rdparty/sophus/geometry.hpp:
--------------------------------------------------------------------------------
1 | #ifndef GEOMETRY_HPP
2 | #define GEOMETRY_HPP
3 |
4 | #include "se2.hpp"
5 | #include "se3.hpp"
6 | #include "so2.hpp"
7 | #include "so3.hpp"
8 | #include "types.hpp"
9 |
10 | namespace Sophus {
11 |
12 | // Takes in a rotation ``R_foo_plane`` and returns the corresponding line
13 | // normal along the y-axis (in reference frame ``foo``).
14 | //
15 | template
16 | Vector2 normalFromSO2(SO2 const& R_foo_line) {
17 | return R_foo_line.matrix().col(1);
18 | }
19 |
20 | // Takes in line normal in reference frame foo and constructs a corresponding
21 | // rotation matrix ``R_foo_line``.
22 | //
23 | // Precondition: ``normal_foo`` must not be close to zero.
24 | //
25 | template
26 | SO2 SO2FromNormal(Vector2 normal_foo) {
27 | SOPHUS_ENSURE(normal_foo.squaredNorm() > Constants::epsilon(), "%",
28 | normal_foo.transpose());
29 | normal_foo.normalize();
30 | return SO2(normal_foo.y(), -normal_foo.x());
31 | }
32 |
33 | // Takes in a rotation ``R_foo_plane`` and returns the corresponding plane
34 | // normal along the z-axis
35 | // (in reference frame ``foo``).
36 | //
37 | template
38 | Vector3 normalFromSO3(SO3 const& R_foo_plane) {
39 | return R_foo_plane.matrix().col(2);
40 | }
41 |
42 | // Takes in plane normal in reference frame foo and constructs a corresponding
43 | // rotation matrix ``R_foo_plane``.
44 | //
45 | // Note: The ``plane`` frame is defined as such that the normal points along the
46 | // positive z-axis. One can specify hints for the x-axis and y-axis of the
47 | // ``plane`` frame.
48 | //
49 | // Preconditions:
50 | // - ``normal_foo``, ``xDirHint_foo``, ``yDirHint_foo`` must not be close to
51 | // zero.
52 | // - ``xDirHint_foo`` and ``yDirHint_foo`` must be approx. perpendicular.
53 | //
54 | template
55 | Matrix3 rotationFromNormal(Vector3 const& normal_foo,
56 | Vector3 xDirHint_foo = Vector3(T(1), T(0),
57 | T(0)),
58 | Vector3 yDirHint_foo = Vector3(T(0), T(1),
59 | T(0))) {
60 | SOPHUS_ENSURE(xDirHint_foo.dot(yDirHint_foo) < Constants::epsilon(),
61 | "xDirHint (%) and yDirHint (%) must be perpendicular.",
62 | xDirHint_foo.transpose(), yDirHint_foo.transpose());
63 | using std::abs;
64 | using std::sqrt;
65 | T const xDirHint_foo_sqr_length = xDirHint_foo.squaredNorm();
66 | T const yDirHint_foo_sqr_length = yDirHint_foo.squaredNorm();
67 | T const normal_foo_sqr_length = normal_foo.squaredNorm();
68 | SOPHUS_ENSURE(xDirHint_foo_sqr_length > Constants::epsilon(), "%",
69 | xDirHint_foo.transpose());
70 | SOPHUS_ENSURE(yDirHint_foo_sqr_length > Constants::epsilon(), "%",
71 | yDirHint_foo.transpose());
72 | SOPHUS_ENSURE(normal_foo_sqr_length > Constants::epsilon(), "%",
73 | normal_foo.transpose());
74 |
75 | Matrix3 basis_foo;
76 | basis_foo.col(2) = normal_foo;
77 |
78 | if (abs(xDirHint_foo_sqr_length - T(1)) > Constants::epsilon()) {
79 | xDirHint_foo.normalize();
80 | }
81 | if (abs(yDirHint_foo_sqr_length - T(1)) > Constants::epsilon()) {
82 | yDirHint_foo.normalize();
83 | }
84 | if (abs(normal_foo_sqr_length - T(1)) > Constants::epsilon()) {
85 | basis_foo.col(2).normalize();
86 | }
87 |
88 | T abs_x_dot_z = abs(basis_foo.col(2).dot(xDirHint_foo));
89 | T abs_y_dot_z = abs(basis_foo.col(2).dot(yDirHint_foo));
90 | if (abs_x_dot_z < abs_y_dot_z) {
91 | // basis_foo.z and xDirHint are far from parallel.
92 | basis_foo.col(1) = basis_foo.col(2).cross(xDirHint_foo).normalized();
93 | basis_foo.col(0) = basis_foo.col(1).cross(basis_foo.col(2));
94 | } else {
95 | // basis_foo.z and yDirHint are far from parallel.
96 | basis_foo.col(0) = yDirHint_foo.cross(basis_foo.col(2)).normalized();
97 | basis_foo.col(1) = basis_foo.col(2).cross(basis_foo.col(0));
98 | }
99 | T det = basis_foo.determinant();
100 | // sanity check
101 | SOPHUS_ENSURE(abs(det - T(1)) < Constants::epsilon(),
102 | "Determinant of basis is not 1, but %. Basis is \n%\n", det,
103 | basis_foo);
104 | return basis_foo;
105 | }
106 |
107 | // Takes in plane normal in reference frame foo and constructs a corresponding
108 | // rotation matrix ``R_foo_plane``.
109 | //
110 | // See ``rotationFromNormal`` for details.
111 | //
112 | template
113 | SO3 SO3FromNormal(Vector3 const& normal_foo) {
114 | return SO3(rotationFromNormal(normal_foo));
115 | }
116 |
117 | // Returns a line (wrt. to frame ``foo``), given a pose of the ``line`` in
118 | // reference frame ``foo``.
119 | //
120 | // Note: The plane is defined by X-axis of the ``line`` frame.
121 | //
122 | template
123 | Line2 lineFromSE2(SE2 const& T_foo_line) {
124 | return Line2(normalFromSO2(T_foo_line.so2()), T_foo_line.translation());
125 | }
126 |
127 | // Returns the pose ``T_foo_line``, given a line in reference frame ``foo``.
128 | //
129 | // Note: The line is defined by X-axis of the frame ``line``.
130 | //
131 | template
132 | SE2 SE2FromLine(Line2 const& line_foo) {
133 | T const d = line_foo.offset();
134 | Vector2 const n = line_foo.normal();
135 | SO2 const R_foo_plane = SO2FromNormal(n);
136 | return SE2(R_foo_plane, -d * n);
137 | }
138 |
139 | // Returns a plane (wrt. to frame ``foo``), given a pose of the ``plane`` in
140 | // reference frame ``foo``.
141 | //
142 | // Note: The plane is defined by XY-plane of the frame ``plane``.
143 | //
144 | template
145 | Plane3 planeFromSE3(SE3 const& T_foo_plane) {
146 | return Plane3(normalFromSO3(T_foo_plane.so3()), T_foo_plane.translation());
147 | }
148 |
149 | // Returns the pose ``T_foo_plane``, given a plane in reference frame ``foo``.
150 | //
151 | // Note: The plane is defined by XY-plane of the frame ``plane``.
152 | //
153 | template
154 | SE3 SE3FromPlane(Plane3 const& plane_foo) {
155 | T const d = plane_foo.offset();
156 | Vector3 const n = plane_foo.normal();
157 | SO3 const R_foo_plane = SO3FromNormal(n);
158 | return SE3(R_foo_plane, -d * n);
159 | }
160 |
161 | // Takes in a hyperplane and returns unique representation by ensuring that the
162 | // ``offset`` is not negative.
163 | //
164 | template
165 | Eigen::Hyperplane makeHyperplaneUnique(
166 | Eigen::Hyperplane const& plane) {
167 | if (plane.offset() >= 0) {
168 | return plane;
169 | }
170 |
171 | return Eigen::Hyperplane(-plane.normal(), -plane.offset());
172 | }
173 |
174 | } // namespace Sophus
175 |
176 | #endif // GEOMETRY_HPP
177 |
--------------------------------------------------------------------------------
/include/3rdparty/sophus/interpolate.hpp:
--------------------------------------------------------------------------------
1 | #ifndef SOPHUS_INTERPOLATE_HPP
2 | #define SOPHUS_INTERPOLATE_HPP
3 |
4 | #include
5 |
6 | #include "interpolate_details.hpp"
7 |
8 | namespace Sophus {
9 |
10 | // This function interpolates between two Lie group elements ``foo_T_bar``
11 | // and ``foo_T_baz`` with an interpolation factor of ``alpha`` in [0, 1].
12 | //
13 | // It returns a pose ``foo_T_quiz`` with ``quiz`` being a frame between ``bar``
14 | // and ``baz``. If ``alpha=0`` it returns ``foo_T_bar``. If it is 1, it returns
15 | // ``foo_T_bar``.
16 | //
17 | // (Since interpolation on Lie groups is inverse-invariant, we can equivalently
18 | // think of the input arguments as being ``bar_T_foo``, ``baz_T_foo`` and the
19 | // return value being ``quiz_T_foo``.)
20 | //
21 | // Precondition: ``p`` must be in [0, 1].
22 | //
23 | template
24 | enable_if_t::supported, G> interpolate(
25 | G const& foo_T_bar, G const& foo_T_baz, Scalar2 p = Scalar2(0.5f)) {
26 | using Scalar = typename G::Scalar;
27 | Scalar inter_p(p);
28 | SOPHUS_ENSURE(inter_p >= Scalar(0) && inter_p <= Scalar(1),
29 | "p (%) must in [0, 1].");
30 | return foo_T_bar * G::exp(inter_p * (foo_T_bar.inverse() * foo_T_baz).log());
31 | }
32 |
33 | } // namespace Sophus
34 |
35 | #endif // SOPHUS_INTERPOLATE_HPP
36 |
--------------------------------------------------------------------------------
/include/3rdparty/sophus/interpolate_details.hpp:
--------------------------------------------------------------------------------
1 | #ifndef SOPHUS_INTERPOLATE_DETAILS_HPP
2 | #define SOPHUS_INTERPOLATE_DETAILS_HPP
3 |
4 | #include "rxso2.hpp"
5 | #include "rxso3.hpp"
6 | #include "se2.hpp"
7 | #include "se3.hpp"
8 | #include "sim2.hpp"
9 | #include "sim3.hpp"
10 | #include "so2.hpp"
11 | #include "so3.hpp"
12 |
13 | namespace Sophus {
14 | namespace interp_details {
15 |
16 | template
17 | struct Traits;
18 |
19 | template
20 | struct Traits> {
21 | static bool constexpr supported = true;
22 |
23 | static bool hasShortestPathAmbiguity(SO2 const& foo_T_bar) {
24 | using std::abs;
25 | Scalar angle = foo_T_bar.log();
26 | return abs(abs(angle) - Constants::pi()) <
27 | Constants::epsilon();
28 | }
29 | };
30 |
31 | template
32 | struct Traits> {
33 | static bool constexpr supported = true;
34 |
35 | static bool hasShortestPathAmbiguity(RxSO2 const& foo_T_bar) {
36 | return Traits>::hasShortestPathAmbiguity(foo_T_bar.so2());
37 | }
38 | };
39 |
40 | template
41 | struct Traits> {
42 | static bool constexpr supported = true;
43 |
44 | static bool hasShortestPathAmbiguity(SO3 const& foo_T_bar) {
45 | using std::abs;
46 | Scalar angle = foo_T_bar.logAndTheta().theta;
47 | return abs(abs(angle) - Constants::pi()) <
48 | Constants::epsilon();
49 | }
50 | };
51 |
52 | template
53 | struct Traits> {
54 | static bool constexpr supported = true;
55 |
56 | static bool hasShortestPathAmbiguity(RxSO3 const& foo_T_bar) {
57 | return Traits>::hasShortestPathAmbiguity(foo_T_bar.so3());
58 | }
59 | };
60 |
61 | template
62 | struct Traits> {
63 | static bool constexpr supported = true;
64 |
65 | static bool hasShortestPathAmbiguity(SE2 const& foo_T_bar) {
66 | return Traits>::hasShortestPathAmbiguity(foo_T_bar.so2());
67 | }
68 | };
69 |
70 | template
71 | struct Traits> {
72 | static bool constexpr supported = true;
73 |
74 | static bool hasShortestPathAmbiguity(SE3 const& foo_T_bar) {
75 | return Traits>::hasShortestPathAmbiguity(foo_T_bar.so3());
76 | }
77 | };
78 |
79 | template
80 | struct Traits> {
81 | static bool constexpr supported = true;
82 |
83 | static bool hasShortestPathAmbiguity(Sim2 const& foo_T_bar) {
84 | return Traits>::hasShortestPathAmbiguity(
85 | foo_T_bar.rxso2().so2());
86 | ;
87 | }
88 | };
89 |
90 | template
91 | struct Traits> {
92 | static bool constexpr supported = true;
93 |
94 | static bool hasShortestPathAmbiguity(Sim3 const& foo_T_bar) {
95 | return Traits>::hasShortestPathAmbiguity(
96 | foo_T_bar.rxso3().so3());
97 | ;
98 | }
99 | };
100 |
101 | } // namespace details
102 | } // namespace Sophus
103 |
104 | #endif // SOPHUS_INTERPOLATE_DETAILS_HPP
105 |
--------------------------------------------------------------------------------
/include/3rdparty/sophus/num_diff.hpp:
--------------------------------------------------------------------------------
1 | #ifndef SOPHUS_NUM_DIFF_HPP
2 | #define SOPHUS_NUM_DIFF_HPP
3 | // Numerical differentiation using finite differences
4 |
5 | #include
6 | #include
7 | #include
8 |
9 | #include "types.hpp"
10 |
11 | namespace Sophus {
12 |
13 | namespace details {
14 | template
15 | class Curve {
16 | public:
17 | template
18 | static auto num_diff(Fn curve, Scalar t, Scalar h) -> decltype(curve(t)) {
19 | using ReturnType = decltype(curve(t));
20 | static_assert(std::is_floating_point::value,
21 | "Scalar must be a floating point type.");
22 | static_assert(IsFloatingPoint::value,
23 | "ReturnType must be either a floating point scalar, "
24 | "vector or matrix.");
25 |
26 | return (curve(t + h) - curve(t - h)) / (Scalar(2) * h);
27 | }
28 | };
29 |
30 | template
31 | class VectorField {
32 | public:
33 | static Eigen::Matrix num_diff(
34 | std::function(Sophus::Vector)>
35 | vector_field,
36 | Sophus::Vector const& a, Scalar eps) {
37 | static_assert(std::is_floating_point::value,
38 | "Scalar must be a floating point type.");
39 | Eigen::Matrix J;
40 | Sophus::Vector h;
41 | h.setZero();
42 | for (int i = 0; i < M; ++i) {
43 | h[i] = eps;
44 | J.row(i) =
45 | (vector_field(a + h) - vector_field(a - h)) / (Scalar(2) * eps);
46 | h[i] = Scalar(0);
47 | }
48 |
49 | return J;
50 | }
51 | };
52 |
53 | template
54 | class VectorField {
55 | public:
56 | static Eigen::Matrix num_diff(
57 | std::function(Scalar)> vector_field,
58 | Scalar const& a, Scalar eps) {
59 | return details::Curve::num_diff(std::move(vector_field), a, eps);
60 | }
61 | };
62 | } // namespace details
63 |
64 | // Calculates the derivative of a curve at a point ``t``.
65 | //
66 | // Here, a curve is a function from a Scalar to a Euclidean space. Thus, it
67 | // returns either a Scalar, a vector or a matrix.
68 | //
69 | template
70 | auto curveNumDiff(Fn curve, Scalar t,
71 | Scalar h = Constants::epsilonSqrt())
72 | -> decltype(details::Curve::num_diff(std::move(curve), t, h)) {
73 | return details::Curve::num_diff(std::move(curve), t, h);
74 | }
75 |
76 | // Calculates the derivative of a vector field at a point ``a``.
77 | //
78 | // Here, a vector field is a function from a vector space to another vector
79 | // space.
80 | //
81 | template
82 | Eigen::Matrix vectorFieldNumDiff(
83 | Fn vector_field, ScalarOrVector const& a,
84 | Scalar eps = Constants::epsilonSqrt()) {
85 | return details::VectorField::num_diff(std::move(vector_field),
86 | a, eps);
87 | }
88 |
89 | } // namespace Sophus
90 |
91 | #endif // SOPHUS_NUM_DIFF_HPP
92 |
--------------------------------------------------------------------------------
/include/3rdparty/sophus/rotation_matrix.hpp:
--------------------------------------------------------------------------------
1 | #ifndef SOPHUS_ROTATION_MATRIX_HPP
2 | #define SOPHUS_ROTATION_MATRIX_HPP
3 |
4 | #include
5 | #include
6 |
7 | #include "types.hpp"
8 |
9 | namespace Sophus {
10 |
11 | // Takes in arbiray square matrix and returns true if it is
12 | // orthogonal.
13 | template
14 | SOPHUS_FUNC bool isOrthogonal(Eigen::MatrixBase const& R) {
15 | using Scalar = typename D::Scalar;
16 | static int const N = D::RowsAtCompileTime;
17 | static int const M = D::ColsAtCompileTime;
18 |
19 | static_assert(N == M, "must be a square matrix");
20 | static_assert(N >= 2, "must have compile time dimension >= 2");
21 |
22 | return (R * R.transpose() - Matrix::Identity()).norm() <
23 | Constants::epsilon();
24 | }
25 |
26 | // Takes in arbiray square matrix and returns true if it is
27 | // "scaled-orthogonal" with positive determinant.
28 | //
29 | template
30 | SOPHUS_FUNC bool isScaledOrthogonalAndPositive(Eigen::MatrixBase const& sR) {
31 | using Scalar = typename D::Scalar;
32 | static int const N = D::RowsAtCompileTime;
33 | static int const M = D::ColsAtCompileTime;
34 | using std::pow;
35 | using std::sqrt;
36 |
37 | Scalar det = sR.determinant();
38 |
39 | if (det <= Scalar(0)) {
40 | return false;
41 | }
42 |
43 | Scalar scale_sqr = pow(det, Scalar(2. / N));
44 |
45 | static_assert(N == M, "must be a square matrix");
46 | static_assert(N >= 2, "must have compile time dimension >= 2");
47 |
48 | return (sR * sR.transpose() - scale_sqr * Matrix::Identity())
49 | .template lpNorm() <
50 | sqrt(Constants::epsilon());
51 | }
52 |
53 | // Takes in arbiray square matrix (2x2 or larger) and returns closest
54 | // orthogonal matrix with positive determinant.
55 | template
56 | SOPHUS_FUNC enable_if_t<
57 | std::is_floating_point::value,
58 | Matrix>
59 | makeRotationMatrix(Eigen::MatrixBase const& R) {
60 | using Scalar = typename D::Scalar;
61 | static int const N = D::RowsAtCompileTime;
62 | static int const M = D::ColsAtCompileTime;
63 |
64 | static_assert(N == M, "must be a square matrix");
65 | static_assert(N >= 2, "must have compile time dimension >= 2");
66 |
67 | Eigen::JacobiSVD> svd(
68 | R, Eigen::ComputeFullU | Eigen::ComputeFullV);
69 |
70 | // Determine determinant of orthogonal matrix U*V'.
71 | Scalar d = (svd.matrixU() * svd.matrixV().transpose()).determinant();
72 | // Starting from the identity matrix D, set the last entry to d (+1 or
73 | // -1), so that det(U*D*V') = 1.
74 | Matrix Diag = Matrix::Identity();
75 | Diag(N - 1, N - 1) = d;
76 | return svd.matrixU() * Diag * svd.matrixV().transpose();
77 | }
78 |
79 | } // namespace Sophus
80 |
81 | #endif // SOPHUS_ROTATION_MATRIX_HPP
82 |
--------------------------------------------------------------------------------
/include/3rdparty/sophus/sim_details.hpp:
--------------------------------------------------------------------------------
1 | #ifndef SOPHUS_SIM_DETAILS_HPP
2 | #define SOPHUS_SIM_DETAILS_HPP
3 |
4 | #include "types.hpp"
5 |
6 | namespace Sophus {
7 | namespace details {
8 |
9 | template
10 | Matrix calcW(Matrix const& Omega,
11 | Scalar const theta, Scalar const sigma) {
12 | using std::abs;
13 | using std::exp;
14 | using std::sin;
15 | using std::cos;
16 | static Matrix const I = Matrix::Identity();
17 | static Scalar const one(1);
18 | static Scalar const half(0.5);
19 | Matrix const Omega2 = Omega * Omega;
20 | Scalar const scale = exp(sigma);
21 | Scalar A, B, C;
22 | if (abs(sigma) < Constants::epsilon()) {
23 | C = one;
24 | if (abs(theta) < Constants::epsilon()) {
25 | A = half;
26 | B = Scalar(1. / 6.);
27 | } else {
28 | Scalar theta_sq = theta * theta;
29 | A = (one - cos(theta)) / theta_sq;
30 | B = (theta - sin(theta)) / (theta_sq * theta);
31 | }
32 | } else {
33 | C = (scale - one) / sigma;
34 | if (abs(theta) < Constants::epsilon()) {
35 | Scalar sigma_sq = sigma * sigma;
36 | A = ((sigma - one) * scale + one) / sigma_sq;
37 | B = (scale * half * sigma_sq + scale - one - sigma * scale) /
38 | (sigma_sq * sigma);
39 | } else {
40 | Scalar theta_sq = theta * theta;
41 | Scalar a = scale * sin(theta);
42 | Scalar b = scale * cos(theta);
43 | Scalar c = theta_sq + sigma * sigma;
44 | A = (a * sigma + (one - b) * theta) / (theta * c);
45 | B = (C - ((b - one) * sigma + a * theta) / (c)) * one / (theta_sq);
46 | }
47 | }
48 | return A * Omega + B * Omega2 + C * I;
49 | }
50 |
51 | template
52 | Matrix calcWInv(Matrix const& Omega,
53 | Scalar const theta, Scalar const sigma,
54 | Scalar const scale) {
55 | using std::abs;
56 | using std::sin;
57 | using std::cos;
58 | static Matrix const I = Matrix::Identity();
59 | static Scalar const half(0.5);
60 | static Scalar const one(1);
61 | static Scalar const two(2);
62 | Matrix const Omega2 = Omega * Omega;
63 | Scalar const scale_sq = scale * scale;
64 | Scalar const theta_sq = theta * theta;
65 | Scalar const sin_theta = sin(theta);
66 | Scalar const cos_theta = cos(theta);
67 |
68 | Scalar a, b, c;
69 | if (abs(sigma * sigma) < Constants::epsilon()) {
70 | c = one - half * sigma;
71 | a = -half;
72 | if (abs(theta_sq) < Constants::epsilon()) {
73 | b = Scalar(1. / 12.);
74 | } else {
75 | b = (theta * sin_theta + two * cos_theta - two) /
76 | (two * theta_sq * (cos_theta - one));
77 | }
78 | } else {
79 | Scalar const scale_cu = scale_sq * scale;
80 | c = sigma / (scale - one);
81 | if (abs(theta_sq) < Constants::epsilon()) {
82 | a = (-sigma * scale + scale - one) / ((scale - one) * (scale - one));
83 | b = (scale_sq * sigma - two * scale_sq + scale * sigma + two * scale) /
84 | (two * scale_cu - Scalar(6) * scale_sq + Scalar(6) * scale - two);
85 | } else {
86 | Scalar const s_sin_theta = scale * sin_theta;
87 | Scalar const s_cos_theta = scale * cos_theta;
88 | a = (theta * s_cos_theta - theta - sigma * s_sin_theta) /
89 | (theta * (scale_sq - two * s_cos_theta + one));
90 | b = -scale *
91 | (theta * s_sin_theta - theta * sin_theta + sigma * s_cos_theta -
92 | scale * sigma + sigma * cos_theta - sigma) /
93 | (theta_sq * (scale_cu - two * scale * s_cos_theta - scale_sq +
94 | two * s_cos_theta + scale - one));
95 | }
96 | }
97 | return a * Omega + b * Omega2 + c * I;
98 | }
99 |
100 | } // details
101 | } // Sophus
102 |
103 | #endif
104 |
--------------------------------------------------------------------------------
/include/3rdparty/sophus/test_macros.hpp:
--------------------------------------------------------------------------------
1 | #ifndef SOPUHS_TESTS_MACROS_HPP
2 | #define SOPUHS_TESTS_MACROS_HPP
3 |
4 | #include
5 |
6 | namespace Sophus {
7 | namespace details {
8 |
9 | template
10 | class Pretty {
11 | public:
12 | static std::string impl(Scalar s) { return FormatString("%", s); }
13 | };
14 |
15 | template
16 | class Pretty> {
17 | public:
18 | static std::string impl(Matrix const& v) {
19 | return FormatString("\n%\n", v);
20 | }
21 | };
22 |
23 | template
24 | std::string pretty(T const& v) {
25 | return Pretty::impl(v);
26 | }
27 |
28 | template
29 | void testFailed(bool& passed, char const* func, char const* file, int line,
30 | std::string const& msg) {
31 | std::cerr << FormatString("Test failed in function %, file %, line %\n", func,
32 | file, line);
33 | std::cerr << msg << "\n\n";
34 | passed = false;
35 | }
36 | } // namespace details
37 |
38 | void processTestResult(bool passed) {
39 | if (!passed) {
40 | // LCOV_EXCL_START
41 | std::cerr << "failed!" << std::endl << std::endl;
42 | exit(-1);
43 | // LCOV_EXCL_STOP
44 | }
45 | std::cerr << "passed." << std::endl << std::endl;
46 | }
47 | } // namespace Sophus
48 |
49 | #define SOPHUS_STRINGIFY(x) #x
50 |
51 | // GenericTests whether condition is true.
52 | // The in-out parameter passed will be set to false if test fails.
53 | #define SOPHUS_TEST(passed, condition, ...) \
54 | do { \
55 | if (!(condition)) { \
56 | std::string msg = Sophus::details::FormatString( \
57 | "condition ``%`` is false\n", SOPHUS_STRINGIFY(condition)); \
58 | msg += Sophus::details::FormatString(__VA_ARGS__); \
59 | Sophus::details::testFailed(passed, SOPHUS_FUNCTION, __FILE__, __LINE__, \
60 | msg); \
61 | } \
62 | } while (false)
63 |
64 | // GenericTests whether left is equal to right given a threshold.
65 | // The in-out parameter passed will be set to false if test fails.
66 | #define SOPHUS_TEST_EQUAL(passed, left, right, ...) \
67 | do { \
68 | if (left != right) { \
69 | std::string msg = Sophus::details::FormatString( \
70 | "% (=%) is not equal to % (=%)\n", SOPHUS_STRINGIFY(left), \
71 | Sophus::details::pretty(left), SOPHUS_STRINGIFY(right), \
72 | Sophus::details::pretty(right)); \
73 | msg += Sophus::details::FormatString(__VA_ARGS__); \
74 | Sophus::details::testFailed(passed, SOPHUS_FUNCTION, __FILE__, __LINE__, \
75 | msg); \
76 | } \
77 | } while (false)
78 |
79 | // GenericTests whether left is equal to right given a threshold.
80 | // The in-out parameter passed will be set to false if test fails.
81 | #define SOPHUS_TEST_NEQ(passed, left, right, ...) \
82 | do { \
83 | if (left == right) { \
84 | std::string msg = Sophus::details::FormatString( \
85 | "% (=%) shoudl not be equal to % (=%)\n", SOPHUS_STRINGIFY(left), \
86 | Sophus::details::pretty(left), SOPHUS_STRINGIFY(right), \
87 | Sophus::details::pretty(right)); \
88 | msg += Sophus::details::FormatString(__VA_ARGS__); \
89 | Sophus::details::testFailed(passed, SOPHUS_FUNCTION, __FILE__, __LINE__, \
90 | msg); \
91 | } \
92 | } while (false)
93 |
94 | // GenericTests whether left is approximatly equal to right given a threshold.
95 | // The in-out parameter passed will be set to false if test fails.
96 | #define SOPHUS_TEST_APPROX(passed, left, right, thr, ...) \
97 | do { \
98 | auto nrm = Sophus::maxMetric((left), (right)); \
99 | if (!(nrm < (thr))) { \
100 | std::string msg = Sophus::details::FormatString( \
101 | "% (=%) is not approx % (=%); % is %; nrm is %\n", \
102 | SOPHUS_STRINGIFY(left), Sophus::details::pretty(left), \
103 | SOPHUS_STRINGIFY(right), Sophus::details::pretty(right), \
104 | SOPHUS_STRINGIFY(thr), Sophus::details::pretty(thr), nrm); \
105 | msg += Sophus::details::FormatString(__VA_ARGS__); \
106 | Sophus::details::testFailed(passed, SOPHUS_FUNCTION, __FILE__, __LINE__, \
107 | msg); \
108 | } \
109 | } while (false)
110 |
111 | // GenericTests whether left is NOT approximatly equal to right given a
112 | // threshold.
113 | // The in-out parameter passed will be set to false if test fails.
114 | #define SOPHUS_TEST_NOT_APPROX(passed, left, right, thr, ...) \
115 | do { \
116 | auto nrm = Sophus::maxMetric((left), (right)); \
117 | if (nrm < (thr)) { \
118 | std::string msg = Sophus::details::FormatString( \
119 | "% (=%) is approx % (=%), but it should not!\n % is %; nrm is %\n", \
120 | SOPHUS_STRINGIFY(left), Sophus::details::pretty(left), \
121 | SOPHUS_STRINGIFY(right), Sophus::details::pretty(right), \
122 | SOPHUS_STRINGIFY(thr), Sophus::details::pretty(thr), nrm); \
123 | msg += Sophus::details::FormatString(__VA_ARGS__); \
124 | Sophus::details::testFailed(passed, SOPHUS_FUNCTION, __FILE__, __LINE__, \
125 | msg); \
126 | } \
127 | } while (false)
128 |
129 | #endif // SOPUHS_TESTS_MACROS_HPP
130 |
--------------------------------------------------------------------------------
/include/3rdparty/sophus/types.hpp:
--------------------------------------------------------------------------------
1 | #ifndef SOPHUS_TYEPES_HPP
2 | #define SOPHUS_TYEPES_HPP
3 |
4 | #include "common.hpp"
5 |
6 | namespace Sophus {
7 |
8 | template
9 | using Vector = Eigen::Matrix;
10 |
11 | template
12 | using Vector2 = Vector;
13 | using Vector2f = Vector2;
14 | using Vector2d = Vector2;
15 |
16 | template
17 | using Vector3 = Vector;
18 | using Vector3f = Vector3;
19 | using Vector3d = Vector3;
20 |
21 | template
22 | using Vector4 = Vector;
23 | using Vector4f = Vector4;
24 | using Vector4d = Vector4;
25 |
26 | template
27 | using Vector6 = Vector;
28 | using Vector6f = Vector6;
29 | using Vector6d = Vector6;
30 |
31 | template
32 | using Vector7 = Vector;
33 | using Vector7f = Vector7;
34 | using Vector7d = Vector7;
35 |
36 | template
37 | using Matrix = Eigen::Matrix;
38 |
39 | template
40 | using Matrix2 = Matrix;
41 | using Matrix2f = Matrix2;
42 | using Matrix2d = Matrix2;
43 |
44 | template
45 | using Matrix3 = Matrix;
46 | using Matrix3f = Matrix3;
47 | using Matrix3d = Matrix3;
48 |
49 | template
50 | using Matrix4 = Matrix;
51 | using Matrix4f = Matrix4;
52 | using Matrix4d = Matrix4;
53 |
54 | template
55 | using Matrix6 = Matrix;
56 | using Matrix6f = Matrix6;
57 | using Matrix6d = Matrix6;
58 |
59 | template
60 | using Matrix7 = Matrix;
61 | using Matrix7f = Matrix7;
62 | using Matrix7d = Matrix7;
63 |
64 | template
65 | using ParametrizedLine = Eigen::ParametrizedLine;
66 |
67 | template
68 | using ParametrizedLine3 = ParametrizedLine;
69 | using ParametrizedLine3f = ParametrizedLine3;
70 | using ParametrizedLine3d = ParametrizedLine3;
71 |
72 | template
73 | using ParametrizedLine2 = ParametrizedLine;
74 | using ParametrizedLine2f = ParametrizedLine2