Implementation of EVO (RA-L 17)

Overview

EVO: Event based Visual Odometry

EVO: Event based Visual Odometry

Credit, License, and Patent

Citation

This code implements the event-based visual odometry pipeline described in the paper EVO: A Geometric Approach to Event-Based 6-DOF Parallel Tracking and Mapping in Real-time by Henri Rebecq, Timo Horstschaefer, Guillermo Gallego and Davide Scaramuzza.

If you use any of this code, please cite the following publications:

@Article{RebecqEVO,
  author        = {Rebecq, Henri and Horstschaefer, Timo and Gallego, Guillermo and Scaramuzza, Davide},
  journal       = {IEEE Robotics and Automation Letters}, 
  title         = {EVO: A Geometric Approach to Event-Based 6-DOF Parallel Tracking and Mapping in Real Time}, 
  year          = {2017},
  volume        = {2},
  number        = {2},
  pages         = {593-600},
  doi           = {10.1109/LRA.2016.2645143}
}
@InProceedings{Gehrig_2020_CVPR,
  author = {Daniel Gehrig and Mathias Gehrig and Javier Hidalgo-Carri\'o and Davide Scaramuzza},
  title = {Video to Events: Recycling Video Datasets for Event Cameras},
  booktitle = {{IEEE} Conf. Comput. Vis. Pattern Recog. (CVPR)},
  month = {June},
  year = {2020}
}

The code comes with a test dataset. If you don't have an event camera and want to run the code on more data, you can do one of the following:

Patent & License

  • The proposed EVO method is patented.

      H. Rebecq, G. Gallego, D. Scaramuzza
      Simultaneous Localization and Mapping with an Event Camera
      Pub. No.: WO/2018/037079.  International Application No.: PCT/EP2017/071331
    
  • The license is available here.

Acknowledgements

The open sourcing was curated by Antonio Terpin and Daniel Gehrig.

Table of contents

  1. Getting started
  2. Examples
  3. Running live
  4. Further improvements
  5. Additional resources on Event Cameras

Remark that this is research code, any fitness for a particular purpose is disclaimed.

Getting started

This software depends on ROS. Installation instructions can be found here. We have tested this software on Ubuntu 18.04 and ROS Melodic.

  1. Create and initialize a new catkin workspace if needed

     mkdir -p ~/catkin_ws/src && cd ~/catkin_ws/
     catkin config \
         --init --mkdirs --extend /opt/ros/melodic \
         --merge-devel --cmake-args \
         -DCMAKE_BUILD_TYPE=Release
    
  2. Clone this repository

     cd src/ && git clone [email protected]:uzh-rpg/rpg_dvs_evo_open.git
    
  3. Clone (and fix) dependencies

     ./rpg_dvs_evo_open/install.sh [ros-version] # [ros-version]: melodic, ..
    

    Substitute [ros-version] with your actual ROS distribution. For instance:

     ./rpg_dvs_evo_open/install.sh melodic
    

    Make sure to install ROS and the commonly used packages (such as rviz, rqt, ..).

    The above commands do the following:

    • First, we install the required packages.

    • Second, we clone the repositories evo relies on.

    Remark that with the above commands we install also the dependencies required to run the pipeline live. If you do not need them, you can comment the unnecessary packages from the dependencies.yaml file (davis driver).

    Please refer to this repo if there are issues with the driver installation (required for the live).

  4. Build the packages

     catkin build dvs_tracking
    

Building everything might take some time... this might be the right time for a coffee! :)

... and do not forget to source the workspace afterwards!

source ../devel/setup.bash

Examples

EVO: Event based Visual Odometry

Example Launch file Rosbag
Multi-keyframe sequence flyingroom.launch 538 MB
Desk sequence desk.launch 145 MB

To download the rosbags, you can use the following command:

wget [rosbag link] -O /path/to/download/folder/

For instance, the following will download the multi-keyframe sequence rosbag:

wget http://rpg.ifi.uzh.ch/data/EVO/code_examples/evo_flyingroom.bag -O /tmp/evo_flyingroom.bag

To run the pipeline from a rosbag, first start the pipeline as

roslaunch dvs_tracking [launch-file] auto_trigger:=true

where the specific launch file (fine-tuned) for each example is listed in the following table. The most interesting and repeatible one (due to the bootstrapping sequence, see further improvements) is the multi-keyframe sequence.

Then, once the everything is loaded, run the rosbag as

rosbag play -r 0.7 [rosbag-file]

For instance,

rosbag play -r 0.7 /tmp/evo_flyingroom.bag

Remark that we set the auto_trigger parameter to true. You can also set it to false and follow the instruction on how to run it live.

If anything fails, just try it again (give it a couple of chances!), and make sure to follow exactly the above instructions.

In the further improvements section are outlined the things that might go wrong when running the code. To improve the reliability when playing the rosbags (running live is easier), consider using -r .7, to reduce the rate. This helps especially when the hardware is not powerful enough.

For instance,

rosbag play /tmp/evo_flyingroom -r .7

Eventually, setting bootstrap_image_topic:=/dvs/image_raw will bootstrap from traditional frames and later switch to only events. This is the most reliable way currently available to bootstrap.

roslaunch dvs_tracking [launch-file] bootstrap_image_topic:=/dvs/image_raw auto_trigger:=true

Running live

Run

The procedure is analogous to the one explained in the examples:

  1. Run the ros core on the first terminal.

     roscore
    
  2. On a second terminal, launch the event camera driver.

     rosrun davis_ros_driver davis_ros_driver
    
  3. On another terminal, launch the pipeline, disabling the auto-triggering.

     roslaunch dvs_tracking live.launch auto_trigger:=false camera_name:=[calibration filename] events_topic:=[events topic]
    

    For instance:

     roslaunch dvs_tracking live.launch auto_trigger:=false camera_name:=DAVIS-ijrr events_topic:=/dvs/events
    

    If your calibrations filenames are my_camera.yaml, then use camera_name:=my_camera. Make sure to use the same name for both calibration files. If your sensor outputs events under the topic /my_sensor/events, then use events_topic:=/my_sensor/events.

    For the SVO based bootstrapper, proceed with step 4. For the fronto-planar bootstrapper, go to step 5. How to set up the fronto-planar bootstrapper is explained in the live.launch file.

    If you want to bootstrap from traditional frames, you can use the command:

     roslaunch dvs_tracking live.launch bootstrap_image_topic:=[topic raw frames] auto_trigger:=false
    

    For instance bootstrap_image_topic:=/dvs/image_raw.

    In this case, it makes sense to use the SVO-based bootstrapping only. This option is recommended to debug/improve/extend the rest of the EVO pipeline, without worrying about the quality of the bootstrapping.

  4. You should see two rqt GUI. One is the SVO GUI. Reset and start the pipeline until it tracks decently well. Make sure to set the namespace to svo.

  5. Press the Bootstrap button in the EVO GUI. This will automatically trigger the pipeline.

    Alternatively, it is also possible to trigger one module at the time:

    • Press the Start/Reset button in rqt_evo. Perform a circle (or more), and then press Update. This will trigger a map creation.
    • If the map looks correct, press Switch to tracking to start tracking with EVO. If not, reiterate the map creation.
    • As the camera moves out of the current map, the latter will be automatically updated if the Map-Expansion is enabled. You may disable Map-Expansion to track high-speed motions using the current map (single keyframe tracking).
    • The scene should have enough texture and the motions should recall the ones that you can see in the provided examples.
  6. If anything fails, just press Ctrl+C and restart the live node ;)

Some remarks:

  • The calibration files paths will be built as $(find dvs_tracking)/parameters/calib/ncamera/$(arg camera_name).yaml and $(find dvs_tracking)/parameters/calib/$(arg camera_name).yaml, where camera_name is specified as argument to the launch file. You can also set it as default in live.launch.
  • If your sensor provides frames under a topic /my_sensor/image_raw, and you want to bootstrap from the traditional frames, you can use bootstrap_image_topic:=/my_sensor/image_raw.

To run the pipeline live, first adjust the template live.launch to your sensor and scene. You can follow the following steps. Further customization, such as which bootstrapper to use, are explained in the launch file itself.

Calibration

Make sure you have updated calibration files for your event camera, in the dvs_tracking/parameters/calib folder.

Make sure your .yaml files have the same format as the provided ones (single camera format, multiple cameras format).

Remark that we have two calibration files in two different format for the same sensor. The single camera format has to be placed in the dvs_tracking/parameters/calib folder and the multiple cameras format in the dvs_tracking/parameters/calib/ncamera folder.

See this section for further references on calibration.

Tuning

Adjust the parameters in the launch file dvs_tracking/launch/template.launch.

Tuning is crucial for a good performance of the pipeline, in particular the min_depth and max_depth parameters in the mapping node, and the bootstrap node parameters.

An explanation of all the parameters for each module of the pipeline can be found in the Wiki.

The main parameters can be found in the template launch file, and are explained contextually. We still invite you to have a look at the Wiki, to discover further interesting features ;)

Module
Global parameters
Bootstrapping
Mapping
Tracking

If you are not using the fronto-planar bootstrapper, then you might need to tune SVO.

Remark that this might not be needed. You can test the svo tuning bootstrapping from traditional frames:

roslaunch dvs_tracking live.launch bootstrap_image_topic:=[topic of raw frames] auto_trigger:=[true/false]

For instance, bootstrap_image_topic:=/dvs/image_raw.

Further improvements

In the following we outline the main problems currently known and possible remedies. You are very welcome to contribute to this pipeline to make it even better!

What can go wrong TODO
Randomness due to OS scheduler, unreliable rosbags Implement rosbag data provider pattern, and ensure correctness of events consumption
Currently the pipeline uses multiple nodes. Switching to nodelets or using a single node could improve the repeatability of the rosbags.
Robustness bootstrapping: catch whenever SVO does not converge and trigger an automatic restart (what a human operator would eventually do manually).
tracking: catch whenever the tracker diverges, and re-initialize. Currently we have two parameters to predict this situation, namely min_map_size and min_n_keypoints.
Improve bootstrapping robustness Currently we have two working ways to bootstrap the pipeline from events: from SVO (feeding it with events frames) and with a fronto-planar assumption.
Reducing the assumptions required and making them more reliable would allow a better bootstrapping, reducing the gap to the bootstrapping from traditional frames (bootstrap_image_topic:=/dvs/image_raw).

Additional resources on Event Cameras

Comments
  • Pose Tracking Issues with DVS128?

    Pose Tracking Issues with DVS128?

    Hi! I'm currently using this package in conjunction with a DVS128 camera. The pose tracking is very jumpy, and the program almost inevitably crashes. I suspect it has to do with the lower resolution (128x128 instead of 240x180)--you'll notice in the screen shot below that only the upper left corner of the svo display is being used. Screenshot from 2021-07-01 16-26-24

    The camera will usually fly out of the scene, crashing the GUI and leaving this error message in the terminal:

    REQUIRED process [dvs_tracking-6] has died!
    process has died [pid 17992, exit code -8, cmd /home/ant/catkin_ws/devel/lib/dvs_tracking/dvs_tracking_ros events:=/dvs/events remote_key:=/evo/remote_key pointcloud:=dvs_mapping/pointcloud __name:=dvs_tracking __log:=/home/ant/.ros/log/af509da8-daa6-11eb-b294-ec8eb5ff88bf/dvs_tracking-6.log].
    log file: /home/ant/.ros/log/af509da8-daa6-11eb-b294-ec8eb5ff88bf/dvs_tracking-6*.log
    Initiating shutdown!
    

    I've tried to change the resolution manually, but there are a lot of places where that gets pretty tricky, like dealing with the eigenvectors in test_cameras.cpp.

    Any ideas on what might be the issue?

    opened by rrnyquist 7
  • Errors when building dvs_reconstruction

    Errors when building dvs_reconstruction

    Hi, thanks for your work! I meet an error when building dvs_mapping and dvs_reconstruction. The logs are: image and image How to address these problems? Are these two problems caused by the version mismatch of OpenCV (The opencv version I use is 4.2.0)?

    opened by xujingao13 6
  • Prophesee event camera and EVO

    Prophesee event camera and EVO

    Hello! Has anyone managed to get the VO running with Prophesee cameras (more specifically EVK4 HD). There seems to be an issue with having so much higher resolution on the camera. What would be the parameters to tune?

    Been trying out different values, but there's no sensible output from the algorithm. Seems to be that such a huge number of extra events can't be processed quickly enough.

    opened by stensalumets 0
  • dvs_bootstrapping process has died

    dvs_bootstrapping process has died

    started roslaunch server http://thinkstation-p920:38373/

    SUMMARY

    CLEAR PARAMETERS

    • /svo/

    PARAMETERS

    • /calib_file: /home/xuhaidong/c...
    • /camera_name: DAVIS-evo
    • /dvs_bootstrap_frame_id: /camera_0
    • /dvs_bootstrapping/activation_threshold_min: 10
    • /dvs_bootstrapping/activation_threshold_patch_size: 13
    • /dvs_bootstrapping/adaptive_thresholding: True
    • /dvs_bootstrapping/auto_trigger: True
    • /dvs_bootstrapping/enable_visualizations: True
    • /dvs_bootstrapping/events_offset: 0
    • /dvs_bootstrapping/events_scale_factor: 4.0
    • /dvs_bootstrapping/frame_size: 15000
    • /dvs_bootstrapping/local_frame_size: 5000
    • /dvs_bootstrapping/median_filter_size: 1
    • /dvs_bootstrapping/median_filtering: False
    • /dvs_bootstrapping/min_step_size: 15000
    • /dvs_bootstrapping/motion_corrected_topic: /events/image_raw
    • /dvs_bootstrapping/optical_flow_topic: /evo/bootstrap/op...
    • /dvs_bootstrapping/rate_hz: 30
    • /dvs_bootstrapping/unwarp_estimate_eps: 0.0001
    • /dvs_bootstrapping/unwarp_estimate_n_it: 75
    • /dvs_bootstrapping/unwarp_estimate_pyramid_lvls: 2
    • /dvs_frame_id: /dvs_evo
    • /dvs_mapping/accumulate_local_map_once_every: 25
    • /dvs_mapping/adaptive_threshold_c: 7
    • /dvs_mapping/adaptive_threshold_kernel_size: 5
    • /dvs_mapping/auto_trigger: True
    • /dvs_mapping/events_to_recreate_kf: 1000000
    • /dvs_mapping/frame_size: 2048
    • /dvs_mapping/global_point_cloud_skip_first: 15
    • /dvs_mapping/half_patchsize: 1
    • /dvs_mapping/median_filter_size: 15
    • /dvs_mapping/min_batch_size: 20000
    • /dvs_mapping/min_num_neighbors: 2
    • /dvs_mapping/min_num_neighbors_global_map: 2
    • /dvs_mapping/radius_search: 0.2
    • /dvs_mapping/radius_search_global_map: 0.05
    • /dvs_mapping/skip_batches: 0
    • /dvs_mapping/type_focus_measure: 0
    • /dvs_mapping/voxel_filter_leaf_size: 0.01
    • /dvs_renderer_left/display_method: red-blue
    • /dvs_tracking/auto_trigger: True
    • /dvs_tracking/batch_size: 500
    • /dvs_tracking/discard_events_when_idle: True
    • /dvs_tracking/event_map_overlap_rate: 15
    • /dvs_tracking/events_per_kf: 100000
    • /dvs_tracking/frame_size: 5000
    • /dvs_tracking/map_blur: 3
    • /dvs_tracking/max_event_rate: 4000000
    • /dvs_tracking/max_iterations: 200
    • /dvs_tracking/min_map_size: 200
    • /dvs_tracking/min_n_keypoints: 2000
    • /dvs_tracking/noise_rate: 10000
    • /dvs_tracking/pose_mean_filter_size: 5
    • /dvs_tracking/pyramid_levels: 2
    • /dvs_tracking/step_size: 10000
    • /dvs_tracking/weight_scale: 1.0
    • /fov_virtual_camera_deg: 80.0
    • /max_depth: 5
    • /min_depth: 0.4
    • /num_depth_cells: 100
    • /pose_to_tf/relative_to_first_pose: False
    • /pose_to_tf/source_topic_name: /svo/pose_cam/0
    • /rosdistro: melodic
    • /rosversion: 1.14.13
    • /snakify/length: 100000
    • /svo/T_world_imuinit/qw: 1.0
    • /svo/T_world_imuinit/qx: 0.0
    • /svo/T_world_imuinit/qy: 0.0
    • /svo/T_world_imuinit/qz: 0.0
    • /svo/calib_file: /home/xuhaidong/c...
    • /svo/cam0_topic: /events/image_raw
    • /svo/depth_filter_affine_est_gain: False
    • /svo/depth_filter_affine_est_offset: True
    • /svo/detector_threshold_primary: 8
    • /svo/detector_threshold_secondary: 200
    • /svo/grid_size: 5
    • /svo/img_align_est_illumination_gain: False
    • /svo/img_align_est_illumination_offset: False
    • /svo/img_align_max_level: 4
    • /svo/img_align_min_level: 2
    • /svo/img_align_prior_lambda_rot: 0.0
    • /svo/img_align_prior_lambda_trans: 0.0
    • /svo/init_min_disparity: 25
    • /svo/kfselect_criterion: DOWNLOOKING
    • /svo/kfselect_min_angle: 20
    • /svo/kfselect_min_disparity: 30
    • /svo/kfselect_min_dist_metric: 0.1
    • /svo/kfselect_numkfs_lower_thresh: 70
    • /svo/kfselect_numkfs_upper_thresh: 120
    • /svo/map_scale: 0.6
    • /svo/max_depth_inv: 0.05
    • /svo/max_fts: 180
    • /svo/max_n_kfs: 30
    • /svo/mean_depth_inv: 0.3
    • /svo/min_depth_inv: 1.0
    • /svo/n_pyr_levels: 2
    • /svo/pipeline_is_stereo: False
    • /svo/poseoptim_prior_lambda: 0.0
    • /svo/poseoptim_thresh: 2.0
    • /svo/poseoptim_using_unit_sphere: False
    • /svo/publish_every_nth_dense_input: 5
    • /svo/publish_marker_scale: 0.5
    • /svo/reprojector_affine_est_gain: False
    • /svo/reprojector_affine_est_offset: True
    • /svo/reprojector_max_n_kfs: 5
    • /svo/runlc: False
    • /svo/scan_epi_unit_sphere: False
    • /svo/seed_convergence_sigma2_thresh: 100
    • /svo/update_seeds_with_old_keyframes: True
    • /svo/use_async_reprojectors: False
    • /svo/use_imu: False
    • /tf_to_camera_marker/marker_scale: 0.2
    • /trigger_map_expansion/baseline_threshold: 0.1
    • /trigger_map_expansion/coverage_threshold: 0.4
    • /trigger_map_expansion/number_of_initial_maps_to_skip: 0
    • /trigger_map_expansion/rate: 3
    • /trigger_map_expansion/visibility_threshold: 0.9
    • /virtual_height: 180
    • /virtual_width: 240
    • /world_frame_id: /world

    NODES / dvs_bootstrapping (dvs_bootstrapping/dvs_bootstrapping_ef_ros) dvs_mapping (dvs_mapping/dvs_mapping_ros) dvs_renderer_left (dvs_renderer/dvs_renderer) dvs_tracking (dvs_tracking/dvs_tracking_ros) pose_to_tf (dvs_bootstrapping/pose_to_tf.py) record (rosbag/record) rqt_evo (rqt_evo/rqt_evo) rviz (rviz/rviz) snakify (evo_utils/snakify.py) svo (svo_ros/svo_node) svo_gui (rqt_gui/rqt_gui) tf_to_camera_marker (evo_utils/tf_to_camera_markers.py) trigger_map_expansion (dvs_mapping/trigger_map_expansion.py)

    auto-starting new master process[master]: started with pid [11331] ROS_MASTER_URI=http://localhost:11311

    setting /run_id to 6aa9e2fe-3be9-11ed-a2e9-8cc68119fcb7 process[rosout-1]: started with pid [11375] started core service [/rosout] process[svo-2]: started with pid [11383] process[svo_gui-3]: started with pid [11384] process[pose_to_tf-4]: started with pid [11385] process[dvs_mapping-5]: started with pid [11386] process[trigger_map_expansion-6]: started with pid [11387] process[dvs_tracking-7]: started with pid [11388] process[dvs_bootstrapping-8]: started with pid [11389] process[tf_to_camera_marker-9]: started with pid [11391] [ INFO] [1664010923.500156010]: Found parameter: pipeline_is_stereo, value: 0 [ WARN] [1664010923.501745132]: Cannot find value for parameter: set_initial_attitude_from_gravity, assigning default: 1 [ WARN] [1664010923.502205683]: Cannot find value for parameter: automatic_reinitialization, assigning default: 0 [ INFO] [1664010923.503386602]: Found parameter: calib_file, value: /home/xuhaidong/catkin_evo/src/rpg_dvs_evo_open/dvs_tracking/parameters/calib/ncamera/DAVIS-evo.yaml loaded 1 cameras name = cam0 size = [240, 180] Projection = Pinhole Focal length = (197.316, 197.248) Principal point = (128.193, 110.949) Distortion: RadTan(0, 0, 0, 0) [ WARN] [1664010923.504487761]: Cannot find value for parameter: klt_max_level, assigning default: 4 [ WARN] [1664010923.504994154]: Cannot find value for parameter: klt_min_level, assigning default: 0 [ INFO] [1664010923.506238938]: Found parameter: reprojector_max_n_kfs, value: 5 [ INFO] [1664010923.507398129]: Found parameter: max_fts, value: 180 [ INFO] [1664010923.508651229]: Found parameter: grid_size, value: 5 [ WARN] [1664010923.509109362]: Cannot find value for parameter: reproject_unconverged_seeds, assigning default: 1 [ INFO] [1664010923.510328535]: Found parameter: reprojector_affine_est_offset, value: 1 process[snakify-10]: started with pid [11396] [ INFO] [1664010923.511555219]: Found parameter: reprojector_affine_est_gain, value: 0 [ WARN] [1664010923.511994487]: Cannot find value for parameter: init_min_features, assigning default: 100 [ WARN] [1664010923.512422536]: Cannot find value for parameter: init_min_tracked, assigning default: 80 [ WARN] [1664010923.512848633]: Cannot find value for parameter: init_min_inliers, assigning default: 70 [ INFO] [1664010923.514019104]: Found parameter: init_min_disparity, value: 25 [ WARN] [1664010923.514462264]: Cannot find value for parameter: init_min_features_factor, assigning default: 2 [ WARN] [1664010923.514896876]: Cannot find value for parameter: reproj_err_thresh, assigning default: 2 [ WARN] [1664010923.515299271]: Cannot find value for parameter: init_disparity_pivot_ratio, assigning default: 0.5 [ WARN] [1664010923.515703779]: Cannot find value for parameter: init_method, assigning default: FivePoint [ INFO] [1664010923.516713702]: Found parameter: grid_size, value: 5 [ INFO] [1664010923.517719821]: Found parameter: n_pyr_levels, value: 2 [ INFO] [1664010923.518720641]: Found parameter: detector_threshold_primary, value: 8 [ INFO] [1664010923.519726689]: Found parameter: detector_threshold_secondary, value: 200 [ WARN] [1664010923.520097794]: Cannot find value for parameter: use_edgelets, assigning default: 1 [ INFO] [1664010923.521096946]: Found parameter: n_pyr_levels, value: 2 [ WARN] [1664010923.521469989]: Cannot find value for parameter: use_threaded_depthfilter, assigning default: 1 [ INFO] [1664010923.522503513]: Found parameter: seed_convergence_sigma2_thresh, value: 100 [ INFO] [1664010923.523500626]: Found parameter: scan_epi_unit_sphere, value: 0 process[rqt_evo-11]: started with pid [11397] [ INFO] [1664010923.524543342]: Found parameter: depth_filter_affine_est_offset, value: 1 [ INFO] [1664010923.525537113]: Found parameter: depth_filter_affine_est_gain, value: 0 [ INFO] [1664010923.526370994]: Found parameter: max_fts, value: 180 [ WARN] [1664010923.526693361]: Cannot find value for parameter: max_seeds_ratio, assigning default: 3 [ INFO] [1664010923.527628174]: Found parameter: max_n_kfs, value: 30 [ INFO] [1664010923.528588223]: Found parameter: use_imu, value: 0 process[dvs_renderer_left-12]: started with pid [11398] [ INFO] [1664010923.558822078]: Found parameter: auto_trigger, value: 1 I20220924 17:15:23.559906 11389 Bootstrapper.cpp:18] Bootstrapper initially idle: 0 [ INFO] [1664010923.561384452]: Found parameter: camera_name, value: DAVIS-evo [ INFO] [1664010923.562605345]: Found parameter: calib_file, value: /home/xuhaidong/catkin_evo/src/rpg_dvs_evo_open/dvs_tracking/parameters/calib/DAVIS-evo.yaml [ INFO] [1664010923.563250408]: camera calibration URL: file:///home/xuhaidong/catkin_evo/src/rpg_dvs_evo_open/dvs_tracking/parameters/calib/DAVIS-evo.yaml process[rviz-13]: started with pid [11431] [ INFO] [1664010923.572131425]: Found parameter: world_frame_id, value: /world [ INFO] [1664010923.572933906]: Found parameter: dvs_bootstrap_frame_id, value: /camera_0 [ INFO] [1664010923.580756844]: Found parameter: camera_name, value: DAVIS-evo [ INFO] [1664010923.582599932]: Found parameter: calib_file, value: /home/xuhaidong/catkin_evo/src/rpg_dvs_evo_open/dvs_tracking/parameters/calib/DAVIS-evo.yaml [ WARN] [1664010923.583478369]: Cannot find value for parameter: trace_dir, assigning default: /home/xuhaidong/catkin_evo/src/rpg_dvs_evo_open/svo/trace [ INFO] [1664010923.583731597]: camera calibration URL: file:///home/xuhaidong/catkin_evo/src/rpg_dvs_evo_open/dvs_tracking/parameters/calib/DAVIS-evo.yaml [ WARN] [1664010923.583902147]: Cannot find value for parameter: quality_min_fts, assigning default: 50 [ WARN] [1664010923.584223440]: Cannot find value for parameter: quality_max_drop_fts, assigning default: 40 [ WARN] [1664010923.584526644]: Cannot find value for parameter: relocalization_max_trials, assigning default: 50 [ INFO] [1664010923.585868301]: Found parameter: poseoptim_prior_lambda, value: 0 [ INFO] [1664010923.586781433]: Found parameter: poseoptim_using_unit_sphere, value: 0 [ INFO] [1664010923.587623297]: Found parameter: img_align_prior_lambda_rot, value: 0 [ INFO] [1664010923.588449710]: Found parameter: img_align_prior_lambda_trans, value: 0 [ WARN] [1664010923.588751669]: Cannot find value for parameter: structure_optimization_max_pts, assigning default: 20 [ INFO] [1664010923.589565002]: Found parameter: map_scale, value: 0.6 [ INFO] [1664010923.590379988]: Found parameter: kfselect_criterion, value: DOWNLOOKING [ WARN] [1664010923.590680529]: Cannot find value for parameter: kfselect_min_dist, assigning default: 0.12 [ INFO] [1664010923.591505177]: Found parameter: kfselect_numkfs_upper_thresh, value: 120 [ INFO] [1664010923.592326400]: Found parameter: kfselect_numkfs_lower_thresh, value: 70 [ INFO] [1664010923.593142740]: Found parameter: kfselect_min_dist_metric, value: 0.1 [ INFO] [1664010923.593953688]: Found parameter: kfselect_min_angle, value: 20 [ INFO] [1664010923.594792984]: Found parameter: kfselect_min_disparity, value: 30 [ WARN] [1664010923.595116301]: Cannot find value for parameter: kfselect_min_num_frames_between_kfs, assigning default: 2 [ INFO] [1664010923.595986947]: Found parameter: img_align_max_level, value: 4 [ INFO] [1664010923.596761846]: Found parameter: img_align_min_level, value: 2 [ WARN] [1664010923.597060409]: Cannot find value for parameter: img_align_robustification, assigning default: 0 [ WARN] [1664010923.597357511]: Cannot find value for parameter: img_align_use_distortion_jacobian, assigning default: 0 [ INFO] [1664010923.598323382]: Found parameter: img_align_est_illumination_gain, value: 0 [ INFO] [1664010923.599679834]: Found parameter: img_align_est_illumination_offset, value: 0 process[record-14]: started with pid [11476] [ INFO] [1664010923.600466407]: Found parameter: poseoptim_thresh, value: 2 [ INFO] [1664010923.601247402]: Found parameter: update_seeds_with_old_keyframes, value: 1 [ INFO] [1664010923.602020814]: Found parameter: use_async_reprojectors, value: 0 [ INFO] [1664010923.602190423]: DepthFilter: created. [ INFO] [1664010923.602212470]: DepthFilter: Start thread. [ WARN] [1664010923.602730283]: Cannot find value for parameter: T_world_imuinit/tz, assigning default: 0 [ WARN] [1664010923.603459434]: Cannot find value for parameter: T_world_imuinit/ty, assigning default: 0 [ WARN] [1664010923.604174126]: Cannot find value for parameter: T_world_imuinit/tx, assigning default: 0 [ INFO] [1664010923.606644904]: Found parameter: T_world_imuinit/qz, value: 0 [ INFO] [1664010923.608810694]: Found parameter: T_world_imuinit/qy, value: 0 [ INFO] [1664010923.610543571]: Found parameter: T_world_imuinit/qx, value: 0 [ INFO] [1664010923.612700994]: Found parameter: T_world_imuinit/qw, value: 1 [ WARN] [1664010923.613394546]: Cannot find value for parameter: publish_img_pyr_level, assigning default: 0 [ WARN] [1664010923.614092437]: Cannot find value for parameter: publish_every_nth_img, assigning default: 1 [ WARN] [1664010923.614542609]: Cannot find value for parameter: weight_scale_translation, assigning default: 0 [ INFO] [1664010923.616682256]: Found parameter: publish_every_nth_dense_input, value: 5 [ WARN] [1664010923.618248208]: Cannot find value for parameter: weight_scale_rotation, assigning default: 0 [ INFO] [1664010923.618605490]: Found parameter: unwarp_estimate_n_it, value: 75 [ INFO] [1664010923.620703501]: Found parameter: unwarp_estimate_eps, value: 0.0001 [ WARN] [1664010923.621449121]: Cannot find value for parameter: publish_world_in_cam_frame, assigning default: 1 [ INFO] [1664010923.621487124]: Found parameter: camera_name, value: DAVIS-evo [ WARN] [1664010923.622912406]: Cannot find value for parameter: publish_map_every_frame, assigning default: 0 [ WARN] [1664010923.623600541]: Cannot find value for parameter: publish_point_display_time, assigning default: 0 [ INFO] [1664010923.624077925]: Found parameter: unwarp_estimate_pyramid_lvls, value: 2 [ WARN] [1664010923.624383898]: Cannot find value for parameter: publish_seeds, assigning default: 1 [ WARN] [1664010923.624961955]: Cannot find value for parameter: publish_seeds_uncertainty, assigning default: 0 [ INFO] [1664010923.625177058]: Found parameter: calib_file, value: /home/xuhaidong/catkin_evo/src/rpg_dvs_evo_open/dvs_tracking/parameters/calib/DAVIS-evo.yaml [ WARN] [1664010923.625462145]: Cannot find value for parameter: trace_pointcloud, assigning default: 0 [ INFO] [1664010923.626580816]: camera calibration URL: file:///home/xuhaidong/catkin_evo/src/rpg_dvs_evo_open/dvs_tracking/parameters/calib/DAVIS-evo.yaml [ INFO] [1664010923.626789937]: Found parameter: publish_marker_scale, value: 0.5 I20220924 17:15:23.628573 11388 tracker.cpp:58] Field of view: 62.6128 [ INFO] [1664010923.660093431]: Found parameter: dvs_frame_id, value: /dvs_evo [ INFO] [1664010923.662734104]: Found parameter: world_frame_id, value: /world [ INFO] [1664010923.664676186]: Found parameter: radius_search, value: 0.2 [ INFO] [1664010923.666025415]: Found parameter: min_num_neighbors, value: 2 [ INFO] [1664010923.666893328]: Found parameter: median_filter_size, value: 15 [ INFO] [1664010923.668113561]: Found parameter: dvs_frame_id, value: /dvs_evo [ INFO] [1664010923.669456496]: Found parameter: dvs_bootstrap_frame_id, value: /camera_0 [ INFO] [1664010923.672419169]: Found parameter: world_frame_id, value: /world [ INFO] [1664010923.673259237]: Found parameter: auto_trigger, value: 1 I20220924 17:15:23.673393 11588 tracker.cpp:150] Spawned tracking thread. [ WARN] [1664010923.686773807]: Less than 5 x 1G of space free on disk with 'evo_track_pose2.bag.active'. [ INFO] [1664010923.702184756]: Found parameter: events_to_recreate_kf, value: 1000000 [ INFO] [1664010923.710056612]: Found parameter: fov_virtual_camera_deg, value: 80 [ INFO] [1664010923.718305074]: Found parameter: use_imu, value: 0 [ INFO] [1664010923.720962177]: Found parameter: virtual_width, value: 240 [ INFO] [1664010923.725126954]: Found parameter: runlc, value: 0 [ INFO] [1664010923.725349832]: SvoNode: Started Image loop. [ WARN] [1664010923.725920896]: Cannot find value for parameter: remote_key_topic, assigning default: svo/remote_key [ INFO] [1664010923.731663595]: Found parameter: cam0_topic, value: /events/image_raw [ INFO] [1664010923.741587816]: Found parameter: virtual_height, value: 180 I20220924 17:15:23.741658 11386 depth_defocus_node.cpp:63] Focal length of virtual camera: 143.01 pixels I20220924 17:15:24.001956 11389 camera.cpp:21] Distortion type: plumb_bob [ INFO] [1664010924.008050632]: Found parameter: rate_hz, value: 30 [ INFO] [1664010924.010212935]: Found parameter: frame_size, value: 15000 [ INFO] [1664010924.012570924]: Found parameter: local_frame_size, value: 5000 [ INFO] [1664010924.014908869]: Found parameter: enable_visualizations, value: 1 [ INFO] [1664010924.017153467]: Found parameter: motion_corrected_topic, value: /events/image_raw [ INFO] [1664010924.056293521]: Found parameter: min_depth, value: 0.4 [ INFO] [1664010924.057549590]: Found parameter: max_depth, value: 5 [ INFO] [1664010924.058949104]: Found parameter: num_depth_cells, value: 100 [ INFO] [1664010924.060319708]: Found parameter: adaptive_threshold_kernel_size, value: 5 [ INFO] [1664010924.061693220]: Found parameter: adaptive_threshold_c, value: 7 [ INFO] [1664010924.074330276]: Found parameter: auto_trigger, value: 1 [ INFO] [1664010924.083298729]: Found parameter: optical_flow_topic, value: /evo/bootstrap/optical_flow [ INFO] [1664010924.152411140]: Found parameter: min_step_size, value: 15000 [ INFO] [1664010924.153821451]: Found parameter: events_scale_factor, value: 4 [ INFO] [1664010924.155126569]: Found parameter: activation_threshold_min, value: 10 [ INFO] [1664010924.156455951]: Found parameter: activation_threshold_patch_size, value: 13 [ INFO] [1664010924.157740987]: Found parameter: median_filter_size, value: 1 [ INFO] [1664010924.159017251]: Found parameter: median_filtering, value: 0 [ INFO] [1664010924.160301386]: Found parameter: adaptive_thresholding, value: 1 [ INFO] [1664010930.637079467]: Found parameter: discard_events_when_idle, value: 1 OpenCV Error: Iterations do not converge (The algorithm stopped before its convergence. The correlation is going to be minimized. Images may be uncorrelated or non-overlapped) in findTransformECC, file /build/opencv-L2vuMj/opencv-3.2.0+dfsg/modules/video/src/ecc.cpp, line 530 W20220924 17:15:42.754611 11701 motion_correction.cpp:69] The algorithm stopped before its convergence. The correlation is going to be minimized. Images may be uncorrelated or non-overlapped *** Aborted at 1664010942 (unix time) try "date -d @1664010942" if you are using GNU date *** PC: @ 0x0 (unknown) *** SIGSEGV (@0x7b98d0142840) received by PID 11389 (TID 0x7f58d5dea700) from PID 18446744072905566272; stack trace: *** @ 0x7f5936256f10 (unknown) @ 0x7f5936c54fcd motion_correction::drawEventsMotionCorrectedOpticalFlow() @ 0x7f5936c4f860 dvs_bootstrapping::EventsFramesBootstrapper::integrateEvents() @ 0x7f5936c50da0 dvs_bootstrapping::EventsFramesBootstrapper::integratingThread() @ 0x7f59368f54c0 (unknown) @ 0x7f59360006db start_thread @ 0x7f593633961f clone @ 0x0 (unknown) [dvs_bootstrapping-8] process has died [pid 11389, exit code -11, cmd /home/xuhaidong/catkin_evo/devel/lib/dvs_bootstrapping/dvs_bootstrapping_ef_ros events:=/dvs/events remote_key:=/evo/remote_key __name:=dvs_bootstrapping __log:=/home/xuhaidong/.ros/log/6aa9e2fe-3be9-11ed-a2e9-8cc68119fcb7/dvs_bootstrapping-8.log]. log file: /home/xuhaidong/.ros/log/6aa9e2fe-3be9-11ed-a2e9-8cc68119fcb7/dvs_bootstrapping-8*.log

    ^C[record-14] killing on exit [rviz-13] killing on exit [dvs_renderer_left-12] killing on exit [rqt_evo-11] killing on exit [snakify-10] killing on exit [tf_to_camera_marker-9] killing on exit [dvs_tracking-7] killing on exit [trigger_map_expansion-6] killing on exit [dvs_mapping-5] killing on exit [pose_to_tf-4] killing on exit [svo_gui-3] killing on exit [pcl::KdTreeFLANN::setInputCloud] Cannot create a KDTree with an empty input cloud! [svo-2] killing on exit [rosout-1] killing on exit [master] killing on exit shutting down processing monitor... ... shutting down processing monitor complete done

    opened by SeaEastXu 1
  • SparseImgAlign: no features to track

    SparseImgAlign: no features to track

    Hi, I've been testing the code on Ubuntu 18.04,

    And ran the code roslaunch dvs_tracking live.launch auto_trigger:=false camera_name:=DAVIS-evo events_topic:=/dvs/events

    with the provided evo_flyingroom.bag file.

    However, I keep getting the SVO tracking loss, SparseImgAlign: no features to track!

    I tried changing the parameters, however, it is weird that the preset given does not works. I've attached the log below, and would any of the warnings below will be relevant to this error?

    Thanks in advance!

    
    SUMMARY
    ========
    
    CLEAR PARAMETERS
     * /svo/
    
    PARAMETERS
     * /calib_file: /home/jhlee/ws_ev...
     * /camera_name: DAVIS-evo
     * /dvs_bootstrap_frame_id: /camera_0
     * /dvs_bootstrapping/activation_threshold_min: 10
     * /dvs_bootstrapping/activation_threshold_patch_size: 13
     * /dvs_bootstrapping/adaptive_thresholding: True
     * /dvs_bootstrapping/auto_trigger: True
     * /dvs_bootstrapping/enable_visualizations: True
     * /dvs_bootstrapping/events_scale_factor: 4.0
     * /dvs_bootstrapping/frame_size: 10000
     * /dvs_bootstrapping/local_frame_size: 5000
     * /dvs_bootstrapping/median_filter_size: 1
     * /dvs_bootstrapping/median_filtering: False
     * /dvs_bootstrapping/min_step_size: 5000
     * /dvs_bootstrapping/motion_corrected_topic: /events/image_raw
     * /dvs_bootstrapping/optical_flow_topic: /evo/bootstrap/op...
     * /dvs_bootstrapping/rate_hz: 30
     * /dvs_bootstrapping/unwarp_estimate_eps: 0.0001
     * /dvs_bootstrapping/unwarp_estimate_n_it: 75
     * /dvs_bootstrapping/unwarp_estimate_pyramid_lvls: 2
     * /dvs_frame_id: /dvs_evo
     * /dvs_mapping/accumulate_local_map_once_every: 10
     * /dvs_mapping/adaptive_threshold_c: 7
     * /dvs_mapping/adaptive_threshold_kernel_size: 5
     * /dvs_mapping/auto_trigger: False
     * /dvs_mapping/events_to_recreate_kf: 1000000
     * /dvs_mapping/frame_size: 4096
     * /dvs_mapping/global_point_cloud_skip_first: 5
     * /dvs_mapping/half_patchsize: 1
     * /dvs_mapping/median_filter_size: 15
     * /dvs_mapping/min_batch_size: 20000
     * /dvs_mapping/min_num_neighbors: 2
     * /dvs_mapping/min_num_neighbors_global_map: 2
     * /dvs_mapping/radius_search: 0.2
     * /dvs_mapping/radius_search_global_map: 0.05
     * /dvs_mapping/skip_batches: 0
     * /dvs_mapping/type_focus_measure: 0
     * /dvs_mapping/voxel_filter_leaf_size: 0.005
     * /dvs_reconstruction/init_cov: 10.0
     * /dvs_reconstruction/map_blur: 15
     * /dvs_reconstruction/sigma_m: 10.0
     * /dvs_reconstruction/window_size: 5000
     * /dvs_renderer_left/display_method: red-blue
     * /dvs_tracking/auto_trigger: False
     * /dvs_tracking/batch_size: 500
     * /dvs_tracking/discard_events_when_idle: True
     * /dvs_tracking/event_map_overlap_rate: 15
     * /dvs_tracking/events_per_kf: 100000
     * /dvs_tracking/frame_size: 5000
     * /dvs_tracking/map_blur: 3
     * /dvs_tracking/max_event_rate: 4000000
     * /dvs_tracking/max_iterations: 150
     * /dvs_tracking/min_map_size: 0
     * /dvs_tracking/min_n_keypoints: 0
     * /dvs_tracking/noise_rate: 10000
     * /dvs_tracking/pose_mean_filter_size: 5
     * /dvs_tracking/pyramid_levels: 2
     * /dvs_tracking/step_size: 15000
     * /fov_virtual_camera_deg: 80.0
     * /max_depth: 5
     * /min_depth: 0.4
     * /num_depth_cells: 100
     * /pose_to_tf/relative_to_first_pose: False
     * /pose_to_tf/source_topic_name: /svo/pose_cam/0
     * /rosdistro: melodic
     * /rosversion: 1.14.10
     * /snakify/length: 100
     * /svo/T_world_imuinit/qw: 1
     * /svo/T_world_imuinit/qx: 0
     * /svo/T_world_imuinit/qy: 0
     * /svo/T_world_imuinit/qz: 0
     * /svo/calib_file: /home/jhlee/ws_ev...
     * /svo/cam0_topic: /events/image_raw
     * /svo/depth_filter_affine_est_gain: False
     * /svo/depth_filter_affine_est_offset: True
     * /svo/detector_threshold_primary: 8
     * /svo/detector_threshold_secondary: 200
     * /svo/grid_size: 5
     * /svo/img_align_est_illumination_gain: False
     * /svo/img_align_est_illumination_offset: False
     * /svo/img_align_max_level: 3
     * /svo/img_align_min_level: 2
     * /svo/img_align_prior_lambda_rot: 0.0
     * /svo/img_align_prior_lambda_trans: 0.0
     * /svo/init_min_disparity: 25
     * /svo/kfselect_criterion: DOWNLOOKING
     * /svo/kfselect_min_angle: 20
     * /svo/kfselect_min_disparity: 30
     * /svo/kfselect_min_dist_metric: 0.1
     * /svo/kfselect_numkfs_lower_thresh: 70
     * /svo/kfselect_numkfs_upper_thresh: 120
     * /svo/map_scale: 0.6
     * /svo/max_depth_inv: 0.05
     * /svo/max_fts: 180
     * /svo/max_n_kfs: 30
     * /svo/mean_depth_inv: 0.3
     * /svo/min_depth_inv: 1.0
     * /svo/n_pyr_levels: 2
     * /svo/pipeline_is_stereo: False
     * /svo/poseoptim_prior_lambda: 0.0
     * /svo/poseoptim_thresh: 2.0
     * /svo/poseoptim_using_unit_sphere: False
     * /svo/publish_every_nth_dense_input: 5
     * /svo/publish_marker_scale: 0.5
     * /svo/reprojector_affine_est_gain: False
     * /svo/reprojector_affine_est_offset: True
     * /svo/reprojector_max_n_kfs: 5
     * /svo/runlc: False
     * /svo/scan_epi_unit_sphere: False
     * /svo/seed_convergence_sigma2_thresh: 100
     * /svo/update_seeds_with_old_keyframes: True
     * /svo/use_async_reprojectors: False
     * /svo/use_imu: False
     * /tf_to_camera_marker/marker_scale: 0.2
     * /trigger_map_expansion/baseline_threshold: 0.1
     * /trigger_map_expansion/coverage_threshold: 0.4
     * /trigger_map_expansion/number_of_initial_maps_to_skip: 0
     * /trigger_map_expansion/rate: 3
     * /trigger_map_expansion/visibility_threshold: 0.9
     * /virtual_height: 180
     * /virtual_width: 240
     * /world_frame_id: /world
    
    NODES
      /
        dvs_bootstrapping (dvs_bootstrapping/dvs_bootstrapping_ef_ros)
        dvs_mapping (dvs_mapping/dvs_mapping_ros)
        dvs_reconstruction (dvs_reconstruction/dvs_reconstruction_ros)
        dvs_renderer_left (dvs_renderer/dvs_renderer)
        dvs_tracking (dvs_tracking/dvs_tracking_ros)
        pose_to_tf (dvs_bootstrapping/pose_to_tf.py)
        rqt_evo (rqt_evo/rqt_evo)
        rviz (rviz/rviz)
        snakify (evo_utils/snakify.py)
        svo (svo_ros/svo_node)
        svo_gui (rqt_gui/rqt_gui)
        tf_to_camera_marker (evo_utils/tf_to_camera_markers.py)
        trigger_map_expansion (dvs_mapping/trigger_map_expansion.py)
    
    ROS_MASTER_URI=http://localhost:11311
    
    process[svo-1]: started with pid [14850]
    process[svo_gui-2]: started with pid [14851]
    process[pose_to_tf-3]: started with pid [14852]
    process[dvs_mapping-4]: started with pid [14853]
    process[trigger_map_expansion-5]: started with pid [14854]
    process[dvs_tracking-6]: started with pid [14855]
    process[dvs_bootstrapping-7]: started with pid [14856]
    process[dvs_reconstruction-8]: started with pid [14857]
    process[tf_to_camera_marker-9]: started with pid [14858]
    process[snakify-10]: started with pid [14859]
    process[rqt_evo-11]: started with pid [14860]
    process[dvs_renderer_left-12]: started with pid [14861]
    [ INFO] [1654230606.209067072]: Found parameter: pipeline_is_stereo, value: 0
    process[rviz-13]: started with pid [14884]
    [ WARN] [1654230606.212348800]: Cannot find value for parameter: set_initial_attitude_from_gravity, assigning default: 1
    [ WARN] [1654230606.213275895]: Cannot find value for parameter: automatic_reinitialization, assigning default: 0
    [ INFO] [1654230606.216441423]: Found parameter: calib_file, value: /home/jhlee/ws_event/src/rpg_dvs_evo_open/dvs_tracking/parameters/calib/ncamera/DAVIS-evo.yaml
    loaded 1 cameras
      name = cam0
      size = [240, 180]
      Projection = Pinhole
      Focal length = (197.316, 197.248)
      Principal point = (128.193, 110.949)
      Distortion: RadTan(0, 0, 0, 0)
    [ WARN] [1654230606.227937020]: Cannot find value for parameter: klt_max_level, assigning default: 4
    [ WARN] [1654230606.228734322]: Cannot find value for parameter: klt_min_level, assigning default: 0
    [ INFO] [1654230606.230253109]: Found parameter: reprojector_max_n_kfs, value: 5
    [ INFO] [1654230606.231691166]: Found parameter: max_fts, value: 180
    [ INFO] [1654230606.233122692]: Found parameter: grid_size, value: 5
    [ WARN] [1654230606.233732580]: Cannot find value for parameter: reproject_unconverged_seeds, assigning default: 1
    [ INFO] [1654230606.235650168]: Found parameter: reprojector_affine_est_offset, value: 1
    [ INFO] [1654230606.239043292]: Found parameter: reprojector_affine_est_gain, value: 0
    [ WARN] [1654230606.240234889]: Cannot find value for parameter: init_min_features, assigning default: 100
    [ WARN] [1654230606.241462633]: Cannot find value for parameter: init_min_tracked, assigning default: 80
    [ WARN] [1654230606.242709601]: Cannot find value for parameter: init_min_inliers, assigning default: 70
    [ INFO] [1654230606.246221677]: Found parameter: init_min_disparity, value: 25
    [ WARN] [1654230606.247386535]: Cannot find value for parameter: init_min_features_factor, assigning default: 2
    [ WARN] [1654230606.248600608]: Cannot find value for parameter: reproj_err_thresh, assigning default: 2
    [ WARN] [1654230606.249850842]: Cannot find value for parameter: init_disparity_pivot_ratio, assigning default: 0.5
    [ WARN] [1654230606.251166495]: Cannot find value for parameter: init_method, assigning default: FivePoint
    [ INFO] [1654230606.254575793]: Found parameter: grid_size, value: 5
    [ INFO] [1654230606.257414840]: Found parameter: n_pyr_levels, value: 2
    [ INFO] [1654230606.259910138]: Found parameter: detector_threshold_primary, value: 8
    [ INFO] [1654230606.260749265]: Found parameter: detector_threshold_secondary, value: 200
    [ WARN] [1654230606.261089149]: Cannot find value for parameter: use_edgelets, assigning default: 1
    [ INFO] [1654230606.261941066]: Found parameter: n_pyr_levels, value: 2
    [ WARN] [1654230606.262278528]: Cannot find value for parameter: use_threaded_depthfilter, assigning default: 1
    [ INFO] [1654230606.263134960]: Found parameter: seed_convergence_sigma2_thresh, value: 100
    [ INFO] [1654230606.264182244]: Found parameter: scan_epi_unit_sphere, value: 0
    [ INFO] [1654230606.266365998]: Found parameter: depth_filter_affine_est_offset, value: 1
    [ INFO] [1654230606.269186765]: Found parameter: depth_filter_affine_est_gain, value: 0
    [ INFO] [1654230606.271391645]: Found parameter: max_fts, value: 180
    [ WARN] [1654230606.272142475]: Cannot find value for parameter: max_seeds_ratio, assigning default: 3
    [ INFO] [1654230606.282365438]: Found parameter: max_n_kfs, value: 30
    [ INFO] [1654230606.283991740]: Found parameter: use_imu, value: 0
    [ INFO] [1654230606.310293087]: Found parameter: auto_trigger, value: 1
    I20220603 13:30:06.312415 14856 Bootstrapper.cpp:18] Bootstrapper initially idle: 0
    [ INFO] [1654230606.315085303]: Found parameter: camera_name, value: DAVIS-evo
    [ WARN] [1654230606.315360755]: Cannot find value for parameter: trace_dir, assigning default: /home/jhlee/ws_event/src/rpg_dvs_evo_open/svo/trace
    [ WARN] [1654230606.315719102]: Cannot find value for parameter: quality_min_fts, assigning default: 50
    [ WARN] [1654230606.316226507]: Cannot find value for parameter: quality_max_drop_fts, assigning default: 40
    [ WARN] [1654230606.316556534]: Cannot find value for parameter: relocalization_max_trials, assigning default: 50
    [ INFO] [1654230606.317627837]: Found parameter: poseoptim_prior_lambda, value: 0
    [ INFO] [1654230606.317854508]: Found parameter: calib_file, value: /home/jhlee/ws_event/src/rpg_dvs_evo_open/dvs_tracking/parameters/calib/DAVIS-evo.yaml
    [ INFO] [1654230606.318978025]: Found parameter: poseoptim_using_unit_sphere, value: 0
    [ INFO] [1654230606.319891675]: camera calibration URL: file:///home/jhlee/ws_event/src/rpg_dvs_evo_open/dvs_tracking/parameters/calib/DAVIS-evo.yaml
    [ INFO] [1654230606.320107188]: Found parameter: img_align_prior_lambda_rot, value: 0
    [ INFO] [1654230606.320987917]: Found parameter: img_align_prior_lambda_trans, value: 0
    [ WARN] [1654230606.321555817]: Cannot find value for parameter: structure_optimization_max_pts, assigning default: 20
    [ INFO] [1654230606.322546835]: Found parameter: map_scale, value: 0.6
    [ INFO] [1654230606.324072713]: Found parameter: kfselect_criterion, value: DOWNLOOKING
    [ WARN] [1654230606.324524299]: Cannot find value for parameter: kfselect_min_dist, assigning default: 0.12
    [ INFO] [1654230606.325765184]: Found parameter: kfselect_numkfs_upper_thresh, value: 120
    [ INFO] [1654230606.326947160]: Found parameter: kfselect_numkfs_lower_thresh, value: 70
    [ INFO] [1654230606.328041138]: Found parameter: kfselect_min_dist_metric, value: 0.1
    [ INFO] [1654230606.329182363]: Found parameter: kfselect_min_angle, value: 20
    [ INFO] [1654230606.330095334]: Found parameter: kfselect_min_disparity, value: 30
    [ WARN] [1654230606.333263540]: Cannot find value for parameter: kfselect_min_num_frames_between_kfs, assigning default: 2
    [ INFO] [1654230606.334149599]: Found parameter: img_align_max_level, value: 3
    [ INFO] [1654230606.335167355]: Found parameter: img_align_min_level, value: 2
    [ WARN] [1654230606.336477855]: Cannot find value for parameter: img_align_robustification, assigning default: 0
    [ WARN] [1654230606.338864382]: Cannot find value for parameter: img_align_use_distortion_jacobian, assigning default: 0
    [ INFO] [1654230606.339906272]: Found parameter: img_align_est_illumination_gain, value: 0
    [ INFO] [1654230606.340694041]: Found parameter: img_align_est_illumination_offset, value: 0
    [ INFO] [1654230606.341492002]: Found parameter: poseoptim_thresh, value: 2
    [ INFO] [1654230606.342275174]: Found parameter: update_seeds_with_old_keyframes, value: 1
    [ INFO] [1654230606.343446164]: Found parameter: use_async_reprojectors, value: 0
    [ INFO] [1654230606.343650762]: DepthFilter: created.
    [ INFO] [1654230606.343750864]: DepthFilter: Start thread.
    [ WARN] [1654230606.344207343]: Cannot find value for parameter: T_world_imuinit/tz, assigning default: 0
    [ WARN] [1654230606.344717311]: Cannot find value for parameter: T_world_imuinit/ty, assigning default: 0
    [ WARN] [1654230606.345076860]: Cannot find value for parameter: T_world_imuinit/tx, assigning default: 0
    [ INFO] [1654230606.346677908]: Found parameter: T_world_imuinit/qz, value: 0
    [ INFO] [1654230606.347455257]: Found parameter: world_frame_id, value: /world
    [ INFO] [1654230606.350960188]: Found parameter: T_world_imuinit/qy, value: 0
    [ INFO] [1654230606.351180534]: Found parameter: dvs_bootstrap_frame_id, value: /camera_0
    [ INFO] [1654230606.355359242]: Found parameter: T_world_imuinit/qx, value: 0
    [ INFO] [1654230606.356222706]: Found parameter: T_world_imuinit/qw, value: 1
    [ WARN] [1654230606.356568806]: Cannot find value for parameter: publish_img_pyr_level, assigning default: 0
    [ WARN] [1654230606.356893005]: Cannot find value for parameter: publish_every_nth_img, assigning default: 1
    [ INFO] [1654230606.357715941]: Found parameter: publish_every_nth_dense_input, value: 5
    [ WARN] [1654230606.358602514]: Cannot find value for parameter: publish_world_in_cam_frame, assigning default: 1
    [ WARN] [1654230606.358930436]: Cannot find value for parameter: publish_map_every_frame, assigning default: 0
    [ WARN] [1654230606.359456519]: Cannot find value for parameter: publish_point_display_time, assigning default: 0
    [ WARN] [1654230606.360010500]: Cannot find value for parameter: publish_seeds, assigning default: 1
    [ WARN] [1654230606.360562839]: Cannot find value for parameter: publish_seeds_uncertainty, assigning default: 0
    [ WARN] [1654230606.361133968]: Cannot find value for parameter: trace_pointcloud, assigning default: 0
    [ WARN] [1654230606.362952583]: Cannot find value for parameter: weight_scale_translation, assigning default: 0
    [ WARN] [1654230606.364089734]: Cannot find value for parameter: weight_scale_rotation, assigning default: 0
    [ INFO] [1654230606.364978028]: Found parameter: camera_name, value: DAVIS-evo
    [ INFO] [1654230606.366043031]: Found parameter: calib_file, value: /home/jhlee/ws_event/src/rpg_dvs_evo_open/dvs_tracking/parameters/calib/DAVIS-evo.yaml
    [ INFO] [1654230606.366675058]: camera calibration URL: file:///home/jhlee/ws_event/src/rpg_dvs_evo_open/dvs_tracking/parameters/calib/DAVIS-evo.yaml
    [ INFO] [1654230606.370137073]: Found parameter: publish_marker_scale, value: 0.5
    I20220603 13:30:06.369302 14855 tracker.cpp:58] Field of view: 62.6128
    [ INFO] [1654230606.408046445]: Found parameter: map_blur, value: 15
    [ INFO] [1654230606.410995845]: Found parameter: dvs_frame_id, value: /dvs_evo
    [ INFO] [1654230606.413750185]: Found parameter: window_size, value: 5000
    [ INFO] [1654230606.416011685]: Found parameter: init_cov, value: 10
    [ INFO] [1654230606.416770070]: Found parameter: sigma_m, value: 10
    [ INFO] [1654230606.425639606]: Found parameter: unwarp_estimate_n_it, value: 75
    [ INFO] [1654230606.426459565]: Found parameter: unwarp_estimate_eps, value: 0.0001
    [ INFO] [1654230606.427212154]: Found parameter: unwarp_estimate_pyramid_lvls, value: 2
    [ INFO] [1654230606.433954524]: Found parameter: world_frame_id, value: /world
    [ INFO] [1654230606.447581312]: Found parameter: auto_trigger, value: 0
    [ INFO] [1654230606.447817768]: Found parameter: camera_name, value: DAVIS-evo
    [ INFO] [1654230606.450775512]: Found parameter: calib_file, value: /home/jhlee/ws_event/src/rpg_dvs_evo_open/dvs_tracking/parameters/calib/DAVIS-evo.yaml
    [ INFO] [1654230606.453170954]: camera calibration URL: file:///home/jhlee/ws_event/src/rpg_dvs_evo_open/dvs_tracking/parameters/calib/DAVIS-evo.yaml
    [ INFO] [1654230606.454203472]: Found parameter: use_imu, value: 0
    [ INFO] [1654230606.455399691]: Found parameter: runlc, value: 0
    [ WARN] [1654230606.455888280]: Cannot find value for parameter: remote_key_topic, assigning default: svo/remote_key
    [ INFO] [1654230606.467620874]: SvoNode: Started Image loop.
    [ INFO] [1654230606.472123081]: Found parameter: cam0_topic, value: /events/image_raw
    [ INFO] [1654230606.479668529]: Found parameter: dvs_frame_id, value: /dvs_evo
    [ INFO] [1654230606.480440005]: Found parameter: world_frame_id, value: /world
    [ INFO] [1654230606.481360757]: Found parameter: camera_name, value: DAVIS-evo
    [ INFO] [1654230606.482101867]: Found parameter: calib_file, value: /home/jhlee/ws_event/src/rpg_dvs_evo_open/dvs_tracking/parameters/calib/DAVIS-evo.yaml
    [ INFO] [1654230606.482578941]: camera calibration URL: file:///home/jhlee/ws_event/src/rpg_dvs_evo_open/dvs_tracking/parameters/calib/DAVIS-evo.yaml
    I20220603 13:30:06.483680 15014 tracker.cpp:150] Spawned tracking thread.
    [ INFO] [1654230606.511812370]: Found parameter: radius_search, value: 0.2
    [ INFO] [1654230606.512593665]: Found parameter: min_num_neighbors, value: 2
    [ INFO] [1654230606.513561137]: Found parameter: median_filter_size, value: 15
    [ INFO] [1654230606.515638176]: Found parameter: dvs_frame_id, value: /dvs_evo
    [ INFO] [1654230606.541098583]: Found parameter: dvs_bootstrap_frame_id, value: /camera_0
    [ INFO] [1654230606.542522827]: Found parameter: world_frame_id, value: /world
    [ INFO] [1654230606.551403586]: Found parameter: events_to_recreate_kf, value: 1000000
    [ INFO] [1654230606.553768089]: Found parameter: fov_virtual_camera_deg, value: 80
    [ INFO] [1654230606.554750971]: Found parameter: virtual_width, value: 240
    [ INFO] [1654230606.555776148]: Found parameter: virtual_height, value: 180
    I20220603 13:30:06.556963 14853 depth_defocus_node.cpp:63] Focal length of virtual camera: 143.01 pixels
    I20220603 13:30:06.678784 14856 camera.cpp:21] Distortion type: plumb_bob
    [ INFO] [1654230606.683401865]: Found parameter: rate_hz, value: 30
    [ INFO] [1654230606.684372713]: Found parameter: frame_size, value: 10000
    [ INFO] [1654230606.685555220]: Found parameter: local_frame_size, value: 5000
    [ INFO] [1654230606.686650451]: Found parameter: enable_visualizations, value: 1
    [ INFO] [1654230606.689345894]: Found parameter: motion_corrected_topic, value: /events/image_raw
    [ INFO] [1654230606.719264604]: Found parameter: optical_flow_topic, value: /evo/bootstrap/optical_flow
    [ INFO] [1654230606.742759762]: Found parameter: dvs_frame_id, value: /dvs_evo
    [ INFO] [1654230606.747854437]: Found parameter: min_depth, value: 0.4
    [ INFO] [1654230606.748439415]: Found parameter: world_frame_id, value: /world
    [ INFO] [1654230606.748780850]: Found parameter: max_depth, value: 5
    [ INFO] [1654230606.749609039]: Found parameter: num_depth_cells, value: 100
    [ INFO] [1654230606.750503475]: Found parameter: adaptive_threshold_kernel_size, value: 5
    [ INFO] [1654230606.751203363]: Found parameter: adaptive_threshold_c, value: 7
    [ INFO] [1654230606.757611040]: Found parameter: auto_trigger, value: 0
    [ INFO] [1654230619.848036796, 1621933189.867400344]: Found parameter: discard_events_when_idle, value: 1
    [ INFO] [1654230619.867998363, 1621933189.881573985]: Found parameter: min_step_size, value: 5000
    [ INFO] [1654230619.871506713, 1621933189.881573985]: Found parameter: events_scale_factor, value: 4
    [ INFO] [1654230619.874985271, 1621933189.888596113]: Found parameter: activation_threshold_min, value: 10
    [ INFO] [1654230619.878249253, 1621933189.888596113]: Found parameter: activation_threshold_patch_size, value: 13
    [ INFO] [1654230619.881612270, 1621933189.888596113]: Found parameter: median_filter_size, value: 1
    [ INFO] [1654230619.885056177, 1621933189.895676929]: Found parameter: median_filtering, value: 0
    [ INFO] [1654230619.888591069, 1621933189.895676929]: Found parameter: adaptive_thresholding, value: 1
    [ INFO] [1654230619.939237153, 1621933189.930938694]: DepthFilter: RESET.
    [ WARN] [1654230619.939352967, 1621933189.930938694]: Cannot find value for parameter: max_events_frames_saved_to_file, assigning default: 0
    [ WARN] [1654230619.939681429, 1621933189.930938694]: Cannot find value for parameter: events_frames_filename_format, assigning default: /media/user/data/example/%06d.bmp
    [ INFO] [1654230620.567679223, 1621933190.368656560]: Init: Triangulated 305 points
    [ WARN] [1654230620.571055268, 1621933190.375696945]: Lost 58 features!
    [ WARN] [1654230620.844022139, 1621933190.566367684]: Not enough matched features.
    [ WARN] [1654230622.278418883, 1621933191.568936148]: Not enough matched features.
    [ INFO] [1654230622.307378716, 1621933191.590077048]: SVO user input: START
    [ INFO] [1654230622.321178301, 1621933191.597135774]: DepthFilter: RESET.
    [ INFO] [1654230623.277309731, 1621933192.267329317]: Init: Triangulated 453 points
    [ WARN] [1654230623.282450246, 1621933192.274382425]: Lost 48 features!
    [ INFO] [1654230624.275339085, 1621933192.965906926]: SVO user input: START
    [ INFO] [1654230624.313291141, 1621933192.994120771]: DepthFilter: RESET.
    [ WARN] [1654230625.271730414, 1621933193.664730358]: Cannot set scene depth. Frame has no point-observations!
    [ERROR] [1654230625.272181470, 1621933193.664730358]: SparseImgAlign: no features to track!
    [ WARN] [1654230625.272215759, 1621933193.664730358]: Not enough matched features.
    [ERROR] [1654230625.272295848, 1621933193.664730358]: SparseImgAlign: no features to track!
    [ERROR] [1654230625.272387499, 1621933193.664730358]: SparseImgAlign: no features to track!
    [ERROR] [1654230625.272463544, 1621933193.664730358]: SparseImgAlign: no features to track!
    [ERROR] [1654230625.272557892, 1621933193.664730358]: SparseImgAlign: no features to track!
    [ERROR] [1654230625.289151528, 1621933193.678842205]: SparseImgAlign: no features to track!
    [ERROR] [1654230625.340071714, 1621933193.714125281]: SparseImgAlign: no features to track!
    [ERROR] [1654230625.387398751, 1621933193.742460572]: SparseImgAlign: no features to track!
    [ERROR] [1654230625.469447529, 1621933193.799021468]: SparseImgAlign: no features to track!
    [ERROR] [1654230625.513216398, 1621933193.834253529]: SparseImgAlign: no features to track!
    
    opened by alexjunholee 0
  • Error in roslaunch dvs_tracking live.launch

    Error in roslaunch dvs_tracking live.launch

    I have tried to run EVO in Ubuntu 20.04, Neotic ROS and for Dvxplorer camera. I have error when the I want to run:

    roslaunch dvs_tracking live.launch auto_trigger:=false camera_name:=DVXplorer-DXB00056 events_topic:=/dvs/events

    ROS_MASTER_URI=http://localhost:11311

    process[svo-1]: started with pid [23811] process[svo_gui-2]: started with pid [23812] process[pose_to_tf-3]: started with pid [23813] /usr/bin/env: ‘python’: No such file or directory [pose_to_tf-3] process has died [pid 23813, exit code 127, cmd /home/labuser/catkin_ws/src/rpg_dvs_evo_open/dvs_bootstrapping/src/pose_to_tf.py events:=/my_sensor/events remote_key:=/evo/remote_key __name:=pose_to_tf __log:=/home/labuser/.ros/log/fe1dcbba-d6c5-11ec-889c-c1e36d81b261/pose_to_tf-3.log]. log file: /home/labuser/.ros/log/fe1dcbba-d6c5-11ec-889c-c1e36d81b261/pose_to_tf-3*.log process[dvs_mapping-4]: started with pid [23814] process[trigger_map_expansion-5]: started with pid [23815] /usr/bin/env: ‘python’: No such file or directory process[dvs_tracking-6]: started with pid [23816] [trigger_map_expansion-5] process has died [pid 23815, exit code 127, cmd /home/labuser/catkin_ws/src/rpg_dvs_evo_open/dvs_mapping/src/trigger_map_expansion.py events:=/my_sensor/events remote_key:=evo/remote_key pointcloud:=dvs_mapping/pointcloud __name:=trigger_map_expansion __log:=/home/labuser/.ros/log/fe1dcbba-d6c5-11ec-889c-c1e36d81b261/trigger_map_expansion-5.log]. log file: /home/labuser/.ros/log/fe1dcbba-d6c5-11ec-889c-c1e36d81b261/trigger_map_expansion-5*.log process[dvs_bootstrapping-7]: started with pid [23817] process[dvs_reconstruction-8]: started with pid [23818] /usr/bin/env: process[tf_to_camera_marker-9]: started with pid [23819] ‘python’: No such file or directory [tf_to_camera_marker-9] process has died [pid 23819, exit code 127, cmd /home/labuser/catkin_ws/src/rpg_dvs_evo_open/evo_utils/src/evo_utils/tf_to_camera_markers.py events:=/my_sensor/events remote_key:=/evo/remote_key __name:=tf_to_camera_marker __log:=/home/labuser/.ros/log/fe1dcbba-d6c5-11ec-889c-c1e36d81b261/tf_to_camera_marker-9.log]. log file: /home/labuser/.ros/log/fe1dcbba-d6c5-11ec-889c-c1e36d81b261/tf_to_camera_marker-9*.log /usr/bin/env: ‘python’: No such file or directory process[snakify-10]: started with pid [23820] process[rqt_evo-11]: started with pid [23821] /usr/bin/env: ‘python’: No such file or directory [snakify-10] process has died [pid 23820, exit code 127, cmd /home/labuser/catkin_ws/src/rpg_dvs_evo_open/evo_utils/src/evo_utils/snakify.py events:=/my_sensor/events remote_key:=/evo/remote_key __name:=snakify __log:=/home/labuser/.ros/log/fe1dcbba-d6c5-11ec-889c-c1e36d81b261/snakify-10.log]. log file: /home/labuser/.ros/log/fe1dcbba-d6c5-11ec-889c-c1e36d81b261/snakify-10*.log [rqt_evo-11] process has died [pid 23821, exit code 127, cmd /home/labuser/catkin_ws/src/rpg_dvs_evo_open/rqt_evo/scripts/rqt_evo events:=/my_sensor/events remote_key:=/evo/remote_key __name:=rqt_evo __log:=/home/labuser/.ros/log/fe1dcbba-d6c5-11ec-889c-c1e36d81b261/rqt_evo-11.log]. log file: /home/labuser/.ros/log/fe1dcbba-d6c5-11ec-889c-c1e36d81b261/rqt_evo-11*.log

    REQUIRED process [dvs_tracking-6] has died! process has died [pid 23816, exit code -11, cmd /home/labuser/catkin_ws/devel/lib/dvs_tracking/dvs_tracking_ros events:=/my_sensor/events remote_key:=/evo/remote_key pointcloud:=dvs_mapping/pointcloud __name:=dvs_tracking __log:=/home/labuser/.ros/log/fe1dcbba-d6c5-11ec-889c-c1e36d81b261/dvs_tracking-6.log]. log file: /home/labuser/.ros/log/fe1dcbba-d6c5-11ec-889c-c1e36d81b261/dvs_tracking-6*.log Initiating shutdown!

    [pcl::KdTreeFLANN::setInputCloud] Cannot create a KDTree with an empty input cloud!

    Traceback (most recent call last): File "/opt/ros/noetic/lib/rqt_gui/rqt_gui", line 13, in sys.exit(main.main()) File "/opt/ros/noetic/lib/python3/dist-packages/rqt_gui/main.py", line 61, in main return super( File "/opt/ros/noetic/lib/python3/dist-packages/qt_gui/main.py", line 444, in main app = self.create_application(argv) File "/opt/ros/noetic/lib/python3/dist-packages/rqt_gui/main.py", line 71, in create_application icon = QIcon(logo) KeyboardInterrupt W20220518 12:34:48.865370 25255 motion_correction.cpp:69] s >= 0 [pcl::KdTreeFLANN::setInputCloud] Cannot create a KDTree with an empty input cloud! shutting down processing monitor... ... shutting down processing monitor complete done

    opened by hmirh 0
  • Run EVO in Ubuntu 20.04 and Neotic ROS

    Run EVO in Ubuntu 20.04 and Neotic ROS

    I could not run the EVO code in Ubuntu 20.04 and Neotic ROS. I would appreciate if you can solve my problem. I have also tried on this code in Melodic ROS and Ubuntu 16.04 but it did not work because INIVATION DV provide a PPA repository for Ubuntu Focal (20.04 LTS) and the latest Ubuntu Hirsute (21.04) on the x86_64, arm64, armhf and ppc64 architectures. The error in Ubuntu 20.04 and Neotic ROS is as follows:

    Some packages could not be installed. This may mean that you have requested an impossible situation or if you are using the unstable distribution that some required packages have not yet been created or been moved out of Incoming. The following information may help to resolve the situation:

    The following packages have unmet dependencies: python-catkin-tools : Depends: python-catkin-pkg (>= 0.2.9) but it is not installable Depends: python-osrf-pycommon but it is not installable E: Unable to correct problems, you have held broken packages. Second, we clone the evo dependencies ./rpg_dvs_evo_open/install.sh: line 24: vcs-import: command not found

    opened by hmirh 11
Owner
Robotics and Perception Group
Robotics and Perception Group
TensorRT implementation of RepVGG models from RepVGG: Making VGG-style ConvNets Great Again

RepVGG RepVGG models from "RepVGG: Making VGG-style ConvNets Great Again" https://arxiv.org/pdf/2101.03697.pdf For the Pytorch implementation, you can

weiwei zhou 69 Sep 10, 2022
A CUDA implementation of Lattice Boltzmann for fluid dynamics simulation

Lattice Boltzmann simulation I am conscious of being only an individual struggling weakly against the stream of time. But it still remains in my power

Long Nguyen 17 Mar 1, 2022
The official implementation of our CVPR 2021 paper - Hybrid Rotation Averaging: A Fast and Robust Rotation Averaging Approach

Graph Optimizer This repo contains the official implementation of our CVPR 2021 paper - Hybrid Rotation Averaging: A Fast and Robust Rotation Averagin

Chenyu 109 Dec 23, 2022
Implementation for the "Surface Reconstruction from 3D Line Segments" paper.

Surface Reconstruction from 3D Line Segments Surface reconstruction from 3d line segments. [Paper] [Supplementary Material] Langlois, P. A., Boulch, A

null 84 Dec 31, 2022
C++ Implementation of "An Equivariant Filter for Visual Inertial Odometry", ICRA 2021

EqF VIO (Equivariant Filter for Visual Inertial Odometry) This repository contains an implementation of an Equivariant Filter (EqF) for Visual Inertia

null 60 Nov 15, 2022
Unofficial third-party implementation of FFD (fast feature detector) published in IEEE TIP 2020.

fast_feature_detector Unofficial third-party implementation of FFD (fast feature detector) published in IEEE TIP 2020. Caution I have not got any perm

kamino410 12 Feb 17, 2022
ResNet Implementation, Training, and Inference Using LibTorch C++ API

LibTorch C++ ResNet CIFAR Example Introduction ResNet implementation, training, and inference using LibTorch C++ API. Because there is no native imple

Lei Mao 23 Oct 29, 2022
Swin Transformer C++ Implementation

This is Swin Transformer C++ Implementation, inspired by swin-transformer-pytorch.

null 20 Dec 14, 2022
An Efficient Implementation of Analytic Mesh Algorithm for 3D Iso-surface Extraction from Neural Networks

AnalyticMesh Analytic Marching is an exact meshing solution from neural networks. Compared to standard methods, it completely avoids geometric and top

Jiabao Lei 45 Dec 21, 2022
AlphaZero like implementation for Oware Abapa game

CGZero AlphaZero like implementation for Oware abapa game, in Codingame (https://www.codingame.com/multiplayer/bot-programming/oware-abapa) See https:

null 23 Dec 27, 2022
An Efficient Implementation of Analytic Mesh Algorithm for 3D Iso-surface Extraction from Neural Networks

AnalyticMesh Analytic Marching is an exact meshing solution from neural networks. Compared to standard methods, it completely avoids geometric and top

null 45 Dec 21, 2022
The official implementation of the research paper "DAG Amendment for Inverse Control of Parametric Shapes"

DAG Amendment for Inverse Control of Parametric Shapes This repository is the official Blender implementation of the paper "DAG Amendment for Inverse

Elie Michel 157 Dec 26, 2022
Python and C++ implementation of "MarkerPose: Robust real-time planar target tracking for accurate stereo pose estimation". Accepted at LXCV Workshop @ CVPR 2021.

MarkerPose: Robust Real-time Planar Target Tracking for Accurate Stereo Pose Estimation This is a PyTorch and LibTorch implementation of MarkerPose: a

Jhacson Meza 47 Nov 18, 2022
An implementation of [Jimenez et al., 2016] Ground Truth Ambient Occlusion, MIT license

XeGTAO Introduction XeGTAO is an open source, MIT licensed, DirectX/HLSL implementation of the Practical Realtime Strategies for Accurate Indirect Occ

null 491 Jan 5, 2023
Provide sample code of efficient operator implementation based on the Cambrian Machine Learning Unit (MLU) .

Cambricon CNNL-Example CNNL-Example 提供基于寒武纪机器学习单元(Machine Learning Unit,MLU)开发高性能算子、C 接口封装的示例代码。 依赖条件 操作系统: 目前只支持 Ubuntu 16.04 x86_64 寒武纪 MLU SDK: 编译和

Cambricon Technologies 1 Mar 7, 2022
A c++ implementation of yolov5 and deepsort

A C++ implementation of Yolov5 and Deepsort in Jetson Xavier nx and Jetson nano This repository uses yolov5 and deepsort to follow humna heads which c

null 266 Dec 28, 2022
An implementation on Fast Ground Segmentation for 3D LiDAR Point Cloud Based on Jump-Convolution-Process.

An implementation on "Shen Z, Liang H, Lin L, Wang Z, Huang W, Yu J. Fast Ground Segmentation for 3D LiDAR Point Cloud Based on Jump-Convolution-Process. Remote Sensing. 2021; 13(16):3239. https://doi.org/10.3390/rs13163239"

Wangxu1996 59 Jan 5, 2023
An inofficial PyTorch implementation of PREDATOR based on KPConv.

PREDATOR: Registration of 3D Point Clouds with Low Overlap An inofficial PyTorch implementation of PREDATOR based on KPConv. The code has been tested

ZhuLifa 14 Aug 3, 2022