A flexible submap-based framework towards spatio-temporally consistent volumetric mapping and scene understanding.

Overview

Panoptic Mapping

This package contains panoptic_mapping, a general framework for semantic volumetric mapping. We provide, among other, a submap-based approach that leverages panoptic scene understanding towards adaptive spatio-temporally consistent volumetric mapping, as well as regular, monolithic semantic mapping.

combined

Multi-resolution 3D Reconstruction, active and inactive panoptic submaps for temporal consistency, online change detection, and more.

Table of Contents

Credits

Setup

Examples

Other

Paper

If you find this package useful for your research, please consider citing our paper:

  • Lukas Schmid, Jeffrey Delmerico, Johannes Schönberger, Juan Nieto, Marc Pollefeys, Roland Siegwart, and Cesar Cadena. "Panoptic Multi-TSDFs: a Flexible Representation for Online Multi-resolution Volumetric Mapping and Long-term Dynamic Scene Consistency" arXiv preprint arXiv:2109.10165 (2021). [ArXiv]
    @ARTICLE{schmid2021panoptic,
      title={Panoptic Multi-TSDFs: a Flexible Representation for Online Multi-resolution Volumetric Mapping and Long-term Dynamic Scene Consistency},
      author={Schmid, Lukas and Delmerico, Jeffrey and Sch{\"o}nberger, Johannes and Nieto, Juan and Pollefeys, Marc and Siegwart, Roland and Cadena, Cesar},
      journal={arXiv preprint arXiv:2109.10165},
      year={2021}
    }

Video

A short video overview explaining the approach will be released upon publication.

Installation

Installation instructions for Linux. The repository was developed on Ubuntu 18.04 with ROS melodic and also tested on Ubuntu 20.04 with ROS noetic.

Prerequisites

  1. If not already done so, install ROS (Desktop-Full is recommended).

  2. If not already done so, create a catkin workspace with catkin tools:

    # Create a new workspace
    sudo apt-get install python-catkin-tools
    mkdir -p ~/catkin_ws/src
    cd ~/catkin_ws
    catkin init
    catkin config --extend /opt/ros/$ROS_DISTRO
    catkin config --cmake-args -DCMAKE_BUILD_TYPE=RelWithDebInfo
    catkin config --merge-devel

Installation

  1. Install system dependencies:

    sudo apt-get install python-wstool python-catkin-tools
  2. Move to your catkin workspace:

    cd ~/catkin_ws/src
  3. Download repo using SSH:

    git clone [email protected]:ethz-asl/panoptic_mapping.git
  4. Download and install package dependencies using ros install:

    • If you created a new workspace.
    wstool init . ./panoptic_mapping/panoptic_mapping.rosinstall
    wstool update
    • If you use an existing workspace. Notice that some dependencies require specific branches that will be checked out.
    wstool merge -t . ./panoptic_mapping/panoptic_mapping.rosinstall
    wstool update
  5. Compile and source:

    catkin build panoptic_mapping_utils
    source ../devel/setup.bash

Datasets

The datasets described in the paper and used for the demo can be downloaded from the ASL Datasets.

To a utility script is provided to directly download the data:

roscd panoptic_mapping_utils
export FLAT_DATA_DIR="/home/$USER/Documents"  # Or whichever path you prefer.
chmod +x panoptic_mapping_utils/scripts/download_flat_dataset.sh
./panoptic_mapping_utils/scripts/download_flat_dataset.sh

Additional data to run the mapper on the 3RScan dataset will follow.

Examples

Running the Panoptic Mapper

This example explains how to run the Panoptic Multi-TSDF mapper on the flat dataset.

  1. First, download the flat dataset:

    export FLAT_DATA_DIR="/home/$USER/Documents"  # Or whichever path you prefer.
    chmod +x panoptic_mapping_utils/scripts/download_flat_dataset.sh
    ./panoptic_mapping_utils/scripts/download_flat_dataset.sh
    
  2. Replace the data base_path in launch/run.launch (L10) and file_name in config/mapper/flat_groundtruth.yaml (L15) to the downloaded path.

  3. Run the mapper:

    roslaunch panoptic_mapping_ros run.launch
    
  4. You should now see the map being incrementally built:

  5. After the map finished building, you can save the map:

    rosservice call /panoptic_mapper/save_map "file_path: '/path/to/run1.panmap'" 
    
  6. Terminate the mapper pressing Ctrl+C. You can continue the experiment on run2 of the flat dataset by changing the base_path-ending in launch/run.launch (L10) to run2, and load_map and load_path in launch/run.launch (L26-27) to true and /path/to/run1.panmap, respectively. Optionally, you can also change the color_mode in config/mapper/flat_groundtruth.yaml (L118) to change to better highlight the change detection at work.

    roslaunch panoptic_mapping_ros run.launch
    
  7. You should now see the map being updated based on the first run:

Monolithic Semantic Mapping

This example will follow shortly.

Running the RIO Dataset

This example will follow shortly.

Contributing

panoptic_mapping is an open-source project, any contributions are welcome!

For issues, bugs, or suggestions, please open a GitHub Issue.

To add to this repository:

  • Please employ the feature-branch workflow.
  • Setup our auto-formatter for coherent style (we follow the google style guide):
    # Download the linter
    cd <linter_dest>
    git clone [email protected]:ethz-asl/linter.git
    cd linter
    echo ". $(realpath setup_linter.sh)" >> ~/.bashrc
    bash
    roscd panoptic_mapping/..
    init_linter_git_hooks
    # You're all set to go!
    
  • Please open a Pull Request for your changes.
  • Thank you for contributing!
Comments
  • Intermittent panoptic_mapper crashing (segfaulting)

    Intermittent panoptic_mapper crashing (segfaulting)

    Hello @Schmluk

    First of all you have a great package over here. I was able to compile your package on my ubuntu 18.04 and was successfully able to run the flatdataset demo files as well.

    However when I tried to run the same node on my custom dataset I am facing intermittent segmentation fault issues from the panoptic_mapper side. These segfaults are happening at variable timestamps within the same rosbag file over multiple runs. I have had 1 or 2 successful instances in avoiding the crash over the same rosbag play duration. This is what the stack trace showed:

    I0218 00:26:42.016423 24927 single_tsdf_integrator.cpp:120] Allocate: 306ms, Integrate: 1208ms.
    I0218 00:26:42.081941 24927 map_manager.cpp:101] Pruned active blocks in 65ms.
    Pruned 131 blocks from submap 0 (Unknown) in 65ms.
    W0218 00:26:42.095261 24927 single_tsdf_visualizer.cpp:63] No Map to visualize.
    I0218 00:26:42.108364 24927 panoptic_mapper.cpp:315] Processed input data.
    (tracking: 0 + integration: 1515 + management: 78 + visual: 0 = 1594, frame: 1627ms)
    terminate called after throwing an instance of 'std::out_of_range'
      what():  _Map_base::at
    *** Aborted at 1645136547 (unix time) try "date -d @1645136547" if you are using GNU date ***
    PC: @     0x7f88cc039fb7 gsignal
    *** SIGABRT (@0x4e7b) received by PID 20091 (TID 0x7f88697fa700) from PID 20091; stack trace: ***
        @     0x7f88cc03a040 (unknown)
        @     0x7f88cc039fb7 gsignal
        @     0x7f88cc03b921 abort
        @     0x7f88cc690957 (unknown)
        @     0x7f88cc696ae6 (unknown)
        @     0x7f88cc696b21 std::terminate()
        @     0x7f88cc696d54 __cxa_throw
        @     0x7f88cc692837 (unknown)
        @     0x7f88c9404ebe panoptic_mapping::SubmapCollection::getSubmapPtr()
        @     0x7f88c94823b7 panoptic_mapping::SingleTsdfIntegrator::processInput()
        @     0x7f88cc9d4aea panoptic_mapping::PanopticMapper::processInput()
        @     0x7f88cc9d57f4 panoptic_mapping::PanopticMapper::inputCallback()
        @     0x7f88cd7f9dd7 ros::TimerManager<>::TimerQueueCallback::call()
        @     0x7f88cd81e829 ros::CallbackQueue::callOneCB()
        @     0x7f88cd81fb15 ros::CallbackQueue::callOne()
        @     0x7f88cd876f44 ros::AsyncSpinnerImpl::threadFunc()
        @     0x7f88ca8c3bcd (unknown)
        @     0x7f88cb4aa6db start_thread
        @     0x7f88cc11c71f clone
    

    This made me think that I probably have some wrong parameters set due to which the mapper is trying to access a submap which might have gotten already pruned. However I did come across 1-2 instances in which the same node did not crash here is the console ouput from that run. (Note: No parameters were changed for either of runs).

    I0218 00:23:16.871966 21811 single_tsdf_integrator.cpp:120] Allocate: 6ms, Integrate: 65ms.
    I0218 00:23:16.973881 21811 planning_visualizer.cpp:186] Map lookups based on 1 submaps took 0.3+/-0.2, max 14.3us.
    I0218 00:23:17.072490 21811 panoptic_mapper.cpp:315] Processed input data.
    (tracking: 0 + integration: 71 + management: 0 + visual: 102 = 174, frame: 456ms)
    I0218 00:23:17.122951 21806 single_tsdf_integrator.cpp:120] Allocate: 2ms, Integrate: 44ms.
    I0218 00:23:17.229359 21806 planning_visualizer.cpp:186] Map lookups based on 1 submaps took 0.3+/-0.2, max 17.8us.
    I0218 00:23:17.317369 21806 panoptic_mapper.cpp:315] Processed input data.
    (tracking: 0 + integration: 47 + management: 0 + visual: 107 = 154, frame: 244ms)
    I0218 00:23:17.365311 21800 single_tsdf_integrator.cpp:120] Allocate: 2ms, Integrate: 42ms.
    I0218 00:23:17.468127 21800 planning_visualizer.cpp:186] Map lookups based on 1 submaps took 0.3+/-0.2, max 24.1us.
    I0218 00:23:17.552709 21800 panoptic_mapper.cpp:315] Processed input data.
    (tracking: 0 + integration: 44 + management: 0 + visual: 103 = 148, frame: 235ms)
    I0218 00:23:17.605499 21806 single_tsdf_integrator.cpp:120] Allocate: 2ms, Integrate: 40ms.
    I0218 00:23:17.704886 21806 planning_visualizer.cpp:186] Map lookups based on 1 submaps took 0.3+/-0.6, max 77.6us.
    I0218 00:23:17.791018 21806 panoptic_mapper.cpp:315] Processed input data.
    (tracking: 0 + integration: 43 + management: 0 + visual: 100 = 143, frame: 238ms) 
    

    Here is the output from the Rviz TSDF pointcloud: Screenshot from 2022-02-17 19-22-54 (1)

    However even in this run I could not see any visual output from the voxblox mesh on RViz.

    My voxel size is set to 0.05 which I don't think is the issue since I was able to run my same data on the Kimera-Semantic mapping Library (which also uses voxblox on its backend) successfully and got a decent output as well

    EG(Output from Kimera mapping package): with_person

    Could you please provide me with any hint as to what parameter I should look into (or how should I try to debug this) to get a proper output with the visual generated mesh ? or do you think this issue is caused by something else entirely ? I am attaching my custom config file along with its label csv file as well. (Note: I build my code in Release Mode).

    Any help is appreciat custom.csv ed ... thanks!!

    custom (1).txt

    opened by abhileshborode 12
  • Class Layer Missclassification problem

    Class Layer Missclassification problem

    Hi @Schmluk ,

    I am facing an issue in which for many submap allocations voxels of other semantic classes are grouped into 1 submap. Due to inaccurate allocations the tracker tries to track those falsely classified voxels and integrates them . This is causing the dynamic objects to not getting cleared from the map.

    Here is an example of the rendered image in which it allocates and classifies the ground pixel voxels into a single submap. It classifies the static pixels on ground as a human.

    classification

    I am using moving_binary_count as the classification method and my segmentation image is accurate as well.

    Any idea why this issue might happen ? Is there a way to avoid this ?

    opened by marcokat81 5
  •  Semantic Temporal Decay rate

    Semantic Temporal Decay rate

    Hit @Schmluk .... Is there a parameter which will enable us to semantically control the temporal decay rate for the mesh generation ? like slowly decay the maps for specific class and rapid decay rates for some others.

    I experimented with max_weight param inside the tsdf_integrator I had to drastically lower it down to 100 to get faster decay rate. is it possible to control this semantically ? I noticed that mesh of smaller objects with less pixel coverage in the input image are rapidly eaten up by the mesh of its surrounding semantic class ? is it possible to custom control this behavior ? like providing ground truth segmentation for specific semantic classes so it stays within the map for longer period and providing higher uncertainty to other segmentation classes ?

    weight_dropoff_epsilon did not seem to do anything I did not understand how that is used ?

    opened by marcokat81 4
  •  proto import compilation error

    proto import compilation error

    Hi @Schmluk I am using ubuntu 18.04 + melodic environment. I am unable to compile the panoptic_mapping package due to the following error.

    cblox/QuatTransformation.proto: File not found.
    panoptic_mapping/Submap.proto: Import "cblox/QuatTransformation.proto" was not found or had errors.
    panoptic_mapping/Submap.proto:26:12: "cblox.QuatTransformationProto" is not defined.
    make[2]: *** [compiled_proto/panoptic_mapping/Submap.pb.cc] Error 1
    make[2]: *** Waiting for unfinished jobs....
    make[1]: *** [CMakeFiles/panoptic_mapping_proto.dir/all] Error 2
    make: *** [all] Error 2
    

    However I can successfully compile the cblox package

    It looks like the panoptic mapping package is not able to locate the QuatTransformation.proto files. Any idea why this would happen ? What would you suggest I do to resolve this ?

    opened by marcokat81 4
  • Unsynchronization and error in updateSubmap()

    Unsynchronization and error in updateSubmap()

    Hi Lukas,

    I tried to configure the panoptic_mapping package on my new PC since I want to use the graphics card on it for real-time computation. Yet due to the hardware-driver compatbility I can only use Ubuntu 20.04.

    I successfully built the project, but when I ran the demo, I found that the the construction/publishing of mesh seems quite slow and out of sync with the motion of camera frame in RVIZ. There is an enormous delay between the movement of the camera frame and the appearance of the mesh.

    Even after the end of the bag file, the mesh update process is still running ( but quite slow). Then it runs into an unknown error. I doubt if it is caused by the unsynchronization.

    Could you please give some hints about the cause of this? The related log is below:

    W0416 09:29:23.920747 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 3.362259445s into the past.  Requested time 1605017369.923819542 but the earliest data is at time 1605017373.286078930, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:23.921140 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 3.024920696s into the past.  Requested time 1605017370.261158228 but the earliest data is at time 1605017373.286078930, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:23.921512 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 2.678477480s into the past.  Requested time 1605017370.607601404 but the earliest data is at time 1605017373.286078930, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:23.921911 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 2.351890960s into the past.  Requested time 1605017370.934188128 but the earliest data is at time 1605017373.286078930, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:23.922278 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 2.014413965s into the past.  Requested time 1605017371.271665096 but the earliest data is at time 1605017373.286078930, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:23.922631 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 1.683479630s into the past.  Requested time 1605017371.602599382 but the earliest data is at time 1605017373.286078930, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:23.922986 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 1.360916383s into the past.  Requested time 1605017371.925162554 but the earliest data is at time 1605017373.286078930, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:23.923352 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 0.992926696s into the past.  Requested time 1605017372.293152332 but the earliest data is at time 1605017373.286078930, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:23.923722 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 0.669217580s into the past.  Requested time 1605017372.616861343 but the earliest data is at time 1605017373.286078930, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:23.924079 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 0.326745558s into the past.  Requested time 1605017372.959333420 but the earliest data is at time 1605017373.286078930, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:23.924474 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 0.327113512s into the past.  Requested time 1605017373.286078930 but the earliest data is at time 1605017373.613192558, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    I0416 09:29:28.456105 27242 panoptic_mapper.cpp:175] Processed input data.
    (tracking: 71 + integration: 2965 + change: 0 + visual: 1494 = 4531ms)
    W0416 09:29:28.456730 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 4.046588923s into the past.  Requested time 1605017373.944589376 but the earliest data is at time 1605017377.991178274, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:28.457131 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 3.712568924s into the past.  Requested time 1605017374.278609514 but the earliest data is at time 1605017377.991178274, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:28.457497 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 3.397104514s into the past.  Requested time 1605017374.594073772 but the earliest data is at time 1605017377.991178274, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:28.457866 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 3.042720641s into the past.  Requested time 1605017374.948457718 but the earliest data is at time 1605017377.991178274, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:28.458220 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 2.709790756s into the past.  Requested time 1605017375.281387568 but the earliest data is at time 1605017377.991178274, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:28.458741 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 2.364874763s into the past.  Requested time 1605017375.626303673 but the earliest data is at time 1605017377.991178274, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:28.459097 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 2.000442074s into the past.  Requested time 1605017375.990736246 but the earliest data is at time 1605017377.991178274, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:28.459451 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 1.690820713s into the past.  Requested time 1605017376.300357580 but the earliest data is at time 1605017377.991178274, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:28.459811 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 1.284152408s into the past.  Requested time 1605017376.707026005 but the earliest data is at time 1605017377.991178274, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:28.460175 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 1.026710062s into the past.  Requested time 1605017376.964468241 but the earliest data is at time 1605017377.991178274, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:28.460530 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 0.682723611s into the past.  Requested time 1605017377.308454752 but the earliest data is at time 1605017377.991178274, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:28.460888 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 0.370004968s into the past.  Requested time 1605017377.621173382 but the earliest data is at time 1605017377.991178274, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:28.461237 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 0.127738458s into the past.  Requested time 1605017377.991178274 but the earliest data is at time 1605017378.118916750, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    I0416 09:29:31.918720 27242 panoptic_mapper.cpp:175] Processed input data.
    (tracking: 75 + integration: 2494 + change: 0 + visual: 887 = 3457ms)
    W0416 09:29:31.919297 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 2.987589521s into the past.  Requested time 1605017378.601023436 but the earliest data is at time 1605017381.588612795, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:31.919859 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 2.637597758s into the past.  Requested time 1605017378.951015234 but the earliest data is at time 1605017381.588612795, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:31.920235 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 2.302431612s into the past.  Requested time 1605017379.286181211 but the earliest data is at time 1605017381.588612795, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:31.920600 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 1.978180917s into the past.  Requested time 1605017379.610431910 but the earliest data is at time 1605017381.588612795, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:31.920964 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 1.630929542s into the past.  Requested time 1605017379.957683325 but the earliest data is at time 1605017381.588612795, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:31.921340 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 1.337194904s into the past.  Requested time 1605017380.251417875 but the earliest data is at time 1605017381.588612795, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:31.921705 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 1.004092449s into the past.  Requested time 1605017380.584520340 but the earliest data is at time 1605017381.588612795, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:31.922072 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 0.644855255s into the past.  Requested time 1605017380.943757534 but the earliest data is at time 1605017381.588612795, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:31.922430 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 0.286332873s into the past.  Requested time 1605017381.302279949 but the earliest data is at time 1605017381.588612795, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:31.922794 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 0.034806381s into the past.  Requested time 1605017381.588612795 but the earliest data is at time 1605017381.623419285, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    I0416 09:29:35.651805 27242 panoptic_mapper.cpp:175] Processed input data.
    (tracking: 74 + integration: 2718 + change: 0 + visual: 935 = 3728ms)
    W0416 09:29:35.652314 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 2.733728249s into the past.  Requested time 1605017382.259883165 but the earliest data is at time 1605017384.993611336, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:35.652737 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 2.392772164s into the past.  Requested time 1605017382.600839138 but the earliest data is at time 1605017384.993611336, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:35.653132 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 2.063864897s into the past.  Requested time 1605017382.929746389 but the earliest data is at time 1605017384.993611336, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:35.653497 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 1.720581760s into the past.  Requested time 1605017383.273029566 but the earliest data is at time 1605017384.993611336, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:35.653857 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 1.403507593s into the past.  Requested time 1605017383.590103865 but the earliest data is at time 1605017384.993611336, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:35.654207 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 1.059471012s into the past.  Requested time 1605017383.934140444 but the earliest data is at time 1605017384.993611336, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:35.654564 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 0.712723489s into the past.  Requested time 1605017384.280887842 but the earliest data is at time 1605017384.993611336, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:35.654913 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 0.360051756s into the past.  Requested time 1605017384.633559704 but the earliest data is at time 1605017384.993611336, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:35.655269 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 0.334813311s into the past.  Requested time 1605017384.993611336 but the earliest data is at time 1605017385.328424692, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    I0416 09:29:39.665402 27242 panoptic_mapper.cpp:175] Processed input data.
    (tracking: 72 + integration: 2880 + change: 0 + visual: 1057 = 4009ms)
    W0416 09:29:39.665992 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 3.296952642s into the past.  Requested time 1605017385.690282345 but the earliest data is at time 1605017388.987234831, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:39.666409 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 2.972384378s into the past.  Requested time 1605017386.014850616 but the earliest data is at time 1605017388.987234831, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:39.666786 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 2.672943477s into the past.  Requested time 1605017386.314291477 but the earliest data is at time 1605017388.987234831, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:39.667150 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 2.346161108s into the past.  Requested time 1605017386.641073942 but the earliest data is at time 1605017388.987234831, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:39.667505 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 2.021839026s into the past.  Requested time 1605017386.965395927 but the earliest data is at time 1605017388.987234831, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:39.667871 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 1.670098242s into the past.  Requested time 1605017387.317136765 but the earliest data is at time 1605017388.987234831, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:39.668229 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 1.347513787s into the past.  Requested time 1605017387.639721155 but the earliest data is at time 1605017388.987234831, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:39.668593 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 0.997993928s into the past.  Requested time 1605017387.989241123 but the earliest data is at time 1605017388.987234831, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:39.668957 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 0.631336907s into the past.  Requested time 1605017388.355898142 but the earliest data is at time 1605017388.987234831, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:39.670078 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 0.260955374s into the past.  Requested time 1605017388.726279497 but the earliest data is at time 1605017388.987234831, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:39.670455 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 0.346477864s into the past.  Requested time 1605017388.987234831 but the earliest data is at time 1605017389.333712816, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    I0416 09:29:42.327642 27242 panoptic_mapper.cpp:175] Processed input data.
    (tracking: 61 + integration: 2318 + change: 0 + visual: 276 = 2656ms)
    W0416 09:29:42.328330 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 2.359689600s into the past.  Requested time 1605017389.646519423 but the earliest data is at time 1605017392.006209135, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:42.328728 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 2.038731819s into the past.  Requested time 1605017389.967477322 but the earliest data is at time 1605017392.006209135, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:42.329116 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 1.618196955s into the past.  Requested time 1605017390.388012171 but the earliest data is at time 1605017392.006209135, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:42.329494 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 1.337878469s into the past.  Requested time 1605017390.668330669 but the earliest data is at time 1605017392.006209135, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:42.329874 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 0.981905755s into the past.  Requested time 1605017391.024303436 but the earliest data is at time 1605017392.006209135, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:42.330233 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 0.686298739s into the past.  Requested time 1605017391.319910288 but the earliest data is at time 1605017392.006209135, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:42.330596 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 0.348469008s into the past.  Requested time 1605017391.657740116 but the earliest data is at time 1605017392.006209135, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:42.330962 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 0.031402793s into the past.  Requested time 1605017392.006209135 but the earliest data is at time 1605017392.037611961, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    I0416 09:29:45.984400 27242 panoptic_mapper.cpp:175] Processed input data.
    (tracking: 65 + integration: 2659 + change: 0 + visual: 927 = 3653ms)
    W0416 09:29:45.984999 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 2.659971079s into the past.  Requested time 1605017392.666702271 but the earliest data is at time 1605017395.326673508, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:45.985409 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 2.340158105s into the past.  Requested time 1605017392.986515284 but the earliest data is at time 1605017395.326673508, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:45.985951 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 2.014286095s into the past.  Requested time 1605017393.312387228 but the earliest data is at time 1605017395.326673508, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:45.986346 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 1.676987820s into the past.  Requested time 1605017393.649685621 but the earliest data is at time 1605017395.326673508, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:45.986716 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 1.324782025s into the past.  Requested time 1605017394.001891375 but the earliest data is at time 1605017395.326673508, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:45.987090 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 0.984794860s into the past.  Requested time 1605017394.341878653 but the earliest data is at time 1605017395.326673508, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:45.987493 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 0.706773596s into the past.  Requested time 1605017394.619899750 but the earliest data is at time 1605017395.326673508, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:45.987896 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 0.377081740s into the past.  Requested time 1605017394.949591637 but the earliest data is at time 1605017395.326673508, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    W0416 09:29:45.988313 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 0.316155156s into the past.  Requested time 1605017395.326673508 but the earliest data is at time 1605017395.642828465, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    [rosbag-2] process has finished cleanly
    log file: /home/junting/.ros/log/4fb047ac-9e85-11eb-a2d1-af46e70c6af9/rosbag-2*.log
    I0416 09:29:52.151887 27242 panoptic_mapper.cpp:175] Processed input data.
    (tracking: 76 + integration: 2812 + change: 0 + visual: 3274 = 6163ms)
    W0416 09:29:52.152420 27242 input_synchronizer.cpp:117] Unable to lookup transform between 'airsim_drone/Depth_cam' and 'world' (Lookup would require extrapolation 0.088299534s into the past.  Requested time 1605017395.955047369 but the earliest data is at time 1605017396.043346882, when looking up transform from frame [airsim_drone/Depth_cam] to frame [world]), skipping inputs.
    I0416 09:29:58.360947 27242 panoptic_mapper.cpp:175] Processed input data.
    (tracking: 82 + integration: 2816 + change: 0 + visual: 3309 = 6208ms)
    I0416 09:30:04.702169 27242 panoptic_mapper.cpp:175] Processed input data.
    (tracking: 95 + integration: 2807 + change: 0 + visual: 3437 = 6340ms)
    I0416 09:30:11.064498 27242 panoptic_mapper.cpp:175] Processed input data.
    (tracking: 84 + integration: 2832 + change: 0 + visual: 3445 = 6361ms)
    I0416 09:30:17.432153 27242 panoptic_mapper.cpp:175] Processed input data.
    (tracking: 83 + integration: 2949 + change: 0 + visual: 3334 = 6367ms)
    I0416 09:30:23.765028 27242 panoptic_mapper.cpp:175] Processed input data.
    (tracking: 71 + integration: 3000 + change: 0 + visual: 3260 = 6332ms)
    I0416 09:30:30.269341 27242 panoptic_mapper.cpp:175] Processed input data.
    (tracking: 72 + integration: 3142 + change: 0 + visual: 3288 = 6503ms)
    I0416 09:30:36.738009 27242 panoptic_mapper.cpp:175] Processed input data.
    (tracking: 72 + integration: 3127 + change: 0 + visual: 3268 = 6468ms)
    panoptic_mapper_node: /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h:117: Eigen::DenseCoeffsBase<Derived, 0>::CoeffReturnType Eigen::DenseCoeffsBase<Derived, 0>::operator()(Eigen::Index, Eigen::Index) const [with Derived = Eigen::Matrix<float, -1, -1>; Eigen::DenseCoeffsBase<Derived, 0>::CoeffReturnType = const float&; Eigen::Index = long int]: Assertion `row >= 0 && row < rows() && col >= 0 && col < cols()' failed.
    *** Aborted at 1618558239 (unix time) try "date -d @1618558239" if you are using GNU date ***
    PC: @     0x7f162370218b gsignal
    *** SIGABRT (@0x3e800006a6a) received by PID 27242 (TID 0x7f16077fe700) from PID 27242; stack trace: ***
        @     0x7f1623ddc781 google::(anonymous namespace)::FailureSignalHandler()
        @     0x7f1623e0a3c0 (unknown)
        @     0x7f162370218b gsignal
        @     0x7f16236e1859 abort
        @     0x7f16236e1729 (unknown)
        @     0x7f16236f2f36 __assert_fail
        @     0x7f1622e8fe43 Eigen::DenseCoeffsBase<>::operator()()
        @     0x7f1622e8ecab panoptic_mapping::InterpolatorBilinear::interpolateDepth()
        @     0x7f1622e78ec1 panoptic_mapping::ProjectiveIntegrator::computeVoxelDistanceAndWeight()
        @     0x7f1622e78aad panoptic_mapping::ProjectiveIntegrator::updateBlock()
        @     0x7f1622e78797 panoptic_mapping::ProjectiveIntegrator::updateSubmap()
        @     0x7f1622e77f02 _ZZN16panoptic_mapping20ProjectiveIntegrator12processInputEPNS_16SubmapCollectionEPNS_9InputDataEENKUlvE_clEv
        @     0x7f1622e7bc76 _ZSt13__invoke_implIbZN16panoptic_mapping20ProjectiveIntegrator12processInputEPNS0_16SubmapCollectionEPNS0_9InputDataEEUlvE_JEET_St14__invoke_otherOT0_DpOT1_
        @     0x7f1622e7bc1e _ZSt8__invokeIZN16panoptic_mapping20ProjectiveIntegrator12processInputEPNS0_16SubmapCollectionEPNS0_9InputDataEEUlvE_JEENSt15__invoke_resultIT_JDpT0_EE4typeEOS8_DpOS9_
        @     0x7f1622e7bbb2 _ZNSt6thread8_InvokerISt5tupleIJZN16panoptic_mapping20ProjectiveIntegrator12processInputEPNS2_16SubmapCollectionEPNS2_9InputDataEEUlvE_EEE9_M_invokeIJLm0EEEEbSt12_Index_tupleIJXspT_EEE
        @     0x7f1622e7bb32 _ZNSt6thread8_InvokerISt5tupleIJZN16panoptic_mapping20ProjectiveIntegrator12processInputEPNS2_16SubmapCollectionEPNS2_9InputDataEEUlvE_EEEclEv
        @     0x7f1622e7b8e8 _ZNKSt13__future_base12_Task_setterISt10unique_ptrINS_7_ResultIbEENS_12_Result_base8_DeleterEENSt6thread8_InvokerISt5tupleIJZN16panoptic_mapping20ProjectiveIntegrator12processInputEPNSA_16SubmapCollectionEPNSA_9InputDataEEUlvE_EEEEbEclEv
        @     0x7f1622e7b5f3 _ZNSt17_Function_handlerIFSt10unique_ptrINSt13__future_base12_Result_baseENS2_8_DeleterEEvENS1_12_Task_setterIS0_INS1_7_ResultIbEES3_ENSt6thread8_InvokerISt5tupleIJZN16panoptic_mapping20ProjectiveIntegrator12processInputEPNSD_16SubmapCollectionEPNSD_9InputDataEEUlvE_EEEEbEEE9_M_invokeERKSt9_Any_data
        @     0x7f1622e6e942 std::function<>::operator()()
        @     0x7f1622e6d516 std::__future_base::_State_baseV2::_M_do_set()
        @     0x7f1622e71d29 _ZSt13__invoke_implIvMNSt13__future_base13_State_baseV2EFvPSt8functionIFSt10unique_ptrINS0_12_Result_baseENS4_8_DeleterEEvEEPbEPS1_JS9_SA_EET_St21__invoke_memfun_derefOT0_OT1_DpOT2_
        @     0x7f1622e70247 _ZSt8__invokeIMNSt13__future_base13_State_baseV2EFvPSt8functionIFSt10unique_ptrINS0_12_Result_baseENS4_8_DeleterEEvEEPbEJPS1_S9_SA_EENSt15__invoke_resultIT_JDpT0_EE4typeEOSF_DpOSG_
        @     0x7f1622e6e67a _ZZSt9call_onceIMNSt13__future_base13_State_baseV2EFvPSt8functionIFSt10unique_ptrINS0_12_Result_baseENS4_8_DeleterEEvEEPbEJPS1_S9_SA_EEvRSt9once_flagOT_DpOT0_ENKUlvE_clEv
        @     0x7f1622e6e6b1 _ZZSt9call_onceIMNSt13__future_base13_State_baseV2EFvPSt8functionIFSt10unique_ptrINS0_12_Result_baseENS4_8_DeleterEEvEEPbEJPS1_S9_SA_EEvRSt9once_flagOT_DpOT0_ENKUlvE0_clEv
        @     0x7f1622e6e6c6 _ZZSt9call_onceIMNSt13__future_base13_State_baseV2EFvPSt8functionIFSt10unique_ptrINS0_12_Result_baseENS4_8_DeleterEEvEEPbEJPS1_S9_SA_EEvRSt9once_flagOT_DpOT0_ENUlvE0_4_FUNEv
        @     0x7f1623e0747f __pthread_once_slow
        @     0x7f1622e6596a __gthread_once()
        @     0x7f1622e6e787 _ZSt9call_onceIMNSt13__future_base13_State_baseV2EFvPSt8functionIFSt10unique_ptrINS0_12_Result_baseENS4_8_DeleterEEvEEPbEJPS1_S9_SA_EEvRSt9once_flagOT_DpOT0_
        @     0x7f1622e6d2e8 std::__future_base::_State_baseV2::_M_set_result()
        @     0x7f1622e7b062 _ZZNSt13__future_base17_Async_state_implINSt6thread8_InvokerISt5tupleIJZN16panoptic_mapping20ProjectiveIntegrator12processInputEPNS4_16SubmapCollectionEPNS4_9InputDataEEUlvE_EEEEbEC4EOSC_ENKUlvE_clEv
        @     0x7f1622e7c716 _ZSt13__invoke_implIvZNSt13__future_base17_Async_state_implINSt6thread8_InvokerISt5tupleIJZN16panoptic_mapping20ProjectiveIntegrator12processInputEPNS5_16SubmapCollectionEPNS5_9InputDataEEUlvE_EEEEbEC4EOSD_EUlvE_JEET_St14__invoke_otherOT0_DpOT1_
        @     0x7f1622e7c6cb _ZSt8__invokeIZNSt13__future_base17_Async_state_implINSt6thread8_InvokerISt5tupleIJZN16panoptic_mapping20ProjectiveIntegrator12processInputEPNS5_16SubmapCollectionEPNS5_9InputDataEEUlvE_EEEEbEC4EOSD_EUlvE_JEENSt15__invoke_resultIT_JDpT0_EE4typeEOSI_DpOSJ_
    [panoptic_mapper-3] process has died [pid 27242, exit code -6, cmd /home/junting/panoptic_ws/devel/lib/panoptic_mapping_ros/panoptic_mapper_node color_image_in:=data/color_image depth_image_in:=data/depth_image segmentation_image_in:=data/segmentation_image labels_in:=data/segmentation_labels __name:=panoptic_mapper __log:=/home/junting/.ros/log/4fb047ac-9e85-11eb-a2d1-af46e70c6af9/panoptic_mapper-3.log].
    log file: /home/junting/.ros/log/4fb047ac-9e85-11eb-a2d1-af46e70c6af9/panoptic_mapper-3*.log
    
    opened by SgtVincent 4
  • panoptic_utils package detected by catkin_tools but not ros built-in tools

    panoptic_utils package detected by catkin_tools but not ros built-in tools

    I built the panoptic_mapping_ros package with the given instruction catkin build panoptic_mapping_ros successfully, but when I want to run to run the demo, I found that panoptic_mapping_utils not detected by rospack:

    ❯ rospack list | grep panoptic_mapping
    panoptic_mapping /home/junting/panoptic_ws/src/panoptic_mapping/panoptic_mapping
    panoptic_mapping_msgs /home/junting/panoptic_ws/src/panoptic_mapping/panoptic_mapping_msgs
    panoptic_mapping_ros /home/junting/panoptic_ws/src/panoptic_mapping/panoptic_mapping_ros
    

    Yet catkin list returns all panoptic_mapping packages:

    ❯ catkin list | grep panoptic_mapping
    - panoptic_mapping_msgs
    - panoptic_mapping
    - panoptic_mapping_ros
    - panoptic_mapping_utils
    
    opened by SgtVincent 2
  • Link problem probably caused by opencv built from source code

    Link problem probably caused by opencv built from source code

    This error happens when building panoptic_mapping_ros package.

    The error output is

    Errors     << panoptic_mapping_ros:make /home/junting/panoptic_ws/logs/panoptic_mapping_ros/build.make.001.log
    /home/junting/panoptic_ws/devel/lib/libpanoptic_mapping.so: undefined reference to `cv::Mat::Mat()'
    /home/junting/panoptic_ws/devel/lib/libpanoptic_mapping.so: undefined reference to `cv::Mat::operator=(cv::Mat&&)'
    /home/junting/panoptic_ws/devel/lib/libpanoptic_mapping.so: undefined reference to `cv::Mat::Mat(int, int, int)'
    /home/junting/panoptic_ws/devel/lib/libpanoptic_mapping.so: undefined reference to `cv::error(int, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, char const*, char const*, int)'
    /home/junting/panoptic_ws/devel/lib/libpanoptic_mapping.so: undefined reference to `cv::Mat::total() const'
    /home/junting/panoptic_ws/devel/lib/libpanoptic_mapping.so: undefined reference to `cv::Mat::Mat(cv::Size_<int>, int, cv::Scalar_<double> const&)'
    /home/junting/panoptic_ws/devel/lib/libpanoptic_mapping.so: undefined reference to `cv::Mat::Mat(int, int, int, cv::Scalar_<double> const&)'
    collect2: error: ld returned 1 exit status
    make[2]: *** [/home/junting/panoptic_ws/devel/lib/panoptic_mapping_ros/panoptic_mapper_node] Error 1
    make[1]: *** [CMakeFiles/panoptic_mapper_node.dir/all] Error 2
    make: *** [all] Error 2
    cd /home/junting/panoptic_ws/build/panoptic_mapping_ros; catkin build --get-env panoptic_mapping_ros | catkin env -si  /usr/bin/make --jobserver-fds=6,7 -j; cd -
    

    I have my opencv built&installed from source and the library files are under /usr/local/lib rather than /usr/lib directory.

    I built some opencv samples successfully with flags -L/usr/local/lib -lopencv_gapi -lopencv_highgui -lopencv_ml -lopencv_objdetect -lopencv_photo -lopencv_stitching -lopencv_video -lopencv_calib3d -lopencv_features2d -lopencv_dnn -lopencv_flann -lopencv_videoio -lopencv_imgcodecs -lopencv_imgproc -lopencv_core and I wonder how can I modify the cmake files to specify this link flag.

    opened by SgtVincent 2
  • Build error triggered by static_cast from XmlRpcValue to double/int/bool etc.

    Build error triggered by static_cast from XmlRpcValue to double/int/bool etc.

    Hi Lukas,

    I had a strange error when building panoptic_mapping package with catkin build panoptic_mapping.

    ...
    /home/junting/panoptic_ws/src/panoptic_mapping/panoptic_mapping/include/panoptic_mapping/3rd_party/config_utilities.hpp:204:39: error: invalid static_cast from type ‘const XmlRpc::XmlRpcValue’ to type ‘bool’
      204 |         *param = static_cast<bool>(xml);
    ...
    

    Each static_cast raised one error in {workspace_dir}/src/panoptic_mapping/panoptic_mapping/include/panoptic_mapping/3rd_party/config_utilities.hpp Here is the full logging of terminal output. build.log

    Here is my environment setup:

    ❯g++ --version g++ (Ubuntu 9.3.0-21ubuntu1~16.04) 9.3.0 ❯ cmake --version cmake version 3.10.3 ❯ python --version Python 2.7.12

    Do you have any ideas about this error?

    opened by SgtVincent 2
  • Docker building

    Docker building

    Builds docker images based on ros:noetic with a fully functional workspace for panoptic mapping. This can be used to deploy on the robot, or set up a devcontainer such that students can work on the project more easily.

    opened by hermannsblum 1
  • Question on calculation in Trackinginfo::insertRenderdPoint

    Question on calculation in Trackinginfo::insertRenderdPoint

    Codes here: https://github.com/ethz-asl/panoptic_mapping/blob/354597b7e4b5f5cfef4e57c467a0e4ec4230f9c3/panoptic_mapping/src/tracking/tracking_info.cpp#L36-L37

    Question: It's a little bit weird for the width calculation. we assume that u<size_x, and the width will be 3*size_x+1, but the truth we want should be 2*size_x+1 according to the u.

    const int u_min = std::max(0, u - size_x);
    const int width = u_min + 2 * size_x + 1;
    

    Is there any other I missed for understanding?

    opened by Kin-Zhang 1
  • flat data class id not consistent

    flat data class id not consistent

    hello, when I check the flat dataset groundtruth_label.csv, I found the class id is not consistent, For example, there are two beds which have the names bed_a and bed_b respectively. In my opinion, they should have the same class id. However, I found one of them has class id 6 and one is 7. The same class id not-matching problem can be found for other category objects. Is there anything wrong when I did?

    opened by hutslib 1
  • Turn Uncertainty Voxel into Score Layer

    Turn Uncertainty Voxel into Score Layer

    Use the new score layer of #48 to get rid of the uncertainty voxel. Make sure the deps of https://github.com/ethz-asl/active_learning_for_segmentation are still met.

    enhancement 
    opened by Schmluk 0
  • node that saves the meshes send to RVIZ

    node that saves the meshes send to RVIZ

    Since colorized meshes are published directly in the voxblox rviz message format, which requires further computation in the voxblox rviz plugin, there is currently no way to save the meshes that are produced by the map-visualisation nodes, e.g. colorized by class, instance, or uncertainty.

    This node is independent of the rest of the code. It simply listens to the message that is send to the rviz plugin, processes it with the same code as the plugin, and saves it as ply. Every time the visualisation parameters are changes (e.g. through service calls), the saved mesh gets updated. Once it looks good in rviz, a user can simply copy or rename the current output file to save the mesh of the current state.

    opened by hermannsblum 1
  • [ROS] Share PanopticSubmaps between two ROS Nodes

    [ROS] Share PanopticSubmaps between two ROS Nodes

    Allow two PanopticMapping nodes to be synchronized using ros Messages. (One active mapper and one passive that e.g. could be used for path planning). Currently under development here /feature/ros_sync_maps

    enhancement 
    opened by renezurbruegg 0
  • Migrate CameraRenderer to Map Renderer

    Migrate CameraRenderer to Map Renderer

    There's already a map renderer (quite ugly one though) in panoptic_mapping package. This is essentially a single_tsdf_renderer, right? Would be nicer to have this as part of the library and keep the ROS interface separate.

    Originally posted by @Schmluk in https://github.com/ethz-asl/panoptic_mapping/pull/23#r721508273

    enhancement 
    opened by renezurbruegg 0
Owner
ETHZ ASL
ETHZ ASL
Official PyTorch code of DeepPanoContext: Panoramic 3D Scene Understanding with Holistic Scene Context Graph and Relation-based Optimization (ICCV 2021 Oral).

DeepPanoContext (DPC) [Project Page (with interactive results)][Paper] DeepPanoContext: Panoramic 3D Scene Understanding with Holistic Scene Context G

Cheng Zhang 66 Nov 16, 2022
Code for CVPR 2021 oral paper "Exploring Data-Efficient 3D Scene Understanding with Contrastive Scene Contexts"

Exploring Data-Efficient 3D Scene Understanding with Contrastive Scene Contexts The rapid progress in 3D scene understanding has come with growing dem

Facebook Research 182 Dec 30, 2022
SSL_SLAM2: Lightweight 3-D Localization and Mapping for Solid-State LiDAR (mapping and localization separated) ICRA 2021

SSL_SLAM2 Lightweight 3-D Localization and Mapping for Solid-State LiDAR (Intel Realsense L515 as an example) This repo is an extension work of SSL_SL

Wang Han 王晗 1.3k Jan 8, 2023
[ICRA2021] Reconstructing Interactive 3D Scene by Panoptic Mapping and CAD Model Alignment

Interactive Scene Reconstruction Project Page | Paper This repository contains the implementation of our ICRA2021 paper Reconstructing Interactive 3D

null 97 Dec 28, 2022
Towards Part-Based Understanding of RGB-D Scans

Towards Part-Based Understanding of RGB-D Scans (CVPR 2021) We propose the task of part-based scene understanding of real-world 3D environments: from

null 26 Nov 23, 2022
Unofficial implementation of Point-Unet: A Context-Aware Point-Based Neural Network for Volumetric Segmentation

Point-Unet This is an unofficial implementation of the MICCAI 2021 paper Point-Unet: A Context-Aware Point-Based Neural Network for Volumetric Segment

Namt0d 9 Dec 7, 2022
[TIP 2020] Multi-Temporal Scene Classification and Scene Change Detection with Correlation based Fusion

Multi-Temporal Scene Classification and Scene Change Detection with Correlation based Fusion Code for Multi-Temporal Scene Classification and Scene Ch

Lixiang Ru 33 Dec 12, 2022
[ICML 2021] Towards Understanding and Mitigating Social Biases in Language Models

Towards Understanding and Mitigating Social Biases in Language Models This repo contains code and data for evaluating and mitigating bias from generat

Paul Liang 42 Jan 3, 2023
Towards Flexible Blind JPEG Artifacts Removal (FBCNN, ICCV 2021)

Towards Flexible Blind JPEG Artifacts Removal (FBCNN, ICCV 2021)

Jiaxi Jiang 282 Jan 2, 2023
Towards Flexible Blind JPEG Artifacts Removal (FBCNN, ICCV 2021)

Towards Flexible Blind JPEG Artifacts Removal (FBCNN, ICCV 2021) Jiaxi Jiang, Kai Zhang, Radu Timofte Computer Vision Lab, ETH Zurich, Switzerland ??

Jiaxi Jiang 80 Sep 30, 2021
TSP: Temporally-Sensitive Pretraining of Video Encoders for Localization Tasks

TSP: Temporally-Sensitive Pretraining of Video Encoders for Localization Tasks [Paper] [Project Website] This repository holds the source code, pretra

Humam Alwassel 83 Dec 21, 2022
A PyTorch Reimplementation of TecoGAN: Temporally Coherent GAN for Video Super-Resolution

TecoGAN-PyTorch Introduction This is a PyTorch reimplementation of TecoGAN: Temporally Coherent GAN for Video Super-Resolution (VSR). Please refer to

null 165 Dec 17, 2022
This is the official implementation of the paper "Object Propagation via Inter-Frame Attentions for Temporally Stable Video Instance Segmentation".

[CVPRW 2021] - Object Propagation via Inter-Frame Attentions for Temporally Stable Video Instance Segmentation

Anirudh S Chakravarthy 6 May 3, 2022
Temporally Coherent GAN SIGGRAPH project.

TecoGAN This repository contains source code and materials for the TecoGAN project, i.e. code for a TEmporally COherent GAN for video super-resolution

Duc Linh Nguyen 2 Jan 18, 2022
Temporally Efficient Vision Transformer for Video Instance Segmentation, CVPR 2022, Oral

Temporally Efficient Vision Transformer for Video Instance Segmentation Temporally Efficient Vision Transformer for Video Instance Segmentation (CVPR

Hust Visual Learning Team 203 Dec 31, 2022
Pytorch implementation of Make-A-Scene: Scene-Based Text-to-Image Generation with Human Priors

Make-A-Scene - PyTorch Pytorch implementation (inofficial) of Make-A-Scene: Scene-Based Text-to-Image Generation with Human Priors (https://arxiv.org/

Casual GAN Papers 259 Dec 28, 2022
Towards Long-Form Video Understanding

Towards Long-Form Video Understanding Chao-Yuan Wu, Philipp Krähenbühl, CVPR 2021 [Paper] [Project Page] [Dataset] Citation @inproceedings{lvu2021,

Chao-Yuan Wu 69 Dec 26, 2022
The source code for Generating Training Data with Language Models: Towards Zero-Shot Language Understanding.

SuperGen The source code for Generating Training Data with Language Models: Towards Zero-Shot Language Understanding. Requirements Before running, you

Yu Meng 38 Dec 12, 2022