Showing preview only (2,040K chars total). Download the full file or copy to clipboard to get everything.
Repository: mpkuse/cerebro
Branch: master
Commit: 1dea0b09e12e
Files: 154
Total size: 1.9 MB
Directory structure:
gitextract_xwomkigw/
├── .gitignore
├── CMakeLists.txt
├── README.md
├── config/
│ ├── echo__terminator_config_vins_fusion_cerebro
│ ├── euroc/
│ │ └── euroc_config_no_extrinsic.yaml
│ ├── fly
│ ├── mynteye/
│ │ ├── camera_left.yaml
│ │ ├── camera_right.yaml
│ │ ├── extrinsics.yaml
│ │ └── mynteye_config.yaml
│ ├── mynteye__terminator_config_vins_fusion_cerebro
│ ├── mynteye_kannala_brandt/
│ │ ├── camera_left.yaml
│ │ ├── camera_right.yaml
│ │ ├── extrinsics.yaml
│ │ └── mynteye_config.yaml
│ ├── mynteye_pinhole/
│ │ ├── camera_left.yaml
│ │ ├── camera_right.yaml
│ │ ├── extrinsics.yaml
│ │ └── mynteye_config.yaml
│ ├── realsense__terminator_config_vins_fusion_cerebro
│ ├── vinsfusion/
│ │ ├── djirosimu_realsense_d435i/
│ │ │ ├── README.md
│ │ │ ├── extrinsics.yaml
│ │ │ ├── left.yaml
│ │ │ ├── realsense_stereo_imu_config.yaml
│ │ │ └── right.yaml
│ │ ├── euroc/
│ │ │ ├── cam0_pinhole.yaml
│ │ │ ├── cam1_pinhole.yaml
│ │ │ ├── euroc_stereo_imu_config.yaml
│ │ │ └── extrinsics.yaml
│ │ ├── mynteye/
│ │ │ ├── camera_left.yaml
│ │ │ ├── camera_left_pinhole.yaml
│ │ │ ├── camera_right.yaml
│ │ │ ├── camera_right_pinhole.yaml
│ │ │ ├── extrinsics.yaml
│ │ │ └── mynteye_stereo_imu_config.yaml
│ │ └── realsense_d435i/
│ │ ├── extrinsics.yaml
│ │ ├── left.yaml
│ │ ├── realsense_stereo_imu_config.yaml
│ │ └── right.yaml
│ └── vinsmono_debug_config.yaml
├── launch/
│ ├── debugging_vinsmono.launch
│ ├── euroc_vinsfusion.launch
│ ├── keras_server.launch
│ ├── mynteye_vinsfusion.launch
│ ├── mynteye_vinsfusion_loadstate.launch
│ ├── mynteye_vinsfusion_ondrone.launch
│ ├── mynteye_vinsfusion_savestate.launch
│ ├── realsense_camera.launch
│ ├── realsense_vinsfusion.launch
│ ├── realsense_vinsfusion_ondrone_repeat.launch
│ └── realsense_vinsfusion_ondrone_teach.launch
├── msg/
│ └── LoopEdge.msg
├── package.xml
├── rviz/
│ ├── dev-config.rviz
│ ├── good-viz.rviz
│ └── vins-fusion.rviz
├── scripts/
│ ├── TerminalColors.py
│ ├── keras.models/
│ │ ├── .gitignore
│ │ ├── Apr2019/
│ │ │ └── gray_conv6_K16__centeredinput/
│ │ │ ├── core_model.1000.keras
│ │ │ └── model.json
│ │ ├── June2019/
│ │ │ ├── centeredinput-m1to1-240x320x1__mobilenetv2-block_9_add__K16__allpairloss/
│ │ │ │ └── modelarch_and_weights.2000.h5
│ │ │ ├── centeredinput-m1to1-240x320x3__mobilenet-conv_pw_6_relu__K16__allpairloss/
│ │ │ │ └── modelarch_and_weights.700.h5
│ │ │ └── centeredinput-m1to1-240x320x3__mobilenetv2-block_9_add__K16__allpairloss/
│ │ │ └── modelarch_and_weights.800.h5
│ │ ├── README.md
│ │ ├── core_model.keras
│ │ ├── mobilenet_conv7_allpairloss.keras
│ │ ├── model.json
│ │ └── modelarch_and_weights.h5
│ ├── keras_helpers.py
│ ├── predict_utils.py
│ ├── unittest/
│ │ ├── demo_superpoint.py
│ │ └── rtry_superpoint.py
│ ├── whole_image_desc_compute_client.py
│ └── whole_image_desc_compute_server.py
├── src/
│ ├── Cerebro.cpp
│ ├── Cerebro.h
│ ├── DataManager.cpp
│ ├── DataManager.h
│ ├── DataNode.cpp
│ ├── DataNode.h
│ ├── DlsPnpWithRansac.cpp
│ ├── DlsPnpWithRansac.h
│ ├── HypothesisManager.cpp
│ ├── HypothesisManager.h
│ ├── ImageDataManager.cpp
│ ├── ImageDataManager.h
│ ├── PNPCeresCostFunctions.h
│ ├── PinholeCamera.cpp
│ ├── PinholeCamera.h
│ ├── ProcessedLoopCandidate.cpp
│ ├── ProcessedLoopCandidate.h
│ ├── Visualization.cpp
│ ├── Visualization.h
│ ├── cerebro_node.cpp
│ ├── unittest/
│ │ ├── unittest_camera_geom_class_usage.cpp
│ │ ├── unittest_camodocal_proj.cpp
│ │ ├── unittest_plot2mat.cpp
│ │ ├── unittest_pose_tester.cpp
│ │ ├── unittest_rosservice_client.cpp
│ │ ├── unittest_termcolor.cpp
│ │ ├── unittest_theia.cpp
│ │ └── unittest_theia_ransac.cpp
│ └── utils/
│ ├── CameraGeometry.cpp
│ ├── CameraGeometry.h
│ ├── ElapsedTime.h
│ ├── GMSMatcher/
│ │ ├── gms_matcher.cpp
│ │ └── gms_matcher.h
│ ├── MiscUtils.cpp
│ ├── MiscUtils.h
│ ├── Plot2Mat.cpp
│ ├── Plot2Mat.h
│ ├── PointFeatureMatching.cpp
│ ├── PointFeatureMatching.h
│ ├── PoseManipUtils.cpp
│ ├── PoseManipUtils.h
│ ├── RawFileIO.cpp
│ ├── RawFileIO.h
│ ├── RosMarkerUtils.cpp
│ ├── RosMarkerUtils.h
│ ├── SafeQueue.h
│ ├── TermColor.h
│ ├── camera_geometry_usage.cpp
│ ├── camodocal/
│ │ ├── README.md
│ │ ├── include/
│ │ │ └── camodocal/
│ │ │ ├── calib/
│ │ │ │ └── CameraCalibration.h
│ │ │ ├── camera_models/
│ │ │ │ ├── Camera.h
│ │ │ │ ├── CameraFactory.h
│ │ │ │ ├── CataCamera.h
│ │ │ │ ├── CostFunctionFactory.h
│ │ │ │ ├── EquidistantCamera.h
│ │ │ │ ├── PinholeCamera.h
│ │ │ │ └── ScaramuzzaCamera.h
│ │ │ ├── chessboard/
│ │ │ │ ├── Chessboard.h
│ │ │ │ ├── ChessboardCorner.h
│ │ │ │ ├── ChessboardQuad.h
│ │ │ │ └── Spline.h
│ │ │ ├── gpl/
│ │ │ │ ├── EigenQuaternionParameterization.h
│ │ │ │ ├── EigenUtils.h
│ │ │ │ └── gpl.h
│ │ │ └── sparse_graph/
│ │ │ └── Transform.h
│ │ └── src/
│ │ ├── calib/
│ │ │ └── CameraCalibration.cc
│ │ ├── camera_models/
│ │ │ ├── Camera.cc
│ │ │ ├── CameraFactory.cc
│ │ │ ├── CataCamera.cc
│ │ │ ├── CostFunctionFactory.cc
│ │ │ ├── EquidistantCamera.cc
│ │ │ ├── PinholeCamera.cc
│ │ │ └── ScaramuzzaCamera.cc
│ │ ├── chessboard/
│ │ │ └── Chessboard.cc
│ │ ├── gpl/
│ │ │ ├── EigenQuaternionParameterization.cc
│ │ │ └── gpl.cc
│ │ ├── intrinsic_calib.cc
│ │ └── sparse_graph/
│ │ └── Transform.cc
│ └── nlohmann/
│ └── json.hpp
└── srv/
└── WholeImageDescriptorCompute.srv
================================================
FILE CONTENTS
================================================
================================================
FILE: .gitignore
================================================
*.data
*.pyc
*.npy
*.npz
*.pth
*.bak
================================================
FILE: CMakeLists.txt
================================================
cmake_minimum_required(VERSION 2.8.3)
project(cerebro)
# Catkin components
find_package(catkin REQUIRED COMPONENTS
cv_bridge
image_transport
roscpp
rospy
std_msgs
message_generation
)
## System dependencies are found with CMake's conventions
# find_package(Boost REQUIRED COMPONENTS system)
set( CMAKE_CXX_STANDARD 11 )
find_package(Threads)
find_package(Eigen3 REQUIRED)
find_package(Ceres REQUIRED)
find_package(OpenCV 3 REQUIRED)
#set( CMAKE_CXX_FLAGS "-fpermissive -std=c++11 -O3 -Wall -Wextra -pedantic" )
# Removing the dependence on theia for the production code.
# If you want to compile unit tests, some of those need theia-sfm as dependence.
find_package(Theia REQUIRED)
include_directories(${THEIA_INCLUDE_DIRS})
find_package(Boost REQUIRED COMPONENTS filesystem program_options system)
include_directories(${Boost_INCLUDE_DIRS})
#----------START gperftools
# install : sudo apt-get install google-perftools libgoogle-perftools-dev
# get cmake file: https://raw.githubusercontent.com/vast-io/vast/master/cmake/FindGperftools.cmake
# save to '/usr/local/lib/cmake'
#list(APPEND CMAKE_MODULE_PATH "/usr/local/lib/cmake")
#find_package(Gperftools REQUIRED)
#message( "----- GPERF")
#message( "----- "${GPERFTOOLS_LIBRARIES} )
set (CMAKE_CXX_FLAGS " -Wl,-no-as-needed")
#set(CMAKE_BUILD_TYPE Debug)
set(CMAKE_BUILD_TYPE Release)
#set(CMAKE_BUILD_TYPE RelWithDebInfo)
#----------END GPERFTOOLS
option(COMPILE_UNIT_TEST "Compile unit tests" OFF) #OFF by default. catkin_make -DCOMPILE_UNIT_TEST=ON will compile it. OFF will skip it
################################################
## Declare ROS messages, services and actions ##
################################################
## To declare and build messages, services or actions from within this
## package, follow these steps:
## * Let MSG_DEP_SET be the set of packages whose message types you use in
## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
## * In the file package.xml:
## * add a build_depend tag for "message_generation"
## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET
## * If MSG_DEP_SET isn't empty the following dependency has been pulled in
## but can be declared for certainty nonetheless:
## * add a run_depend tag for "message_runtime"
## * In this file (CMakeLists.txt):
## * add "message_generation" and every package in MSG_DEP_SET to
## find_package(catkin REQUIRED COMPONENTS ...)
## * add "message_runtime" and every package in MSG_DEP_SET to
## catkin_package(CATKIN_DEPENDS ...)
## * uncomment the add_*_files sections below as needed
## and list every .msg/.srv/.action file to be processed
## * uncomment the generate_messages entry below
## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
## Generate messages in the 'msg' folder
add_message_files(
FILES
LoopEdge.msg
)
## Generate services in the 'srv' folder
add_service_files(
FILES
WholeImageDescriptorCompute.srv
)
## Generate added messages and services with any dependencies listed here
generate_messages(
DEPENDENCIES
std_msgs
sensor_msgs
)
###################################
## catkin specific configuration ##
###################################
## The catkin_package macro generates cmake config files for your package
## Declare things to be passed to dependent projects
## INCLUDE_DIRS: uncomment this if you package contains header files
## LIBRARIES: libraries you create in this project that dependent projects also need
## CATKIN_DEPENDS: catkin_packages dependent projects also need
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
INCLUDE_DIRS include
# LIBRARIES cerebro
# CATKIN_DEPENDS cv_bridge image_transport roscpp rospy std_msgs
# DEPENDS system_lib
CATKIN_DEPENDS message_runtime
)
###########
## Build ##
###########
## Specify additional locations of header files
## Your package locations should be listed before other locations
include_directories(include)
include_directories(
${catkin_INCLUDE_DIRS}
${CERES_INCLUDE_DIRS}
${EIGEN3_INCLUDE_DIRS}
${OpenCV_INCLUDE_DIRS}
)
include_directories(
src/utils/camodocal/include
src/utils/
)
FILE(GLOB CamodocalCameraModelSources
src/utils/camodocal/src/chessboard/Chessboard.cc
src/utils/camodocal/src/calib/CameraCalibration.cc
src/utils/camodocal/src/camera_models/Camera.cc
src/utils/camodocal/src/camera_models/CameraFactory.cc
src/utils/camodocal/src/camera_models/CostFunctionFactory.cc
src/utils/camodocal/src/camera_models/PinholeCamera.cc
src/utils/camodocal/src/camera_models/CataCamera.cc
src/utils/camodocal/src/camera_models/EquidistantCamera.cc
src/utils/camodocal/src/camera_models/ScaramuzzaCamera.cc
src/utils/camodocal/src/sparse_graph/Transform.cc
src/utils/camodocal/src/gpl/gpl.cc
src/utils/camodocal/src/gpl/EigenQuaternionParameterization.cc
)
FILE( GLOB KuseUtilsSources
src/utils/PoseManipUtils.cpp
src/utils/RosMarkerUtils.cpp
src/utils/RawFileIO.cpp
src/utils/MiscUtils.cpp
src/utils/Plot2Mat.cpp
src/utils/CameraGeometry.cpp
src/utils/PointFeatureMatching.cpp
src/utils/GMSMatcher/gms_matcher.cpp
)
## Declare a C++ executable
add_executable(
cerebro_node
src/cerebro_node.cpp
src/PinholeCamera.cpp
src/DataManager.cpp
src/DataNode.cpp
src/Cerebro.cpp
src/Visualization.cpp
src/ProcessedLoopCandidate.cpp
src/DlsPnpWithRansac.cpp
src/HypothesisManager.cpp
src/ImageDataManager.cpp
${KuseUtilsSources}
${CamodocalCameraModelSources}
)
# this is needed to indicate this this executable depends on the messages of the pkg.
add_dependencies(cerebro_node cerebro_generate_messages_cpp)
target_link_libraries(cerebro_node
${catkin_LIBRARIES}
${OpenCV_LIBRARIES}
${CMAKE_THREAD_LIBS_INIT}
${CERES_LIBRARIES}
${Boost_LIBRARIES}
${THEIA_LIBRARIES}
#${GPERFTOOLS_LIBRARIES}
#/usr/local/lib/libfaiss.so
)
if(COMPILE_UNIT_TEST)
#add some compilation flags
## Unit Tests
add_executable (
unittest_termcolor
src/unittest/unittest_termcolor.cpp
)
add_executable (
unittest_rosservice_client
src/unittest/unittest_rosservice_client.cpp
)
add_executable (
unittest_camodocal_proj
src/unittest/unittest_camodocal_proj.cpp
${KuseUtilsSources}
${CamodocalCameraModelSources}
)
add_executable (
unittest_camera_geom_class_usage
src/unittest/unittest_camera_geom_class_usage.cpp
${KuseUtilsSources}
${CamodocalCameraModelSources}
)
add_executable (
unittest_theia
src/unittest/unittest_theia.cpp
${KuseUtilsSources}
${CamodocalCameraModelSources}
)
add_executable (
unittest_pose_tester
src/unittest/unittest_pose_tester.cpp
${KuseUtilsSources}
${CamodocalCameraModelSources}
src/DlsPnpWithRansac.cpp
)
add_executable (
unittest_plot2mat
src/unittest/unittest_plot2mat.cpp
src/utils/Plot2Mat.cpp
)
target_link_libraries(unittest_rosservice_client
${catkin_LIBRARIES}
${OpenCV_LIBRARIES}
${CMAKE_THREAD_LIBS_INIT}
${CERES_LIBRARIES}
)
target_link_libraries(unittest_camodocal_proj
${catkin_LIBRARIES}
${OpenCV_LIBRARIES}
${CMAKE_THREAD_LIBS_INIT}
${CERES_LIBRARIES}
)
target_link_libraries(unittest_camera_geom_class_usage
${catkin_LIBRARIES}
${OpenCV_LIBRARIES}
${CMAKE_THREAD_LIBS_INIT}
${CERES_LIBRARIES}
)
target_link_libraries(unittest_theia
${catkin_LIBRARIES}
${OpenCV_LIBRARIES}
${CMAKE_THREAD_LIBS_INIT}
${CERES_LIBRARIES}
${THEIA_LIBRARIES}
)
target_link_libraries(unittest_pose_tester
${catkin_LIBRARIES}
${OpenCV_LIBRARIES}
${CMAKE_THREAD_LIBS_INIT}
${CERES_LIBRARIES}
${THEIA_LIBRARIES}
)
target_link_libraries(unittest_plot2mat
${catkin_LIBRARIES}
${OpenCV_LIBRARIES}
)
else()
#add some other compilation flags
endif(COMPILE_UNIT_TEST)
unset(COMPILE_UNIT_TEST CACHE) # <---- this is the important!!
#############
## Install ##
#############
# all install targets should use catkin DESTINATION variables
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
## Mark executable scripts (Python etc.) for installation
## in contrast to setup.py, you can choose the destination
# install(PROGRAMS
# scripts/my_python_script
# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )
## Mark executables and/or libraries for installation
# install(TARGETS cerebro cerebro_node
# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )
## Mark cpp header files for installation
# install(DIRECTORY include/${PROJECT_NAME}/
# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
# FILES_MATCHING PATTERN "*.h"
# PATTERN ".svn" EXCLUDE
# )
## Mark other files for installation (e.g. launch and bag files, etc.)
# install(FILES
# # myfile1
# # myfile2
# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
# )
#############
## Testing ##
#############
## Add gtest based cpp test target and link libraries
# catkin_add_gtest(${PROJECT_NAME}-test test/test_cerebro.cpp)
# if(TARGET ${PROJECT_NAME}-test)
# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
# endif()
## Add folders to be run by python nosetests
# catkin_add_nosetests(test)
================================================
FILE: README.md
================================================
# VINS-Fusion with Cerebro
This is the cerebro module for VINS-Fusion. The aim of this project
is better loop detection and recover from kidnap. The cerebro node connects to
the vins_estimator nodes of VINS-Fusion
(with ros interface). The DataManager class handles
all the incoming data. Visualization handles all the visualization.
Cerebro class handles the loop closure intelligence part. It publishes a LoopMsg
which contains timestamps of the identified loopcandidate along with the
computed relative pose between the pair. The pose computation needs a stereo pair
for reliable pose computation.
This is a multi-threaded object oriented implementation and I observe a CPU load factor
of about 2.0. A separate node handles pose graph solver (it is in [github-repo](https://github.com/mpkuse/solve_keyframe_pose_graph) ).
This repo also support for saving the trajectories to file and later
loading it from file for relocalization. See [launch/realsense_vinsfusion_ondrone_teach.launch](launch/realsense_vinsfusion_ondrone_teach.launch) on how to do it.
If you use this work in your research, please cite:
Manohar Kuse and Shaojie Shen, *“Learning Whole-Image Descriptors for Real-time Loop Detection and Kidnap Recovery under Large Viewpoint Difference“*, https://arxiv.org/abs/1904.06962
## Highlight Video
[](http://www.youtube.com/watch?v=lDzDHZkInos "Video Title")
## MyntEye Demo (Using VINS-Fusion as Odometry Estimator)
We showcase the kidnap recovery and relocalization.
[](http://www.youtube.com/watch?v=3YQF4_v7AEg "Video Title")
[](http://www.youtube.com/watch?v=sTd_rZdW4DQ "Video Title")
## In Plane Rotation Test (Uses Realsense Camera)
[](http://www.youtube.com/watch?v=8bsRCNF2rnA "Video Title")
## Relocalization from Previously Constructed Trajectories.
We show the accurary of the system by plotting a previously constructed surfel map (in gray color)
and the newly constructed surfel map (rainbox colored). We can observe that the boxes for example in the environment overlap. Similarly other objects in the seen also overlap.
[](http://www.youtube.com/watch?v=OViEEB3rINo "Video Title")
## MyntEye Demo (Using VINS-Mono as Odometry Estimator)
[](http://www.youtube.com/watch?v=KDRo9LpL6Hs "Video Title")
[](http://www.youtube.com/watch?v=XvoCrLFq99I "Video Title")
## EuRoC MAV Dataset live merge MH-01, ... MH-05.
[](http://www.youtube.com/watch?v=mnnoAlAIsN8 "Video Title")
## EuRoC MAV Dataset live merge V1_01, V1_02, V1_03, V2_01, V2_02
[](http://www.youtube.com/watch?v=rIaANkd74cQ "Video Title")
For more demonstration, have a look at my [youtube playlist](https://www.youtube.com/playlist?list=PLWyydx20vdPzs5VVhZu0TGsReT7U17Fxp)
## Visual-Inertial Datasets
- [ETHZ EuroC Dataset](https://projects.asl.ethz.ch/datasets/doku.php?id=kmavvisualinertialdatasets)
- [TUM Visual Inertial Dataset](https://vision.in.tum.de/data/datasets/visual-inertial-dataset)
- UPenn - [Penncosyvio](https://github.com/daniilidis-group/penncosyvio)
- [ADVIO](https://github.com/AaltoVision/ADVIO) ARKIT, Tango logging.
- Our MyntEye (Stereo+IMU) [One-drive-link](https://hkustconnect-my.sharepoint.com/:f:/g/personal/mpkuse_connect_ust_hk/EkTisuLkXLFBs_WHYkxoH2oBeVIkdLc3-5a_t1J9c_4wkg?e=h9cifx)
## How to run - Docker
I highly recommend the already deployed packages with docker.
Run the roscore on your host pc and all the packages run inside
of docker container. rviz runs on the host pc.
I assume you have a PC with a graphics card and cuda9 working smoothly
and nvidia-docker installed.
```
$(host) export ROS_HOSTNAME=`hostname`
$(host) roscore
# assume that host has the ip address 172.17.0.1 in docker-network aka docker0
$(host) docker run --runtime=nvidia -it --rm \
--add-host `hostname`:172.17.0.1 \
--env ROS_MASTER_URI=http://`hostname`:11311/ \
--env CUDA_VISIBLE_DEVICES=0 \
--hostname happy_go \
--name happy_go \
mpkuse/kusevisionkit:ros-kinetic-vins-tf-faiss bash
$(host) rviz # inside rviz open config cerebro/config/good-viz.rviz. If you open rviz in a new tab you might need to do set ROS_HOSTNAME again.
$(docker) roslaunch cerebro mynteye_vinsfusion.launch
OR
$(docker) roslaunch cerebro euroc_vinsfusion.launch
$(host) rosbag play 1.bag
```
If you are unfamiliar with docker, you may want to read [my blog post](https://kusemanohar.wordpress.com/2018/10/03/docker-for-computer-vision-researchers/)
on using docker for computer vision researchers.
You might want to have a look at my test ros-package to ensure things work with docker [docker_ros_test](https://github.com/mpkuse/docker_ros_test).
List of all my docker-images can be found [here](https://hub.docker.com/r/mpkuse/kusevisionkit).
Other docker images that work:
- mpkuse/kusevisionkit:ros-kinetic-vins-tf-faiss (preferred)
- mpkuse/kusevisionkit:vins-kidnap
## How to compile (from scratch)
You will need a) VINS-Fusion (with modification for reset by mpkuse), b) cerebro
and c) solve_keyframe_pose_graph. Besure to setup a `catkin_ws` and make sure
your ROS works correctly.
### Dependencies
- ROS Kinetic
- Eigen3
- Ceres
- OpenCV3 (should also work with 2.4 (not tested), 3.3 (tested Ok) and 3.4 (tested ok))
- [Theia-sfm](http://theia-sfm.org/). *As of May2019 dependence on theia-sfm has been eliminated. The code is able to compile even when you do not have Theia-sfm installed. The pose estimation PNP/P3P has been implemented from scratch using ceres. *
- [OpenImageIO](https://github.com/OpenImageIO/oiio) (Release-1.7.6RC1) <br/>
- [RocksDB](https://github.com/facebook/rocksdb) (v5.9.2) <br/>
- OpenExr <br/>
- Tensorflow (tested on 1.11.0)
- Keras (atleast 2.2.4), I noticed issues in jsonmodel with 2.2.2, 2.2.2 still works though!
### Get VINS-Fusion Working
I recommend you use my fork of VINS-Fusion, in which I have fixed some bugs
and added mechanism for reseting the VINS.
```
cd catkin_ws/src
#git clone https://github.com/HKUST-Aerial-Robotics/VINS-Fusion.git
git clone https://github.com/mpkuse/VINS-Fusion
cd ../
catkin_make
source catkin_ws/devel/setup.bash
```
Make sure your vins-fusion can compile and run correctly. See vins-fusion github repo
for the latest information on prerequisites and compilation instructions.
For compatibility I recommend using my fork of vins-mono/vins-fusion. Some minor
modifications have been made by me for working with kidnap cases.
### Cerebro
```
cd catkin_ws/src/
git clone https://github.com/mpkuse/cerebro
cd ../
catkin_make
```
This has 2 exectables. **a)** ros server that takes as input an image and
returns a image descriptor. **b)** cerebro_node, this
finds the loop candidates and computes the relative poses. I have also
included my trained model (about 4 MB) in this package (located scripts/keras.model). The pose computation
uses the stereo pair in this node. This node publishes the loopcandidate's relative pose
which is expected to be consumed the pose-graph solver.
If you wish to train your own model, you may use [my learning code here](https://github.com/mpkuse/cartwheel_train).
**Threads in cerebro_node:**
- *Main Thread* : ros-callbacks
- *data_association_th* : Sync the incoming image data and incoming data vins_estimator.
- *desc_th* : Consumes the images to produce whole-image-descriptors.
- *dot_product_th* : Dot product of current image descriptor with all the previous ones.
- *loopcandidate_consumer_th* : Computes the relative pose at the loopcandidates. Publishes the loopEdge.
- *kidnap_th* : Identifies kidnap. If kidnap publishes the reset signals for vins_estimator.
- *viz_th* : Publishes the image-pair, and more things for debugging and analysis.
- *dm_cleanup_th* : Deallocate/Store to file images to reduce RAM consumption.
**Nvidia TX2**: Often times for live run, you might want to run the
ros-server on a Nvidia-TX2. I recommend compiling tensorflow from scratch.
The thing is prebuilt binaries may not be compatible with the version
of CUDA and CUDNN on your device. Also some binaries may not be
compatible to arm (could likely be built for x86). Before you can
compile tensorflow you need java, bazel. See this [gist](https://gist.github.com/vellamike/7c26158c93e89ef155c1cc953bbba956). Also tools and repos from [jetsonhacks](https://github.com/jetsonhacks)
might come in handy.
### Pose Graph Solver
Use my pose graph solver, [github-repo](https://github.com/mpkuse/solve_keyframe_pose_graph).
The differences between this implementation and the
original from VINS-Fusion is that mine can handle kidnap cases,
handles multiple world co-ordinate frames and it
uses a switch-constraint formulation of the pose-graph problem.
```
cd catkin_ws/src/
git clone https://github.com/mpkuse/solve_keyframe_pose_graph
cd ../
catkin_make
```
**Threads:**
- *Main thread* : ros-callbacks for odometry poses (from vins_estimator) and LoopMsg (from cerebro).
- *SLAM* : Monitors the node-poses and loop-edges, on new loop-edges constructs and solves the pose-graph optimization problem.
- *th4* : Publish latest odometry.
- *th5* : Display image to visualize disjoint set datastructure.
- *th6* : Publish corrected poses, Different color for nodes in different co-ordinate systems.
### vins_mono_debug_pkg (optional, needed only if you wish to debug vins-mono/vins-fusion)
With cerebro node it is possible to live run the vins and make it log all the
details to file for further analysis/debugging. This might be useful
for researchers and other Ph.D. student to help VINS-Fusion improve further.
see [github/mpkuse/vins_mono](https://github.com/mpkuse/vins_mono_debug_pkg).
It basically contains unit tests and some standalone tools which might come in handy.
If you are looking to help improve VINS-fusion or cerebro also look at 'Development Guidelines'.
## How to run the Full System
```
roslaunch cerebro mynteye_vinsfusion.launch
```
You can get some of my bag files collected with the mynteye camera HERE. More
example launch files in folder `launch`, all the config files which contains
calibration info are in folder `config`.
## Development Guidelines
If you are developing I still recommend using docker. with -v flags in docker you could mount your
pc's folders on the docker. I recommend keeping all the packages in folder `docker_ws_slam/catkin_ws/src`
on your host pc. And all the rosbags in folder `/media/mpkuse/Bulk_Data`. And then mount these
two folders on the docker-container. Edit the following command as needed.
```
docker run --runtime=nvidia -it -v /media/mpkuse/Bulk_Data/:/Bulk_Data -v /home/mpkuse/docker_ws_slam:/app --add-host `hostname`:172.17.0.1 --env ROS_MASTER_URI=http://`hostname`:11311/ --env CUDA_VISIBLE_DEVICES=0 --hostname happy_go --name happy_go mpkuse/kusevisionkit:ros-kinetic-vins bash
```
Use the following if you wish to use xhost(gui) from inside docker
```
$(host) xhost +local:root
$(host)
docker run --runtime=nvidia -it -e DISPLAY=$DISPLAY -v /tmp/.X11-unix:/tmp/.X11-unix -v /media/mpkuse/Bulk_Data/:/Bulk_Data -v /home/mpkuse/docker_ws_slam:/app --add-host `hostname`:172.17.0.1 --env ROS_MASTER_URI=http://`hostname`:11311/ --env CUDA_VISIBLE_DEVICES=0 --hostname happy_go --name happy_go mpkuse/kusevisionkit:ros-kinetic-vins bash
```
Other docker images that work:
- mpkuse/kusevisionkit:ros-kinetic-vins-tf-faiss (preferred)
- mpkuse/kusevisionkit:vins-kidnap
Each of my classes can export the data they hold as json objects and image files. Look at the
end of `main()` in `cerebro_node.cpp` and modify as needed to extract more debug data. Similarly
the pose graph solver can also be debugged.
If writing a lot of debug data (usually taking more than 10sec) roslaunch force-kills the process.
To get around this issue, you need to increase the timeout:
```
For kinetic this can be found in:
/opt/ros/kinetic/lib/python2.7/dist-packages/roslaunch
In the file nodeprocess.py there will be 2 variables on line 57 and 58.
_TIMEOUT_SIGINT = 15.0 #seconds
_TIMEOUT_SIGTERM = 2.0 #seconds
```
For streamlining printing messages
I have preprocessor macros at the start of function implementation (of classes DataManager and Cerebro),
read the comments there and edit as per need. Try to implement your algorithms in
object oriented way and using the producer-consumer paradigm. Look at my thread-mains for example.
Finally, sensible PR with bug fixes, enhancements are welcome!

## Authors
Manohar Kuse <mpkuse@connect.ust.hk>
================================================
FILE: config/echo__terminator_config_vins_fusion_cerebro
================================================
[global_config]
[keybindings]
[layouts]
[[default]]
[[[child0]]]
fullscreen = False
last_active_term = 1cc3df64-f997-4766-9317-0ce75d5dc2cd
last_active_window = True
maximised = True
order = 0
parent = ""
position = 65:24
size = 1855, 1056
title = dji@MANIFOLD-2-C: ~
type = Window
[[[child1]]]
order = 0
parent = child0
position = 525
ratio = 0.5
type = VPaned
[[[child2]]]
order = 0
parent = child1
position = 513
ratio = 0.278167115903
type = HPaned
[[[child4]]]
order = 1
parent = child2
position = 648
ratio = 0.487275449102
type = HPaned
[[[child7]]]
order = 1
parent = child1
position = 513
ratio = 0.278167115903
type = HPaned
[[[child9]]]
order = 1
parent = child7
position = 644
ratio = 0.484281437126
type = HPaned
[[[terminal10]]]
command = echo "roslaunch cerebro realsense_vinsfusion_ondrone.launch"; echo "roslaunch cerebro mynteye_vinsfusion_ondrone.launch"; bash
order = 0
parent = child9
profile = default
type = Terminal
uuid = 8fc7a21c-3feb-468d-aae5-c363bc5c9f80
[[[terminal11]]]
command = echo "roslaunch cerebro realsense_camera.launch"; echo "roslaunch mynt_eye_ros_wrapper mynteye.launch"; echo "rosbag play <file.bag>"; bash
order = 1
parent = child9
profile = default
type = Terminal
uuid = a63545ab-f3c1-4426-a8ef-173f57ca8f28
[[[terminal3]]]
command = echo "roscore"; bash
order = 0
parent = child2
profile = default
type = Terminal
uuid = 27ae967a-b56c-4d92-a56e-67a2abe6b22d
[[[terminal5]]]
command = '''echo "ssh root@dji-tx2 'nvpmodel -m 0 && jetson_clocks'"; echo ""; echo "ssh -t dji@dji-tx2 'export ROS_MASTER_URI=http://MANIFOLD-2-C:11311/; source $HOME/catkin_ws/devel/setup.bash && roslaunch tx2_whole_image_desc_server py3_tf_server_realsense.launch'" ; echo "ssh -t dji@dji-tx2 'export ROS_MASTER_URI=http://MANIFOLD-2-C:11311/; source $HOME/catkin_ws/devel/setup.bash && roslaunch tx2_whole_image_desc_server py3_tf_server_mynteye.launch'"; bash'''
order = 0
parent = child4
profile = default
type = Terminal
uuid = 6184900a-1468-4ffa-96a0-b1c00563ead7
[[[terminal6]]]
command = '''echo "ssh dji@dji-tx2 'export ROS_MASTER_URI=http://MANIFOLD-2-C:11311/; source $HOME/catkin_ws/devel/setup.bash && rosrun solve_keyframe_pose_graph keyframe_pose_graph_slam' "; bash'''
order = 1
parent = child4
profile = default
type = Terminal
uuid = 09e32ec9-5e11-4bb0-980d-4c1abeb77791
[[[terminal8]]]
command = echo "rviz -d catkin_ws/src/cerebro/rviz/vins-fusion.rviz"; bash
order = 0
parent = child7
profile = default
type = Terminal
uuid = 1cc3df64-f997-4766-9317-0ce75d5dc2cd
[[vins-cerebro]]
[[[child0]]]
fullscreen = False
last_active_term = b015529f-251d-4563-81f8-86f2d24badbe
last_active_window = True
maximised = False
order = 0
parent = ""
position = 289:106
size = 642, 378
title = dji@MANIFOLD-2-C: ~
type = Window
[[[terminal1]]]
order = 0
parent = child0
profile = vins-cerebro
type = Terminal
uuid = b015529f-251d-4563-81f8-86f2d24badbe
[plugins]
[profiles]
[[default]]
background_image = None
scrollback_lines = 5000
[[vins-cerebro]]
background_image = None
================================================
FILE: config/euroc/euroc_config_no_extrinsic.yaml
================================================
%YAML:1.0
#common parameters
imu_topic: "/imu0"
image_topic: "/cam0/image_raw"
output_path: "/home/tony-ws1/output/"
#camera calibration
model_type: PINHOLE
camera_name: camera
image_width: 752
image_height: 480
distortion_parameters:
k1: -2.917e-01
k2: 8.228e-02
p1: 5.333e-05
p2: -1.578e-04
projection_parameters:
fx: 4.616e+02
fy: 4.603e+02
cx: 3.630e+02
cy: 2.481e+02
# Extrinsic parameter between IMU and Camera.
estimate_extrinsic: 2 # 0 Have an accurate extrinsic parameters. We will trust the following imu^R_cam, imu^T_cam, don't change it.
# 1 Have an initial guess about extrinsic parameters. We will optimize around your initial guess.
# 2 Don't know anything about extrinsic parameters. You don't need to give R,T. We will try to calibrate it. Do some rotation movement at beginning.
#If you choose 0 or 1, you should write down the following matrix.
#feature traker paprameters
max_cnt: 150 # max feature number in feature tracking
min_dist: 30 # min distance between two features
freq: 10 # frequence (Hz) of publish tracking result. At least 10Hz for good estimation. If set 0, the frequence will be same as raw image
F_threshold: 1.0 # ransac threshold (pixel)
show_track: 1 # publish tracking image as topic
equalize: 1 # if image is too dark or light, trun on equalize to find enough features
fisheye: 0 # if using fisheye, trun on it. A circle mask will be loaded to remove edge noisy points
#optimization parameters
max_solver_time: 0.04 # max solver itration time (ms), to guarantee real time
max_num_iterations: 8 # max solver itrations, to guarantee real time
keyframe_parallax: 10.0 # keyframe selection threshold (pixel)
#imu parameters The more accurate parameters you provide, the better performance
acc_n: 0.2 # accelerometer measurement noise standard deviation. #0.2
gyr_n: 0.02 # gyroscope measurement noise standard deviation. #0.05
acc_w: 0.0002 # accelerometer bias random work noise standard deviation. #0.02
gyr_w: 2.0e-5 # gyroscope bias random work noise standard deviation. #4.0e-5
g_norm: 9.81007 # gravity magnitude
#loop closure parameters
loop_closure: 1 # start loop closure
load_previous_pose_graph: 0 # load and reuse previous pose graph; load from 'pose_graph_save_path'
fast_relocalization: 0 # useful in real-time and large project
pose_graph_save_path: "/home/tony-ws1/output/pose_graph/" # save and load path
#unsynchronization parameters
estimate_td: 0 # online estimate time offset between camera and imu
td: 0.0 # initial value of time offset. unit: s. readed image clock + td = real image clock (IMU clock)
#rolling shutter parameters
rolling_shutter: 0 # 0: global shutter camera, 1: rolling shutter camera
rolling_shutter_tr: 0 # unit: s. rolling shutter read out time per frame (from data sheet).
#visualization parameters
save_image: 1 # save image in pose graph for visualization prupose; you can close this function by setting 0
visualize_imu_forward: 0 # output imu forward propogation to achieve low latency and high frequence results
visualize_camera_size: 0.4 # size of camera marker in RVIZ
================================================
FILE: config/fly
================================================
[global_config]
[keybindings]
[layouts]
[[default]]
[[[child0]]]
fullscreen = False
last_active_term = 1cc3df64-f997-4766-9317-0ce75d5dc2cd
last_active_window = True
maximised = True
order = 0
parent = ""
position = 65:24
size = 1855, 1056
title = dji@MANIFOLD-2-C: ~
type = Window
[[[child1]]]
order = 0
parent = child0
position = 525
ratio = 0.5
type = VPaned
[[[child2]]]
order = 0
parent = child1
position = 513
ratio = 0.278167115903
type = HPaned
[[[child4]]]
order = 1
parent = child2
position = 648
ratio = 0.487275449102
type = HPaned
[[[child7]]]
order = 1
parent = child1
position = 513
ratio = 0.278167115903
type = HPaned
[[[child9]]]
order = 1
parent = child7
position = 644
ratio = 0.484281437126
type = HPaned
[[[terminal10]]]
command = echo "roslaunch cerebro realsense_vinsfusion.launch"; sleep 15s; roslaunch --wait cerebro realsense_vinsfusion.launch; bash
order = 0
parent = child9
profile = default
type = Terminal
uuid = 8fc7a21c-3feb-468d-aae5-c363bc5c9f80
[[[terminal11]]]
command = echo "roslaunch cerebro realsense_camera.launch"; sleep 5s; roslaunch --wait cerebro realsense_camera.launch; bash
order = 1
parent = child9
profile = default
type = Terminal
uuid = a63545ab-f3c1-4426-a8ef-173f57ca8f28
[[[terminal3]]]
command = echo "roscore"; roscore; bash
order = 0
parent = child2
profile = default
type = Terminal
uuid = 27ae967a-b56c-4d92-a56e-67a2abe6b22d
[[[terminal5]]]
#command = '''echo "ssh root@dji-tx2 'nvpmodel -m 0 && jetson_clocks'"; echo ""; echo "ssh -t dji@dji-tx2 'export ROS_MASTER_URI=http://MANIFOLD-2-C:11311/; source $HOME/catkin_ws/devel/setup.bash && roslaunch tx2_whole_image_desc_server py3_tf_server_realsense.launch'" ; echo "ssh -t dji@dji-tx2 'export ROS_MASTER_URI=http://MANIFOLD-2-C:11311/; source $HOME/catkin_ws/devel/setup.bash && roslaunch tx2_whole_image_desc_server py3_tf_server_mynteye.launch'"; bash'''
command = ''' coproc rviz -d catkin_ws/src/cerebro/rviz/vins-fusion.rviz ; ssh root@dji-tx2 'nvpmodel -m 0 && jetson_clocks'; ssh -t dji@dji-tx2 "export ROS_MASTER_URI=http://MANIFOLD-2-C:11311/; export DJIROS_APPID='1014582' ; export DJIROS_ENCKEY='821c8c3abeb6e340637b01f908ddeefb6c76d18d5f289e5cdb3cd5756a17bef5'; source $HOME/catkin_ws/devel/setup.bash && roslaunch djiros djiros.launch" ; bash '''
order = 0
parent = child4
profile = default
type = Terminal
uuid = 6184900a-1468-4ffa-96a0-b1c00563ead7
[[[terminal6]]]
#command = '''echo "ssh dji@dji-tx2 'export ROS_MASTER_URI=http://MANIFOLD-2-C:11311/; source $HOME/catkin_ws/devel/setup.bash && rosrun solve_keyframe_pose_graph keyframe_pose_graph_slam' "; bash'''
command = " sleep 3s; echo 'rosrun trajectory_node trajectory_node' ; export ROS_MASTER_URI=http://MANIFOLD-2-C:11311/; rosrun trajectory_node trajectory_node ; bash "
order = 1
parent = child4
profile = default
type = Terminal
uuid = 09e32ec9-5e11-4bb0-980d-4c1abeb77791
[[[terminal8]]]
command = echo "roslaunch --wait machine_defined ctrl_md.launch"; roslaunch --wait machine_defined ctrl_md.launch ; bash
order = 0
parent = child7
profile = default
type = Terminal
uuid = 1cc3df64-f997-4766-9317-0ce75d5dc2cd
[[vins-cerebro]]
[[[child0]]]
fullscreen = False
last_active_term = b015529f-251d-4563-81f8-86f2d24badbe
last_active_window = True
maximised = False
order = 0
parent = ""
position = 289:106
size = 642, 378
title = dji@MANIFOLD-2-C: ~
type = Window
[[[terminal1]]]
order = 0
parent = child0
profile = vins-cerebro
type = Terminal
uuid = b015529f-251d-4563-81f8-86f2d24badbe
[plugins]
[profiles]
[[default]]
background_image = None
scrollback_lines = 5000
[[vins-cerebro]]
background_image = None
================================================
FILE: config/mynteye/camera_left.yaml
================================================
%YAML:1.0
---
model_type: MEI
camera_name: camera_left
image_width: 752
image_height: 480
mirror_parameters:
xi: 9.1080215802208964e-01
distortion_parameters:
k1: -4.1813210333143819e-01
k2: 1.7403431210939191e-01
p1: 9.9413203823357906e-04
p2: 7.3177696678596699e-04
projection_parameters:
gamma1: 7.0261362770226128e+02
gamma2: 7.0163099053315807e+02
u0: 3.7079141993914720e+02
v0: 2.3833755987148535e+02
================================================
FILE: config/mynteye/camera_right.yaml
================================================
%YAML:1.0
---
model_type: MEI
camera_name: camera_right
image_width: 752
image_height: 480
mirror_parameters:
xi: 1.0430682060403200e+00
distortion_parameters:
k1: -4.1052639675713765e-01
k2: 1.5594870262700564e-01
p1: 1.0690635619397511e-03
p2: -1.2541037785533519e-04
projection_parameters:
gamma1: 7.5079430544256968e+02
gamma2: 7.5002280082558298e+02
u0: 3.6187005259990548e+02
v0: 2.4784480598161096e+02
================================================
FILE: config/mynteye/extrinsics.yaml
================================================
%YAML:1.0
---
transform:
q_x: -1.8252509868889259e-04
q_y: -1.6291774489779708e-03
q_z: -1.2462127842978489e-03
q_w: 9.9999787970731446e-01
t_x: -1.2075905420832895e+02
t_y: 5.4110610639412482e-01
t_z: 2.4484815673909591e-01
================================================
FILE: config/mynteye/mynteye_config.yaml
================================================
%YAML:1.0
#common parameters
imu_topic: "/mynteye/imu/data_raw"
image_topic: "/mynteye/left/image_raw"
output_path: "/Bulk_Data/vins-mono-output/"
# Additional camera (stereo) for cerebro - added my mpkuse
image_topic_1: "/mynteye/right/image_raw"
camera_yaml_1: "camera_right.yaml" # this yaml file will be searched in directory where this yaml file is.
extrinsic_1_T_0: "extrinsics.yaml" # TODO contains the right_T_left, ie. stereo baseline. I need right_T_left that a transform that transforms 3d points of left to 3d points of right. in other words, if you sir of right the position of left camera.
#camera calibration
model_type: MEI
camera_name: camera_left
image_width: 752
image_height: 480
mirror_parameters:
xi: 9.1080215802208964e-01
distortion_parameters:
k1: -4.1813210333143819e-01
k2: 1.7403431210939191e-01
p1: 9.9413203823357906e-04
p2: 7.3177696678596699e-04
projection_parameters:
gamma1: 7.0261362770226128e+02
gamma2: 7.0163099053315807e+02
u0: 3.7079141993914720e+02
v0: 2.3833755987148535e+02
# Extrinsic parameter between IMU and Camera.
estimate_extrinsic: 1 # 0 Have an accurate extrinsic parameters. We will trust the following imu^R_cam, imu^T_cam, don't change it.
# 1 Have an initial guess about extrinsic parameters. We will optimize around your initial guess.
# 2 Don't know anything about extrinsic parameters. You don't need to give R,T. We will try to calibrate it. Do some rotation movement at beginning.
#If you choose 0 or 1, you should write down the following matrix.
#Rotation from camera frame to imu frame, imu^R_cam
extrinsicRotation: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [ 4.2739206953025244e-03, -9.9997227378122833e-01,
-6.0979726705474944e-03, 9.9998919890819160e-01,
4.2626966744552242e-03, 1.8524265207998580e-03,
-1.8263813521932205e-03, -6.1058239298286089e-03,
9.9997969141642784e-01 ]
extrinsicTranslation: !!opencv-matrix
rows: 3
cols: 1
dt: d
data: [ 6.1040452082857912e-03, -4.8408978130397302e-02,
2.2594515206886469e-02 ]
#feature traker paprameters
max_cnt: 150 # max feature number in feature tracking
min_dist: 25 # min distance between two features
freq: 10 # frequence (Hz) of publish tracking result. At least 10Hz for good estimation. If set 0, the frequence will be same as raw image
F_threshold: 1.0 # ransac threshold (pixel)
show_track: 1 # publish tracking image as topic
equalize: 1 # if image is too dark or light, trun on equalize to find enough features
fisheye: 0 # if using fisheye, trun on it. A circle mask will be loaded to remove edge noisy points
#optimization parameters
max_solver_time: 0.04 # max solver itration time (ms), to guarantee real time
max_num_iterations: 8 # max solver itrations, to guarantee real time
keyframe_parallax: 10.0 # keyframe selection threshold (pixel)
#imu parameters The more accurate parameters you provide, the better performance
acc_n: 0.04 # accelerometer measurement noise standard deviation. #0.2 0.04
gyr_n: 0.004 # gyroscope measurement noise standard deviation. #0.05 0.004
acc_w: 0.0004 # accelerometer bias random work noise standard deviation. #0.02
gyr_w: 2.0e-5 # gyroscope bias random work noise standard deviation. #4.0e-5
g_norm: 9.80766 # gravity magnitude
#loop closure parameters
loop_closure: 0 # start loop closure
load_previous_pose_graph: 0 # load and reuse previous pose graph; load from 'pose_graph_save_path'
fast_relocalization: 0 # useful in real-time and large project
pose_graph_save_path: "/home/tony-ws1/output/pose_graph/" # save and load path
#unsynchronization parameters
estimate_td: 0 # online estimate time offset between camera and imu
td: 0.0 # initial value of time offset. unit: s. readed image clock + td = real image clock (IMU clock)
#rolling shutter parameters
rolling_shutter: 0 # 0: global shutter camera, 1: rolling shutter camera
rolling_shutter_tr: 0 # unit: s. rolling shutter read out time per frame (from data sheet).
#visualization parameters
save_image: 0 # save image in pose graph for visualization prupose; you can close this function by setting 0
visualize_imu_forward: 0 # output imu forward propogation to achieve low latency and high frequence results
visualize_camera_size: 0.4 # size of camera marker in RVIZ
================================================
FILE: config/mynteye__terminator_config_vins_fusion_cerebro
================================================
[global_config]
[keybindings]
[layouts]
[[default]]
[[[child0]]]
fullscreen = False
last_active_term = 1cc3df64-f997-4766-9317-0ce75d5dc2cd
last_active_window = True
maximised = True
order = 0
parent = ""
position = 65:24
size = 1855, 1056
title = dji@MANIFOLD-2-C: ~
type = Window
[[[child1]]]
order = 0
parent = child0
position = 525
ratio = 0.5
type = VPaned
[[[child2]]]
order = 0
parent = child1
position = 513
ratio = 0.278167115903
type = HPaned
[[[child4]]]
order = 1
parent = child2
position = 648
ratio = 0.487275449102
type = HPaned
[[[child7]]]
order = 1
parent = child1
position = 513
ratio = 0.278167115903
type = HPaned
[[[child9]]]
order = 1
parent = child7
position = 644
ratio = 0.484281437126
type = HPaned
[[[terminal10]]]
command = '''echo "roslaunch cerebro realsense_vinsfusion_ondrone.launch";
echo "roslaunch cerebro mynteye_vinsfusion_ondrone.launch";
export KUSE_CMD="roslaunch cerebro mynteye_vinsfusion_ondrone.launch";
roslaunch --wait cerebro mynteye_vinsfusion_ondrone.launch;
bash'''
order = 0
parent = child9
profile = default
type = Terminal
uuid = 8fc7a21c-3feb-468d-aae5-c363bc5c9f80
[[[terminal11]]]
command = '''#echo "roslaunch cerebro realsense_camera.launch";
echo "roslaunch mynt_eye_ros_wrapper mynteye.launch";
echo "rosbag play <file.bag>";
export KUSE_CMD="roslaunch mynt_eye_ros_wrapper mynteye.launch or rosbag play"
bash'''
order = 1
parent = child9
profile = default
type = Terminal
uuid = a63545ab-f3c1-4426-a8ef-173f57ca8f28
[[[terminal3]]]
command = echo "roscore"; exec "roscore"; bash
order = 0
parent = child2
profile = default
type = Terminal
uuid = 27ae967a-b56c-4d92-a56e-67a2abe6b22d
[[[terminal5]]]
command = '''echo "ssh root@dji-tx2 'nvpmodel -m 0 && jetson_clocks'";
ssh root@dji-tx2 'nvpmodel -m 0 && jetson_clocks';
echo "";
#echo "ssh -t dji@dji-tx2 'export ROS_MASTER_URI=http://MANIFOLD-2-C:11311/; source $HOME/catkin_ws/devel/setup.bash && roslaunch --wait tx2_whole_image_desc_server py3_tf_server_realsense.launch'";
echo "ssh -t dji@dji-tx2 'export ROS_MASTER_URI=http://MANIFOLD-2-C:11311/; source $HOME/catkin_ws/devel/setup.bash && roslaunch --wait tx2_whole_image_desc_server py3_tf_server_mynteye.launch'";
export KUSE_CMD="ssh -t dji@dji-tx2 'export ROS_MASTER_URI=http://MANIFOLD-2-C:11311/; source $HOME/catkin_ws/devel/setup.bash && roslaunch --wait tx2_whole_image_desc_server py3_tf_server_mynteye.launch'";
ssh -t dji@dji-tx2 'export ROS_MASTER_URI=http://MANIFOLD-2-C:11311/; source $HOME/catkin_ws/devel/setup.bash && roslaunch --wait tx2_whole_image_desc_server py3_tf_server_mynteye.launch'
bash'''
order = 0
parent = child4
profile = default
type = Terminal
uuid = 6184900a-1468-4ffa-96a0-b1c00563ead7
[[[terminal6]]]
command = '''echo "ssh dji@dji-tx2 'export ROS_MASTER_URI=http://MANIFOLD-2-C:11311/; source $HOME/catkin_ws/devel/setup.bash && rosrun solve_keyframe_pose_graph keyframe_pose_graph_slam'";
export KUSE_CMD="ssh dji@dji-tx2 'export ROS_MASTER_URI=http://MANIFOLD-2-C:11311/; source $HOME/catkin_ws/devel/setup.bash && rosrun solve_keyframe_pose_graph keyframe_pose_graph_slam'";
ssh dji@dji-tx2 "export ROS_MASTER_URI=http://MANIFOLD-2-C:11311/; source $HOME/catkin_ws/devel/setup.bash && rosrun solve_keyframe_pose_graph keyframe_pose_graph_slam";
bash'''
order = 1
parent = child4
profile = default
type = Terminal
uuid = 09e32ec9-5e11-4bb0-980d-4c1abeb77791
[[[terminal8]]]
command = '''echo "rviz -d catkin_ws/src/cerebro/rviz/vins-fusion.rviz";
rviz -d catkin_ws/src/cerebro/rviz/vins-fusion.rviz
bash'''
order = 0
parent = child7
profile = default
type = Terminal
uuid = 1cc3df64-f997-4766-9317-0ce75d5dc2cd
[[vins-cerebro]]
[[[child0]]]
fullscreen = False
last_active_term = b015529f-251d-4563-81f8-86f2d24badbe
last_active_window = True
maximised = False
order = 0
parent = ""
position = 289:106
size = 642, 378
title = dji@MANIFOLD-2-C: ~
type = Window
[[[terminal1]]]
order = 0
parent = child0
profile = vins-cerebro
type = Terminal
uuid = b015529f-251d-4563-81f8-86f2d24badbe
[plugins]
[profiles]
[[default]]
background_image = None
scrollback_lines = 5000
[[vins-cerebro]]
background_image = None
================================================
FILE: config/mynteye_kannala_brandt/camera_left.yaml
================================================
%YAML:1.0
---
model_type: KANNALA_BRANDT
camera_name: camera_left
image_width: 752
image_height: 480
projection_parameters:
k2: -1.9372136316513616e-02
k3: -9.8140934466631590e-03
k4: 5.2090950264238800e-03
k5: -2.5384805224148016e-03
mu: 3.6779833417894611e+02
mv: 3.6735717027889308e+02
u0: 3.7150938938370604e+02
v0: 2.3994369620747401e+02
================================================
FILE: config/mynteye_kannala_brandt/camera_right.yaml
================================================
%YAML:1.0
---
model_type: KANNALA_BRANDT
camera_name: camera_right
image_width: 752
image_height: 480
projection_parameters:
k2: -1.6877708507279571e-02
k3: -2.2125250367976849e-02
k4: 2.5629804328110812e-02
k5: -1.3352680211095494e-02
mu: 3.6746513955323167e+02
mv: 3.6703089274525593e+02
u0: 3.6200946050656484e+02
v0: 2.4919721516867821e+02
================================================
FILE: config/mynteye_kannala_brandt/extrinsics.yaml
================================================
%YAML:1.0
---
transform:
q_x: -7.0955103716253032e-04
q_y: -1.5775578725333590e-03
q_z: -1.2732644461763854e-03
q_w: 9.9999769332040711e-01
t_x: -1.2006984141573309e+02
t_y: 3.3956264524978619e-01
t_z: -1.6784055634087214e-01
================================================
FILE: config/mynteye_kannala_brandt/mynteye_config.yaml
================================================
%YAML:1.0
#common parameters
imu_topic: "/mynteye/imu/data_raw"
image_topic: "/mynteye/left/image_raw"
output_path: "/Bulk_Data/vins-mono-output/"
# Additional camera (stereo) for cerebro - added my mpkuse
image_topic_1: "/mynteye/right/image_raw"
camera_yaml_1: "camera_right.yaml" # this yaml file will be searched in directory where this yaml file is.
extrinsic_1_T_0: "extrinsics.yaml" # contains the right_T_left, ie. stereo baseline. I need right_T_left that a transform that transforms 3d points of left to 3d points of right. in other words, if you sir of right the position of left camera.
# publish image pair on loopcandidate detection
#camera calibration
model_type: KANNALA_BRANDT
camera_name: camera_left
image_width: 752
image_height: 480
projection_parameters:
k2: -1.9372136316513616e-02
k3: -9.8140934466631590e-03
k4: 5.2090950264238800e-03
k5: -2.5384805224148016e-03
mu: 3.6779833417894611e+02
mv: 3.6735717027889308e+02
u0: 3.7150938938370604e+02
v0: 2.3994369620747401e+02
# Extrinsic parameter between IMU and Camera.
estimate_extrinsic: 1 # 0 Have an accurate extrinsic parameters. We will trust the following imu^R_cam, imu^T_cam, don't change it.
# 1 Have an initial guess about extrinsic parameters. We will optimize around your initial guess.
# 2 Don't know anything about extrinsic parameters. You don't need to give R,T. We will try to calibrate it. Do some rotation movement at beginning.
#If you choose 0 or 1, you should write down the following matrix.
#Rotation from camera frame to imu frame, imu^R_cam
extrinsicRotation: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [ 4.2739206953025244e-03, -9.9997227378122833e-01,
-6.0979726705474944e-03, 9.9998919890819160e-01,
4.2626966744552242e-03, 1.8524265207998580e-03,
-1.8263813521932205e-03, -6.1058239298286089e-03,
9.9997969141642784e-01 ]
extrinsicTranslation: !!opencv-matrix
rows: 3
cols: 1
dt: d
data: [ 6.1040452082857912e-03, -4.8408978130397302e-02,
2.2594515206886469e-02 ]
#feature traker paprameters
max_cnt: 150 # max feature number in feature tracking
min_dist: 25 # min distance between two features
freq: 10 # frequence (Hz) of publish tracking result. At least 10Hz for good estimation. If set 0, the frequence will be same as raw image
F_threshold: 1.0 # ransac threshold (pixel)
show_track: 1 # publish tracking image as topic
equalize: 1 # if image is too dark or light, trun on equalize to find enough features
fisheye: 0 # if using fisheye, trun on it. A circle mask will be loaded to remove edge noisy points
#optimization parameters
max_solver_time: 0.04 # max solver itration time (ms), to guarantee real time
max_num_iterations: 10 # max solver itrations, to guarantee real time
keyframe_parallax: 10.0 # keyframe selection threshold (pixel)
#imu parameters The more accurate parameters you provide, the better performance
acc_n: 0.04 # accelerometer measurement noise standard deviation. #0.2 0.04
gyr_n: 0.004 # gyroscope measurement noise standard deviation. #0.05 0.004
acc_w: 0.0004 # accelerometer bias random work noise standard deviation. #0.02
gyr_w: 2.0e-5 # gyroscope bias random work noise standard deviation. #4.0e-5
g_norm: 9.80766 # gravity magnitude
#loop closure parameters
loop_closure: 1 # start loop closure
load_previous_pose_graph: 0 # load and reuse previous pose graph; load from 'pose_graph_save_path'
fast_relocalization: 1 # useful in real-time and large project
pose_graph_save_path: "/Bulk_Data/vins-mono-output/pose_graph/" # save and load path
#unsynchronization parameters
estimate_td: 0 # online estimate time offset between camera and imu
td: 0.0 # initial value of time offset. unit: s. readed image clock + td = real image clock (IMU clock)
#rolling shutter parameters
rolling_shutter: 0 # 0: global shutter camera, 1: rolling shutter camera
rolling_shutter_tr: 0 # unit: s. rolling shutter read out time per frame (from data sheet).
#visualization parameters
save_image: 1 # save image in pose graph for visualization prupose; you can close this function by setting 0
visualize_imu_forward: 0 # output imu forward propogation to achieve low latency and high frequence results
visualize_camera_size: 0.4 # size of camera marker in RVIZ
================================================
FILE: config/mynteye_pinhole/camera_left.yaml
================================================
%YAML:1.0
---
model_type: PINHOLE
camera_name: camera_left
image_width: 752
image_height: 480
distortion_parameters:
k1: -3.0304011877067349e-01
k2: 7.8611376314970768e-02
p1: 1.3200427858719645e-03
p2: -1.2942361409192899e-03
projection_parameters:
fx: 3.7560167589977470e+02
fy: 3.7552589588133230e+02
cx: 3.7887177487131697e+02
cy: 2.3402525474822104e+02
================================================
FILE: config/mynteye_pinhole/camera_right.yaml
================================================
%YAML:1.0
---
model_type: PINHOLE
camera_name: camera_right
image_width: 752
image_height: 480
distortion_parameters:
k1: -3.0790744874410708e-01
k2: 8.3037204977051693e-02
p1: 1.1347651021695062e-03
p2: -7.8671202943393290e-04
projection_parameters:
fx: 3.7573448135250288e+02
fy: 3.7536464618331070e+02
cx: 3.6634215933104940e+02
cy: 2.4325470902936044e+02
================================================
FILE: config/mynteye_pinhole/extrinsics.yaml
================================================
%YAML:1.0
---
transform:
q_x: -7.8278125678242136e-04
q_y: 2.4666921736014214e-03
q_z: -1.4477856356187120e-03
q_w: 9.9999560329032322e-01
t_x: -1.1985630585227842e+02
t_y: 1.2186198275182303e-01
t_z: -1.4431533628123798e+00
================================================
FILE: config/mynteye_pinhole/mynteye_config.yaml
================================================
%YAML:1.0
#common parameters
imu_topic: "/mynteye/imu/data_raw"
image_topic: "/mynteye/left/image_raw"
output_path: "/Bulk_Data/vins-mono-output/"
# Additional camera (stereo) for cerebro - added my mpkuse
image_topic_1: "/mynteye/right/image_raw"
camera_yaml_1: "camera_right.yaml" # this yaml file will be searched in directory where this yaml file is.
extrinsic_1_T_0: "extrinsics.yaml" # contains the right_T_left, ie. stereo baseline. I need right_T_left that a transform that transforms 3d points of left to 3d points of right. in other words, if you sir of right the position of left camera.
#camera calibration
model_type: PINHOLE
camera_name: camera_left
image_width: 752
image_height: 480
distortion_parameters:
k1: -3.0304011877067349e-01
k2: 7.8611376314970768e-02
p1: 1.3200427858719645e-03
p2: -1.2942361409192899e-03
projection_parameters:
fx: 3.7560167589977470e+02
fy: 3.7552589588133230e+02
cx: 3.7887177487131697e+02
cy: 2.3402525474822104e+02
# Extrinsic parameter between IMU and Camera.
estimate_extrinsic: 1 # 0 Have an accurate extrinsic parameters. We will trust the following imu^R_cam, imu^T_cam, don't change it.
# 1 Have an initial guess about extrinsic parameters. We will optimize around your initial guess.
# 2 Don't know anything about extrinsic parameters. You don't need to give R,T. We will try to calibrate it. Do some rotation movement at beginning.
#If you choose 0 or 1, you should write down the following matrix.
#Rotation from camera frame to imu frame, imu^R_cam
extrinsicRotation: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [ 4.2739206953025244e-03, -9.9997227378122833e-01,
-6.0979726705474944e-03, 9.9998919890819160e-01,
4.2626966744552242e-03, 1.8524265207998580e-03,
-1.8263813521932205e-03, -6.1058239298286089e-03,
9.9997969141642784e-01 ]
extrinsicTranslation: !!opencv-matrix
rows: 3
cols: 1
dt: d
data: [ 6.1040452082857912e-03, -4.8408978130397302e-02,
2.2594515206886469e-02 ]
#feature traker paprameters
max_cnt: 130 # max feature number in feature tracking
min_dist: 25 # min distance between two features
freq: 10 # frequence (Hz) of publish tracking result. At least 10Hz for good estimation. If set 0, the frequence will be same as raw image
F_threshold: 1.0 # ransac threshold (pixel)
show_track: 1 # publish tracking image as topic
equalize: 1 # if image is too dark or light, trun on equalize to find enough features
fisheye: 0 # if using fisheye, trun on it. A circle mask will be loaded to remove edge noisy points
#optimization parameters
max_solver_time: 0.04 # max solver itration time (ms), to guarantee real time
max_num_iterations: 8 # max solver itrations, to guarantee real time
keyframe_parallax: 10.0 # keyframe selection threshold (pixel)
#imu parameters The more accurate parameters you provide, the better performance
acc_n: 0.04 # accelerometer measurement noise standard deviation. #0.2 0.04
gyr_n: 0.004 # gyroscope measurement noise standard deviation. #0.05 0.004
acc_w: 0.0004 # accelerometer bias random work noise standard deviation. #0.02
gyr_w: 2.0e-5 # gyroscope bias random work noise standard deviation. #4.0e-5
g_norm: 9.80766 # gravity magnitude
#loop closure parameters
loop_closure: 0 # start loop closure
load_previous_pose_graph: 0 # load and reuse previous pose graph; load from 'pose_graph_save_path'
fast_relocalization: 0 # useful in real-time and large project
pose_graph_save_path: "/home/tony-ws1/output/pose_graph/" # save and load path
#unsynchronization parameters
estimate_td: 0 # online estimate time offset between camera and imu
td: 0.0 # initial value of time offset. unit: s. readed image clock + td = real image clock (IMU clock)
#rolling shutter parameters
rolling_shutter: 0 # 0: global shutter camera, 1: rolling shutter camera
rolling_shutter_tr: 0 # unit: s. rolling shutter read out time per frame (from data sheet).
#visualization parameters
save_image: 0 # save image in pose graph for visualization prupose; you can close this function by setting 0
visualize_imu_forward: 0 # output imu forward propogation to achieve low latency and high frequence results
visualize_camera_size: 0.4 # size of camera marker in RVIZ
================================================
FILE: config/realsense__terminator_config_vins_fusion_cerebro
================================================
[global_config]
[keybindings]
[layouts]
[[default]]
[[[child0]]]
fullscreen = False
last_active_term = 1cc3df64-f997-4766-9317-0ce75d5dc2cd
last_active_window = True
maximised = True
order = 0
parent = ""
position = 65:24
size = 1855, 1056
title = dji@MANIFOLD-2-C: ~
type = Window
[[[child1]]]
order = 0
parent = child0
position = 525
ratio = 0.5
type = VPaned
[[[child2]]]
order = 0
parent = child1
position = 513
ratio = 0.278167115903
type = HPaned
[[[child4]]]
order = 1
parent = child2
position = 648
ratio = 0.487275449102
type = HPaned
[[[child7]]]
order = 1
parent = child1
position = 513
ratio = 0.278167115903
type = HPaned
[[[child9]]]
order = 1
parent = child7
position = 644
ratio = 0.484281437126
type = HPaned
[[[terminal10]]]
command = '''echo "roslaunch cerebro realsense_vinsfusion_ondrone.launch";
roslaunch --wait cerebro realsense_vinsfusion_ondrone.launch
#echo "roslaunch cerebro mynteye_vinsfusion_ondrone.launch";
#roslaunch --wait cerebro mynteye_vinsfusion_ondrone.launch;
bash'''
order = 0
parent = child9
profile = default
type = Terminal
uuid = 8fc7a21c-3feb-468d-aae5-c363bc5c9f80
[[[terminal11]]]
command = '''echo "roslaunch cerebro realsense_camera.launch";
#echo "roslaunch mynt_eye_ros_wrapper mynteye.launch";
echo "rosbag play <file.bag>"; bash'''
order = 1
parent = child9
profile = default
type = Terminal
uuid = a63545ab-f3c1-4426-a8ef-173f57ca8f28
[[[terminal3]]]
command = echo "roscore"; exec "roscore"; bash
order = 0
parent = child2
profile = default
type = Terminal
uuid = 27ae967a-b56c-4d92-a56e-67a2abe6b22d
[[[terminal5]]]
command = '''echo "ssh root@dji-tx2 'nvpmodel -m 0 && jetson_clocks'";
ssh root@dji-tx2 'nvpmodel -m 0 && jetson_clocks';
echo "";
#echo "ssh -t dji@dji-tx2 'export ROS_MASTER_URI=http://MANIFOLD-2-C:11311/; source $HOME/catkin_ws/devel/setup.bash && roslaunch --wait tx2_whole_image_desc_server py3_tf_server_realsense.launch'";
ssh -t dji@dji-tx2 'export ROS_MASTER_URI=http://MANIFOLD-2-C:11311/; source $HOME/catkin_ws/devel/setup.bash && roslaunch --wait tx2_whole_image_desc_server py3_tf_server_realsense.launch'
#echo "ssh -t dji@dji-tx2 'export ROS_MASTER_URI=http://MANIFOLD-2-C:11311/; source $HOME/catkin_ws/devel/setup.bash && roslaunch --wait tx2_whole_image_desc_server py3_tf_server_mynteye.launch'";
#ssh -t dji@dji-tx2 'export ROS_MASTER_URI=http://MANIFOLD-2-C:11311/; source $HOME/catkin_ws/devel/setup.bash && roslaunch --wait tx2_whole_image_desc_server py3_tf_server_mynteye.launch'
bash'''
order = 0
parent = child4
profile = default
type = Terminal
uuid = 6184900a-1468-4ffa-96a0-b1c00563ead7
[[[terminal6]]]
command = '''echo "ssh dji@dji-tx2 'export ROS_MASTER_URI=http://MANIFOLD-2-C:11311/; source $HOME/catkin_ws/devel/setup.bash && rosrun solve_keyframe_pose_graph keyframe_pose_graph_slam'";
ssh dji@dji-tx2 'export ROS_MASTER_URI=http://MANIFOLD-2-C:11311/; source $HOME/catkin_ws/devel/setup.bash && rosrun solve_keyframe_pose_graph keyframe_pose_graph_slam';
bash'''
order = 1
parent = child4
profile = default
type = Terminal
uuid = 09e32ec9-5e11-4bb0-980d-4c1abeb77791
[[[terminal8]]]
command = '''echo "rviz -d catkin_ws/src/cerebro/rviz/vins-fusion.rviz";
rviz -d catkin_ws/src/cerebro/rviz/vins-fusion.rviz
bash'''
order = 0
parent = child7
profile = default
type = Terminal
uuid = 1cc3df64-f997-4766-9317-0ce75d5dc2cd
[[vins-cerebro]]
[[[child0]]]
fullscreen = False
last_active_term = b015529f-251d-4563-81f8-86f2d24badbe
last_active_window = True
maximised = False
order = 0
parent = ""
position = 289:106
size = 642, 378
title = dji@MANIFOLD-2-C: ~
type = Window
[[[terminal1]]]
order = 0
parent = child0
profile = vins-cerebro
type = Terminal
uuid = b015529f-251d-4563-81f8-86f2d24badbe
[plugins]
[profiles]
[[default]]
background_image = None
scrollback_lines = 5000
[[vins-cerebro]]
background_image = None
================================================
FILE: config/vinsfusion/djirosimu_realsense_d435i/README.md
================================================
The configuration when using realsense stereo camera and djiros's imu (ie. imu data from N3)
================================================
FILE: config/vinsfusion/djirosimu_realsense_d435i/extrinsics.yaml
================================================
%YAML:1.0
---
transform:
q_x: 0.
q_y: 0.
q_z: 0.
q_w: 1.
t_x: -49.8
t_y: 0.
t_z: 0.
#4.98 cm for the realsense d435i device. This device has hardware undistort so can safely use the pinhole model
================================================
FILE: config/vinsfusion/djirosimu_realsense_d435i/left.yaml
================================================
%YAML:1.0
---
model_type: PINHOLE
camera_name: camera
image_width: 640
image_height: 480
distortion_parameters:
k1: 0.0
k2: 0.0
p1: 0.0
p2: 0.0
projection_parameters:
fx: 385.7544860839844
fy: 385.7544860839844
cx: 323.1204833984375
cy: 236.7432098388672
================================================
FILE: config/vinsfusion/djirosimu_realsense_d435i/realsense_stereo_imu_config.yaml
================================================
%YAML:1.0
#common parameters
#support: 1 imu 1 cam; 1 imu 2 cam: 2 cam;
imu: 1
num_of_cam: 2
# imu_topic: "/camera/imu"
imu_topic: "/djiros/imu"
image0_topic: "/camera/infra1/image_rect_raw"
image1_topic: "/camera/infra2/image_rect_raw"
output_path: "/home/dji/vinsfusion-output/"
cam0_calib: "left.yaml"
cam1_calib: "right.yaml"
image_width: 640
image_height: 480
# contains the right_T_left aka 1_T_0, ie. stereo baseline. I need right_T_left that a transform that transforms 3d points of left to 3d points of right. in other words, if you sure of right the position of left camera.
# This is an optional argument even if using `num_of_cam:=2`. If I cannot
# find this key I will use `body_T_cam0` and `body_T_cam1` to compute cam1_T_cam0.
# But if this key exists, we will use these values as stereo baseline.
# **In this file, I assume translation re specified ****in mm**** (and not in meters).**
extrinsic_1_T_0: "extrinsics.yaml"
# Extrinsic parameter between IMU and Camera.
estimate_extrinsic: 1 # 0 Have an accurate extrinsic parameters. We will trust the following imu^R_cam, imu^T_cam, don't change it.
# 1 Have an initial guess about extrinsic parameters. We will optimize around your initial guess.
body_T_cam0: !!opencv-matrix
rows: 4
cols: 4
dt: d
data: [ -1.0406548080980293e-02, -6.8339359975994052e-04,
9.9994561688635142e-01, 5.2600599061337287e-02,
-9.9994461366801901e-01, -1.5656625000493030e-03,
-1.0407607662295648e-02, 2.5510536758700533e-02,
1.5726898469127781e-03, -9.9999854083599726e-01,
-6.6706260700977182e-04, 9.5887981235633201e-03, 0., 0., 0., 1. ]
body_T_cam1: !!opencv-matrix
rows: 4
cols: 4
dt: d
data: [ -1.3185778504660295e-02, 1.2513252883544768e-04,
9.9991305601390978e-01, 4.2975722207919849e-02,
-9.9984703667423980e-01, 1.1490149582040754e-02,
-1.3186345829069746e-02, -5.4397185804457168e-02,
-1.1490800623434938e-02, -9.9993397822277874e-01,
-2.6393179226591457e-05, 1.8167602224138771e-02, 0., 0., 0., 1. ]
#Multiple thread support
multiple_thread: 1
#feature traker paprameters
max_cnt: 150 # max feature number in feature tracking
min_dist: 30 # min distance between two features
freq: 10 # frequence (Hz) of publish tracking result. At least 10Hz for good estimation. If set 0, the frequence will be same as raw image
F_threshold: 1.0 # ransac threshold (pixel)
show_track: 0 # publish tracking image as topic
flow_back: 1 # perform forward and backward optical flow to improve feature tracking accuracy
#optimization parameters
max_solver_time: 0.04 # max solver itration time (ms), to guarantee real time
max_num_iterations: 8 # max solver itrations, to guarantee real time
keyframe_parallax: 10.0 # keyframe selection threshold (pixel)
#imu parameters The more accurate parameters you provide, the better performance
acc_n: 0.1 # accelerometer measurement noise standard deviation. #0.2 0.04
gyr_n: 0.02 # gyroscope measurement noise standard deviation. #0.05 0.004
acc_w: 0.002 # accelerometer bias random work noise standard deviation. #0.002
gyr_w: 0.00005 # gyroscope bias random work noise standard deviation. #4.0e-5
g_norm: 9.805 # gravity magnitude
#unsynchronization parameters
estimate_td: 1 # online estimate time offset between camera and imu
td: 0 # initial value of time offset. unit: s. readed image clock + td = real image clock (IMU clock)
#loop closure parameters
load_previous_pose_graph: 0 # load and reuse previous pose graph; load from 'pose_graph_save_path'
pose_graph_save_path: "/home/dji/output/pose_graph/" # save and load path
save_image: 0 # save image in pose graph for visualization prupose; you can close this function by setting 0
================================================
FILE: config/vinsfusion/djirosimu_realsense_d435i/right.yaml
================================================
%YAML:1.0
---
model_type: PINHOLE
camera_name: camera
image_width: 640
image_height: 480
distortion_parameters:
k1: 0.0
k2: 0.0
p1: 0.0
p2: 0.0
projection_parameters:
fx: 385.7544860839844
fy: 385.7544860839844
cx: 323.1204833984375
cy: 236.7432098388672
================================================
FILE: config/vinsfusion/euroc/cam0_pinhole.yaml
================================================
%YAML:1.0
---
model_type: PINHOLE
camera_name: camera
image_width: 752
image_height: 480
distortion_parameters:
k1: -2.9545645106987750e-01
k2: 8.6623215640186171e-02
p1: 2.0132892276082517e-06
p2: 1.3924531371276508e-05
projection_parameters:
fx: 4.6115862106007575e+02
fy: 4.5975286598073296e+02
cx: 3.6265929181685937e+02
cy: 2.4852105668448124e+02
================================================
FILE: config/vinsfusion/euroc/cam1_pinhole.yaml
================================================
%YAML:1.0
---
model_type: PINHOLE
camera_name: camera
image_width: 752
image_height: 480
distortion_parameters:
k1: -2.9294124381930947e-01
k2: 8.4798002331543665e-02
p1: -2.9984646536002372e-04
p2: 3.0028216325237329e-04
projection_parameters:
fx: 4.6009781682258682e+02
fy: 4.5890983492218902e+02
cx: 3.7314916359808268e+02
cy: 2.5440734973672119e+02
================================================
FILE: config/vinsfusion/euroc/euroc_stereo_imu_config.yaml
================================================
%YAML:1.0
#common parameters
#support: 1 imu 1 cam; 1 imu 2 cam: 2 cam;
imu: 1
num_of_cam: 2
imu_topic: "/imu0"
image0_topic: "/cam0/image_raw"
image1_topic: "/cam1/image_raw"
output_path: "~/output/"
#cam0_calib: "cam0_mei.yaml"
#cam1_calib: "cam1_mei.yaml"
cam0_calib: "cam0_pinhole.yaml"
cam1_calib: "cam1_pinhole.yaml"
image_width: 752
image_height: 480
# contains the right_T_left aka 1_T_0, ie. stereo baseline. I need right_T_left that a transform that transforms 3d points of left to 3d points of right. in other words, if you sure of right the position of left camera.
# This is an optional argument even if using `num_of_cam:=2`. If I cannot
# find this key I will use `body_T_cam0` and `body_T_cam1` to compute cam1_T_cam0.
# But if this key exists, we will use these values as stereo baseline.
# **In this file, I assume translation re specified ****in mm**** (and not in meters).**
extrinsic_1_T_0: "extrinsics.yaml"
# Extrinsic parameter between IMU and Camera.
estimate_extrinsic: 0 # 0 Have an accurate extrinsic parameters. We will trust the following imu^R_cam, imu^T_cam, don't change it.
# 1 Have an initial guess about extrinsic parameters. We will optimize around your initial guess.
body_T_cam0: !!opencv-matrix
rows: 4
cols: 4
dt: d
data: [0.0148655429818, -0.999880929698, 0.00414029679422, -0.0216401454975,
0.999557249008, 0.0149672133247, 0.025715529948, -0.064676986768,
-0.0257744366974, 0.00375618835797, 0.999660727178, 0.00981073058949,
0, 0, 0, 1]
body_T_cam1: !!opencv-matrix
rows: 4
cols: 4
dt: d
data: [0.0125552670891, -0.999755099723, 0.0182237714554, -0.0198435579556,
0.999598781151, 0.0130119051815, 0.0251588363115, 0.0453689425024,
-0.0253898008918, 0.0179005838253, 0.999517347078, 0.00786212447038,
0, 0, 0, 1]
#Multiple thread support
multiple_thread: 1
#feature traker paprameters
max_cnt: 150 # max feature number in feature tracking
min_dist: 30 # min distance between two features
freq: 10 # frequence (Hz) of publish tracking result. At least 10Hz for good estimation. If set 0, the frequence will be same as raw image
F_threshold: 1.0 # ransac threshold (pixel)
show_track: 1 # publish tracking image as topic
flow_back: 0 # perform forward and backward optical flow to improve feature tracking accuracy
#optimization parameters
max_solver_time: 0.04 # max solver itration time (ms), to guarantee real time
max_num_iterations: 8 # max solver itrations, to guarantee real time
keyframe_parallax: 10.0 # keyframe selection threshold (pixel)
#imu parameters The more accurate parameters you provide, the better performance
acc_n: 0.1 # accelerometer measurement noise standard deviation.
gyr_n: 0.01 # gyroscope measurement noise standard deviation.
acc_w: 0.001 # accelerometer bias random work noise standard deviation.
gyr_w: 0.0001 # gyroscope bias random work noise standard deviation.
g_norm: 9.81007 # gravity magnitude
#unsynchronization parameters
estimate_td: 0 # online estimate time offset between camera and imu
td: 0.0 # initial value of time offset. unit: s. readed image clock + td = real image clock (IMU clock)
#loop closure parameters
load_previous_pose_graph: 0 # load and reuse previous pose graph; load from 'pose_graph_save_path'
pose_graph_save_path: "~/output/pose_graph/" # save and load path
save_image: 1 # save image in pose graph for visualization prupose; you can close this function by setting 0
================================================
FILE: config/vinsfusion/euroc/extrinsics.yaml
================================================
%YAML:1.0
---
# this is computed for euric using body_T_cam0 and body_T_cam1.
transform:
q_x: -0.00704531
q_y: 0.000179855
q_z: -0.00115733
q_w: 0.999974
t_x: -110.074
t_y: 0.399122
t_z: -0.853703
================================================
FILE: config/vinsfusion/mynteye/camera_left.yaml
================================================
%YAML:1.0
---
model_type: KANNALA_BRANDT
camera_name: camera_left
image_width: 752
image_height: 480
projection_parameters:
k2: -1.9372136316513616e-02
k3: -9.8140934466631590e-03
k4: 5.2090950264238800e-03
k5: -2.5384805224148016e-03
mu: 3.6779833417894611e+02
mv: 3.6735717027889308e+02
u0: 3.7150938938370604e+02
v0: 2.3994369620747401e+02
================================================
FILE: config/vinsfusion/mynteye/camera_left_pinhole.yaml
================================================
%YAML:1.0
---
model_type: PINHOLE
camera_name: camera_left
image_width: 752
image_height: 480
distortion_parameters:
k1: -3.0304011877067349e-01
k2: 7.8611376314970768e-02
p1: 1.3200427858719645e-03
p2: -1.2942361409192899e-03
projection_parameters:
fx: 3.7560167589977470e+02
fy: 3.7552589588133230e+02
cx: 3.7887177487131697e+02
cy: 2.3402525474822104e+02
================================================
FILE: config/vinsfusion/mynteye/camera_right.yaml
================================================
%YAML:1.0
---
model_type: KANNALA_BRANDT
camera_name: camera_right
image_width: 752
image_height: 480
projection_parameters:
k2: -1.6877708507279571e-02
k3: -2.2125250367976849e-02
k4: 2.5629804328110812e-02
k5: -1.3352680211095494e-02
mu: 3.6746513955323167e+02
mv: 3.6703089274525593e+02
u0: 3.6200946050656484e+02
v0: 2.4919721516867821e+02
================================================
FILE: config/vinsfusion/mynteye/camera_right_pinhole.yaml
================================================
%YAML:1.0
---
model_type: PINHOLE
camera_name: camera_right
image_width: 752
image_height: 480
distortion_parameters:
k1: -3.0790744874410708e-01
k2: 8.3037204977051693e-02
p1: 1.1347651021695062e-03
p2: -7.8671202943393290e-04
projection_parameters:
fx: 3.7573448135250288e+02
fy: 3.7536464618331070e+02
cx: 3.6634215933104940e+02
cy: 2.4325470902936044e+02
================================================
FILE: config/vinsfusion/mynteye/extrinsics.yaml
================================================
%YAML:1.0
---
transform:
q_x: -7.0955103716253032e-04
q_y: -1.5775578725333590e-03
q_z: -1.2732644461763854e-03
q_w: 9.9999769332040711e-01
t_x: -1.2006984141573309e+02
t_y: 3.3956264524978619e-01
t_z: -1.6784055634087214e-01
================================================
FILE: config/vinsfusion/mynteye/mynteye_stereo_imu_config.yaml
================================================
%YAML:1.0
#common parameters
#support: 1 imu 1 cam; 1 imu 2 cam: 2 cam;
imu: 1
num_of_cam: 2
imu_topic: "/mynteye/imu/data_raw"
image0_topic: "/mynteye/left/image_raw"
image1_topic: "/mynteye/right/image_raw"
output_path: "/Bulk_Data/vins-mono-output/"
#cam0_calib: "camera_left_pinhole.yaml"
#cam1_calib: "camera_right_pinhole.yaml"
cam0_calib: "camera_left.yaml"
cam1_calib: "camera_right.yaml"
image_width: 752
image_height: 480
# contains the right_T_left aka 1_T_0, ie. stereo baseline. I need right_T_left that a transform that transforms 3d points of left to 3d points of right. in other words, if you sure of right the position of left camera.
# This is an optional argument even if using `num_of_cam:=2`. If I cannot
# find this key I will use `body_T_cam0` and `body_T_cam1` to compute cam1_T_cam0.
# But if this key exists, we will use these values as stereo baseline.
# **In this file, I assume translation re specified ****in mm**** (and not in meters).**
extrinsic_1_T_0: "extrinsics.yaml"
# Extrinsic parameter between IMU and Camera.
estimate_extrinsic: 0 # 0 Have an accurate extrinsic parameters. We will trust the following imu^R_cam, imu^T_cam, don't change it.
# 1 Have an initial guess about extrinsic parameters. We will optimize around your initial guess.
body_T_cam0: !!opencv-matrix
rows: 4
cols: 4
dt: d
data: [4.2739206953025244e-03, -9.9997227378122833e-01,-6.0979726705474944e-03,6.1040452082857912e-03,
9.9998919890819160e-01, 4.2626966744552242e-03, 1.8524265207998580e-03,-4.8408978130397302e-02,
-1.8263813521932205e-03, -6.1058239298286089e-03, 9.9997969141642784e-01,2.2594515206886469e-02,
0,0,0,1]
# ===> imu_T_cam0 * inv( cam1_T_cam0 )
body_T_cam1: !!opencv-matrix
rows: 4
cols: 4
dt: d
data: [ 0.00174443, -0.99998733, -0.0046694 , 0.00665227,
0.99998578, 0.00172106, 0.00500326, 0.07165957,
-0.00499517, -0.00467806, 0.9999766 , 0.02216417,
0. , 0. , 0. , 1. ]
#Multiple thread support
multiple_thread: 1
#feature traker paprameters
max_cnt: 100 # max feature number in feature tracking
min_dist: 30 # min distance between two features
freq: 10 # frequence (Hz) of publish tracking result. At least 10Hz for good estimation. If set 0, the frequence will be same as raw image
F_threshold: 1.1 # ransac threshold (pixel)
show_track: 0 # publish tracking image as topic
flow_back: 1 # perform forward and backward optical flow to improve feature tracking accuracy
#optimization parameters
max_solver_time: 0.05 # max solver itration time (ms), to guarantee real time
max_num_iterations: 12 # max solver itrations, to guarantee real time
keyframe_parallax: 10.0 # keyframe selection threshold (pixel)
#imu parameters The more accurate parameters you provide, the better performance
acc_n: 0.04 # accelerometer measurement noise standard deviation. #0.2 0.04
gyr_n: 0.004 # gyroscope measurement noise standard deviation. #0.05 0.004
acc_w: 0.0004 # accelerometer bias random work noise standard deviation. #0.02
gyr_w: 2.0e-5 # gyroscope bias random work noise standard deviation. #4.0e-5
g_norm: 9.80766 # gravity magnitude
#unsynchronization parameters
estimate_td: 0 # online estimate time offset between camera and imu
td: 0.0 # initial value of time offset. unit: s. readed image clock + td = real image clock (IMU clock)
#loop closure parameters
load_previous_pose_graph: 0 # load and reuse previous pose graph; load from 'pose_graph_save_path'
pose_graph_save_path: "~/output/pose_graph/" # save and load path
save_image: 0 # save image in pose graph for visualization prupose; you can close this function by setting 0
================================================
FILE: config/vinsfusion/realsense_d435i/extrinsics.yaml
================================================
%YAML:1.0
---
transform:
q_x: 0.
q_y: 0.
q_z: 0.
q_w: 1.
t_x: -49.8
t_y: 0.
t_z: 0.
#4.98 cm for the realsense d435i device. This device has hardware undistort so can safely use the pinhole model
================================================
FILE: config/vinsfusion/realsense_d435i/left.yaml
================================================
%YAML:1.0
---
model_type: PINHOLE
camera_name: camera
image_width: 640
image_height: 480
distortion_parameters:
k1: 0.0
k2: 0.0
p1: 0.0
p2: 0.0
projection_parameters:
fx: 385.7544860839844
fy: 385.7544860839844
cx: 323.1204833984375
cy: 236.7432098388672
================================================
FILE: config/vinsfusion/realsense_d435i/realsense_stereo_imu_config.yaml
================================================
%YAML:1.0
#common parameters
#support: 1 imu 1 cam; 1 imu 2 cam: 2 cam;
imu: 1
num_of_cam: 2
#imu_topic: "/camera/imu"
imu_topic: "/djiros/imu"
image0_topic: "/camera/infra1/image_rect_raw"
image1_topic: "/camera/infra2/image_rect_raw"
output_path: "/home/dji/output/"
cam0_calib: "left.yaml"
cam1_calib: "right.yaml"
image_width: 640
image_height: 480
# contains the right_T_left aka 1_T_0, ie. stereo baseline. I need right_T_left that a transform that transforms 3d points of left to 3d points of right. in other words, if you sure of right the position of left camera.
# This is an optional argument even if using `num_of_cam:=2`. If I cannot
# find this key I will use `body_T_cam0` and `body_T_cam1` to compute cam1_T_cam0.
# But if this key exists, we will use these values as stereo baseline.
# **In this file, I assume translation re specified ****in mm**** (and not in meters).**
extrinsic_1_T_0: "extrinsics.yaml"
# Extrinsic parameter between IMU and Camera.
estimate_extrinsic: 1 # 0 Have an accurate extrinsic parameters. We will trust the following imu^R_cam, imu^T_cam, don't change it.
# 1 Have an initial guess about extrinsic parameters. We will optimize around your initial guess.
body_T_cam0: !!opencv-matrix
rows: 4
cols: 4
dt: d
data: [ -1.0406548080980293e-02, -6.8339359975994052e-04,
9.9994561688635142e-01, 5.2600599061337287e-02,
-9.9994461366801901e-01, -1.5656625000493030e-03,
-1.0407607662295648e-02, 2.5510536758700533e-02,
1.5726898469127781e-03, -9.9999854083599726e-01,
-6.6706260700977182e-04, 9.5887981235633201e-03, 0., 0., 0., 1. ]
body_T_cam1: !!opencv-matrix
rows: 4
cols: 4
dt: d
data: [ -1.3185778504660295e-02, 1.2513252883544768e-04,
9.9991305601390978e-01, 4.2975722207919849e-02,
-9.9984703667423980e-01, 1.1490149582040754e-02,
-1.3186345829069746e-02, -5.4397185804457168e-02,
-1.1490800623434938e-02, -9.9993397822277874e-01,
-2.6393179226591457e-05, 1.8167602224138771e-02, 0., 0., 0., 1. ]
#Multiple thread support
multiple_thread: 1
#feature traker paprameters
max_cnt: 100 # max feature number in feature tracking
min_dist: 30 # min distance between two features
freq: 10 # frequence (Hz) of publish tracking result. At least 10Hz for good estimation. If set 0, the frequence will be same as raw image
F_threshold: 1.0 # ransac threshold (pixel)
show_track: 0 # publish tracking image as topic
flow_back: 1 # perform forward and backward optical flow to improve feature tracking accuracy
#optimization parameters
max_solver_time: 0.04 # max solver itration time (ms), to guarantee real time
max_num_iterations: 8 # max solver itrations, to guarantee real time
keyframe_parallax: 10.0 # keyframe selection threshold (pixel)
#imu parameters The more accurate parameters you provide, the better performance
acc_n: 0.2 # accelerometer measurement noise standard deviation. #0.2 0.04
gyr_n: 0.02 # gyroscope measurement noise standard deviation. #0.05 0.004
acc_w: 0.001 # accelerometer bias random work noise standard deviation. #0.002
gyr_w: 0.0001 # gyroscope bias random work noise standard deviation. #4.0e-5
g_norm: 9.805 # gravity magnitude
#unsynchronization parameters
estimate_td: 0 # online estimate time offset between camera and imu
td: 0.00 # initial value of time offset. unit: s. readed image clock + td = real image clock (IMU clock)
#loop closure parameters
load_previous_pose_graph: 0 # load and reuse previous pose graph; load from 'pose_graph_save_path'
pose_graph_save_path: "/home/dji/output/pose_graph/" # save and load path
save_image: 0 # save image in pose graph for visualization prupose; you can close this function by setting 0
================================================
FILE: config/vinsfusion/realsense_d435i/right.yaml
================================================
%YAML:1.0
---
model_type: PINHOLE
camera_name: camera
image_width: 640
image_height: 480
distortion_parameters:
k1: 0.0
k2: 0.0
p1: 0.0
p2: 0.0
projection_parameters:
fx: 385.7544860839844
fy: 385.7544860839844
cx: 323.1204833984375
cy: 236.7432098388672
================================================
FILE: config/vinsmono_debug_config.yaml
================================================
%YAML:1.0
#######
## This is config file for running vins-mono. We use this for imu_T_camera calibration.
## Set the estimate_extrinsic to 2. If vins mono works on, just copy (written in `output_path`)
#######
# imu_topic: "/camera/imu"
imu_topic: "/djiros/imu"
image_topic: "/camera/infra1/image_rect_raw"
#image_topic: "/camera/infra2/image_rect_raw"
# output_path: "/home/tony-ws1/output/"
output_path: "/home/dji/output/"
#camera calibration - left , right same for realsense
model_type: PINHOLE
camera_name: camera
image_width: 640
image_height: 480
distortion_parameters:
k1: 0.0
k2: 0.0
p1: 0.0
p2: 0.0
projection_parameters:
fx: 385.7544860839844
fy: 385.7544860839844
cx: 323.1204833984375
cy: 236.7432098388672
# Extrinsic parameter between IMU and Camera.
estimate_extrinsic: 2 # 0 Have an accurate extrinsic parameters. We will trust the following imu^R_cam, imu^T_cam, don't change it.
# 1 Have an initial guess about extrinsic parameters. We will optimize around your initial guess.
# 2 Don't know anything about extrinsic parameters. You don't need to give R,T. We will try to calibrate it. Do some rotation movement at beginning.
#If you choose 0 or 1, you should write down the following matrix.
#Rotation from camera frame to imu frame, imu^R_cam
extrinsicRotation: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [ -1.0406548080980293e-02, -6.8339359975994052e-04,
9.9994561688635142e-01, -9.9994461366801901e-01,
-1.5656625000493030e-03, -1.0407607662295648e-02,
1.5726898469127781e-03, -9.9999854083599726e-01,
-6.6706260700977182e-04 ]
extrinsicTranslation: !!opencv-matrix
rows: 3
cols: 1
dt: d
data: [ 5.2600599061337287e-02, 2.5510536758700533e-02,
9.5887981235633201e-03 ]
#feature traker paprameters
max_cnt: 200 # max feature number in feature tracking
min_dist: 25 # min distance between two features
freq: 15 # frequence (Hz) of publish tracking result. At least 10Hz for good estimation. If set 0, the frequence will be same as raw image
F_threshold: 1.0 # ransac threshold (pixel)
show_track: 1 # publish tracking image as topic
equalize: 1 # if image is too dark or light, trun on equalize to find enough features
fisheye: 0 # if using fisheye, trun on it. A circle mask will be loaded to remove edge noisy points
#optimization parameters
max_solver_time: 0.04 # max solver itration time (ms), to guarantee real time
max_num_iterations: 8 # max solver itrations, to guarantee real time
keyframe_parallax: 10.0 # keyframe selection threshold (pixel)
#imu parameters The more accurate parameters you provide, the better performance
acc_n: 0.05 # accelerometer measurement noise standard deviation. #0.2 0.04
gyr_n: 0.01 # gyroscope measurement noise standard deviation. #0.05 0.004
acc_w: 0.002 # accelerometer bias random work noise standard deviation. #0.02
gyr_w: 2.0e-5 # gyroscope bias random work noise standard deviation. #4.0e-5
g_norm: 9.805 # gravity magnitude
#loop closure parameters
loop_closure: 0 # start loop closure
load_previous_pose_graph: 0 # load and reuse previous pose graph; load from 'pose_graph_save_path'
fast_relocalization: 0 # useful in real-time and large project
pose_graph_save_path: "/home/tony-ws1/output/pose_graph/" # save and load path
#unsynchronization parameters
estimate_td: 1 # online estimate time offset between camera and imu
td: 0.038 # initial value of time offset. unit: s. readed image clock + td = real image clock (IMU clock)
#rolling shutter parameters
rolling_shutter: 0 # 0: global shutter camera, 1: rolling shutter camera
rolling_shutter_tr: 0 # unit: s. rolling shutter read out time per frame (from data sheet).
#visualization parameters
save_image: 1 # save image in pose graph for visualization prupose; you can close this function by setting 0
visualize_imu_forward: 0 # output imu forward propogation to achieve low latency and high frequence results
visualize_camera_size: 0.4 # size of camera marker in RVIZ
================================================
FILE: launch/debugging_vinsmono.launch
================================================
<launch>
<arg name="config_path" default = "$(find cerebro)/config/vinsmono_debug_config.yaml" />
<arg name="vins_path" default = "$(find feature_tracker)/../config/../" />
<node name="feature_tracker" pkg="feature_tracker" type="feature_tracker" output="log">
<param name="config_file" type="string" value="$(arg config_path)" />
<param name="vins_folder" type="string" value="$(arg vins_path)" />
</node>
<node name="vins_estimator" pkg="vins_estimator" type="vins_estimator" output="screen">
<param name="config_file" type="string" value="$(arg config_path)" />
<param name="vins_folder" type="string" value="$(arg vins_path)" />
</node>
<!-- <node name="pose_graph" pkg="pose_graph" type="pose_graph" output="screen">
<param name="config_file" type="string" value="$(arg config_path)" />
<param name="visualization_shift_x" type="int" value="0" />
<param name="visualization_shift_y" type="int" value="0" />
<param name="skip_cnt" type="int" value="0" />
<param name="skip_dis" type="double" value="0" />
</node> -->
</launch>
================================================
FILE: launch/euroc_vinsfusion.launch
================================================
<launch timeout="100.0">
<!-- CONFIG FILE -->
<!-- <arg name="config_path" default="$(find cerebro)/config/vinsfusion/euroc/euroc_mono_imu_config.yaml" /> -->
<arg name="config_path" default="$(find cerebro)/config/vinsfusion/euroc/euroc_stereo_imu_config.yaml" />
<!-- BAG -->
<arg name="bag_path" default="/Bulk_Data/ros_bags/euroc/" />
<!-- <arg name="bag_file" default="MH_01_easy.bag" /> -->
<!-- <arg name="bag_file" default="MH_02_easy.bag" /> -->
<!-- <arg name="bag_file" default="MH_03_medium.bag" /> -->
<!-- <arg name="bag_file" default="MH_04_difficult.bag" /> -->
<arg name="bag_file" default="MH_05_difficult.bag" />
<!-- <arg name="bag_file" default="V1_01_easy.bag" /> -->
<!--<arg name="bag_file" default="V1_02_medium.bag" />-->
<!--<arg name="bag_file" default="V1_03_difficult.bag" />-->
<!-- <arg name="bag_file" default="V2_01_easy.bag" /> -->
<!-- <arg name="bag_file" default="V2_02_medium.bag" /> -->
<!-- <arg name="bag_file" default="V2_03_difficult.bag" /> -->
<!-- <node pkg="rosbag" type="play" name="rosbag" args="$(arg bag_path)/$(arg bag_file) -s 35" output="log"/> -->
<!-- END Bag -->
<!-- VINS-Fusion Odometry Estimator -->
<!-- unlike previous vins-mono, even the feature tracker is put inside 1 node ie. vins_node.
$(ubuntu) rosrun vins vins_node /app/catkin_ws/src/cerebro/config/vinsfusion/euroc/euroc_stereo_imu_config.yaml
-->
<node name="vins_estimator" pkg="vins" type="vins_node" args=" $(arg config_path)" output="log">
</node>
<group if="0">
<!-- VINS-Fusion loop_fusion -->
<!-- This is the DBOW + posegraph optimization from Qin Tong
$(ubuntu) rosrun loop_fusion loop_fusion_node /app/catkin_ws/src/cerebro/config/vinsfusion/euroc/euroc_stereo_imu_config.yaml
-->
<node name="loop_fusion" pkg="loop_fusion" type="loop_fusion_node" args=" $(arg config_path)" output="log">
</node>
</group>
<group if="1">
<!-- Cerebro -->
<node name="cerebro_node" pkg="cerebro" type="cerebro_node" output="log">
<param name="config_file" type="string" value="$(arg config_path)" />
</node>
<!-- KERAS SERVER -->
<!-- $(ubuntu) rosrun cerebro whole_image_desc_compute_server.py _config_file:=/app/catk_ws/src/cerebro/config/vinsfusion/euroc/euroc_stereo_imu_config.yaml -->
<node name="my_desc_server" pkg="cerebro" type="whole_image_desc_compute_server.py" output="screen">
<!-- <param name="kerasmodel_file" type="string" value="/models.keras/Apr2019/gray_conv6_K16Ghost1__centeredinput/core_model.500.keras" /> -->
<!-- <param name="kerasmodel_file" type="string" value="$(find cerebro)/scripts/keras.models/Apr2019/gray_conv6_K16__centeredinput/core_model.1000.keras" /> -->
<param name="kerasmodel_file" type="string" value="$(find cerebro)/scripts/keras.models/mobilenet_conv7_allpairloss.keras" />
<param name="config_file" type="string" value="$(arg config_path)" />
<!-- OR -->
<!-- <param name="nrows" type="string" value="480" />
<param name="ncols" type="string" value="752" />
<param name="nchnls" type="string" value="1" /> -->
<param name="nchnls" type="string" value="3" />
</node>
<!-- Pose graph (kidnap aware) -->
<!-- $(ubuntu) rosrun solve_keyframe_pose_graph keyframe_pose_graph_slam -->
<node name="keyframe_pose_graph_slam_node" pkg="solve_keyframe_pose_graph" type="keyframe_pose_graph_slam" output="log" >
</node>
</group>
</launch>
================================================
FILE: launch/keras_server.launch
================================================
<launch>
<!-- <arg name="config_path" default="$(find cerebro)/config/euroc/euroc_config.yaml" /> -->
<!-- <arg name="config_path" default="$(find cerebro)/config/blackbox4/blackbox4_config.yaml" /> -->
<!-- <arg name="config_path" default="$(find cerebro)/config/tum_vi/tum_jie_config.yaml" /> -->
<arg name="config_path" default="$(find cerebro)/config/mynteye/mynteye_config.yaml" />
<!-- <arg name="config_path" default="$(find cerebro)/config/vinsfusion/euroc/cam0_mei.yaml" /> -->
<!-- <arg name="config_path" default="$(find cerebro)/config/vinsfusion/euroc/euroc_stereo_imu_config.yaml" /> -->
<node name="my_desc_server" pkg="cerebro" type="whole_image_desc_compute_server.py" output="screen">
<!-- <param name="kerasmodel_file" type="string" value="/models.keras/Apr2019/gray_conv6_K16Ghost1__centeredinput/core_model.500.keras" /> -->
<!-- <param name="kerasmodel_file" type="string" value="$(find cerebro)/scripts/keras.models/Apr2019/gray_conv6_K16__centeredinput/core_model.1000.keras" /> -->
<param name="kerasmodel_file" type="string" value="$(find cerebro)/scripts/keras.models/mobilenet_conv7_allpairloss.keras" />
<!-- <param name="config_file" type="string" value="$(arg config_path)" /> -->
<!-- OR -->
<param name="nrows" type="string" value="480" />
<param name="ncols" type="string" value="752" />
<param name="nchnls" type="string" value="3" />
</node>
</launch>
================================================
FILE: launch/mynteye_vinsfusion.launch
================================================
<launch timeout="100.0">
<!-- CONFIG FILE -->
<arg name="config_path" default="$(find cerebro)/config/vinsfusion/mynteye/mynteye_stereo_imu_config.yaml" />
<!-- BAG -->
<arg name="bag_path" default="/Bulk_Data/ros_bags/mynteye/" />
<!-- ### IN LAB -->
<!-- <arg name="bag_file" default="1.bag" doc="sitting on my desk"/> -->
<!-- <arg name="bag_file" default="2018-11-20-17-45-55.bag" doc="single loop in lab"/> -->
<!-- <arg name="bag_file" default="2018-11-20-17-42-54.bag" doc="multiple loops in lab"/> -->
<arg name="bag_file" default="2019-01-28-16-32-23.bag" doc="many-10 loops in lab"/>
<!-- <arg name="bag_file" default="2018-11-22-12-06-47.bag" doc="drone fly area loopy"/> -->
<!-- <arg name="bag_file" default="2018-11-22-12-09-21.bag" doc="conference room RI"/> -->
<!-- <arg name="bag_file" default="2018-11-29-12-37-49.bag" doc="lab rotated loops"/> -->
<!-- <arg name="bag_file" default="2018-11-29-15-10-24.bag" doc="outside RI"/> -->
<!-- <arg name="bag_file" default="2019-01-14-18-25-18.bag" doc="lab AR test"/> -->
<!-- <arg name="bag_file" default="2019-06-26-16-09-04.bag" doc="seq0, 1 loop. loop-0: walk in lab; lap-1: same place with 90 degree in place rotation"/> -->
<!-- <arg name="bag_file" default="2019-06-26-16-19-43.bag" doc="seq1,1 loop. loop-0: walk in lab; lap-1: same place with 90 degree in place rotation"/> -->
<!-- <arg name="bag_file" default="2019-06-26-16-36-20.bag" doc="seq2,1 loop. loop-0: walk in lab +45 degrees; lap-1: same place with -45degres in place rotation"/> -->
<!-- ### In HKUST Academic block and CYT UG -->
<!-- <arg name="bag_file" default="2018-11-29-15-13-44.bag" doc="CYT UG floor"/> -->
<!-- <arg name="bag_file" default="2018-11-29-15-22-50.bag" doc="academic concourse, no loop in this"/> -->
<!-- <arg name="bag_file" default="2018-11-29-15-30-39.bag" doc="near coffee shop 1"/> -->
<!-- <arg name="bag_file" default="2018-11-29-15-36-41.bag" doc="seng"/> -->
<!-- <arg name="bag_file" default="2018-12-13-16-48-46.bag" doc="seng3. walking on academic concouse CYT end, walking down the escalator and back up."/> -->
<!-- <arg name="bag_file" default="2018-12-13-16-56-36.bag" doc="concourse-seng4. from coffee-shop to atrium"/> -->
<!-- ### Kidnap sequences in lab -->
<!-- <arg name="bag_path" default="/Bulk_Data/ros_bags/mynteye/" /> -->
<!-- <arg name="bag_file" default="/kidnap/2019-01-14-17-20-06.bag" doc="lab kidnap. easy"/> -->
<!-- <arg name="bag_file" default="/kidnap/2019-02-14-12-00-21.bag" doc="3 kidnaps in lab. This gives the chained case for pose computation between worlds"/> -->
<!-- <arg name="bag_file" default="/kidnap/2019-02-14-17-19-29.bag" doc="4 kidnaps in lab"/> -->
<!-- <arg name="bag_file" default="/kidnap/2019-02-14-17-19-29.bag" doc="4 kidnaps in lab"/> -->
<!-- <arg name="bag_file" default="/kidnap/2019-02-21-17-10-30.bag" doc="0:-; 1:-; 2:merge(0), merge(1). 2nd merges with both 0 and 1."/> -->
<!-- <arg name="bag_file" default="/kidnap/2019-02-21-17-38-58.bag" doc="0:-; 1:-; 2:merge(0), merge(1). 2nd merges with both 0 and 1."/> -->
<!-- <arg name="bag_file" default="/kidnap/2019-03-07-14-58-00.bag" doc="2 independent runs"/> -->
<!-- <arg name="bag_file" default="/kidnap/2019-03-14-16-12-22.bag" doc="7 kidnaps. 0:; 1:; all next merges with 1. Final merge with 0 and 3."/> -->
<!-- <arg name="bag_file" default="/kidnap/2019-03-14-16-36-58.bag" doc="10 kidnaps. 0; 1; merge everything with 1. finall all merge to zero. very complicated dependence structure of the walk,"/> -->
<!-- ### Mall -->
<!-- <arg name="bag_file" default="/mall/2019-04-08-16-02-10.bag" doc=""/> -->
<!-- <arg name="bag_file" default="/mall/2019-04-08-16-09-41.bag" doc="good. no kidnap, but just 1 loop starting from Muji"/> -->
<!-- <arg name="bag_file" default="/mall/2019-04-08-16-14-19.bag" doc="1 moderate loop;kidnap;a very short seq in a portion of the loop. near marathon sports, (shoes shops)"/> -->
<!-- <arg name="bag_file" default="/mall/2019-04-08-16-17-05.bag" doc="corridor near shoes shop;kidnap;"/> -->
<!-- <arg name="bag_file" default="/mall/2019-04-10-15-07-51.bag" doc="3 kidnaps. k1:hsbc;right to muji; shoes;;k1: panash;atrium;shoes;panash" /> -->
<!-- <arg name="bag_file" default="/mall/2019-04-10-15-17-34.bag" doc="2 kidnaps. k1:fancl;bossino;muji;right of hsbc rotated and tilted; k2:bodyshop ; k3: fancl;bossini,shoes" /> -->
<!-- <arg name="bag_file" default="/mall/2019-04-10-15-40-35.bag" doc="level-1 from from PacificC to muji to hsbc. 1kidnap" /> -->
<!-- <arg name="bag_file" default="/mall/2019-04-10-15-23-38.bag" doc="start from atrium near pacific-coffee;go up; casual walking on top floor 4 kidnaps" /> -->
<!-- <arg name="bag_file" default="/mall/2019-04-10-15-34-01.bag" doc="1 corridor on top floor. no loop no kidnap" /> -->
<!-- <arg name="bag_file" default="/mall/2019-04-10-15-34-57.bag" doc="1 kidnaps. both runs r independent, no interworld revisit" /> -->
<!-- <arg name="bag_file" default="/mall/2019-04-10-15-38-51.bag" doc="really short (abt 30 sec near broadway)" /> -->
<node pkg="rosbag" type="play" name="rosbag" args="$(arg bag_path)/$(arg bag_file) -s 35 -d 10" output="log"/>
<!-- END Bag -->
<!-- VINS-Fusion Estimator -->
<!-- unlike previous vins-mono, even the feature tracker is put inside 1 node ie. vins_node.
$(ubuntu) rosrun vins vins_node /app/catkin_ws/src/cerebro/config/vinsfusion/mynteye/mynteye_stereo_imu_config.yaml
-->
<node name="vins_estimator" pkg="vins" type="vins_node" args=" $(arg config_path)" output="log">
</node>
<group if="0">
<!-- VINS-Fusion loop_fusion -->
<!-- This is the DBOW + posegraph optimization from Qin Tong
$(ubuntu) rosrun loop_fusion loop_fusion_node /app/catkin_ws/src/cerebro/config/vinsfusion/euroc/euroc_stereo_imu_config.yaml
-->
<node name="loop_fusion" pkg="loop_fusion" type="loop_fusion_node" args=" $(arg config_path)" output="log">
</node>
</group>
<group if="1">
<!-- Cerebro -->
<node name="cerebro_node" pkg="cerebro" type="cerebro_node" output="screen">
<param name="config_file" type="string" value="$(arg config_path)" />
</node>
<!-- KERAS SERVER -->
<!-- $(ubuntu) rosrun cerebro whole_image_desc_compute_server.py _config_file:=/app/catk_ws/src/cerebro/config/vinsfusion/euroc/euroc_stereo_imu_config.yaml -->
<node name="my_desc_server" pkg="cerebro" type="whole_image_desc_compute_server.py" output="log">
<!-- <param name="kerasmodel_file" type="string" value="$(find cerebro)/scripts/keras.models/modelarch_and_weights.h5" /> -->
<!-- <param name="kerasmodel_file" type="string" value="/models.keras/June2019/centeredinput-m1to1-240x320x3__mobilenet-conv_pw_6_relu__K16__allpairloss/modelarch_and_weights.500.h5" /> -->
<!-- <param name="kerasmodel_file" type="string" value="$(find cerebro)/scripts/keras.models/June2019/centeredinput-m1to1-240x320x3__mobilenet-conv_pw_6_relu__K16__allpairloss/modelarch_and_weights.700.h5" /> -->
<!-- <param name="kerasmodel_file" type="string" value="$(find cerebro)/scripts/keras.models/June2019/centeredinput-m1to1-240x320x3__mobilenetv2-block_9_add__K16__allpairloss/modelarch_and_weights.800.h5" /> -->
<param name="kerasmodel_file" type="string" value="/models.keras/June2019/centeredinput-m1to1-240x320x1__mobilenetv2-block_9_add__K16__allpairloss/modelarch_and_weights.2000.h5" />
<param name="config_file" type="string" value="$(arg config_path)" />
<!-- OR -->
<!--
<param name="nrows" type="string" value="480" />
<param name="ncols" type="string" value="752" />
-->
<!-- this is needed irrespective of the config_file or the nrows and ncols set manually here. -->
<param name="nchnls" type="string" value="1" />
<!-- <param name="nchnls" type="string" value="3" /> -->
</node>
<!-- Pose graph (kidnap aware) -->
<!-- $(ubuntu) rosrun solve_keyframe_pose_graph keyframe_pose_graph_slam -->
<node name="keyframe_pose_graph_slam_node" pkg="solve_keyframe_pose_graph" type="keyframe_pose_graph_slam" output="log" >
</node>
</group>
</launch>
================================================
FILE: launch/mynteye_vinsfusion_loadstate.launch
================================================
<launch timeout="100.0">
<!-- CONFIG FILE -->
<arg name="config_path" default="$(find cerebro)/config/vinsfusion/mynteye/mynteye_stereo_imu_config.yaml" />
<!-- BAG -->
<arg name="bag_path" default="/Bulk_Data/ros_bags/mynteye/" />
<!-- ### IN LAB -->
<!-- <arg name="bag_file" default="1.bag" doc="sitting on my desk"/> -->
<!-- <arg name="bag_file" default="2018-11-20-17-45-55.bag" doc="single loop in lab"/> -->
<!-- <arg name="bag_file" default="2018-11-20-17-42-54.bag" doc="multiple loops in lab"/> -->
<!-- <arg name="bag_file" default="2019-01-28-16-32-23.bag" doc="many-10 loops in lab"/> -->
<!-- <arg name="bag_file" default="2018-11-22-12-06-47.bag" doc="drone fly area loopy"/> -->
<!-- <arg name="bag_file" default="2018-11-22-12-09-21.bag" doc="conference room RI"/> -->
<!-- <arg name="bag_file" default="2018-11-29-12-37-49.bag" doc="lab rotated loops"/> -->
<!-- <arg name="bag_file" default="2018-11-29-15-10-24.bag" doc="outside RI"/> -->
<!-- <arg name="bag_file" default="2019-01-14-18-25-18.bag" doc="lab AR test"/> -->
<!-- <arg name="bag_file" default="2019-06-26-16-09-04.bag" doc="seq0, 1 loop. loop-0: walk in lab; lap-1: same place with 90 degree in place rotation"/> -->
<!-- <arg name="bag_file" default="2019-06-26-16-19-43.bag" doc="seq1,1 loop. loop-0: walk in lab; lap-1: same place with 90 degree in place rotation"/> -->
<!-- <arg name="bag_file" default="2019-06-26-16-36-20.bag" doc="seq2,1 loop. loop-0: walk in lab +45 degrees; lap-1: same place with -45degres in place rotation"/> -->
<!-- ### In HKUST Academic block and CYT UG -->
<!-- <arg name="bag_file" default="2018-11-29-15-13-44.bag" doc="CYT UG floor"/> -->
<!-- <arg name="bag_file" default="2018-11-29-15-22-50.bag" doc="academic concourse, no loop in this"/> -->
<!-- <arg name="bag_file" default="2018-11-29-15-30-39.bag" doc="near coffee shop 1"/> -->
<!-- <arg name="bag_file" default="2018-11-29-15-36-41.bag" doc="seng"/> -->
<!-- <arg name="bag_file" default="2018-12-13-16-48-46.bag" doc="seng3. walking on academic concouse CYT end, walking down the escalator and back up."/> -->
<!-- <arg name="bag_file" default="2018-12-13-16-56-36.bag" doc="concourse-seng4. from coffee-shop to atrium"/> -->
<!-- ### Kidnap sequences in lab -->
<!-- <arg name="bag_path" default="/Bulk_Data/ros_bags/mynteye/" /> -->
<!-- <arg name="bag_file" default="/kidnap/2019-01-14-17-20-06.bag" doc="lab kidnap. easy"/> -->
<!-- <arg name="bag_file" default="/kidnap/2019-02-14-12-00-21.bag" doc="3 kidnaps in lab. This gives the chained case for pose computation between worlds"/> -->
<!-- <arg name="bag_file" default="/kidnap/2019-02-14-17-19-29.bag" doc="4 kidnaps in lab"/> -->
<!-- <arg name="bag_file" default="/kidnap/2019-02-14-17-19-29.bag" doc="4 kidnaps in lab"/> -->
<!-- <arg name="bag_file" default="/kidnap/2019-02-21-17-10-30.bag" doc="0:-; 1:-; 2:merge(0), merge(1). 2nd merges with both 0 and 1."/> -->
<arg name="bag_file" default="/kidnap/2019-02-21-17-38-58.bag" doc="0:-; 1:-; 2:merge(0), merge(1). 2nd merges with both 0 and 1."/>
<!-- <arg name="bag_file" default="/kidnap/2019-03-07-14-58-00.bag" doc="2 independent runs"/> -->
<!-- <arg name="bag_file" default="/kidnap/2019-03-14-16-12-22.bag" doc="7 kidnaps. 0:; 1:; all next merges with 1. Final merge with 0 and 3."/> -->
<!-- <arg name="bag_file" default="/kidnap/2019-03-14-16-36-58.bag" doc="10 kidnaps. 0; 1; merge everything with 1. finall all merge to zero. very complicated dependence structure of the walk,"/> -->
<!-- ### Mall -->
<!-- <arg name="bag_file" default="/mall/2019-04-08-16-02-10.bag" doc=""/> -->
<!-- <arg name="bag_file" default="/mall/2019-04-08-16-09-41.bag" doc="good. no kidnap, but just 1 loop starting from Muji"/> -->
<!-- <arg name="bag_file" default="/mall/2019-04-08-16-14-19.bag" doc="1 moderate loop;kidnap;a very short seq in a portion of the loop. near marathon sports, (shoes shops)"/> -->
<!-- <arg name="bag_file" default="/mall/2019-04-08-16-17-05.bag" doc="corridor near shoes shop;kidnap;"/> -->
<!-- <arg name="bag_file" default="/mall/2019-04-10-15-07-51.bag" doc="3 kidnaps. k1:hsbc;right to muji; shoes;;k1: panash;atrium;shoes;panash" /> -->
<!-- <arg name="bag_file" default="/mall/2019-04-10-15-17-34.bag" doc="2 kidnaps. k1:fancl;bossino;muji;right of hsbc rotated and tilted; k2:bodyshop ; k3: fancl;bossini,shoes" /> -->
<!-- <arg name="bag_file" default="/mall/2019-04-10-15-40-35.bag" doc="level-1 from from PacificC to muji to hsbc. 1kidnap" /> -->
<!-- <arg name="bag_file" default="/mall/2019-04-10-15-23-38.bag" doc="start from atrium near pacific-coffee;go up; casual walking on top floor 4 kidnaps" /> -->
<!-- <arg name="bag_file" default="/mall/2019-04-10-15-34-01.bag" doc="1 corridor on top floor. no loop no kidnap" /> -->
<!-- <arg name="bag_file" default="/mall/2019-04-10-15-34-57.bag" doc="1 kidnaps. both runs r independent, no interworld revisit" /> -->
<!-- <arg name="bag_file" default="/mall/2019-04-10-15-38-51.bag" doc="really short (abt 30 sec near broadway)" /> -->
<node pkg="rosbag" type="play" name="rosbag" args="$(arg bag_path)/$(arg bag_file) -s 2 -d 10" output="log"/>
<!-- END Bag -->
<!-- VINS-Fusion Estimator -->
<!-- unlike previous vins-mono, even the feature tracker is put inside 1 node ie. vins_node.
$(ubuntu) rosrun vins vins_node /app/catkin_ws/src/cerebro/config/vinsfusion/mynteye/mynteye_stereo_imu_config.yaml
-->
<node name="vins_estimator" pkg="vins" type="vins_node" args=" $(arg config_path)" output="log">
</node>
<group if="0">
<!-- VINS-Fusion loop_fusion -->
<!-- This is the DBOW + posegraph optimization from Qin Tong
$(ubuntu) rosrun loop_fusion loop_fusion_node /app/catkin_ws/src/cerebro/config/vinsfusion/euroc/euroc_stereo_imu_config.yaml
-->
<node name="loop_fusion" pkg="loop_fusion" type="loop_fusion_node" args=" $(arg config_path)" output="log">
</node>
</group>
<group if="1">
<!-- Cerebro -->
<!-- NOTE:
X) `config_file` Same as the vins-fusion, but you need to set cam=2 and imu=1 also you need to specify extrinsic_1_T_0 as I depend on stereo vision
X) Specify the path for saving/loading state. Keep value as empty string to disable the function.
For example if you kept loadStateFromDisk as empty string, I will not load aka fresh start.
Similarly if you kept saveStateToDisk as empty, I will not write data to disk upon exit
-->
<node name="cerebro_node" pkg="cerebro" type="cerebro_node" output="log">
<param name="config_file" type="string" value="$(arg config_path)" />
<param name="loadStateFromDisk" type="string" value="/Bulk_Data/chkpts_cerebro/" />
<!-- <param name="loadStateFromDisk" type="string" value="" /> -->
<!-- <param name="saveStateToDisk" type="string" value="/Bulk_Data/chkpts_cerebro/" /> -->
<param name="saveStateToDisk" type="string" value="" />
</node>
<!-- KERAS SERVER -->
<!-- $(ubuntu) rosrun cerebro whole_image_desc_compute_server.py _config_file:=/app/catk_ws/src/cerebro/config/vinsfusion/euroc/euroc_stereo_imu_config.yaml -->
<node name="my_desc_server" pkg="cerebro" type="whole_image_desc_compute_server.py" output="screen">
<!-- <param name="kerasmodel_file" type="string" value="$(find cerebro)/scripts/keras.models/modelarch_and_weights.h5" /> -->
<!-- <param name="kerasmodel_file" type="string" value="/models.keras/June2019/centeredinput-m1to1-240x320x3__mobilenet-conv_pw_6_relu__K16__allpairloss/modelarch_and_weights.500.h5" /> -->
<!-- <param name="kerasmodel_file" type="string" value="$(find cerebro)/scripts/keras.models/June2019/centeredinput-m1to1-240x320x3__mobilenet-conv_pw_6_relu__K16__allpairloss/modelarch_and_weights.700.h5" /> -->
<!-- <param name="kerasmodel_file" type="string" value="$(find cerebro)/scripts/keras.models/June2019/centeredinput-m1to1-240x320x3__mobilenetv2-block_9_add__K16__allpairloss/modelarch_and_weights.800.h5" /> -->
<!-- <param name="kerasmodel_file" type="string" value="/models.keras/June2019/centeredinput-m1to1-240x320x1__mobilenetv2-block_9_add__K16__allpairloss/modelarch_and_weights.2000.h5" /> -->
<param name="kerasmodel_file" type="string" value="$(find cerebro)/scripts/keras.models/June2019/centeredinput-m1to1-240x320x1__mobilenetv2-block_9_add__K16__allpairloss/modelarch_and_weights.2000.h5" />
<param name="config_file" type="string" value="$(arg config_path)" />
<!-- OR -->
<!--
<param name="nrows" type="string" value="480" />
<param name="ncols" type="string" value="752" />
-->
<!-- this is needed irrespective of the config_file or the nrows and ncols set manually here. -->
<param name="nchnls" type="string" value="1" />
<!-- <param name="nchnls" type="string" value="3" /> -->
</node>
<!-- Pose graph (kidnap aware) -->
<!-- $(ubuntu) rosrun solve_keyframe_pose_graph keyframe_pose_graph_slam -->
<node name="keyframe_pose_graph_slam_node" pkg="solve_keyframe_pose_graph" type="keyframe_pose_graph_slam" output="log" >
<param name="loadStateFromDisk" type="string" value="/Bulk_Data/chkpts_posegraph_solver/" />
<!-- <param name="loadStateFromDisk" type="string" value="" /> -->
<!-- <param name="saveStateToDisk" type="string" value="/Bulk_Data/chkpts_posegraph_solver/" /> -->
<param name="saveStateToDisk" type="string" value="" />
</node>
</group>
</launch>
================================================
FILE: launch/mynteye_vinsfusion_ondrone.launch
================================================
<launch timeout="100.0">
<!-- CONFIG FILE -->
<arg name="config_path" default="$(find cerebro)/config/vinsfusion/mynteye/mynteye_stereo_imu_config.yaml" />
<!-- VINS-Fusion Estimator -->
<!-- unlike previous vins-mono, even the feature tracker is put inside 1 node ie. vins_node.
$(ubuntu) rosrun vins vins_node /app/catkin_ws/src/cerebro/config/vinsfusion/mynteye/mynteye_stereo_imu_config.yaml
-->
<node name="vins_estimator" pkg="vins" type="vins_node" args=" $(arg config_path)" output="log">
</node>
<group if="0">
<!-- VINS-Fusion loop_fusion -->
<!-- This is the DBOW + posegraph optimization from Qin Tong
$(ubuntu) rosrun loop_fusion loop_fusion_node /app/catkin_ws/src/cerebro/config/vinsfusion/euroc/euroc_stereo_imu_config.yaml
-->
<node name="loop_fusion" pkg="loop_fusion" type="loop_fusion_node" args=" $(arg config_path)" output="log">
</node>
</group>
<group if="1">
<!-- Cerebro -->
<node name="cerebro_node" pkg="cerebro" type="cerebro_node" output="screen">
<param name="config_file" type="string" value="$(arg config_path)" />
</node>
<!-- KERAS SERVER -->
<!-- $(ubuntu) rosrun cerebro whole_image_desc_compute_server.py _config_file:=/app/catk_ws/src/cerebro/config/vinsfusion/euroc/euroc_stereo_imu_config.yaml -->
<!-- Since I run the server on tx2 dont need to run it here -->
<group if="0" >
<node name="my_desc_server" pkg="cerebro" type="whole_image_desc_compute_server.py" output="screen">
<!-- <param name="kerasmodel_file" type="string" value="$(find cerebro)/scripts/keras.models/modelarch_and_weights.h5" /> -->
<!-- <param name="kerasmodel_file" type="string" value="/models.keras/June2019/centeredinput-m1to1-240x320x3__mobilenet-conv_pw_6_relu__K16__allpairloss/modelarch_and_weights.500.h5" /> -->
<param name="kerasmodel_file" type="string" value="$(find cerebro)/scripts/keras.models/June2019/centeredinput-m1to1-240x320x3__mobilenet-conv_pw_6_relu__K16__allpairloss/modelarch_and_weights.700.h5" />
<param name="config_file" type="string" value="$(arg config_path)" />
<!-- OR -->
<!--
<param name="nrows" type="string" value="480" />
<param name="ncols" type="string" value="752" />
-->
<!-- this is needed irrespective of the config_file or the nrows and ncols set manually here. -->
<!-- <param name="nchnls" type="string" value="1" /> -->
<param name="nchnls" type="string" value="3" />
</node>
<!-- Pose graph (kidnap aware) -->
<!-- $(ubuntu) rosrun solve_keyframe_pose_graph keyframe_pose_graph_slam -->
<node name="keyframe_pose_graph_slam_node" pkg="solve_keyframe_pose_graph" type="keyframe_pose_graph_slam" output="log" >
</node>
</group>
</group>
</launch>
================================================
FILE: launch/mynteye_vinsfusion_savestate.launch
================================================
<launch timeout="100.0">
<!-- CONFIG FILE -->
<arg name="config_path" default="$(find cerebro)/config/vinsfusion/mynteye/mynteye_stereo_imu_config.yaml" />
<!-- BAG -->
<arg name="bag_path" default="/Bulk_Data/ros_bags/mynteye/" />
<!-- ### IN LAB -->
<!-- <arg name="bag_file" default="1.bag" doc="sitting on my desk"/> -->
<!-- <arg name="bag_file" default="2018-11-20-17-45-55.bag" doc="single loop in lab"/> -->
<!-- <arg name="bag_file" default="2018-11-20-17-42-54.bag" doc="multiple loops in lab"/> -->
<!-- <arg name="bag_file" default="2019-01-28-16-32-23.bag" doc="many-10 loops in lab"/> -->
<!-- <arg name="bag_file" default="2018-11-22-12-06-47.bag" doc="drone fly area loopy"/> -->
<!-- <arg name="bag_file" default="2018-11-22-12-09-21.bag" doc="conference room RI"/> -->
<!-- <arg name="bag_file" default="2018-11-29-12-37-49.bag" doc="lab rotated loops"/> -->
<!-- <arg name="bag_file" default="2018-11-29-15-10-24.bag" doc="outside RI"/> -->
<!-- <arg name="bag_file" default="2019-01-14-18-25-18.bag" doc="lab AR test"/> -->
<!-- <arg name="bag_file" default="2019-06-26-16-09-04.bag" doc="seq0, 1 loop. loop-0: walk in lab; lap-1: same place with 90 degree in place rotation"/> -->
<!-- <arg name="bag_file" default="2019-06-26-16-19-43.bag" doc="seq1,1 loop. loop-0: walk in lab; lap-1: same place with 90 degree in place rotation"/> -->
<!-- <arg name="bag_file" default="2019-06-26-16-36-20.bag" doc="seq2,1 loop. loop-0: walk in lab +45 degrees; lap-1: same place with -45degres in place rotation"/> -->
<!-- ### In HKUST Academic block and CYT UG -->
<!-- <arg name="bag_file" default="2018-11-29-15-13-44.bag" doc="CYT UG floor"/> -->
<!-- <arg name="bag_file" default="2018-11-29-15-22-50.bag" doc="academic concourse, no loop in this"/> -->
<!-- <arg name="bag_file" default="2018-11-29-15-30-39.bag" doc="near coffee shop 1"/> -->
<!-- <arg name="bag_file" default="2018-11-29-15-36-41.bag" doc="seng"/> -->
<!-- <arg name="bag_file" default="2018-12-13-16-48-46.bag" doc="seng3. walking on academic concouse CYT end, walking down the escalator and back up."/> -->
<!-- <arg name="bag_file" default="2018-12-13-16-56-36.bag" doc="concourse-seng4. from coffee-shop to atrium"/> -->
<!-- ### Kidnap sequences in lab -->
<!-- <arg name="bag_path" default="/Bulk_Data/ros_bags/mynteye/" /> -->
<!-- <arg name="bag_file" default="/kidnap/2019-01-14-17-20-06.bag" doc="lab kidnap. easy"/> -->
<!-- <arg name="bag_file" default="/kidnap/2019-02-14-12-00-21.bag" doc="3 kidnaps in lab. This gives the chained case for pose computation between worlds"/> -->
<!-- <arg name="bag_file" default="/kidnap/2019-02-14-17-19-29.bag" doc="4 kidnaps in lab"/> -->
<!-- <arg name="bag_file" default="/kidnap/2019-02-14-17-19-29.bag" doc="4 kidnaps in lab"/> -->
<arg name="bag_file" default="/kidnap/2019-02-21-17-10-30.bag" doc="0:-; 1:-; 2:merge(0), merge(1). 2nd merges with both 0 and 1."/>
<!-- <arg name="bag_file" default="/kidnap/2019-02-21-17-38-58.bag" doc="0:-; 1:-; 2:merge(0), merge(1). 2nd merges with both 0 and 1."/> -->
<!-- <arg name="bag_file" default="/kidnap/2019-03-07-14-58-00.bag" doc="2 independent runs"/> -->
<!-- <arg name="bag_file" default="/kidnap/2019-03-14-16-12-22.bag" doc="7 kidnaps. 0:; 1:; all next merges with 1. Final merge with 0 and 3."/> -->
<!-- <arg name="bag_file" default="/kidnap/2019-03-14-16-36-58.bag" doc="10 kidnaps. 0; 1; merge everything with 1. finall all merge to zero. very complicated dependence structure of the walk,"/> -->
<!-- ### Mall -->
<!-- <arg name="bag_file" default="/mall/2019-04-08-16-02-10.bag" doc=""/> -->
<!-- <arg name="bag_file" default="/mall/2019-04-08-16-09-41.bag" doc="good. no kidnap, but just 1 loop starting from Muji"/> -->
<!-- <arg name="bag_file" default="/mall/2019-04-08-16-14-19.bag" doc="1 moderate loop;kidnap;a very short seq in a portion of the loop. near marathon sports, (shoes shops)"/> -->
<!-- <arg name="bag_file" default="/mall/2019-04-08-16-17-05.bag" doc="corridor near shoes shop;kidnap;"/> -->
<!-- <arg name="bag_file" default="/mall/2019-04-10-15-07-51.bag" doc="3 kidnaps. k1:hsbc;right to muji; shoes;;k1: panash;atrium;shoes;panash" /> -->
<!-- <arg name="bag_file" default="/mall/2019-04-10-15-17-34.bag" doc="2 kidnaps. k1:fancl;bossino;muji;right of hsbc rotated and tilted; k2:bodyshop ; k3: fancl;bossini,shoes" /> -->
<!-- <arg name="bag_file" default="/mall/2019-04-10-15-40-35.bag" doc="level-1 from from PacificC to muji to hsbc. 1kidnap" /> -->
<!-- <arg name="bag_file" default="/mall/2019-04-10-15-23-38.bag" doc="start from atrium near pacific-coffee;go up; casual walking on top floor 4 kidnaps" /> -->
<!-- <arg name="bag_file" default="/mall/2019-04-10-15-34-01.bag" doc="1 corridor on top floor. no loop no kidnap" /> -->
<!-- <arg name="bag_file" default="/mall/2019-04-10-15-34-57.bag" doc="1 kidnaps. both runs r independent, no interworld revisit" /> -->
<!-- <arg name="bag_file" default="/mall/2019-04-10-15-38-51.bag" doc="really short (abt 30 sec near broadway)" /> -->
<node pkg="rosbag" type="play" name="rosbag" args="$(arg bag_path)/$(arg bag_file) -s 2 -d 10" output="log"/>
<!-- END Bag -->
<!-- VINS-Fusion Estimator -->
<!-- unlike previous vins-mono, even the feature tracker is put inside 1 node ie. vins_node.
$(ubuntu) rosrun vins vins_node /app/catkin_ws/src/cerebro/config/vinsfusion/mynteye/mynteye_stereo_imu_config.yaml
-->
<node name="vins_estimator" pkg="vins" type="vins_node" args=" $(arg config_path)" output="log">
</node>
<group if="0">
<!-- VINS-Fusion loop_fusion -->
<!-- This is the DBOW + posegraph optimization from Qin Tong
$(ubuntu) rosrun loop_fusion loop_fusion_node /app/catkin_ws/src/cerebro/config/vinsfusion/euroc/euroc_stereo_imu_config.yaml
-->
<node name="loop_fusion" pkg="loop_fusion" type="loop_fusion_node" args=" $(arg config_path)" output="log">
</node>
</group>
<group if="1">
<!-- Cerebro -->
<!-- NOTE:
X) `config_file` Same as the vins-fusion, but you need to set cam=2 and imu=1 also you need to specify extrinsic_1_T_0 as I depend on stereo vision
X) Specify the path for saving/loading state. Keep value as empty string to disable the function.
For example if you kept loadStateFromDisk as empty string, I will not load aka fresh start.
Similarly if you kept saveStateToDisk as empty, I will not write data to disk upon exit
-->
<node name="cerebro_node" pkg="cerebro" type="cerebro_node" output="screen">
<param name="config_file" type="string" value="$(arg config_path)" />
<!-- <param name="loadStateFromDisk" type="string" value="/Bulk_Data/chkpts_cerebro/" /> -->
<param name="loadStateFromDisk" type="string" value="" />
<param name="saveStateToDisk" type="string" value="/Bulk_Data/chkpts_cerebro/" />
<!-- <param name="saveStateToDisk" type="string" value="" /> -->
</node>
<!-- KERAS SERVER -->
<!-- $(ubuntu) rosrun cerebro whole_image_desc_compute_server.py _config_file:=/app/catk_ws/src/cerebro/config/vinsfusion/euroc/euroc_stereo_imu_config.yaml -->
<node name="my_desc_server" pkg="cerebro" type="whole_image_desc_compute_server.py" output="log">
<!-- <param name="kerasmodel_file" type="string" value="$(find cerebro)/scripts/keras.models/modelarch_and_weights.h5" /> -->
<!-- <param name="kerasmodel_file" type="string" value="/models.keras/June2019/centeredinput-m1to1-240x320x3__mobilenet-conv_pw_6_relu__K16__allpairloss/modelarch_and_weights.500.h5" /> -->
<!-- <param name="kerasmodel_file" type="string" value="$(find cerebro)/scripts/keras.models/June2019/centeredinput-m1to1-240x320x3__mobilenet-conv_pw_6_relu__K16__allpairloss/modelarch_and_weights.700.h5" /> -->
<!-- <param name="kerasmodel_file" type="string" value="$(find cerebro)/scripts/keras.models/June2019/centeredinput-m1to1-240x320x3__mobilenetv2-block_9_add__K16__allpairloss/modelarch_and_weights.800.h5" /> -->
<!-- <param name="kerasmodel_file" type="string" value="/models.keras/June2019/centeredinput-m1to1-240x320x1__mobilenetv2-block_9_add__K16__allpairloss/modelarch_and_weights.2000.h5" /> -->
<param name="kerasmodel_file" type="string" value="$(find cerebro)/scripts/keras.models/June2019/centeredinput-m1to1-240x320x1__mobilenetv2-block_9_add__K16__allpairloss/modelarch_and_weights.2000.h5" />
<param name="config_file" type="string" value="$(arg config_path)" />
<!-- OR -->
<!--
<param name="nrows" type="string" value="480" />
<param name="ncols" type="string" value="752" />
-->
<!-- this is needed irrespective of the config_file or the nrows and ncols set manually here. -->
<param name="nchnls" type="string" value="1" />
<!-- <param name="nchnls" type="string" value="3" /> -->
</node>
<!-- Pose graph (kidnap aware) -->
<!-- $(ubuntu) rosrun solve_keyframe_pose_graph keyframe_pose_graph_slam -->
<node name="keyframe_pose_graph_slam_node" pkg="solve_keyframe_pose_graph" type="keyframe_pose_graph_slam" output="log" >
<!-- <param name="loadStateFromDisk" type="string" value="/Bulk_Data/chkpts_posegraph_solver/" /> -->
<param name="loadStateFromDisk" type="string" value="" />
<param name="saveStateToDisk" type="string" value="/Bulk_Data/chkpts_posegraph_solver/" />
<!-- <param name="saveStateToDisk" type="string" value="" /> -->
</node>
</group>
</launch>
================================================
FILE: launch/realsense_camera.launch
================================================
<launch>
<arg name="serial_no" default=""/>
<arg name="json_file_path" default=""/>
<arg name="camera" default="camera"/>
<arg name="tf_prefix" default="$(arg camera)"/>
<arg name="external_manager" default="false"/>
<arg name="manager" default="realsense2_camera_manager"/>
<arg name="fisheye_width" default="640"/>
<arg name="fisheye_height" default="480"/>
<arg name="enable_fisheye" default="false"/>
<arg name="depth_width" default="640"/>
<arg name="depth_height" default="480"/>
<arg name="enable_depth" default="false"/>
<arg name="infra_width" default="640"/>
<arg name="infra_height" default="480"/>
<arg name="enable_infra1" default="true"/>
<arg name="enable_infra2" default="true"/>
<arg name="color_width" default="640"/>
<arg name="color_height" default="480"/>
<arg name="enable_color" default="false"/>
<arg name="fisheye_fps" default="30"/>
<arg name="depth_fps" default="30"/>
<arg name="infra_fps" default="30"/>
<arg name="color_fps" default="30"/>
<arg name="gyro_fps" default="200"/>
<arg name="accel_fps" default="250"/>
<arg name="enable_gyro" default="true"/>
<arg name="enable_accel" default="true"/>
<arg name="enable_pointcloud" default="false"/>
<arg name="pointcloud_texture_stream" default="RS2_STREAM_COLOR"/>
<arg name="pointcloud_texture_index" default="0"/>
<arg name="enable_sync" default="true"/>
<arg name="align_depth" default="false"/>
<arg name="filters" default=""/>
<arg name="clip_distance" default="-2"/>
<arg name="linear_accel_cov" default="0.01"/>
<arg name="initial_reset" default="false"/>
<arg name="unite_imu_method" default="linear_interpolation"/>
<arg name="hold_back_imu_for_frames" default="false"/>
<arg name="topic_odom_in" default="odom_in"/>
<arg name="calib_odom_file" default=""/>
<arg name="publish_odom_tf" default="true"/>
<arg name="allow_no_texture_points" default="false "/>
<rosparam>
/camera/stereo_module/emitter_enabled: false
</rosparam>
<group ns="$(arg camera)">
<include file="$(find realsense2_camera)/launch/includes/nodelet.launch.xml">
<arg name="tf_prefix" value="$(arg tf_prefix)"/>
<!-- <arg name="external_manager" value="$(arg external_manager)"/> -->
<arg name="manager" value="$(arg manager)"/>
<arg name="serial_no" value="$(arg serial_no)"/>
<arg name="json_file_path" value="$(arg json_file_path)"/>
<arg name="enable_pointcloud" value="$(arg enable_pointcloud)"/>
<arg name="pointcloud_texture_stream" value="$(arg pointcloud_texture_stream)"/>
<arg name="pointcloud_texture_index" value="$(arg pointcloud_texture_index)"/>
<arg name="enable_sync" value="$(arg enable_sync)"/>
<arg name="align_depth" value="$(arg align_depth)"/>
<arg name="fisheye_width" value="$(arg fisheye_width)"/>
<arg name="fisheye_height" value="$(arg fisheye_height)"/>
<arg name="enable_fisheye" value="$(arg enable_fisheye)"/>
<arg name="depth_width" value="$(arg depth_width)"/>
<arg name="depth_height" value="$(arg depth_height)"/>
<arg name="enable_depth" value="$(arg enable_depth)"/>
<arg name="color_width" value="$(arg color_width)"/>
<arg name="color_height" value="$(arg color_height)"/>
<arg name="enable_color" value="$(arg enable_color)"/>
<arg name="infra_width" value="$(arg infra_width)"/>
<arg name="infra_height" value="$(arg infra_height)"/>
<arg name="enable_infra1" value="$(arg enable_infra1)"/>
<arg name="enable_infra2" value="$(arg enable_infra2)"/>
<arg name="fisheye_fps" value="$(arg fisheye_fps)"/>
<arg name="depth_fps" value="$(arg depth_fps)"/>
<arg name="infra_fps" value="$(arg infra_fps)"/>
<arg name="color_fps" value="$(arg color_fps)"/>
<arg name="gyro_fps" value="$(arg gyro_fps)"/>
<arg name="accel_fps" value="$(arg accel_fps)"/>
<arg name="enable_gyro" value="$(arg enable_gyro)"/>
<arg name="enable_accel" value="$(arg enable_accel)"/>
<arg name="filters" value="$(arg filters)"/>
<arg name="clip_distance" value="$(arg clip_distance)"/>
<arg name="linear_accel_cov" value="$(arg linear_accel_cov)"/>
<arg name="initial_reset" value="$(arg initial_reset)"/>
<arg name="unite_imu_method" value="$(arg unite_imu_method)"/>
<arg name="topic_odom_in" value="$(arg topic_odom_in)"/>
<arg name="calib_odom_file" value="$(arg calib_odom_file)"/>
<arg name="publish_odom_tf" value="$(arg publish_odom_tf)"/>
<arg name="allow_no_texture_points" value="$(arg allow_no_texture_points)"/>
</include>
</group>
</launch>
================================================
FILE: launch/realsense_vinsfusion.launch
================================================
<launch timeout="100.0">
<!-- CONFIG FILE -->
<arg name="config_path" default="$(find cerebro)/config/vinsfusion/djirosimu_realsense_d435i/realsense_stereo_imu_config.yaml" />
<!-- BAG -->
<!-- <arg name="bag_path" default="/Bulk_Data/ros_bags/realsense/" /> -->
<!-- Teach repeat -->
<arg name="bag_file" default="/teach-repeat-bags/2019-07-09-11-06-23.bag" doc="teach"/>
<!-- <arg name="bag_file" default="/teach-repeat-bags/2019-07-09-11-08-10.bag" doc="teach"/> -->
<!-- <node pkg="rosbag" type="play" name="rosbag" args="$(arg bag_path)/$(arg bag_file) -s 1 -d 2" output="log"/> -->
<!-- END Bag -->
<!-- VINS-Fusion Estimator -->
<!-- unlike previous vins-mono, even the feature tracker is put inside 1 node ie. vins_node.
$(ubuntu) rosrun vins vins_node /app/catkin_ws/src/cerebro/config/vinsfusion/mynteye/mynteye_stereo_imu_config.yaml
-->
<node name="vins_estimator" pkg="vins" type="vins_node" args=" $(arg config_path)" output="screen">
</node>
<group if="0">
<!-- VINS-Fusion loop_fusion -->
<!-- This is the DBOW + posegraph optimization from Qin Tong
$(ubuntu) rosrun loop_fusion loop_fusion_node /app/catkin_ws/src/cerebro/config/vinsfusion/euroc/euroc_stereo_imu_config.yaml
-->
<node name="loop_fusion" pkg="loop_fusion" type="loop_fusion_node" args=" $(arg config_path)" output="log">
</node>
</group>
<group if="0">
<!-- Cerebro -->
<node name="cerebro_node" pkg="cerebro" type="cerebro_node" output="log">
<param name="config_file" type="string" value="$(arg config_path)" />
<!-- <param name="loadStateFromDisk" type="string" value="" />
<param name="saveStateToDisk" type="string" value="/Bulk_Data/chkpts_cerebro/" /> -->
<param name="loadStateFromDisk" type="string" value="/Bulk_Data/chkpts_cerebro/" />
<param name="saveStateToDisk" type="string" value="" />
</node>
<!-- KERAS SERVER -->
<!-- $(ubuntu) rosrun cerebro whole_image_desc_compute_server.py _config_file:=/app/catk_ws/src/cerebro/config/vinsfusion/euroc/euroc_stereo_imu_config.yaml -->
<node name="my_desc_server" pkg="cerebro" type="whole_image_desc_compute_server.py" output="log">
<!-- <param name="kerasmodel_file" type="string" value="$(find cerebro)/scripts/keras.models/mobilenet_conv7_allpairloss.keras" /> -->
<!-- <param name="kerasmodel_file" type="string" value="$(find cerebro)/scripts/keras.models/modelarch_and_weights.h5" /> -->
<!-- <param name="kerasmodel_file" type="string" value="$(find cerebro)/scripts/keras.models/June2019/centeredinput-m1to1-240x320x3__mobilenet-conv_pw_6_relu__K16__allpairloss/modelarch_and_weights.700.h5" /> -->
<!-- <param name="kerasmodel_file" type="string" value="$(find cerebro)/scripts/keras.models/June2019/centeredinput-m1to1-240x320x3__mobilenetv2-block_9_add__K16__allpairloss/modelarch_and_weights.800.h5" /> -->
<param name="kerasmodel_file" type="string" value="$(find cerebro)/scripts/keras.models/June2019/centeredinput-m1to1-240x320x1__mobilenetv2-block_9_add__K16__allpairloss/modelarch_and_weights.2000.h5" />
<param name="config_file" type="string" value="$(arg config_path)" />
<!-- OR -->
<!--
<param name="nrows" type="string" value="480" />
<param name="ncols" type="string" value="752" />
-->
<param name="nchnls" type="string" value="1" />
<!-- <param name="nchnls" type="string" value="3" /> -->
</node>
<!-- Pose graph (kidnap aware) -->
<!-- $(ubuntu) rosrun solve_keyframe_pose_graph keyframe_pose_graph_slam -->
<node name="keyframe_pose_graph_slam_node" pkg="solve_keyframe_pose_graph" type="keyframe_pose_graph_slam" output="screen" >
<!-- <param name="loadStateFromDisk" type="string" value="" />
<param name="saveStateToDisk" type="string" value="/Bulk_Data/chkpts_posegraph_solver/" /> -->
<param name="loadStateFromDisk" type="string" value="/Bulk_Data/chkpts_posegraph_solver/" />
<param name="saveStateToDisk" type="string" value="" />
</node>
</group>
</launch>
================================================
FILE: launch/realsense_vinsfusion_ondrone_repeat.launch
================================================
<launch timeout="100.0">
<!-- CONFIG FILE -->
<arg name="config_path" default="$(find cerebro)/config/vinsfusion/realsense_d435i/realsense_stereo_imu_config.yaml" />
<!-- BAG -->
<arg name="bag_path" default="/Bulk_Data/ros_bags/realsense/" />
<!-- Teach repeat -->
<arg name="bag_file" default="/teach-repeat-bags/2019-07-09-11-06-23.bag" doc="teach"/>
<!-- <arg name="bag_file" default="/teach-repeat-bags/2019-07-09-11-08-10.bag" doc="teach"/> -->
<!-- <node pkg="rosbag" type="play" name="rosbag" args="$(arg bag_path)/$(arg bag_file) -s 1 -d 2" output="log"/> -->
<!-- END Bag -->
<!-- VINS-Fusion Estimator -->
<!-- unlike previous vins-mono, even the feature tracker is put inside 1 node ie. vins_node.
$(ubuntu) rosrun vins vins_node /app/catkin_ws/src/cerebro/config/vinsfusion/mynteye/mynteye_stereo_imu_config.yaml
-->
<node name="vins_estimator" pkg="vins" type="vins_node" args=" $(arg config_path)" output="log">
</node>
<group if="0">
<!-- VINS-Fusion loop_fusion -->
<!-- This is the DBOW + posegraph optimization from Qin Tong
$(ubuntu) rosrun loop_fusion loop_fusion_node /app/catkin_ws/src/cerebro/config/vinsfusion/euroc/euroc_stereo_imu_config.yaml
-->
<node name="loop_fusion" pkg="loop_fusion" type="loop_fusion_node" args=" $(arg config_path)" output="log">
</node>
</group>
<group if="1">
<!-- Cerebro -->
<node name="cerebro_node" pkg="cerebro" type="cerebro_node" output="log">
<param name="config_file" type="string" value="$(arg config_path)" />
<param name="loadStateFromDisk" type="string" value="/Bulk_Data/chkpts_cerebro/" />
<param name="saveStateToDisk" type="string" value="" />
</node>
<!-- no need to run the default server as the server is run else using the package https://github.com/mpkuse/tx2_whole_image_desc_server -->
<group if="1" >
<!-- KERAS SERVER -->
<!-- $(ubuntu) rosrun cerebro whole_image_desc_compute_server.py _config_file:=/app/catk_ws/src/cerebro/config/vinsfusion/euroc/euroc_stereo_imu_config.yaml -->
<node name="my_desc_server" pkg="cerebro" type="whole_image_desc_compute_server.py" output="log">
<!-- <param name="kerasmodel_file" type="string" value="$(find cerebro)/scripts/keras.models/mobilenet_conv7_allpairloss.keras" /> -->
<!-- <param name="kerasmodel_file" type="string" value="$(find cerebro)/scripts/keras.models/modelarch_and_weights.h5" /> -->
<!-- <param name="kerasmodel_file" type="string" value="$(find cerebro)/scripts/keras.models/June2019/centeredinput-m1to1-240x320x3__mobilenet-conv_pw_6_relu__K16__allpairloss/modelarch_and_weights.700.h5" /> -->
<!-- <param name="kerasmodel_file" type="string" value="$(find cerebro)/scripts/keras.models/June2019/centeredinput-m1to1-240x320x3__mobilenetv2-block_9_add__K16__allpairloss/modelarch_and_weights.800.h5" /> -->
<param name="kerasmodel_file" type="string" value="$(find cerebro)/scripts/keras.models/June2019/centeredinput-m1to1-240x320x1__mobilenetv2-block_9_add__K16__allpairloss/modelarch_and_weights.2000.h5" />
<param name="config_file" type="string" value="$(arg config_path)" />
<!-- OR -->
<!--
<param name="nrows" type="string" value="480" />
<param name="ncols" type="string" value="752" />
-->
<param name="nchnls" type="string" value="1" />
<!-- <param name="nchnls" type="string" value="3" /> -->
</node>
</group>
<!-- Pose graph (kidnap aware) -->
<!-- $(ubuntu) rosrun solve_keyframe_pose_graph keyframe_pose_graph_slam -->
<node name="keyframe_pose_graph_slam_node" pkg="solve_keyframe_pose_graph" type="keyframe_pose_graph_slam" output="screen" >
<param name="loadStateFromDisk" type="string" value="/Bulk_Data/chkpts_posegraph_solver/" />
<param name="saveStateToDisk" type="string" value="" />
<param name="adhoc_pubpath" type="string" value="true" />
<param name="adhoc_pubw0_T_w1" type="string" value="false" />
</node>
</group>
</launch>
================================================
FILE: launch/realsense_vinsfusion_ondrone_teach.launch
================================================
<launch timeout="100.0">
<!-- CONFIG FILE -->
<arg name="config_path" default="$(find cerebro)/config/vinsfusion/realsense_d435i/realsense_stereo_imu_config.yaml" />
<!-- BAG -->
<arg name="bag_path" default="/Bulk_Data/ros_bags/realsense/" />
<!-- Teach repeat -->
<arg name="bag_file" default="/teach-repeat-bags/2019-07-09-11-06-23.bag" doc="teach"/>
<!-- <arg name="bag_file" default="/teach-repeat-bags/2019-07-09-11-08-10.bag" doc="teach"/> -->
<!-- <node pkg="rosbag" type="play" name="rosbag" args="$(arg bag_path)/$(arg bag_file) -s 1 -d 2" output="log"/> -->
<!-- END Bag -->
<!-- VINS-Fusion Estimator -->
<!-- unlike previous vins-mono, even the feature tracker is put inside 1 node ie. vins_node.
$(ubuntu) rosrun vins vins_node /app/catkin_ws/src/cerebro/config/vinsfusion/mynteye/mynteye_stereo_imu_config.yaml
-->
<node name="vins_estimator" pkg="vins" type="vins_node" args=" $(arg config_path)" output="log">
</node>
<group if="0">
<!-- VINS-Fusion loop_fusion -->
<!-- This is the DBOW + posegraph optimization from Qin Tong
$(ubuntu) rosrun loop_fusion loop_fusion_node /app/catkin_ws/src/cerebro/config/vinsfusion/euroc/euroc_stereo_imu_config.yaml
-->
<node name="loop_fusion" pkg="loop_fusion" type="loop_fusion_node" args=" $(arg config_path)" output="log">
</node>
</group>
<group if="1">
<!-- Cerebro -->
<node name="cerebro_node" pkg="cerebro" type="cerebro_node" output="screen">
<param name="config_file" type="string" value="$(arg config_path)" />
<param name="loadStateFromDisk" type="string" value="" />
<param name="saveStateToDisk" type="string" value="/Bulk_Data/chkpts_cerebro/" />
</node>
<!-- no need to run the default server as the server is run else using the package https://github.com/mpkuse/tx2_whole_image_desc_server -->
<group if="1" >
<!-- KERAS SERVER -->
<!-- $(ubuntu) rosrun cerebro whole_image_desc_compute_server.py _config_file:=/app/catk_ws/src/cerebro/config/vinsfusion/euroc/euroc_stereo_imu_config.yaml -->
<node name="my_desc_server" pkg="cerebro" type="whole_image_desc_compute_server.py" output="log">
<!-- <param name="kerasmodel_file" type="string" value="$(find cerebro)/scripts/keras.models/mobilenet_conv7_allpairloss.keras" /> -->
<!-- <param name="kerasmodel_file" type="string" value="$(find cerebro)/scripts/keras.models/modelarch_and_weights.h5" /> -->
<!-- <param name="kerasmodel_file" type="string" value="$(find cerebro)/scripts/keras.models/June2019/centeredinput-m1to1-240x320x3__mobilenet-conv_pw_6_relu__K16__allpairloss/modelarch_and_weights.700.h5" /> -->
<!-- <param name="kerasmodel_file" type="string" value="$(find cerebro)/scripts/keras.models/June2019/centeredinput-m1to1-240x320x3__mobilenetv2-block_9_add__K16__allpairloss/modelarch_and_weights.800.h5" /> -->
<param name="kerasmodel_file" type="string" value="$(find cerebro)/scripts/keras.models/June2019/centeredinput-m1to1-240x320x1__mobilenetv2-block_9_add__K16__allpairloss/modelarch_and_weights.2000.h5" />
<param name="config_file" type="string" value="$(arg config_path)" />
<!-- OR -->
<!--
<param name="nrows" type="string" value="480" />
<param name="ncols" type="string" value="752" />
-->
<param name="nchnls" type="string" value="1" />
<!-- <param name="nchnls" type="string" value="3" /> -->
</node>
</group>
<!-- Pose graph (kidnap aware) -->
<!-- $(ubuntu) rosrun solve_keyframe_pose_graph keyframe_pose_graph_slam -->
<node name="keyframe_pose_graph_slam_node" pkg="solve_keyframe_pose_graph" type="keyframe_pose_graph_slam" output="log" >
<param name="loadStateFromDisk" type="string" value="" />
<param name="saveStateToDisk" type="string" value="/Bulk_Data/chkpts_posegraph_solver/" />
<param name="adhoc_pubpath" type="string" value="true" />
<param name="adhoc_pubw0_T_w1" type="string" value="false" />
</node>
</group>
</launch>
================================================
FILE: msg/LoopEdge.msg
================================================
time timestamp0
time timestamp1
geometry_msgs/Pose pose_1T0 # pose of 0 as observed from 1.
float32 weight
string description
================================================
FILE: package.xml
================================================
<?xml version="1.0"?>
<package>
<name>cerebro</name>
<version>0.0.1</version>
<description>The cerebro package. There is a multi-threaded node which stores all the incoming info from vins.
There is a service to compute image level descriptor. Geometry is also a separate service.</description>
<!-- One maintainer tag required, multiple allowed, one person per tag -->
<!-- Example: -->
<!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
<maintainer email="mpkuse@connect.ust.hk">mpkuse</maintainer>
<!-- One license tag required, multiple allowed, one license per tag -->
<!-- Commonly used license strings: -->
<!-- BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->
<license>TODO</license>
<!-- Url tags are optional, but mutiple are allowed, one per tag -->
<!-- Optional attribute type can be: website, bugtracker, or repository -->
<!-- Example: -->
<!-- <url type="website">http://wiki.ros.org/cerebro</url> -->
<!-- Author tags are optional, mutiple are allowed, one per tag -->
<!-- Authors do not have to be maintianers, but could be -->
<!-- Example: -->
<!-- <author email="jane.doe@example.com">Jane Doe</author> -->
<!-- The *_depend tags are used to specify dependencies -->
<!-- Dependencies can be catkin packages or system dependencies -->
<!-- Examples: -->
<!-- Use build_depend for packages you need at compile time: -->
<!-- <build_depend>message_generation</build_depend> -->
<!-- Use buildtool_depend for build tool packages: -->
<!-- <buildtool_depend>catkin</buildtool_depend> -->
<!-- Use run_depend for packages you need at runtime: -->
<!-- <run_depend>message_runtime</run_depend> -->
<!-- Use test_depend for packages you need only for testing: -->
<!-- <test_depend>gtest</test_depend> -->
<buildtool_depend>catkin</buildtool_depend>
<build_depend>cv_bridge</build_depend>
<build_depend>image_transport</build_depend>
<build_depend>roscpp</build_depend>
<build_depend>rospy</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>message_generation</build_depend>
<run_depend>cv_bridge</run_depend>
<run_depend>image_transport</run_depend>
<run_depend>roscpp</run_depend>
<run_depend>rospy</run_depend>
<run_depend>std_msgs</run_depend>
<run_depend>message_runtime</run_depend>
<!-- The export tag contains other, unspecified, tags -->
<export>
<!-- Other tools can request additional information be placed here -->
</export>
</package>
================================================
FILE: rviz/dev-config.rviz
================================================
Panels:
- Class: rviz/Displays
Help Height: 78
Name: Displays
Property Tree Widget:
Expanded:
- /Global Options1
- /Status1
- /Ref1
- /Ref1/Grid1
- /Feat Tracker1/Input Image1
- /Feat Tracker1/Input Image1/Status1
- /VIO1
- /VIO1/Odom In Cam-frame-of-ref1/Cam Odometry1
- /Cerebro1
- /Cerebro1/Marker1
- /Cerebro1/Marker1/Namespaces1
- /AR_demo1
- /AR_demo1/AR_image_odm1/Status1
- /Solve Pose Graph Opt1
- /Solve Pose Graph Opt1/Marker1
- /Solve Pose Graph Opt1/Marker1/Status1
- /Solve Pose Graph Opt1/Marker1/Namespaces1
- /Solve Pose Graph Opt1/Debug Node Marker1/Namespaces1
Splitter Ratio: 0.62647754
Tree Height: 697
- Class: rviz/Selection
Name: Selection
- Class: rviz/Tool Properties
Expanded:
- /2D Pose Estimate1
- /2D Nav Goal1
- /Publish Point1
Name: Tool Properties
Splitter Ratio: 0.588679016
- Class: rviz/Time
Experimental: false
Name: Time
SyncMode: 0
SyncSource: Tracked Features
- Class: rviz/Displays
Help Height: 78
Name: Displays
Property Tree Widget:
Expanded: ~
Splitter Ratio: 0.5
Tree Height: 141
Visualization Manager:
Class: ""
Displays:
- Class: rviz/Group
Displays:
- Class: rviz/Axes
Enabled: true
Length: 1
Name: Axes
Radius: 0.200000003
Reference Frame: <Fixed Frame>
Value: true
- Alpha: 0.5
Cell Size: 1
Class: rviz/Grid
Color: 160; 160; 164
Enabled: true
Line Style:
Line Width: 0.0299999993
Value: Lines
Name: Grid
Normal Cell Count: 0
Offset:
X: 0
Y: 0
Z: 0
Plane: XY
Plane Cell Count: 20
Reference Frame: <Fixed Frame>
Value: true
Enabled: true
Name: Ref
- Class: rviz/Group
Displays:
- Class: rviz/Image
Enabled: false
Image Topic: /cam0/image_raw
Max Value: 1
Median window: 5
Min Value: 0
Name: Input Image
Normalize Range: true
Queue Size: 2
Transport Hint: raw
Unreliable: false
Value: false
- Class: rviz/Image
Enabled: true
Image Topic: /feature_tracker/feature_img
Max Value: 1
Median window: 5
Min Value: 0
Name: Tracked Features
Normalize Range: true
Queue Size: 2
Transport Hint: raw
Unreliable: false
Value: true
Enabled: true
Name: Feat Tracker
- Class: rviz/Group
Displays:
- Alpha: 1
Buffer Length: 1
Class: rviz/Path
Color: 255; 85; 255
Enabled: true
Head Diameter: 0.300000012
Head Length: 0.200000003
Length: 0.300000012
Line Style: Lines
Line Width: 0.0299999993
Name: VIO Path
Offset:
X: 0
Y: 0
Z: 0
Pose Style: None
Radius: 0.0299999993
Shaft Diameter: 0.100000001
Shaft Length: 0.100000001
Topic: /vins_estimator/path
Unreliable: false
Value: true
- Class: rviz/MarkerArray
Enabled: true
Marker Topic: /vins_estimator/camera_pose_visual
Name: Visual
Namespaces:
{}
Queue Size: 100
Value: true
- Alpha: 1
Autocompute Intensity Bounds: true
Autocompute Value Bounds:
Max Value: 1.46719348
Min Value: -0.613372922
Value: true
Axis: Z
Channel Name: intensity
Class: rviz/PointCloud
Color: 0; 255; 0
Color Transformer: FlatColor
Decay Time: 100
Enabled: false
Invert Rainbow: false
Max Color: 255; 255; 255
Max Intensity: 4096
Min Color: 0; 0; 0
Min Intensity: 0
Name: KF PointCloud
Position Transformer: XYZ
Queue Size: 100
Selectable: true
Size (Pixels): 3
Size (m): 0.00999999978
Style: Points
Topic: /vins_estimator/keyframe_point
Unreliable: false
Use Fixed Frame: true
Use rainbow: true
Value: false
- Alpha: 1
Autocompute Intensity Bounds: true
Autocompute Value Bounds:
Max Value: 10
Min Value: -10
Value: true
Axis: Z
Channel Name: intensity
Class: rviz/PointCloud
Color: 255; 255; 255
Color Transformer: Intensity
Decay Time: 100
Enabled: false
Invert Rainbow: false
Max Color: 255; 255; 255
Max Intensity: 4096
Min Color: 0; 0; 0
Min Intensity: 0
Name: PointCloud
Position Transformer: XYZ
Queue Size: 10
Selectable: true
Size (Pixels): 3
Size (m): 0.00999999978
Style: Points
Topic: /vins_estimator/point_cloud
Unreliable: false
Use Fixed Frame: true
Use rainbow: true
Value: false
- Angle Tolerance: 0.100000001
Class: rviz/Odometry
Color: 170; 85; 255
Enabled: false
Keep: 100
Length: 1
Name: imu_T_cam
Position Tolerance: 0.100000001
Topic: /vins_estimator/extrinsic
Value: false
- Class: rviz/Group
Displays:
- Angle Tolerance: 0.100000001
Class: rviz/Odometry
Color: 255; 25; 0
Enabled: true
Keep: 100
Length: 1
Name: Cam Odometry
Position Tolerance: 0.100000001
Topic: /vins_estimator/camera_pose
Value: true
Enabled: false
Name: Odom In Cam-frame-of-ref
- Class: rviz/Group
Displays:
- Angle Tolerance: 0.100000001
Class: rviz/Odometry
Color: 0; 255; 0
Enabled: true
Keep: 100
Length: 1
Name: KF Odometry
Position Tolerance: 0.100000001
Topic: /vins_estimator/keyframe_pose
Value: true
- Angle Tolerance: 0.100000001
Class: rviz/Odometry
Color: 0; 170; 255
Enabled: true
Keep: 100
Length: 1
Name: IMU Odometry
Position Tolerance: 0.100000001
Topic: /vins_estimator/odometry
Value: true
- Angle Tolerance: 0.100000001
Class: rviz/Odometry
Color: 255; 25; 0
Enabled: true
Keep: 100
Length: 1
Name: IMU Prop 200hz
Position Tolerance: 0.100000001
Topic: /vins_estimator/imu_propagate
Value: true
Enabled: false
Name: Odom In IMU-Frame-of-ref
- Class: rviz/Group
Displays:
- Angle Tolerance: 0.100000001
Class: rviz/Odometry
Color: 255; 25; 0
Enabled: false
Keep: 100
Length: 1
Name: vinsmono-reloc-odom
Position Tolerance: 0.100000001
Topic: /vins_estimator/relo_relative_pose
Value: false
- Alpha: 1
Buffer Length: 1
Class: rviz/Path
Color: 255; 85; 255
Enabled: true
Head Diameter: 0.300000012
Head Length: 0.200000003
Length: 0.300000012
Line Style: Lines
Line Width: 0.0299999993
Name: vinsmono-relocalized_path
Offset:
X: 0
Y: 0
Z: 0
Pose Style: None
Radius: 0.0299999993
Shaft Diameter: 0.100000001
Shaft Length: 0.100000001
Topic: /vins_estimator/relocalization_path
Unreliable: false
Value: true
- Class: rviz/Image
Enabled: true
Image Topic: /pose_graph/match_image
Max Value: 1
Median window: 5
Min Value: 0
Name: vins-monomatch-images
Normalize Range: true
Queue Size: 2
Transport Hint: raw
Unreliable: false
Value: true
- Class: rviz/MarkerArray
Enabled: true
Marker Topic: /pose_graph/pose_graph
Name: vinsmono loop viz
Namespaces:
{}
Queue Size: 100
Value: true
Enabled: false
Name: vins-mono relocalized
Enabled: false
Name: VIO
- Class: rviz/Group
Displays:
- Class: rviz/Marker
Enabled: false
Marker Topic: /cerebro_node/viz/framedata
Name: Marker
Namespaces:
{}
Queue Size: 100
Value: false
- Class: rviz/Image
Enabled: true
Image Topic: /cerebro_node/viz/imagepaire
Max Value: 1
Median window: 5
Min Value: 0
Name: imagepaire
Normalize Range: true
Queue Size: 2
Transport Hint: raw
Unreliable: false
Value: true
Enabled: true
Name: Cerebro
- Class: rviz/Group
Displays:
- Class: rviz/Image
Enabled: true
Image Topic: /ar_demo_node3_corrected/AR_image_corrected
Max Value: 1
Median window: 5
Min Value: 0
Name: AR_image_corrected
Normalize Range: true
Queue Size: 2
Transport Hint: raw
Unreliable: false
Value: true
- Class: rviz/Image
Enabled: true
Image Topic: /ar_demo_node3_odom/AR_image_odom
Max Value: 1
Median window: 5
Min Value: 0
Name: AR_image_odm
Normalize Range: true
Queue Size: 2
Transport Hint: raw
Unreliable: false
Value: true
- Class: rviz/MarkerArray
Enabled: false
Marker Topic: /points_and_lines/AR_object
Name: AR_object
Namespaces:
{}
Queue Size: 100
Value: false
- Class: rviz/InteractiveMarkers
Enable Transparency: true
Enabled: true
Name: InteractiveMarkers
Show Axes: false
Show Descriptions: true
Show Visual Aids: false
Update Topic: /interactive_marker_server/update
Value: true
Enabled: true
Name: AR_demo
- Class: rviz/Group
Displays:
- Class: rviz/Marker
Enabled: true
Marker Topic: /keyframe_pose_graph_slam_node/viz/visualization_marker
Name: Marker
Namespaces:
latest_odometry: true
world##_cam_visual: true
world#-1: true
world#-2: true
world#-3: true
world#-4: true
world#0: true
world#1: true
world#2: true
world#3: true
world#4: true
Queue Size: 100
Value: true
- Class: rviz/Marker
Enabled: false
Marker Topic: /debug_pose_graph_solver/visualization_marker
Name: Debug Node Marker
Namespaces:
{}
Queue Size: 100
Value: false
Enabled: true
Name: Solve Pose Graph Opt
Enabled: true
Global Options:
Background Color: 48; 48; 48
Fixed Frame: world
Frame Rate: 30
Name: root
Tools:
- Class: rviz/Interact
Hide Inactive Objects: true
- Class: rviz/MoveCamera
- Class: rviz/Select
- Class: rviz/FocusCamera
- Class: rviz/Measure
- Class: rviz/SetInitialPose
Topic: /initialpose
- Class: rviz/SetGoal
Topic: /move_base_simple/goal
- Class: rviz/PublishPoint
Single click: true
Topic: /clicked_point
Value: true
Views:
Current:
Class: rviz/Orbit
Distance: 46.7297897
Enable Stereo Rendering:
Stereo Eye Separation: 0.0599999987
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Focal Point:
X: 3.76500964
Y: 2.58213377
Z: -2.90765786
Focal Shape Fixed Size: false
Focal Shape Size: 0.0500000007
Name: Current View
Near Clip Distance: 0.00999999978
Pitch: 1.0647974
Target Frame: <Fixed Frame>
Value: Orbit (rviz)
Yaw: 4.69420815
Saved:
- Class: rviz/Orbit
Distance: 49.6446877
Enable Stereo Rendering:
Stereo Eye Separation: 0.0599999987
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Focal Point:
X: 22.8474731
Y: 20.4583664
Z: -6.84013748
Focal Shape Fixed Size: true
Focal Shape Size: 0.0500000007
Name: Orbit
Near Clip Distance: 0.00999999978
Pitch: 1.16479671
Target Frame: <Fixed Frame>
Value: Orbit (rviz)
Yaw: 5.02046442
Window Geometry:
AR_image_corrected:
collapsed: false
AR_image_odm:
collapsed: false
Displays:
collapsed: false
Height: 1003
Hide Left Dock: false
Hide Right Dock: false
Input Image:
collapsed: false
QMainWindow State: 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
Selection:
collapsed: false
Time:
collapsed: false
Tool Properties:
collapsed: false
Tracked Features:
collapsed: false
Width: 1918
X: 0
Y: 24
imagepaire:
collapsed: false
vins-monomatch-images:
collapsed: false
================================================
FILE: rviz/good-viz.rviz
================================================
Panels:
- Class: rviz/Displays
Help Height: 78
Name: Displays
Property Tree Widget:
Expanded:
- /Global Options1
- /Status1
- /Ref1
- /Ref1/Axes1
- /Feat Tracker1/Input Image1
- /Feat Tracker1/Input Image1/Status1
- /VIO1
- /VIO1/Odom In Cam-frame-of-ref1/Cam Odometry1
- /Cerebro1
- /Cerebro1/Marker1
- /Cerebro1/Marker1/Namespaces1
- /AR_demo1
- /Solve Pose Graph Opt1
- /Solve Pose Graph Opt1/Marker1
- /Solve Pose Graph Opt1/Marker1/Namespaces1
- /Solve Pose Graph Opt1/Debug Node Marker1/Namespaces1
- /Ref21
- /Ref21/Grid1/Offset1
Splitter Ratio: 0.62647754
Tree Height: 805
- Class: rviz/Selection
Name: Selection
- Class: rviz/Tool Properties
Expanded:
- /2D Pose Estimate1
- /2D Nav Goal1
- /Publish Point1
Name: Tool Properties
Splitter Ratio: 0.588679016
- Class: rviz/Time
Experimental: false
Name: Time
SyncMode: 0
SyncSource: Tracked Features
- Class: rviz/Displays
Help Height: 78
Name: Displays
Property Tree Widget:
Expanded: ~
Splitter Ratio: 0.5
Tree Height: 359
Visualization Manager:
Class: ""
Displays:
- Class: rviz/Group
Displays:
- Class: rviz/Axes
Enabled: true
Length: 1
Name: Axes
Radius: 0.200000003
Reference Frame: <Fixed Frame>
Value: true
- Alpha: 0.5
Cell Size: 1
Class: rviz/Grid
Color: 160; 160; 164
Enabled: true
Line Style:
Line Width: 0.0299999993
Value: Lines
Name: Grid
Normal Cell Count: 0
Offset:
X: 0
Y: 0
Z: 0
Plane: XY
Plane Cell Count: 20
Reference Frame: <Fixed Frame>
Value: true
Enabled: true
Name: Ref
- Class: rviz/Group
Displays:
- Class: rviz/Image
Enabled: false
Image Topic: /cam0/image_raw
Max Value: 1
Median window: 5
Min Value: 0
Name: Input Image
Normalize Range: true
Queue Size: 2
Transport Hint: raw
Unreliable: false
Value: false
- Class: rviz/Image
Enabled: true
Image Topic: /feature_tracker/feature_img
Max Value: 1
Median window: 5
Min Value: 0
Name: Tracked Features
Normalize Range: true
Queue Size: 2
Transport Hint: raw
Unreliable: false
Value: true
Enabled: true
Name: Feat Tracker
- Class: rviz/Group
Displays:
- Alpha: 1
Buffer Length: 1
Class: rviz/Path
Color: 255; 85; 255
Enabled: true
Head Diameter: 0.300000012
Head Length: 0.200000003
Length: 0.300000012
Line Style: Lines
Line Width: 0.0299999993
Name: VIO Path
Offset:
X: 0
Y: 0
Z: 0
Pose Style: None
Radius: 0.0299999993
Shaft Diameter: 0.100000001
Shaft Length: 0.100000001
Topic: /vins_estimator/path
Unreliable: false
Value: true
- Class: rviz/MarkerArray
Enabled: true
Marker Topic: /vins_estimator/camera_pose_visual
Name: Visual
Namespaces:
{}
Queue Size: 100
Value: true
- Alpha: 1
Autocompute Intensity Bounds: true
Autocompute Value Bounds:
Max Value: 1.46719348
Min Value: -0.613372922
Value: true
Axis: Z
Channel Name: intensity
Class: rviz/PointCloud
Color: 0; 255; 0
Color Transformer: FlatColor
Decay Time: 100
Enabled: false
Invert Rainbow: false
Max Color: 255; 255; 255
Max Intensity: 4096
Min Color: 0; 0; 0
Min Intensity: 0
Name: KF PointCloud
Position Transformer: XYZ
Queue Size: 100
Selectable: true
Size (Pixels): 3
Size (m): 0.00999999978
Style: Points
Topic: /vins_estimator/keyframe_point
Unreliable: false
Use Fixed Frame: true
Use rainbow: true
Value: false
- Alpha: 1
Autocompute Intensity Bounds: true
Autocompute Value Bounds:
Max Value: 10
Min Value: -10
Value: true
Axis: Z
Channel Name: intensity
Class: rviz/PointCloud
Color: 255; 255; 255
Color Transformer: Intensity
Decay Time: 100
Enabled: false
Invert Rainbow: false
Max Color: 255; 255; 255
Max Intensity: 4096
Min Color: 0; 0; 0
Min Intensity: 0
Name: PointCloud
Position Transformer: XYZ
Queue Size: 10
Selectable: true
Size (Pixels): 3
Size (m): 0.00999999978
Style: Points
Topic: /vins_estimator/point_cloud
Unreliable: false
Use Fixed Frame: true
Use rainbow: true
Value: false
- Angle Tolerance: 0.100000001
Class: rviz/Odometry
Color: 170; 85; 255
Enabled: false
Keep: 100
Length: 1
Name: imu_T_cam
Position Tolerance: 0.100000001
Topic: /vins_estimator/extrinsic
Value: false
- Class: rviz/Group
Displays:
- Angle Tolerance: 0.100000001
Class: rviz/Odometry
Color: 255; 25; 0
Enabled: true
Keep: 100
Length: 1
Name: Cam Odometry
Position Tolerance: 0.100000001
Topic: /vins_estimator/camera_pose
Value: true
Enabled: false
Name: Odom In Cam-frame-of-ref
- Class: rviz/Group
Displays:
- Angle Tolerance: 0.100000001
Class: rviz/Odometry
Color: 0; 255; 0
Enabled: true
Keep: 100
Length: 1
Name: KF Odometry
Position Tolerance: 0.100000001
Topic: /vins_estimator/keyframe_pose
Value: true
- Angle Tolerance: 0.100000001
Class: rviz/Odometry
Color: 0; 170; 255
Enabled: true
Keep: 100
Length: 1
Name: IMU Odometry
Position Tolerance: 0.100000001
Topic: /vins_estimator/odometry
Value: true
- Angle Tolerance: 0.100000001
Class: rviz/Odometry
Color: 255; 25; 0
Enabled: true
Keep: 100
Length: 1
Name: IMU Prop 200hz
Position Tolerance: 0.100000001
Topic: /vins_estimator/imu_propagate
Value: true
Enabled: false
Name: Odom In IMU-Frame-of-ref
- Class: rviz/Group
Displays:
- Angle Tolerance: 0.100000001
Class: rviz/Odometry
Color: 255; 25; 0
Enabled: false
Keep: 100
Length: 1
Name: vinsmono-reloc-odom
Position Tolerance: 0.100000001
Topic: /vins_estimator/relo_relative_pose
Value: false
- Alpha: 1
Buffer Length: 1
Class: rviz/Path
Color: 255; 85; 255
Enabled: true
Head Diameter: 0.300000012
Head Length: 0.200000003
Length: 0.300000012
Line Style: Lines
Line Width: 0.0299999993
Name: vinsmono-relocalized_path
Offset:
X: 0
Y: 0
Z: 0
Pose Style: None
Radius: 0.0299999993
Shaft Diameter: 0.100000001
Shaft Length: 0.100000001
Topic: /vins_estimator/relocalization_path
Unreliable: false
Value: true
- Class: rviz/Image
Enabled: true
Image Topic: /pose_graph/match_image
Max Value: 1
Median window: 5
Min Value: 0
Name: vins-monomatch-images
Normalize Range: true
Queue Size: 2
Transport Hint: raw
Unreliable: false
Value: true
- Class: rviz/MarkerArray
Enabled: true
Marker Topic: /pose_graph/pose_graph
Name: vinsmono loop viz
Namespaces:
{}
Queue Size: 100
Value: true
Enabled: false
Name: vins-mono relocalized
Enabled: false
Name: VIO
- Class: rviz/Group
Displays:
- Class: rviz/Marker
Enabled: true
Marker Topic: /cerebro_node/viz/framedata
Name: Marker
Namespaces:
{}
Queue Size: 100
Value: true
- Class: rviz/Image
Enabled: true
Image Topic: /cerebro_node/viz/imagepaire
Max Value: 1
Median window: 5
Min Value: 0
Name: imagepaire
Normalize Range: true
Queue Size: 2
Transport Hint: raw
Unreliable: false
Value: true
Enabled: true
Name: Cerebro
- Class: rviz/Group
Displays:
- Class: rviz/Image
Enabled: true
Image Topic: /ar_demo_node3_corrected/AR_image_corrected
Max Value: 1
Median window: 5
Min Value: 0
Name: AR_image_corrected
Normalize Range: true
Queue Size: 2
Transport Hint: raw
Unreliable: false
Value: true
- Class: rviz/Image
Enabled: true
Image Topic: /ar_demo_node3_odom/AR_image_odom
Max Value: 1
Median window: 5
Min Value: 0
Name: AR_image_odm
Normalize Range: true
Queue Size: 2
Transport Hint: raw
Unreliable: false
Value: true
- Class: rviz/MarkerArray
Enabled: false
Marker Topic: /points_and_lines/AR_object
Name: AR_object
Namespaces:
{}
Queue Size: 100
Value: false
- Class: rviz/InteractiveMarkers
Enable Transparency: true
Enabled: true
Name: InteractiveMarkers
Show Axes: false
Show Descriptions: true
Show Visual Aids: false
Update Topic: /interactive_marker_server/update
Value: true
Enabled: false
Name: AR_demo
- Class: rviz/Group
Displays:
- Class: rviz/Marker
Enabled: true
Marker Topic: /keyframe_pose_graph_slam_node/viz/visualization_marker
Name: Marker
Namespaces:
{}
Queue Size: 100
Value: true
- Class: rviz/Image
Enabled: true
Image Topic: /keyframe_pose_graph_slam_node/viz/disjoint_set_status_image
Max Value: 1
Median window: 5
Min Value: 0
Name: disjoint_set_status_image
Normalize Range: true
Queue Size: 2
Transport Hint: raw
Unreliable: false
Value: true
- Class: rviz/Marker
Enabled: false
Marker Topic: /debug_pose_graph_solver/visualization_marker
Name: Debug Node Marker
Namespaces:
{}
Queue Size: 100
Value: false
Enabled: true
Name: Solve Pose Graph Opt
- Class: rviz/Group
Displays:
- Alpha: 0.5
Cell Size: 1
Class: rviz/Grid
Color: 40; 164; 44
Enabled: true
Line Style:
Line Width: 0.0299999993
Value: Lines
Name: Grid
Normal Cell Count: 0
Offset:
X: 30
Y: 0
Z: 0
Plane: XY
Plane Cell Count: 20
Reference Frame: <Fixed Frame>
Value: true
Enabled: true
Name: Ref2
Enabled: true
Global Options:
Background Color: 48; 48; 48
Fixed Frame: world
Frame Rate: 30
Name: root
Tools:
- Class: rviz/Interact
Hide Inactive Objects: true
- Class: rviz/MoveCamera
- Class: rviz/Select
- Class: rviz/FocusCamera
- Class: rviz/Measure
- Class: rviz/SetInitialPose
Topic: /initialpose
- Class: rviz/SetGoal
Topic: /move_base_simple/goal
- Class: rviz/PublishPoint
Single click: true
Topic: /clicked_point
Value: true
Views:
Current:
Class: rviz/Orbit
Distance: 49.2109833
Enable Stereo Rendering:
Stereo Eye Separation: 0.0599999987
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Focal Point:
X: 3.41268897
Y: -0.305300832
Z: -1.72543097
Focal Shape Fixed Size: false
Focal Shape Size: 0.0500000007
Name: Current View
Near Clip Distance: 0.00999999978
Pitch: 0.884797573
Target Frame: <Fixed Frame>
Value: Orbit (rviz)
Yaw: 3.05431199
Saved:
- Class: rviz/Orbit
Distance: 49.6446877
Enable Stereo Rendering:
Stereo Eye Separation: 0.0599999987
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Focal Point:
X: 22.8474731
Y: 20.4583664
Z: -6.84013748
Focal Shape Fixed Size: true
Focal Shape Size: 0.0500000007
Name: Orbit
Near Clip Distance: 0.00999999978
Pitch: 1.16479671
Target Frame: <Fixed Frame>
Value: Orbit (rviz)
Yaw: 5.02046442
Window Geometry:
AR_image_corrected:
collapsed: false
AR_image_odm:
collapsed: false
Displays:
collapsed: false
Height: 1003
Hide Left Dock: false
Hide Right Dock: false
Input Image:
collapsed: false
QMainWindow State: 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
Selection:
collapsed: false
Time:
collapsed: false
Tool Properties:
collapsed: false
Tracked Features:
collapsed: false
Width: 1918
X: 0
Y: 24
disjoint_set_status_image:
collapsed: false
imagepaire:
collapsed: false
vins-monomatch-images:
collapsed: false
================================================
FILE: rviz/vins-fusion.rviz
================================================
Panels:
- Class: rviz/Displays
Help Height: 78
Name: Displays
Property Tree Widget:
Expanded:
- /Global Options1
- /Status1
- /raw_input_image1
- /Ref1
- /Ref1/Axes1
- /Ref1/Grid1
- /Feat Tracker1/Input Image1
- /AR_demo1
- /AR_demo1/AR_image_corrected1
- /AR_demo1/AR_image_odm1
- /AR_demo1/ModelViz1
- /AR_demo1/ModelViz1/Status1
- /AR_demo1/ModelViz1/Namespaces1
- /Cerebro1
- /Cerebro1/Marker1
- /Cerebro1/Marker1/Namespaces1
- /Solve Pose Graph Opt1/Marker1
- /Solve Pose Graph Opt1/Marker1/Namespaces1
- /Solve Pose Graph Opt1/Debug Node Marker1/Namespaces1
- /VINS-fusion1/MarkerArray1/Namespaces1
- /VINS-fusion1/VIO Path1
- /VINS-fusion1/VIO Path1/Offset1
- /VINS-fusion1/After Loop Fusion1
- /VINS-fusion1/Loop Fusion Edges1
- /Marker1
- /Surfel Mapping1/PointCloud21
Splitter Ratio: 0.62647754
Tree Height: 853
- Class: rviz/Selection
Name: Selection
- Class: rviz/Tool Properties
Expanded:
- /2D Pose Estimate1
- /2D Nav Goal1
- /Publish Point1
Name: Tool Properties
Splitter Ratio: 0.588679016
- Class: rviz/Time
Experimental: false
Name: Time
SyncMode: 0
SyncSource: raw_input_image
- Class: rviz/Displays
Help Height: 78
Name: Displays
Property Tree Widget:
Expanded: ~
Splitter Ratio: 0.5
Tree Height: 359
- Class: rviz/Views
Expanded:
- /Current View1
Name: Views
Splitter Ratio: 0.5
Visualization Manager:
Class: ""
Displays:
- Class: rviz/Image
Enabled: true
Image Topic: /camera/infra1/image_rect_raw
Max Value: 1
Median window: 5
Min Value: 0
Name: raw_input_image
Normalize Range: true
Queue Size: 2
Transport Hint: raw
Unreliable: false
Value: true
- Class: rviz/Group
Displays:
- Class: rviz/Axes
Enabled: false
Length: 1
Name: Axes
Radius: 0.200000003
Reference Frame: <Fixed Frame>
Value: false
- Alpha: 0.5
Cell Size: 1
Class: rviz/Grid
Color: 160; 160; 164
Enabled: true
Line Style:
Line Width: 0.0299999993
Value: Lines
Name: Grid
Normal Cell Count: 0
Offset:
X: 0
Y: 0
Z: 0
Plane: XY
Plane Cell Count: 20
Reference Frame: <Fixed Frame>
Value: true
Enabled: true
Name: Ref
- Class: rviz/Group
Displays:
- Alpha: 0.5
Cell Size: 1
Class: rviz/Grid
Color: 40; 164; 44
Enabled: true
Line Style:
Line Width: 0.0299999993
Value: Lines
Name: Grid
Normal Cell Count: 0
Offset:
X: 30
Y: 0
Z: 0
Plane: XY
Plane Cell Count: 20
Reference Frame: <Fixed Frame>
Value: true
Enabled: true
Name: Ref2
- Class: rviz/Group
Displays:
- Class: rviz/Image
Enabled: true
Image Topic: /cam0/image_raw
Max Value: 1
Median window: 5
Min Value: 0
Name: Input Image
Normalize Range: true
Queue Size: 2
Transport Hint: raw
Unreliable: false
Value: true
- Class: rviz/Image
Enabled: true
Image Topic: /feature_tracker/feature_img
Max Value: 1
Median window: 5
Min Value: 0
Name: Tracked Features
Normalize Range: true
Queue Size: 2
Transport Hint: raw
Unreliable: false
Value: true
Enabled: false
Name: Feat Tracker
- Class: rviz/Group
Displays:
- Class: rviz/Image
Enabled: true
Image Topic: /ar_demo_node3_odom/AR_image_corrected
Max Value: 1
Median window: 5
Min Value: 0
Name: AR_image_corrected
Normalize Range: true
Queue Size: 2
Transport Hint: raw
Unreliable: false
Value: true
- Class: rviz/Image
Enabled: false
Image Topic: /ar_demo_node3_odom/AR_image_odom
Max Value: 1
Median window: 5
Min Value: 0
Name: AR_image_odm
Normalize Range: true
Queue Size: 2
Transport Hint: raw
Unreliable: false
Value: false
- Class: rviz/MarkerArray
Enabled: false
Marker Topic: /points_and_lines/AR_object
Name: AR_object
Namespaces:
{}
Queue Size: 100
Value: false
- Alpha: 1
Autocompute Intensity Bounds: true
Autocompute Value Bounds:
Max Value: 10
Min Value: -10
Value: true
Axis: Z
Channel Name: x
Class: rviz/PointCloud2
Color: 255; 255; 255
Color Transformer: Intensity
Decay Time: 0
Enabled: true
Invert Rainbow: false
Max Color: 255; 255; 255
Max Intensity: 9.04478359
Min Color: 0; 0; 0
Min Intensity: 3.50075197
Name: debug ptcld
Position Transformer: XYZ
Queue Size: 10
Selectable: true
Size (Pixels): 3
Size (m): 0.0199999996
Style: Flat Squares
Topic: /unit_test_estimate_ground_plane/pt_cld
Unreliable: false
Use Fixed Frame: true
Use rainbow: true
Value: true
- Class: rviz/Marker
Enabled: true
Marker Topic: /ar_demo_node3_odom/models
Name: ModelViz
Namespaces:
{}
Queue Size: 100
Value: true
- Class: rviz/InteractiveMarkers
Enable Transparency: true
Enabled: true
Name: InteractiveMarkers
Show Axes: false
Show Descriptions: true
Show Visual Aids: false
Update Topic: /interactive_marker_server/update
Value: true
Enabled: true
Name: AR_demo
- Class: rviz/Group
Displays:
- Class: rviz/Marker
Enabled: false
Marker Topic: /cerebro_node/viz/framedata
Name: Marker
Namespaces:
{}
Queue Size: 100
Value: false
- Class: rviz/Image
Enabled: true
Image Topic: /cerebro_node/viz/imagepaire
Max Value: 1
Median window: 5
Min Value: 0
Name: cerebro - imagepaire
Normalize Range: true
Queue Size: 2
Transport Hint: raw
Unreliable: false
Value: true
Enabled: true
Name: Cerebro
- Class: rviz/Group
Displays:
- Class: rviz/Marker
Enabled: true
Marker Topic: /keyframe_pose_graph_slam_node/viz/visualization_marker
Name: Marker
Namespaces:
{}
Queue Size: 100
Value: true
- Class: rviz/Image
Enabled: true
Image Topic: /keyframe_pose_graph_slam_node/viz/disjoint_set_status_image
Max Value: 1
Median window: 5
Min Value: 0
Name: disjoint_set_status_image
Normalize Range: true
Queue Size: 2
Transport Hint: raw
Unreliable: false
Value: true
- Class: rviz/Marker
Enabled: false
Marker Topic: /debug_pose_graph_solver/visualization_marker
Name: Debug Node Marker
Namespaces:
{}
Queue Size: 100
Value: false
Enabled: true
Name: Solve Pose Graph Opt
- Class: rviz/Group
Displays:
- Class: rviz/Image
Enabled: true
Image Topic: /loop_fusion/match_image
Max Value: 1
Median window: 5
Min Value: 0
Name: DBOW Match Image
Normalize Range: true
Queue Size: 2
Transport Hint: raw
Unreliable: false
Value: true
- Class: rviz/MarkerArray
Enabled: true
Marker Topic: /vins_estimator/camera_pose_visual
Name: MarkerArray
Namespaces:
{}
Queue Size: 100
Value: true
- Alpha: 1
Buffer Length: 1
Class: rviz/Path
Color: 255; 85; 255
Enabled: true
Head Diameter: 0.300000012
Head Length: 0.200000003
Length: 0.300000012
Line Style: Lines
Line Width: 0.0299999993
Name: VIO Path
Offset:
X: 0
Y: 0
Z: 0
Pose Style: None
Radius: 0.0299999993
Shaft Diameter: 0.100000001
Shaft Length: 0.100000001
Topic: /vins_estimator/path
Unreliable: false
Value: true
- Alpha: 1
Buffer Length: 1
Class: rviz/Path
Color: 255; 85; 255
Enabled: true
Head Diameter: 0.300000012
Head Length: 0.200000003
Length: 0.300000012
Line Style: Lines
Line Width: 0.0299999993
Name: After Loop Fusion
Offset:
X: 0
Y: 0
Z: 0
Pose Style: None
Radius: 0.0299999993
Shaft Diameter: 0.100000001
Shaft Length: 0.100000001
Topic: /loop_fusion/pose_graph_path
Unreliable: false
Value: true
- Class: rviz/MarkerArray
Enabled: true
Marker Topic: /loop_fusion/pose_graph
Name: Loop Fusion Edges
Namespaces:
{}
Queue Size: 100
Value: true
Enabled: false
Name: VINS-fusion
- Class: rviz/Marker
Enabled: false
Marker Topic: /keyframe_pose_graph_slam_node/hz200/visualization_marker
Name: Marker
Namespaces:
{}
Queue Size: 100
Value: false
- Class: rviz/Group
Displays:
- Alpha: 1
Autocompute Intensity Bounds: true
Autocompute Value Bounds:
Max Value: 10
Min Value: -10
Value: true
Axis: Z
Channel Name: z
Class: rviz/PointCloud2
Color: 255; 255; 255
Color Transformer: Intensity
Decay Time: 0
Enabled: true
Invert Rainbow: false
Max Color: 255; 255; 255
Max Intensity: 0.863711178
Min Color: 0; 0; 0
Min Intensity: -2.19427705
Name: PointCloud2
Position Transformer: XYZ
Queue Size: 10
Selectable: true
Size (Pixels): 3
Size (m): 0.0500000007
Style: Flat Squares
Topic: /surfel_fusion/pointcloud
Unreliable: false
Use Fixed Frame: true
Use rainbow: true
Value: true
- Alpha: 1
Autocompute Intensity Bounds: true
Autocompute Value Bounds:
Max Value: 10
Min Value: -10
Value: true
Axis: Z
Channel Name: intensity
Class: rviz/PointCloud2
Color: 255; 255; 255
Color Transformer: Intensity
Decay Time: 0
Enabled: false
Invert Rainbow: false
Max Color: 255; 255; 255
Max Intensity: 255
Min Color: 0; 0; 0
Min Intensity: 17
Name: current
Position Transformer: XYZ
Queue Size: 10
Selectable: true
Size (Pixels): 3
Size (m): 0.00999999978
Style: Flat Squares
Topic: /surfel_fusion/raw_pointcloud
Unreliable: false
Use Fixed Frame: true
Use rainbow: true
Value: false
- Alpha: 1
Autocompute Intensity Bounds: true
Autocompute Value Bounds:
Max Value: 10
Min Value: -10
Value: true
Axis: Z
Channel Name: z
Class: rviz/PointCloud2
Color: 255; 255; 255
Color Transformer: Intensity
Decay Time: 0
Enabled: false
Invert Rainbow: true
Max Color: 255; 255; 255
Max Intensity: 1.4563067
Min Color: 0; 0; 0
Min Intensity: -1.5742451
Name: filtered
Position Transformer: XYZ
Queue Size: 10
Selectable: true
Size (Pixels): 3
Size (m): 0.00999999978
Style: Points
Topic: /map_server/filtered_map
Unrelia
gitextract_xwomkigw/
├── .gitignore
├── CMakeLists.txt
├── README.md
├── config/
│ ├── echo__terminator_config_vins_fusion_cerebro
│ ├── euroc/
│ │ └── euroc_config_no_extrinsic.yaml
│ ├── fly
│ ├── mynteye/
│ │ ├── camera_left.yaml
│ │ ├── camera_right.yaml
│ │ ├── extrinsics.yaml
│ │ └── mynteye_config.yaml
│ ├── mynteye__terminator_config_vins_fusion_cerebro
│ ├── mynteye_kannala_brandt/
│ │ ├── camera_left.yaml
│ │ ├── camera_right.yaml
│ │ ├── extrinsics.yaml
│ │ └── mynteye_config.yaml
│ ├── mynteye_pinhole/
│ │ ├── camera_left.yaml
│ │ ├── camera_right.yaml
│ │ ├── extrinsics.yaml
│ │ └── mynteye_config.yaml
│ ├── realsense__terminator_config_vins_fusion_cerebro
│ ├── vinsfusion/
│ │ ├── djirosimu_realsense_d435i/
│ │ │ ├── README.md
│ │ │ ├── extrinsics.yaml
│ │ │ ├── left.yaml
│ │ │ ├── realsense_stereo_imu_config.yaml
│ │ │ └── right.yaml
│ │ ├── euroc/
│ │ │ ├── cam0_pinhole.yaml
│ │ │ ├── cam1_pinhole.yaml
│ │ │ ├── euroc_stereo_imu_config.yaml
│ │ │ └── extrinsics.yaml
│ │ ├── mynteye/
│ │ │ ├── camera_left.yaml
│ │ │ ├── camera_left_pinhole.yaml
│ │ │ ├── camera_right.yaml
│ │ │ ├── camera_right_pinhole.yaml
│ │ │ ├── extrinsics.yaml
│ │ │ └── mynteye_stereo_imu_config.yaml
│ │ └── realsense_d435i/
│ │ ├── extrinsics.yaml
│ │ ├── left.yaml
│ │ ├── realsense_stereo_imu_config.yaml
│ │ └── right.yaml
│ └── vinsmono_debug_config.yaml
├── launch/
│ ├── debugging_vinsmono.launch
│ ├── euroc_vinsfusion.launch
│ ├── keras_server.launch
│ ├── mynteye_vinsfusion.launch
│ ├── mynteye_vinsfusion_loadstate.launch
│ ├── mynteye_vinsfusion_ondrone.launch
│ ├── mynteye_vinsfusion_savestate.launch
│ ├── realsense_camera.launch
│ ├── realsense_vinsfusion.launch
│ ├── realsense_vinsfusion_ondrone_repeat.launch
│ └── realsense_vinsfusion_ondrone_teach.launch
├── msg/
│ └── LoopEdge.msg
├── package.xml
├── rviz/
│ ├── dev-config.rviz
│ ├── good-viz.rviz
│ └── vins-fusion.rviz
├── scripts/
│ ├── TerminalColors.py
│ ├── keras.models/
│ │ ├── .gitignore
│ │ ├── Apr2019/
│ │ │ └── gray_conv6_K16__centeredinput/
│ │ │ ├── core_model.1000.keras
│ │ │ └── model.json
│ │ ├── June2019/
│ │ │ ├── centeredinput-m1to1-240x320x1__mobilenetv2-block_9_add__K16__allpairloss/
│ │ │ │ └── modelarch_and_weights.2000.h5
│ │ │ ├── centeredinput-m1to1-240x320x3__mobilenet-conv_pw_6_relu__K16__allpairloss/
│ │ │ │ └── modelarch_and_weights.700.h5
│ │ │ └── centeredinput-m1to1-240x320x3__mobilenetv2-block_9_add__K16__allpairloss/
│ │ │ └── modelarch_and_weights.800.h5
│ │ ├── README.md
│ │ ├── core_model.keras
│ │ ├── mobilenet_conv7_allpairloss.keras
│ │ ├── model.json
│ │ └── modelarch_and_weights.h5
│ ├── keras_helpers.py
│ ├── predict_utils.py
│ ├── unittest/
│ │ ├── demo_superpoint.py
│ │ └── rtry_superpoint.py
│ ├── whole_image_desc_compute_client.py
│ └── whole_image_desc_compute_server.py
├── src/
│ ├── Cerebro.cpp
│ ├── Cerebro.h
│ ├── DataManager.cpp
│ ├── DataManager.h
│ ├── DataNode.cpp
│ ├── DataNode.h
│ ├── DlsPnpWithRansac.cpp
│ ├── DlsPnpWithRansac.h
│ ├── HypothesisManager.cpp
│ ├── HypothesisManager.h
│ ├── ImageDataManager.cpp
│ ├── ImageDataManager.h
│ ├── PNPCeresCostFunctions.h
│ ├── PinholeCamera.cpp
│ ├── PinholeCamera.h
│ ├── ProcessedLoopCandidate.cpp
│ ├── ProcessedLoopCandidate.h
│ ├── Visualization.cpp
│ ├── Visualization.h
│ ├── cerebro_node.cpp
│ ├── unittest/
│ │ ├── unittest_camera_geom_class_usage.cpp
│ │ ├── unittest_camodocal_proj.cpp
│ │ ├── unittest_plot2mat.cpp
│ │ ├── unittest_pose_tester.cpp
│ │ ├── unittest_rosservice_client.cpp
│ │ ├── unittest_termcolor.cpp
│ │ ├── unittest_theia.cpp
│ │ └── unittest_theia_ransac.cpp
│ └── utils/
│ ├── CameraGeometry.cpp
│ ├── CameraGeometry.h
│ ├── ElapsedTime.h
│ ├── GMSMatcher/
│ │ ├── gms_matcher.cpp
│ │ └── gms_matcher.h
│ ├── MiscUtils.cpp
│ ├── MiscUtils.h
│ ├── Plot2Mat.cpp
│ ├── Plot2Mat.h
│ ├── PointFeatureMatching.cpp
│ ├── PointFeatureMatching.h
│ ├── PoseManipUtils.cpp
│ ├── PoseManipUtils.h
│ ├── RawFileIO.cpp
│ ├── RawFileIO.h
│ ├── RosMarkerUtils.cpp
│ ├── RosMarkerUtils.h
│ ├── SafeQueue.h
│ ├── TermColor.h
│ ├── camera_geometry_usage.cpp
│ ├── camodocal/
│ │ ├── README.md
│ │ ├── include/
│ │ │ └── camodocal/
│ │ │ ├── calib/
│ │ │ │ └── CameraCalibration.h
│ │ │ ├── camera_models/
│ │ │ │ ├── Camera.h
│ │ │ │ ├── CameraFactory.h
│ │ │ │ ├── CataCamera.h
│ │ │ │ ├── CostFunctionFactory.h
│ │ │ │ ├── EquidistantCamera.h
│ │ │ │ ├── PinholeCamera.h
│ │ │ │ └── ScaramuzzaCamera.h
│ │ │ ├── chessboard/
│ │ │ │ ├── Chessboard.h
│ │ │ │ ├── ChessboardCorner.h
│ │ │ │ ├── ChessboardQuad.h
│ │ │ │ └── Spline.h
│ │ │ ├── gpl/
│ │ │ │ ├── EigenQuaternionParameterization.h
│ │ │ │ ├── EigenUtils.h
│ │ │ │ └── gpl.h
│ │ │ └── sparse_graph/
│ │ │ └── Transform.h
│ │ └── src/
│ │ ├── calib/
│ │ │ └── CameraCalibration.cc
│ │ ├── camera_models/
│ │ │ ├── Camera.cc
│ │ │ ├── CameraFactory.cc
│ │ │ ├── CataCamera.cc
│ │ │ ├── CostFunctionFactory.cc
│ │ │ ├── EquidistantCamera.cc
│ │ │ ├── PinholeCamera.cc
│ │ │ └── ScaramuzzaCamera.cc
│ │ ├── chessboard/
│ │ │ └── Chessboard.cc
│ │ ├── gpl/
│ │ │ ├── EigenQuaternionParameterization.cc
│ │ │ └── gpl.cc
│ │ ├── intrinsic_calib.cc
│ │ └── sparse_graph/
│ │ └── Transform.cc
│ └── nlohmann/
│ └── json.hpp
└── srv/
└── WholeImageDescriptorCompute.srv
Copy disabled (too large)
Download .txt
Showing preview only (32,863K chars total). Download the full file to get everything.
SYMBOL INDEX (989 symbols across 76 files)
FILE: scripts/TerminalColors.py
class bcolors (line 1) | class bcolors:
FILE: scripts/keras_helpers.py
function make_vgg (line 231) | def make_vgg( input_img ):
function make_upsampling_vgg (line 269) | def make_upsampling_vgg( input_img ):
function make_from_vgg19_multiconvup (line 297) | def make_from_vgg19_multiconvup( input_img, trainable=False ):
function make_from_mobilenet (line 315) | def make_from_mobilenet( input_img, weights=None, layer_name='conv_pw_7_...
function make_from_vgg16 (line 329) | def make_from_vgg16( input_img, weights='imagenet', trainable=False, lay...
FILE: scripts/predict_utils.py
class NetVLADLayer (line 11) | class NetVLADLayer( Layer ):
method __init__ (line 13) | def __init__( self, num_clusters, **kwargs ):
method build (line 17) | def build( self, input_shape ):
method call (line 36) | def call( self, x ):
method compute_output_shape (line 66) | def compute_output_shape( self, input_shape ):
method get_config (line 71) | def get_config( self ):
class GhostVLADLayer (line 83) | class GhostVLADLayer( Layer ):
method __init__ (line 85) | def __init__( self, num_clusters, num_ghost_clusters, **kwargs ):
method build (line 90) | def build( self, input_shape ):
method call (line 110) | def call( self, x ):
method compute_output_shape (line 143) | def compute_output_shape( self, input_shape ):
method get_config (line 148) | def get_config( self ):
function open_json_file (line 159) | def open_json_file( fname ):
function change_model_inputshape (line 165) | def change_model_inputshape(model, new_input_shape=(None, 40, 40, 3), ve...
FILE: scripts/unittest/demo_superpoint.py
class SuperPointNet (line 73) | class SuperPointNet(torch.nn.Module):
method __init__ (line 75) | def __init__(self):
method forward (line 96) | def forward(self, x):
class SuperPointFrontend (line 128) | class SuperPointFrontend(object):
method __init__ (line 130) | def __init__(self, weights_path, nms_dist, conf_thresh, nn_thresh,
method nms_fast (line 152) | def nms_fast(self, in_corners, H, W, dist_thresh):
method run (line 217) | def run(self, img):
class PointTracker (line 288) | class PointTracker(object):
method __init__ (line 297) | def __init__(self, max_length, nn_thresh):
method nn_match_two_way (line 310) | def nn_match_two_way(self, desc1, desc2, nn_thresh):
method get_offsets (line 354) | def get_offsets(self):
method update (line 370) | def update(self, pts, desc):
method get_tracks (line 437) | def get_tracks(self, min_length):
method draw_tracks (line 455) | def draw_tracks(self, out, tracks):
class VideoStreamer (line 488) | class VideoStreamer(object):
method __init__ (line 494) | def __init__(self, basedir, camid, height, width, skip, img_glob):
method read_image (line 533) | def read_image(self, impath, img_size):
method next_frame (line 550) | def next_frame(self):
FILE: scripts/unittest/rtry_superpoint.py
class KSuperPointExp (line 17) | class KSuperPointExp:
method __init__ (line 18) | def __init__(self):
method plot_pts (line 42) | def plot_pts( self, xcanvas, pts ):
method plot_point_sets (line 49) | def plot_point_sets( self, im0, pts0, im1, pts1 ):
method read_image (line 73) | def read_image(self, impath, img_size):
method get_descriptor (line 91) | def get_descriptor( self, image ):
method match_image_pair (line 106) | def match_image_pair( self, fname0, fname1 ):
FILE: scripts/whole_image_desc_compute_server.py
class SampleGPUComputer (line 27) | class SampleGPUComputer:
method __init__ (line 28) | def __init__(self):
method handle_req (line 35) | def handle_req( self, req ):
class ReljaNetVLAD (line 62) | class ReljaNetVLAD:
method __init__ (line 63) | def __init__(self, im_rows=600, im_cols=960, im_chnls=3):
method handle_req (line 116) | def handle_req( self, req ):
class NetVLADImageDescriptor (line 170) | class NetVLADImageDescriptor:
method __init__ (line 171) | def __init__(self, im_rows=600, im_cols=960, im_chnls=3):
method handle_req (line 288) | def handle_req( self, req ):
class JSONModelImageDescriptor (line 328) | class JSONModelImageDescriptor:
method __init__ (line 335) | def __init__(self, kerasmodel_file, im_rows=600, im_cols=960, im_chnls...
method handle_req (line 428) | def handle_req( self, req ):
class HDF5ModelImageDescriptor (line 485) | class HDF5ModelImageDescriptor:
method __init__ (line 493) | def __init__(self, kerasmodel_file, im_rows=600, im_cols=960, im_chnls...
method handle_req (line 596) | def handle_req( self, req ):
FILE: src/Cerebro.cpp
function __faiss_clique_loopcandidate_generator__search (line 611) | __faiss_clique_loopcandidate_generator__search(
function json (line 1127) | json Cerebro::foundLoops_as_JSON()
function ProcessedLoopCandidate (line 1291) | const ProcessedLoopCandidate& Cerebro::processedLoops_i( int i ) const
function __Cerebro__kidnaped_thread__ (line 2349) | __Cerebro__kidnaped_thread__(
function json (line 2408) | json Cerebro::kidnap_info_as_json()
FILE: src/Cerebro.h
function class (line 61) | class Cerebro
function run_thread_disable (line 116) | void run_thread_disable() { b_run_thread = false; }
function loopcandidate_consumer_disable (line 170) | void loopcandidate_consumer_disable() { b_loopcandidate_consumer=false; }
function processedLoops_count (line 173) | const int processedLoops_count() const;
function kidnaped_thread_disable (line 211) | void kidnaped_thread_disable() {b_kidnaped_thread_enable=false;}
FILE: src/DataManager.cpp
function Matrix4d (line 105) | const Matrix4d& DataManager::getCameraRelPose( std::pair<int,int> pair_a...
function Matrix4d (line 127) | const Matrix4d& DataManager::getIMUCamExtrinsic() const
function json (line 391) | json DataManager::asJson()
function string (line 493) | string DataManager::print_queue_size( int verbose=1 ) const
FILE: src/DataManager.h
type std (line 85) | typedef std::map< ros::Time, DataNode* > t__DataNode;
function class (line 87) | class DataManager
FILE: src/DataNode.cpp
function Matrix4d (line 274) | const Matrix4d& DataNode::getPose() const{
function MatrixXd (line 284) | const MatrixXd& DataNode::getPoseCovariance() const {
function MatrixXd (line 291) | const MatrixXd& DataNode::getPointCloud() const {
function MatrixXd (line 297) | const MatrixXd& DataNode::getUnVn() const {
function MatrixXd (line 304) | const MatrixXd& DataNode::getUV() const {
function VectorXi (line 311) | const VectorXi& DataNode::getFeatIds() const {
function VectorXd (line 437) | const VectorXd DataNode::getWholeImageDescriptor() const
FILE: src/DataNode.h
function class (line 49) | class DataNode
function setAsKeyFrame (line 73) | void setAsKeyFrame() { is_key_frame = true; }
function unsetAsKeyFrame (line 74) | void unsetAsKeyFrame() { is_key_frame = false; }
function getNumberOfSuccessfullyTrackedFeatures (line 79) | int getNumberOfSuccessfullyTrackedFeatures() const;
function cv (line 94) | const cv::Mat& getImage() const; //< this will give out the default image.
FILE: src/DlsPnpWithRansac.h
type CorrespondencePair_3d2d (line 31) | struct CorrespondencePair_3d2d {
type RelativePose (line 37) | struct RelativePose {
function EstimateModel (line 48) | bool EstimateModel( const std::vector<CorrespondencePair_3d2d>& data,
function Error (line 75) | double Error( const CorrespondencePair_3d2d& point, const RelativePose& ...
type CorrespondencePair_3d3d (line 107) | struct CorrespondencePair_3d3d {
function EstimateModel (line 122) | bool EstimateModel( const std::vector<CorrespondencePair_3d3d>& data,
function Error (line 151) | double Error( const CorrespondencePair_3d3d& point, const RelativePose& ...
function class (line 169) | class StaticTheiaPoseCompute
function class (line 186) | class StaticCeresPoseCompute
FILE: src/HypothesisManager.h
function class (line 26) | class Hypothesis
function string (line 36) | string info_string()
function print_active_hypothesis (line 62) | void print_active_hypothesis( const string header_str ) {
function increment_ttl (line 110) | void increment_ttl()
function get_ttl (line 123) | int get_ttl() { return time_to_live; }
function is_hypothesis_active (line 125) | bool is_hypothesis_active() { if(time_to_live<=0) return false; else ret...
function n_elements_in_list (line 126) | int n_elements_in_list() { return list_of_nodes_in_this_hypothesis.size(...
function class (line 133) | class HypothesisManager
FILE: src/ImageDataManager.cpp
function json (line 442) | json ImageDataManager::stashAll()
FILE: src/ImageDataManager.h
type MEMSTAT (line 41) | enum MEMSTAT { AVAILABLE_ON_RAM, AVAILABLE_ON_DISK, UNAVAILABLE, AVAILAB...
function class (line 43) | class ImageDataManager
function set_rm_stash_dir_in_destructor_as_false (line 110) | void set_rm_stash_dir_in_destructor_as_false() {rm_stash_dir_in_destruct...
function set_rm_stash_dir_in_destructor_as_true (line 111) | void set_rm_stash_dir_in_destructor_as_true() {rm_stash_dir_in_destruct...
FILE: src/PNPCeresCostFunctions.h
function class (line 16) | class AngleLocalParameterization {
function ceres (line 28) | static ceres::LocalParameterization* Create() {
function class (line 76) | class PNPEulerAngleError
function ceres (line 109) | static ceres::CostFunction* Create( Vector3d _w_X, Vector2d _uv_normed_c...
function class (line 124) | class P3PEulerAngleError
function ceres (line 163) | static ceres::CostFunction* Create( Vector3d _a_X, Vector3d _b_X )
FILE: src/PinholeCamera.cpp
function string (line 133) | string PinholeCamera::getCameraInfoAsJson() const
function string (line 158) | string PinholeCamera::type2str(int type) {
FILE: src/PinholeCamera.h
function class (line 36) | class PinholeCamera {
FILE: src/ProcessedLoopCandidate.h
function class (line 55) | class ProcessedLoopCandidate
FILE: src/Visualization.h
function class (line 33) | class Visualization
FILE: src/cerebro_node.cpp
function main (line 29) | int main( int argc, char ** argv )
FILE: src/unittest/unittest_camera_geom_class_usage.cpp
function monocular_demo (line 34) | int monocular_demo()
function stereo_demo (line 61) | int stereo_demo()
function main (line 125) | int main()
FILE: src/unittest/unittest_camodocal_proj.cpp
function load_i (line 25) | bool load_i( int i, cv::Mat& im, Matrix4d& wTc, MatrixXd& uv, MatrixXd& ...
function load_i (line 45) | bool load_i( int i, cv::Mat& im, Matrix4d& wTc, MatrixXd& uv, MatrixXd& ...
function main (line 67) | int main()
FILE: src/unittest/unittest_plot2mat.cpp
function demo (line 5) | int demo()
function demo_easy (line 28) | int demo_easy() {
function main (line 46) | int main() {
FILE: src/unittest/unittest_pose_tester.cpp
function make_stereo_geom (line 42) | std::shared_ptr<StereoGeometry> make_stereo_geom()
function compute_rel_pose (line 91) | bool compute_rel_pose( std::shared_ptr<StereoGeometry> stereogeom, int f...
function main (line 345) | int main(int argc, char ** argv )
function main1 (line 373) | int main1( int argc, char ** argv )
FILE: src/unittest/unittest_rosservice_client.cpp
function main (line 14) | int main( int argc, char ** argv )
FILE: src/unittest/unittest_termcolor.cpp
function main (line 7) | int main()
FILE: src/unittest/unittest_theia.cpp
type CorrespondencePair_3d2d (line 46) | struct CorrespondencePair_3d2d {
type RelativePose (line 52) | struct RelativePose {
class DlsPnpWithRansac (line 57) | class DlsPnpWithRansac: public theia::Estimator<CorrespondencePair_3d2d,...
method SampleSize (line 60) | double SampleSize() const { return 15; }
method EstimateModel (line 63) | bool EstimateModel( const std::vector<CorrespondencePair_3d2d>& data,
method Error (line 92) | double Error( const CorrespondencePair_3d2d& point, const RelativePose...
type CorrespondencePair_3d3d (line 124) | struct CorrespondencePair_3d3d {
class AlignPointCloudsUmeyamaWithRansac (line 134) | class AlignPointCloudsUmeyamaWithRansac: public theia::Estimator<Corresp...
method SampleSize (line 137) | double SampleSize() const { return 10; }
method EstimateModel (line 139) | bool EstimateModel( const std::vector<CorrespondencePair_3d3d>& data,
method Error (line 168) | double Error( const CorrespondencePair_3d3d& point, const RelativePose...
function point_feature_matches (line 187) | void point_feature_matches( const cv::Mat& imleft_undistorted, const cv:...
function make_stereo_geom (line 253) | std::shared_ptr<StereoGeometry> make_stereo_geom()
function relative_pose_compute_with_theia (line 299) | bool relative_pose_compute_with_theia( std::shared_ptr<StereoGeometry> s...
function plot_vio_poses (line 666) | void plot_vio_poses( json& json_obj, ros::Publisher& pub )
function plot_loop_candidates_as_lines (line 710) | void plot_loop_candidates_as_lines( json& log, json& loopcandidates, ros...
function self_projection_test (line 778) | bool self_projection_test( std::shared_ptr<StereoGeometry> stereogeom,
function make_3d_2d_collection__using__pfmatches_and_disparity (line 997) | bool make_3d_2d_collection__using__pfmatches_and_disparity( std::shared_...
function make_3d_3d_collection__using__pfmatches_and_disparity (line 1060) | bool make_3d_3d_collection__using__pfmatches_and_disparity(
function P3P_ICP (line 1100) | float P3P_ICP( const vector<Vector3d>& uv_X, const vector<Vector3d>& uvd_Y,
function PNP (line 1211) | float PNP( const std::vector<Vector3d>& w_X, const std::vector<Vector2d>...
function verified_alignment (line 1322) | bool verified_alignment( std::shared_ptr<StereoGeometry> stereogeom,
function main0 (line 1463) | int main0( int argc, char ** argv )
function main (line 1483) | int main(int argc, char ** argv)
function main1 (line 1513) | int main1( int argc, char ** argv )
FILE: src/unittest/unittest_theia_ransac.cpp
function main (line 11) | int main()
FILE: src/utils/CameraGeometry.cpp
function Matrix4d (line 116) | const Matrix4d& StereoGeometry::get_stereoextrinsic()
function Matrix3d (line 262) | const Matrix3d& StereoGeometry::get_K()
FILE: src/utils/CameraGeometry.h
function class (line 31) | class MonoGeometry {
function class (line 61) | class StereoGeometry {
function class (line 276) | class GeometryUtils {
FILE: src/utils/ElapsedTime.h
function class (line 9) | class ElapsedTime
function class (line 45) | class DateAndTime
FILE: src/utils/GMSMatcher/gms_matcher.h
function class (line 50) | class gms_matcher
function ConvertMatches (line 135) | void ConvertMatches(const vector<DMatch> &vDMatches, vector<pair<int, in...
function GetGridIndexLeft (line 143) | int GetGridIndexLeft(const Point2f &pt, int type) {
function GetGridIndexRight (line 185) | int GetGridIndexRight(const Point2f &pt) {
function InitalizeNiehbors (line 221) | void InitalizeNiehbors(Mat &neighbor, const Size& GridSize) {
function SetScale (line 230) | void SetScale(int Scale) {
FILE: src/utils/MiscUtils.cpp
function string (line 3) | string MiscUtils::type2str(int type) {
function string (line 26) | string MiscUtils::cvmat_info( const cv::Mat& mat )
function string (line 34) | string MiscUtils::imgmsg_info(const sensor_msgs::ImageConstPtr &img_msg)
function string (line 53) | string MiscUtils::imgmsg_info(const sensor_msgs::Image& img_msg)
FILE: src/utils/MiscUtils.h
function class (line 31) | class MiscUtils
function class (line 163) | class FalseColors
FILE: src/utils/Plot2Mat.h
function class (line 125) | class Plot2Mat {
FILE: src/utils/PointFeatureMatching.h
function class (line 32) | class StaticPointFeatureMatching
FILE: src/utils/PoseManipUtils.cpp
function Vector3d (line 148) | Vector3d PoseManipUtils::R2ypr( const Matrix3d& R)
function Matrix3d (line 166) | Matrix3d PoseManipUtils::ypr2R( const Vector3d& ypr)
function string (line 210) | string PoseManipUtils::prettyprintMatrix4d( const Matrix4d& M )
function string (line 221) | string PoseManipUtils::prettyprintMatrix4d_YPR( const Matrix4d& M )
function string (line 232) | string PoseManipUtils::prettyprintMatrix4d_t( const Matrix4d& M )
FILE: src/utils/PoseManipUtils.h
function class (line 26) | class PoseManipUtils
FILE: src/utils/RawFileIO.cpp
type stat (line 314) | struct stat
FILE: src/utils/RawFileIO.h
function class (line 40) | class RawFileIO
FILE: src/utils/RosMarkerUtils.h
function class (line 32) | class RosMarkerUtils
FILE: src/utils/SafeQueue.h
function T (line 33) | T dequeue(void)
function size (line 49) | int size()
function push (line 58) | void push(T t)
function T (line 67) | T pop(void)
function T (line 81) | T back()
function T (line 91) | T front()
FILE: src/utils/TermColor.h
function class (line 35) | class TermColor
FILE: src/utils/camera_geometry_usage.cpp
function point_feature_matches (line 45) | void point_feature_matches( const cv::Mat& imleft_undistorted, const cv:...
class UnitVectorParameterization (line 114) | class UnitVectorParameterization : public ceres::LocalParameterization {
method UnitVectorParameterization (line 116) | UnitVectorParameterization() {}
method Plus (line 119) | virtual bool Plus(const double* x,
method ComputeJacobian (line 138) | virtual bool ComputeJacobian(const double* x,
method GlobalSize (line 160) | virtual int GlobalSize() const { return 3; }
method LocalSize (line 161) | virtual int LocalSize() const { return 2; }
method gram_schmidt_orthonormalization (line 166) | const bool gram_schmidt_orthonormalization( const double * _x , double...
method VectorXd (line 210) | VectorXd proj( const VectorXd& u, const VectorXd& v ) const
class YonggenResidue (line 219) | class YonggenResidue {
method YonggenResidue (line 221) | YonggenResidue( const Vector3d& Xi, const Vector3d& Xid ) : Xi(Xi), Xi...
function nudge_extrinsics (line 281) | void nudge_extrinsics( const cv::Mat& imleft_undistorted, const cv::Mat&...
function stereo_demo (line 371) | int stereo_demo() {
function stereo_demo_easy (line 564) | int stereo_demo_easy()
function monocular_demo (line 695) | int monocular_demo()
function main (line 720) | int main() {
FILE: src/utils/camodocal/include/camodocal/calib/CameraCalibration.h
function namespace (line 8) | namespace camodocal
FILE: src/utils/camodocal/include/camodocal/camera_models/Camera.h
function namespace (line 9) | namespace camodocal
FILE: src/utils/camodocal/include/camodocal/camera_models/CameraFactory.h
function namespace (line 9) | namespace camodocal
FILE: src/utils/camodocal/include/camodocal/camera_models/CataCamera.h
function namespace (line 10) | namespace camodocal
FILE: src/utils/camodocal/include/camodocal/camera_models/CostFunctionFactory.h
function namespace (line 9) | namespace ceres
function namespace (line 14) | namespace camodocal
FILE: src/utils/camodocal/include/camodocal/camera_models/EquidistantCamera.h
function namespace (line 10) | namespace camodocal
FILE: src/utils/camodocal/include/camodocal/camera_models/PinholeCamera.h
function namespace (line 10) | namespace camodocal
FILE: src/utils/camodocal/include/camodocal/camera_models/ScaramuzzaCamera.h
function namespace (line 10) | namespace camodocal
FILE: src/utils/camodocal/include/camodocal/chessboard/Chessboard.h
function namespace (line 7) | namespace camodocal
FILE: src/utils/camodocal/include/camodocal/chessboard/ChessboardCorner.h
function namespace (line 7) | namespace camodocal
FILE: src/utils/camodocal/include/camodocal/chessboard/ChessboardQuad.h
function namespace (line 8) | namespace camodocal
FILE: src/utils/camodocal/include/camodocal/chessboard/Spline.h
type BC_type (line 33) | enum BC_type {
type Spline_type (line 39) | enum Spline_type {
type std (line 54) | typedef std::vector<std::pair<double, double> > base;
type base (line 55) | typedef base::const_iterator const_iterator;
function const_iterator (line 58) | const_iterator begin() const { return base::begin(); }
function clear (line 60) | void clear() { _valid = false; base::clear(); _data.clear(); }
function size (line 61) | size_t size() const { return base::size(); }
function capacity (line 63) | size_t capacity() const { return base::capacity(); }
function addPoint (line 68) | inline void addPoint(double x, double y)
function setType (line 81) | void setType(Spline_type type) { _type = type; _valid = false; }
type SplineData (line 105) | struct SplineData { double x,a,b,c,d; }
function splineCalc (line 122) | inline double splineCalc(std::vector<SplineData>::const_iterator i, doub...
function lowCalc (line 128) | inline double lowCalc(double xval)
function highCalc (line 149) | inline double highCalc(double xval)
function x (line 171) | inline double x(size_t i) const { return operator[](i).first; }
function y (line 172) | inline double y(size_t i) const { return operator[](i).second; }
function h (line 173) | inline double h(size_t i) const { return x(i+1) - x(i); }
function generate (line 200) | void generate()
FILE: src/utils/camodocal/include/camodocal/gpl/EigenQuaternionParameterization.h
function namespace (line 6) | namespace camodocal
FILE: src/utils/camodocal/include/camodocal/gpl/EigenUtils.h
function namespace (line 9) | namespace camodocal
FILE: src/utils/camodocal/include/camodocal/gpl/gpl.h
function namespace (line 8) | namespace camodocal
FILE: src/utils/camodocal/include/camodocal/sparse_graph/Transform.h
function namespace (line 8) | namespace camodocal
FILE: src/utils/camodocal/src/calib/CameraCalibration.cc
type camodocal (line 21) | namespace camodocal
function CameraPtr (line 167) | CameraPtr&
function CameraConstPtr (line 173) | const CameraConstPtr
FILE: src/utils/camodocal/src/camera_models/Camera.cc
type camodocal (line 6) | namespace camodocal
FILE: src/utils/camodocal/src/camera_models/CameraFactory.cc
type camodocal (line 13) | namespace camodocal
function CameraPtr (line 34) | CameraPtr
function CameraPtr (line 89) | CameraPtr
FILE: src/utils/camodocal/src/camera_models/CataCamera.cc
type camodocal (line 14) | namespace camodocal
FILE: src/utils/camodocal/src/camera_models/CostFunctionFactory.cc
type camodocal (line 9) | namespace camodocal
function worldToCameraTransform (line 13) | void
class ReprojectionError1 (line 58) | class ReprojectionError1
method ReprojectionError1 (line 68) | ReprojectionError1(const Eigen::Vector3d& observed_P,
method ReprojectionError1 (line 74) | ReprojectionError1(const std::vector<double>& intrinsic_params,
class ReprojectionError2 (line 141) | class ReprojectionError2
class ReprojectionError3 (line 180) | class ReprojectionError3
method ReprojectionError3 (line 190) | ReprojectionError3(const Eigen::Vector2d& observed_p,
method ReprojectionError3 (line 196) | ReprojectionError3(const std::vector<double>& intrinsic_params,
method ReprojectionError3 (line 203) | ReprojectionError3(const std::vector<double>& intrinsic_params,
method ReprojectionError3 (line 212) | ReprojectionError3(const std::vector<double>& intrinsic_params,
method ReprojectionError3 (line 222) | ReprojectionError3(const std::vector<double>& intrinsic_params,
class StereoReprojectionError (line 356) | class StereoReprojectionError
class ComprehensionError (line 421) | class ComprehensionError {
FILE: src/utils/camodocal/src/camera_models/EquidistantCamera.cc
type camodocal (line 14) | namespace camodocal
FILE: src/utils/camodocal/src/camera_models/PinholeCamera.cc
type camodocal (line 13) | namespace camodocal
FILE: src/utils/camodocal/src/camera_models/ScaramuzzaCamera.cc
function polyfit (line 18) | Eigen::VectorXd polyfit(Eigen::VectorXd& xVec, Eigen::VectorXd& yVec, in...
type camodocal (line 46) | namespace camodocal
FILE: src/utils/camodocal/src/chessboard/Chessboard.cc
type camodocal (line 11) | namespace camodocal
function less_pred (line 1552) | bool less_pred(const std::pair<float, int>& p1, const std::pair<float,...
function countClasses (line 1557) | void countClasses(const std::vector<std::pair<float, int> >& pairs, si...
FILE: src/utils/camodocal/src/gpl/EigenQuaternionParameterization.cc
type camodocal (line 5) | namespace camodocal
FILE: src/utils/camodocal/src/gpl/gpl.cc
function orwl_gettime (line 20) | struct timespec orwl_gettime(void) {
type camodocal (line 46) | namespace camodocal
function hypot3 (line 49) | double hypot3(double x, double y, double z)
function hypot3f (line 54) | float hypot3f(float x, float y, float z)
function d2r (line 59) | double d2r(double deg)
function d2r (line 64) | float d2r(float deg)
function r2d (line 69) | double r2d(double rad)
function r2d (line 74) | float r2d(float rad)
function sinc (line 79) | double sinc(double theta)
function LARGE_INTEGER (line 88) | LARGE_INTEGER
function clock_gettime (line 109) | int
function timeInMicroseconds (line 149) | unsigned long long timeInMicroseconds(void)
function timeInSeconds (line 161) | double timeInSeconds(void)
function colorDepthImage (line 439) | void colorDepthImage(cv::Mat& imgDepth, cv::Mat& imgColoredDepth,
function colormap (line 465) | bool colormap(const std::string& name, unsigned char idx,
function bresLine (line 492) | std::vector<cv::Point2i> bresLine(int x0, int y0, int x1, int y1)
function bresCircle (line 532) | std::vector<cv::Point2i> bresCircle(int x0, int y0, int r)
function fitCircle (line 621) | void
function intersectCircles (line 676) | std::vector<cv::Point2d>
function UTMLetterDesignator (line 714) | char
function LLtoUTM (line 747) | void
function UTMtoLL (line 827) | void
function timestampDiff (line 897) | long int
FILE: src/utils/camodocal/src/intrinsic_calib.cc
function main (line 15) | int main(int argc, char** argv)
FILE: src/utils/camodocal/src/sparse_graph/Transform.cc
type camodocal (line 3) | namespace camodocal
FILE: src/utils/nlohmann/json.hpp
type nlohmann (line 64) | namespace nlohmann
type adl_serializer (line 74) | struct adl_serializer
method from_json (line 12307) | static auto from_json(BasicJsonType&& j, ValueType& val) noexcept(
method to_json (line 12324) | static auto to_json(BasicJsonType& j, ValueType&& val) noexcept(
class basic_json (line 86) | class basic_json
class json_pointer (line 100) | class json_pointer
class basic_json (line 11602) | class basic_json
method json_pointer (line 11626) | explicit json_pointer(const std::string& s = "")
method to_string (line 11645) | std::string to_string() const
method array_index (line 11668) | static int array_index(const std::string& s)
method pop_back (line 11687) | std::string pop_back()
method is_root (line 11700) | bool is_root() const noexcept
method json_pointer (line 11705) | json_pointer top() const
method BasicJsonType (line 11725) | BasicJsonType& get_and_create(BasicJsonType& j) const
type detail (line 261) | namespace detail
type index_sequence (line 273) | struct index_sequence
method size (line 277) | static constexpr std::size_t size() noexcept
type merge_and_renumber (line 284) | struct merge_and_renumber
type make_index_sequence (line 291) | struct make_index_sequence
type make_index_sequence<0> (line 295) | struct make_index_sequence<0> : index_sequence<> {}
type make_index_sequence<1> (line 296) | struct make_index_sequence<1> : index_sequence<0> {}
type priority_tag (line 302) | struct priority_tag : priority_tag < N - 1 > {}
type priority_tag<0> (line 303) | struct priority_tag<0> {}
type static_const (line 307) | struct static_const
type make_void (line 341) | struct make_void
type nonesuch (line 355) | struct nonesuch
method nonesuch (line 357) | nonesuch() = delete;
method nonesuch (line 359) | nonesuch(nonesuch const&) = delete;
type detector (line 367) | struct detector
type is_basic_json (line 429) | struct is_basic_json : std::false_type {}
type has_from_json (line 473) | struct has_from_json : std::false_type {}
type has_from_json<BasicJsonType, T,
enable_if_t<not is_basic_json<T>::value>> (line 476) | struct has_from_json<BasicJsonType, T,
type has_non_default_from_json (line 489) | struct has_non_default_from_json : std::false_type {}
type has_non_default_from_json<BasicJsonType, T, enable_if_t<not is_basic_json<T>::value>> (line 492) | struct has_non_default_from_json<BasicJsonType, T, enable_if_t<not i...
type has_to_json (line 504) | struct has_to_json : std::false_type {}
type has_to_json<BasicJsonType, T, enable_if_t<not is_basic_json<T>::value>> (line 507) | struct has_to_json<BasicJsonType, T, enable_if_t<not is_basic_json<T...
type is_iterator_traits (line 522) | struct is_iterator_traits : std::false_type {}
type is_iterator_traits<std::iterator_traits<T>> (line 525) | struct is_iterator_traits<std::iterator_traits<T>>
type is_complete_type (line 542) | struct is_complete_type : std::false_type {}
type is_complete_type<T, decltype(void(sizeof(T)))> (line 545) | struct is_complete_type<T, decltype(void(sizeof(T)))> : std::true_ty...
type is_compatible_object_type_impl (line 549) | struct is_compatible_object_type_impl : std::false_type {}
type is_compatible_object_type_impl <
BasicJsonType, CompatibleObjectType,
enable_if_t<is_detected<mapped_type_t, CompatibleObjectType>::value and
is_detected<key_type_t, CompatibleObjectType>::value >> (line 552) | struct is_compatible_object_type_impl <
type is_compatible_object_type (line 569) | struct is_compatible_object_type
type is_constructible_object_type_impl (line 574) | struct is_constructible_object_type_impl : std::false_type {}
type is_constructible_object_type_impl <
BasicJsonType, ConstructibleObjectType,
enable_if_t<is_detected<mapped_type_t, ConstructibleObjectType>::value and
is_detected<key_type_t, ConstructibleObjectType>::value >> (line 577) | struct is_constructible_object_type_impl <
type is_constructible_object_type (line 592) | struct is_constructible_object_type
type is_compatible_string_type_impl (line 598) | struct is_compatible_string_type_impl : std::false_type {}
type is_compatible_string_type_impl <
BasicJsonType, CompatibleStringType,
enable_if_t<is_detected_exact<typename BasicJsonType::string_t::value_type,
value_type_t, CompatibleStringType>::value >> (line 601) | struct is_compatible_string_type_impl <
type is_compatible_string_type (line 611) | struct is_compatible_string_type
type is_constructible_string_type_impl (line 616) | struct is_constructible_string_type_impl : std::false_type {}
type is_constructible_string_type_impl <
BasicJsonType, ConstructibleStringType,
enable_if_t<is_detected_exact<typename BasicJsonType::string_t::value_type,
value_type_t, ConstructibleStringType>::value >> (line 619) | struct is_constructible_string_type_impl <
type is_constructible_string_type (line 630) | struct is_constructible_string_type
type is_compatible_array_type_impl (line 634) | struct is_compatible_array_type_impl : std::false_type {}
type is_compatible_array_type (line 653) | struct is_compatible_array_type
type is_constructible_array_type_impl (line 657) | struct is_constructible_array_type_impl : std::false_type {}
type is_constructible_array_type_impl <
BasicJsonType, ConstructibleArrayType,
enable_if_t<std::is_same<ConstructibleArrayType,
typename BasicJsonType::value_type>::value >> (line 660) | struct is_constructible_array_type_impl <
type is_constructible_array_type_impl <
BasicJsonType, ConstructibleArrayType,
enable_if_t<not std::is_same<ConstructibleArrayType,
typename BasicJsonType::value_type>::value and
is_detected<value_type_t, ConstructibleArrayType>::value and
is_detected<iterator_t, ConstructibleArrayType>::value and
is_complete_type<
detected_t<value_type_t, ConstructibleArrayType>>::value >> (line 667) | struct is_constructible_array_type_impl <
type is_constructible_array_type (line 692) | struct is_constructible_array_type
type is_compatible_integer_type_impl (line 697) | struct is_compatible_integer_type_impl : std::false_type {}
type is_compatible_integer_type_impl <
RealIntegerType, CompatibleNumberIntegerType,
enable_if_t<std::is_integral<RealIntegerType>::value and
std::is_integral<CompatibleNumberIntegerType>::value and
not std::is_same<bool, CompatibleNumberIntegerType>::value >> (line 700) | struct is_compatible_integer_type_impl <
type is_compatible_integer_type (line 718) | struct is_compatible_integer_type
type is_compatible_type_impl (line 723) | struct is_compatible_type_impl: std::false_type {}
type is_compatible_type_impl <
BasicJsonType, CompatibleType,
enable_if_t<is_complete_type<CompatibleType>::value >> (line 726) | struct is_compatible_type_impl <
type is_compatible_type (line 735) | struct is_compatible_type
type position_t (line 757) | struct position_t
class exception (line 813) | class exception : public std::exception
method exception (line 826) | exception(int id_, const char* what_arg) : id(id_), m(what_arg) {}
method name (line 828) | static std::string name(const std::string& ename, int id_)
class parse_error (line 882) | class parse_error : public exception
method parse_error (line 894) | static parse_error create(int id_, const position_t& pos, const st...
method parse_error (line 901) | static parse_error create(int id_, std::size_t byte_, const std::s...
method parse_error (line 921) | parse_error(int id_, std::size_t byte_, const char* what_arg)
method position_string (line 924) | static std::string position_string(const position_t& pos)
class invalid_iterator (line 968) | class invalid_iterator : public exception
method invalid_iterator (line 971) | static invalid_iterator create(int id_, const std::string& what_arg)
method invalid_iterator (line 978) | invalid_iterator(int id_, const char* what_arg)
class type_error (line 1021) | class type_error : public exception
method type_error (line 1024) | static type_error create(int id_, const std::string& what_arg)
method type_error (line 1031) | type_error(int id_, const char* what_arg) : exception(id_, what_ar...
class out_of_range (line 1067) | class out_of_range : public exception
method out_of_range (line 1070) | static out_of_range create(int id_, const std::string& what_arg)
method out_of_range (line 1077) | out_of_range(int id_, const char* what_arg) : exception(id_, what_...
class other_error (line 1104) | class other_error : public exception
method other_error (line 1107) | static other_error create(int id_, const std::string& what_arg)
method other_error (line 1114) | other_error(int id_, const char* what_arg) : exception(id_, what_a...
type value_t (line 1159) | enum class value_t : std::uint8_t
function from_json (line 1229) | void from_json(const BasicJsonType& j, typename std::nullptr_t& n)
function get_arithmetic_value (line 1243) | void get_arithmetic_value(const BasicJsonType& j, ArithmeticType& val)
function from_json (line 1269) | void from_json(const BasicJsonType& j, typename BasicJsonType::boole...
function from_json (line 1279) | void from_json(const BasicJsonType& j, typename BasicJsonType::strin...
function from_json (line 1295) | void from_json(const BasicJsonType& j, ConstructibleStringType& s)
function from_json (line 1306) | void from_json(const BasicJsonType& j, typename BasicJsonType::numbe...
function from_json (line 1312) | void from_json(const BasicJsonType& j, typename BasicJsonType::numbe...
function from_json (line 1318) | void from_json(const BasicJsonType& j, typename BasicJsonType::numbe...
function from_json (line 1325) | void from_json(const BasicJsonType& j, EnumType& e)
function from_json (line 1335) | void from_json(const BasicJsonType& j, std::forward_list<T, Allocato...
function from_json (line 1351) | void from_json(const BasicJsonType& j, std::valarray<T>& l)
function from_json_array_impl (line 1362) | void from_json_array_impl(const BasicJsonType& j, typename BasicJson...
function from_json_array_impl (line 1368) | auto from_json_array_impl(const BasicJsonType& j, std::array<T, N>& ...
function from_json_array_impl (line 1379) | auto from_json_array_impl(const BasicJsonType& j, ConstructibleArray...
function from_json_array_impl (line 1398) | void from_json_array_impl(const BasicJsonType& j, ConstructibleArray...
function from_json (line 1421) | auto from_json(const BasicJsonType& j, ConstructibleArrayType& arr)
function from_json (line 1437) | void from_json(const BasicJsonType& j, ConstructibleObjectType& obj)
function from_json (line 1467) | void from_json(const BasicJsonType& j, ArithmeticType& val)
function from_json (line 1498) | void from_json(const BasicJsonType& j, std::pair<A1, A2>& p)
function from_json_tuple_impl (line 1504) | void from_json_tuple_impl(const BasicJsonType& j, Tuple& t, index_se...
function from_json (line 1510) | void from_json(const BasicJsonType& j, std::tuple<Args...>& t)
function from_json (line 1518) | void from_json(const BasicJsonType& j, std::map<Key, Value, Compare,...
function from_json (line 1537) | void from_json(const BasicJsonType& j, std::unordered_map<Key, Value...
type from_json_fn (line 1553) | struct from_json_fn
class iteration_proxy (line 1606) | class iteration_proxy
class iteration_proxy_internal (line 1610) | class iteration_proxy_internal
method iteration_proxy_internal (line 1632) | explicit iteration_proxy_internal(IteratorType it) noexcept : an...
method iteration_proxy_internal (line 1635) | iteration_proxy_internal& operator*()
method iteration_proxy_internal (line 1641) | iteration_proxy_internal& operator++()
method value (line 1690) | typename IteratorType::reference value() const
method iteration_proxy (line 1701) | explicit iteration_proxy(typename IteratorType::reference cont) no...
method iteration_proxy_internal (line 1705) | iteration_proxy_internal begin() noexcept
method iteration_proxy_internal (line 1632) | explicit iteration_proxy_internal(IteratorType it) noexcept : an...
method iteration_proxy_internal (line 1635) | iteration_proxy_internal& operator*()
method iteration_proxy_internal (line 1641) | iteration_proxy_internal& operator++()
method value (line 1690) | typename IteratorType::reference value() const
method iteration_proxy_internal (line 1711) | iteration_proxy_internal end() noexcept
method iteration_proxy_internal (line 1632) | explicit iteration_proxy_internal(IteratorType it) noexcept : an...
method iteration_proxy_internal (line 1635) | iteration_proxy_internal& operator*()
method iteration_proxy_internal (line 1641) | iteration_proxy_internal& operator++()
method value (line 1690) | typename IteratorType::reference value() const
type external_constructor (line 1728) | struct external_constructor
type external_constructor<value_t::boolean> (line 1731) | struct external_constructor<value_t::boolean>
method construct (line 1734) | static void construct(BasicJsonType& j, typename BasicJsonType::bo...
type external_constructor<value_t::string> (line 1743) | struct external_constructor<value_t::string>
method construct (line 1746) | static void construct(BasicJsonType& j, const typename BasicJsonTy...
method construct (line 1754) | static void construct(BasicJsonType& j, typename BasicJsonType::st...
method construct (line 1764) | static void construct(BasicJsonType& j, const CompatibleStringType...
type external_constructor<value_t::number_float> (line 1773) | struct external_constructor<value_t::number_float>
method construct (line 1776) | static void construct(BasicJsonType& j, typename BasicJsonType::nu...
type external_constructor<value_t::number_unsigned> (line 1785) | struct external_constructor<value_t::number_unsigned>
method construct (line 1788) | static void construct(BasicJsonType& j, typename BasicJsonType::nu...
type external_constructor<value_t::number_integer> (line 1797) | struct external_constructor<value_t::number_integer>
method construct (line 1800) | static void construct(BasicJsonType& j, typename BasicJsonType::nu...
type external_constructor<value_t::array> (line 1809) | struct external_constructor<value_t::array>
method construct (line 1812) | static void construct(BasicJsonType& j, const typename BasicJsonTy...
method construct (line 1820) | static void construct(BasicJsonType& j, typename BasicJsonType::ar...
method construct (line 1830) | static void construct(BasicJsonType& j, const CompatibleArrayType&...
method construct (line 1840) | static void construct(BasicJsonType& j, const std::vector<bool>& arr)
method construct (line 1854) | static void construct(BasicJsonType& j, const std::valarray<T>& arr)
type external_constructor<value_t::object> (line 1865) | struct external_constructor<value_t::object>
method construct (line 1868) | static void construct(BasicJsonType& j, const typename BasicJsonTy...
method construct (line 1876) | static void construct(BasicJsonType& j, typename BasicJsonType::ob...
method construct (line 1885) | static void construct(BasicJsonType& j, const CompatibleObjectType...
function to_json (line 1902) | void to_json(BasicJsonType& j, T b) noexcept
function to_json (line 1909) | void to_json(BasicJsonType& j, const CompatibleString& s)
function to_json (line 1915) | void to_json(BasicJsonType& j, typename BasicJsonType::string_t&& s)
function to_json (line 1922) | void to_json(BasicJsonType& j, FloatType val) noexcept
function to_json (line 1929) | void to_json(BasicJsonType& j, CompatibleNumberUnsignedType val) noe...
function to_json (line 1936) | void to_json(BasicJsonType& j, CompatibleNumberIntegerType val) noex...
function to_json (line 1943) | void to_json(BasicJsonType& j, EnumType e) noexcept
function to_json (line 1950) | void to_json(BasicJsonType& j, const std::vector<bool>& e)
function to_json (line 1963) | void to_json(BasicJsonType& j, const CompatibleArrayType& arr)
function to_json (line 1970) | void to_json(BasicJsonType& j, const std::valarray<T>& arr)
function to_json (line 1976) | void to_json(BasicJsonType& j, typename BasicJsonType::array_t&& arr)
function to_json (line 1983) | void to_json(BasicJsonType& j, const CompatibleObjectType& obj)
function to_json (line 1989) | void to_json(BasicJsonType& j, typename BasicJsonType::object_t&& obj)
function to_json (line 1999) | void to_json(BasicJsonType& j, const T (&arr)[N])
function to_json (line 2005) | void to_json(BasicJsonType& j, const std::pair<Args...>& p)
function to_json (line 2013) | void to_json(BasicJsonType& j, const T& b)
function to_json_tuple_impl (line 2019) | void to_json_tuple_impl(BasicJsonType& j, const Tuple& t, index_sequ...
function to_json (line 2025) | void to_json(BasicJsonType& j, const std::tuple<Args...>& t)
type to_json_fn (line 2030) | struct to_json_fn
type input_format_t (line 2070) | enum class input_format_t { json, cbor, msgpack, ubjson, bson }
type input_adapter_protocol (line 2087) | struct input_adapter_protocol
class input_stream_adapter (line 2106) | class input_stream_adapter : public input_adapter_protocol
method input_stream_adapter (line 2116) | explicit input_stream_adapter(std::istream& i)
method input_stream_adapter (line 2121) | input_stream_adapter(const input_stream_adapter&) = delete;
method input_stream_adapter (line 2122) | input_stream_adapter& operator=(input_stream_adapter&) = delete;
method input_stream_adapter (line 2123) | input_stream_adapter(input_stream_adapter&&) = delete;
method input_stream_adapter (line 2124) | input_stream_adapter& operator=(input_stream_adapter&&) = delete;
method get_character (line 2129) | std::char_traits<char>::int_type get_character() override
class input_buffer_adapter (line 2141) | class input_buffer_adapter : public input_adapter_protocol
method input_buffer_adapter (line 2144) | input_buffer_adapter(const char* b, const std::size_t l) noexcept
method input_buffer_adapter (line 2149) | input_buffer_adapter(const input_buffer_adapter&) = delete;
method input_buffer_adapter (line 2150) | input_buffer_adapter& operator=(input_buffer_adapter&) = delete;
method input_buffer_adapter (line 2151) | input_buffer_adapter(input_buffer_adapter&&) = delete;
method input_buffer_adapter (line 2152) | input_buffer_adapter& operator=(input_buffer_adapter&&) = delete;
method get_character (line 2155) | std::char_traits<char>::int_type get_character() noexcept override
type wide_string_input_helper (line 2173) | struct wide_string_input_helper
method fill_buffer (line 2176) | static void fill_buffer(const WideStringType& str, size_t& current...
type wide_string_input_helper<WideStringType, 2> (line 2228) | struct wide_string_input_helper<WideStringType, 2>
method fill_buffer (line 2231) | static void fill_buffer(const WideStringType& str, size_t& current...
class wide_string_input_adapter (line 2289) | class wide_string_input_adapter : public input_adapter_protocol
method wide_string_input_adapter (line 2292) | explicit wide_string_input_adapter(const WideStringType& w) noexcept
method get_character (line 2296) | std::char_traits<char>::int_type get_character() noexcept override
method fill_buffer (line 2315) | void fill_buffer()
class input_adapter (line 2335) | class input_adapter
method input_adapter (line 2341) | input_adapter(std::istream& i)
method input_adapter (line 2345) | input_adapter(std::istream&& i)
method input_adapter (line 2348) | input_adapter(const std::wstring& ws)
method input_adapter (line 2351) | input_adapter(const std::u16string& ws)
method input_adapter (line 2354) | input_adapter(const std::u32string& ws)
method input_adapter (line 2364) | input_adapter(CharT b, std::size_t l)
method input_adapter (line 2376) | input_adapter(CharT b)
method input_adapter (line 2385) | input_adapter(IteratorType first, IteratorType last)
method input_adapter (line 2420) | input_adapter(T (&array)[N])
method input_adapter (line 2428) | input_adapter(const ContiguousContainer& c)
class lexer (line 2475) | class lexer
type token_type (line 2484) | enum class token_type
method lexer (line 2549) | explicit lexer(detail::input_adapter_t&& adapter)
method lexer (line 2553) | lexer(const lexer&) = delete;
method lexer (line 2554) | lexer(lexer&&) = delete;
method lexer (line 2555) | lexer& operator=(lexer&) = delete;
method lexer (line 2556) | lexer& operator=(lexer&&) = delete;
method get_decimal_point (line 2565) | static char get_decimal_point() noexcept
method get_codepoint (line 2591) | int get_codepoint()
method next_byte_in_range (line 2639) | bool next_byte_in_range(std::initializer_list<int> ranges)
method token_type (line 2676) | token_type scan_string()
method strtof (line 3262) | static void strtof(float& f, const char* str, char** endptr) noexcept
method strtof (line 3267) | static void strtof(double& f, const char* str, char** endptr) noex...
method strtof (line 3272) | static void strtof(long double& f, const char* str, char** endptr)...
method token_type (line 3317) | token_type scan_number() // lgtm [cpp/use-of-goto]
method token_type (line 3651) | token_type scan_literal(const char* literal_text, const std::size_...
method reset (line 3671) | void reset() noexcept
method get (line 3688) | std::char_traits<char>::int_type get()
method unget (line 3725) | void unget()
method add (line 3752) | void add(int c)
method number_integer_t (line 3763) | constexpr number_integer_t get_number_integer() const noexcept
method number_unsigned_t (line 3769) | constexpr number_unsigned_t get_number_unsigned() const noexcept
method number_float_t (line 3775) | constexpr number_float_t get_number_float() const noexcept
method string_t (line 3781) | string_t& get_string()
method position_t (line 3791) | constexpr position_t get_position() const noexcept
method get_token_string (line 3799) | std::string get_token_string() const
method skip_bom (line 3836) | bool skip_bom()
method token_type (line 3850) | token_type scan()
type is_sax (line 4030) | struct is_sax
type is_sax_static_asserts (line 4062) | struct is_sax_static_asserts
class json_sax_dom_parser (line 4260) | class json_sax_dom_parser
method json_sax_dom_parser (line 4273) | explicit json_sax_dom_parser(BasicJsonType& r, const bool allow_ex...
method null (line 4277) | bool null()
method boolean (line 4283) | bool boolean(bool val)
method number_integer (line 4289) | bool number_integer(number_integer_t val)
method number_unsigned (line 4295) | bool number_unsigned(number_unsigned_t val)
method number_float (line 4301) | bool number_float(number_float_t val, const string_t& /*unused*/)
method string (line 4307) | bool string(string_t& val)
method start_object (line 4313) | bool start_object(std::size_t len)
method key (line 4326) | bool key(string_t& val)
method end_object (line 4333) | bool end_object()
method start_array (line 4339) | bool start_array(std::size_t len)
method end_array (line 4352) | bool end_array()
method parse_error (line 4358) | bool parse_error(std::size_t /*unused*/, const std::string& /*unus...
method is_errored (line 4386) | constexpr bool is_errored() const
method BasicJsonType (line 4399) | BasicJsonType* handle_value(Value&& v)
class json_sax_dom_callback_parser (line 4435) | class json_sax_dom_callback_parser
method json_sax_dom_callback_parser (line 4445) | json_sax_dom_callback_parser(BasicJsonType& r,
method null (line 4453) | bool null()
method boolean (line 4459) | bool boolean(bool val)
method number_integer (line 4465) | bool number_integer(number_integer_t val)
method number_unsigned (line 4471) | bool number_unsigned(number_unsigned_t val)
method number_float (line 4477) | bool number_float(number_float_t val, const string_t& /*unused*/)
method string (line 4483) | bool string(string_t& val)
method start_object (line 4489) | bool start_object(std::size_t len)
method key (line 4511) | bool key(string_t& val)
method end_object (line 4528) | bool end_object()
method start_array (line 4563) | bool start_array(std::size_t len)
method end_array (line 4584) | bool end_array()
method parse_error (line 4615) | bool parse_error(std::size_t /*unused*/, const std::string& /*unus...
method is_errored (line 4643) | constexpr bool is_errored() const
method handle_value (line 4665) | std::pair<bool, BasicJsonType*> handle_value(Value&& v, const bool...
class json_sax_acceptor (line 4748) | class json_sax_acceptor
method null (line 4756) | bool null()
method boolean (line 4761) | bool boolean(bool /*unused*/)
method number_integer (line 4766) | bool number_integer(number_integer_t /*unused*/)
method number_unsigned (line 4771) | bool number_unsigned(number_unsigned_t /*unused*/)
method number_float (line 4776) | bool number_float(number_float_t /*unused*/, const string_t& /*unu...
method string (line 4781) | bool string(string_t& /*unused*/)
method start_object (line 4786) | bool start_object(std::size_t /*unused*/ = std::size_t(-1))
method key (line 4791) | bool key(string_t& /*unused*/)
method end_object (line 4796) | bool end_object()
method start_array (line 4801) | bool start_array(std::size_t /*unused*/ = std::size_t(-1))
method end_array (line 4806) | bool end_array()
method parse_error (line 4811) | bool parse_error(std::size_t /*unused*/, const std::string& /*unus...
class parser (line 4839) | class parser
type parse_event_t (line 4849) | enum class parse_event_t : uint8_t
method parser (line 4869) | explicit parser(detail::input_adapter_t&& adapter,
method parse (line 4888) | void parse(const bool strict, BasicJsonType& result)
method accept (line 4949) | bool accept(const bool strict = true)
method sax_parse (line 4956) | bool sax_parse(SAX* sax, const bool strict = true)
method sax_parse_internal (line 4975) | bool sax_parse_internal(SAX* sax)
method token_type (line 5266) | token_type get_token()
method exception_message (line 5271) | std::string exception_message(const token_type expected, const std...
class primitive_iterator_t (line 5332) | class primitive_iterator_t
method difference_type (line 5343) | constexpr difference_type get_value() const noexcept
method set_begin (line 5349) | void set_begin() noexcept
method set_end (line 5355) | void set_end() noexcept
method is_begin (line 5361) | constexpr bool is_begin() const noexcept
method is_end (line 5367) | constexpr bool is_end() const noexcept
method primitive_iterator_t (line 5382) | primitive_iterator_t operator+(difference_type n) noexcept
method difference_type (line 5389) | constexpr difference_type operator-(primitive_iterator_t lhs, prim...
method primitive_iterator_t (line 5394) | primitive_iterator_t& operator++() noexcept
method primitive_iterator_t (line 5400) | primitive_iterator_t const operator++(int) noexcept
method primitive_iterator_t (line 5407) | primitive_iterator_t& operator--() noexcept
method primitive_iterator_t (line 5413) | primitive_iterator_t const operator--(int) noexcept
method primitive_iterator_t (line 5420) | primitive_iterator_t& operator+=(difference_type n) noexcept
method primitive_iterator_t (line 5426) | primitive_iterator_t& operator-=(difference_type n) noexcept
type internal_iterator (line 5451) | struct internal_iterator
class iteration_proxy (line 5488) | class iteration_proxy
class iteration_proxy_internal (line 1610) | class iteration_proxy_internal
method iteration_proxy_internal (line 1632) | explicit iteration_proxy_internal(IteratorType it) noexcept : an...
method iteration_proxy_internal (line 1635) | iteration_proxy_internal& operator*()
method iteration_proxy_internal (line 1641) | iteration_proxy_internal& operator++()
method value (line 1690) | typename IteratorType::reference value() const
method iteration_proxy (line 1701) | explicit iteration_proxy(typename IteratorType::reference cont) no...
method iteration_proxy_internal (line 1705) | iteration_proxy_internal begin() noexcept
method iteration_proxy_internal (line 1632) | explicit iteration_proxy_internal(IteratorType it) noexcept : an...
method iteration_proxy_internal (line 1635) | iteration_proxy_internal& operator*()
method iteration_proxy_internal (line 1641) | iteration_proxy_internal& operator++()
method value (line 1690) | typename IteratorType::reference value() const
method iteration_proxy_internal (line 1711) | iteration_proxy_internal end() noexcept
method iteration_proxy_internal (line 1632) | explicit iteration_proxy_internal(IteratorType it) noexcept : an...
method iteration_proxy_internal (line 1635) | iteration_proxy_internal& operator*()
method iteration_proxy_internal (line 1641) | iteration_proxy_internal& operator++()
method value (line 1690) | typename IteratorType::reference value() const
class iter_impl (line 5511) | class iter_impl
method iter_impl (line 5548) | iter_impl() = default;
method iter_impl (line 5556) | explicit iter_impl(pointer object) noexcept : m_object(object)
method iter_impl (line 5596) | iter_impl(const iter_impl<typename std::remove_const<BasicJsonType...
method iter_impl (line 5605) | iter_impl& operator=(const iter_impl<typename std::remove_const<Ba...
method set_begin (line 5617) | void set_begin() noexcept
method set_end (line 5654) | void set_end() noexcept
method reference (line 5685) | reference operator*() const
method pointer (line 5722) | pointer operator->() const
method iter_impl (line 5756) | iter_impl const operator++(int)
method iter_impl (line 5767) | iter_impl& operator++()
method iter_impl (line 5799) | iter_impl const operator--(int)
method iter_impl (line 5810) | iter_impl& operator--()
method iter_impl (line 5932) | iter_impl& operator+=(difference_type i)
method iter_impl (line 5961) | iter_impl& operator-=(difference_type i)
method iter_impl (line 5970) | iter_impl operator+(difference_type i) const
method iter_impl (line 5981) | iter_impl operator+(difference_type i, const iter_impl& it)
method iter_impl (line 5992) | iter_impl operator-(difference_type i) const
method difference_type (line 6003) | difference_type operator-(const iter_impl& other) const
method reference (line 6024) | reference operator[](difference_type n) const
method reference (line 6071) | reference value() const
class json_reverse_iterator (line 6121) | class json_reverse_iterator : public std::reverse_iterator<Base>
method json_reverse_iterator (line 6131) | explicit json_reverse_iterator(const typename base_iterator::itera...
method json_reverse_iterator (line 6135) | explicit json_reverse_iterator(const base_iterator& it) noexcept :...
method json_reverse_iterator (line 6138) | json_reverse_iterator const operator++(int)
method json_reverse_iterator (line 6144) | json_reverse_iterator& operator++()
method json_reverse_iterator (line 6150) | json_reverse_iterator const operator--(int)
method json_reverse_iterator (line 6156) | json_reverse_iterator& operator--()
method json_reverse_iterator (line 6162) | json_reverse_iterator& operator+=(difference_type i)
method json_reverse_iterator (line 6168) | json_reverse_iterator operator+(difference_type i) const
method json_reverse_iterator (line 6174) | json_reverse_iterator operator-(difference_type i) const
method difference_type (line 6180) | difference_type operator-(const json_reverse_iterator& other) const
method reference (line 6186) | reference operator[](difference_type n) const
method key (line 6192) | auto key() const -> decltype(std::declval<Base>().key())
method reference (line 6199) | reference value() const
type output_adapter_protocol (line 6225) | struct output_adapter_protocol
class output_vector_adapter (line 6238) | class output_vector_adapter : public output_adapter_protocol<CharType>
method output_vector_adapter (line 6241) | explicit output_vector_adapter(std::vector<CharType>& vec) noexcept
method write_character (line 6245) | void write_character(CharType c) override
method write_characters (line 6250) | void write_characters(const CharType* s, std::size_t length) override
class output_stream_adapter (line 6261) | class output_stream_adapter : public output_adapter_protocol<CharType>
method output_stream_adapter (line 6264) | explicit output_stream_adapter(std::basic_ostream<CharType>& s) no...
method write_character (line 6268) | void write_character(CharType c) override
method write_characters (line 6273) | void write_characters(const CharType* s, std::size_t length) override
class output_string_adapter (line 6284) | class output_string_adapter : public output_adapter_protocol<CharType>
method output_string_adapter (line 6287) | explicit output_string_adapter(StringType& s) noexcept
method write_character (line 6291) | void write_character(CharType c) override
method write_characters (line 6296) | void write_characters(const CharType* s, std::size_t length) override
class output_adapter (line 6306) | class output_adapter
method output_adapter (line 6309) | output_adapter(std::vector<CharType>& vec)
method output_adapter (line 6312) | output_adapter(std::basic_ostream<CharType>& s)
method output_adapter (line 6315) | output_adapter(StringType& s)
class binary_reader (line 6370) | class binary_reader
method binary_reader (line 6384) | explicit binary_reader(input_adapter_t adapter) : ia(std::move(ada...
method sax_parse (line 6397) | bool sax_parse(const input_format_t format,
method little_endianess (line 6457) | static constexpr bool little_endianess(int num = 1) noexcept
method parse_bson_internal (line 6471) | bool parse_bson_internal()
method get_bson_cstr (line 6496) | bool get_bson_cstr(string_t& result)
method get_bson_string (line 6528) | bool get_bson_string(const NumberType len, string_t& result)
method parse_bson_element_internal (line 6549) | bool parse_bson_element_internal(const int element_type,
method parse_bson_element_list (line 6620) | bool parse_bson_element_list(const bool is_array)
method parse_bson_array (line 6660) | bool parse_bson_array()
method parse_cbor_internal (line 6689) | bool parse_cbor_internal(const bool get_char = true)
method get_cbor_string (line 7031) | bool get_cbor_string(string_t& result)
method get_cbor_array (line 7120) | bool get_cbor_array(const std::size_t len)
method get_cbor_object (line 7156) | bool get_cbor_object(const std::size_t len)
method parse_msgpack_internal (line 7208) | bool parse_msgpack_internal()
method get_msgpack_string (line 7577) | bool get_msgpack_string(string_t& result)
method get_msgpack_array (line 7653) | bool get_msgpack_array(const std::size_t len)
method get_msgpack_object (line 7675) | bool get_msgpack_object(const std::size_t len)
method parse_ubjson_internal (line 7712) | bool parse_ubjson_internal(const bool get_char = true)
method get_ubjson_string (line 7731) | bool get_ubjson_string(string_t& result, const bool get_char = true)
method get_ubjson_size_value (line 7785) | bool get_ubjson_size_value(std::size_t& result)
method get_ubjson_size_type (line 7862) | bool get_ubjson_size_type(std::pair<std::size_t, int>& result)
method get_ubjson_value (line 7901) | bool get_ubjson_value(const int prefix)
method get_ubjson_array (line 7997) | bool get_ubjson_array()
method get_ubjson_object (line 8059) | bool get_ubjson_object()
method get (line 8144) | int get()
method get_ignore_noop (line 8153) | int get_ignore_noop()
method get_number (line 8178) | bool get_number(const input_format_t format, NumberType& result)
method get_string (line 8221) | bool get_string(const input_format_t format,
method unexpect_eof (line 8243) | bool unexpect_eof(const input_format_t format, const char* context...
method get_token_string (line 8256) | std::string get_token_string() const
method exception_message (line 8269) | std::string exception_message(const input_format_t format,
class binary_writer (line 8347) | class binary_writer
method binary_writer (line 8357) | explicit binary_writer(output_adapter_t<CharType> adapter) : oa(ad...
method write_bson (line 8366) | void write_bson(const BasicJsonType& j)
method write_cbor (line 8386) | void write_cbor(const BasicJsonType& j)
method write_msgpack (line 8630) | void write_msgpack(const BasicJsonType& j)
method write_ubjson (line 8872) | void write_ubjson(const BasicJsonType& j, const bool use_count,
method calc_bson_entry_header_size (line 9036) | static std::size_t calc_bson_entry_header_size(const string_t& name)
method write_bson_entry_header (line 9051) | void write_bson_entry_header(const string_t& name,
method write_bson_boolean (line 9063) | void write_bson_boolean(const string_t& name,
method write_bson_double (line 9073) | void write_bson_double(const string_t& name,
method calc_bson_string_size (line 9083) | static std::size_t calc_bson_string_size(const string_t& value)
method write_bson_string (line 9091) | void write_bson_string(const string_t& name,
method write_bson_null (line 9105) | void write_bson_null(const string_t& name)
method calc_bson_integer_size (line 9113) | static std::size_t calc_bson_integer_size(const std::int64_t value)
method write_bson_integer (line 9128) | void write_bson_integer(const string_t& name,
method calc_bson_unsigned_size (line 9146) | static constexpr std::size_t calc_bson_unsigned_size(const std::ui...
method write_bson_unsigned (line 9156) | void write_bson_unsigned(const string_t& name,
method write_bson_object_entry (line 9178) | void write_bson_object_entry(const string_t& name,
method calc_bson_array_size (line 9188) | static std::size_t calc_bson_array_size(const typename BasicJsonTy...
method write_bson_array (line 9204) | void write_bson_array(const string_t& name,
method calc_bson_element_size (line 9224) | static std::size_t calc_bson_element_size(const string_t& name,
method write_bson_element (line 9269) | void write_bson_element(const string_t& name,
method calc_bson_object_size (line 9312) | static std::size_t calc_bson_object_size(const typename BasicJsonT...
method write_bson_object (line 9327) | void write_bson_object(const typename BasicJsonType::object_t& value)
method CharType (line 9343) | static constexpr CharType get_cbor_float_prefix(float /*unused*/)
method CharType (line 9348) | static constexpr CharType get_cbor_float_prefix(double /*unused*/)
method CharType (line 9357) | static constexpr CharType get_msgpack_float_prefix(float /*unused*/)
method CharType (line 9362) | static constexpr CharType get_msgpack_float_prefix(double /*unused*/)
method write_number_with_ubjson_prefix (line 9374) | void write_number_with_ubjson_prefix(const NumberType n,
method write_number_with_ubjson_prefix (line 9387) | void write_number_with_ubjson_prefix(const NumberType n,
method write_number_with_ubjson_prefix (line 9440) | void write_number_with_ubjson_prefix(const NumberType n,
method CharType (line 9500) | CharType ubjson_prefix(const BasicJsonType& j) const noexcept
method CharType (line 9571) | static constexpr CharType get_ubjson_float_prefix(float /*unused*/)
method CharType (line 9576) | static constexpr CharType get_ubjson_float_prefix(double /*unused*/)
method write_number (line 9597) | void write_number(const NumberType n)
method CharType (line 9620) | static constexpr CharType to_char_type(std::uint8_t x) noexcept
method CharType (line 9627) | static CharType to_char_type(std::uint8_t x) noexcept
method CharType (line 9638) | static constexpr CharType to_char_type(std::uint8_t x) noexcept
method CharType (line 9649) | static constexpr CharType to_char_type(InputCharType x) noexcept
type dtoa_impl (line 9715) | namespace dtoa_impl
function Target (line 9719) | Target reinterpret_bits(const Source source)
type diyfp (line 9728) | struct diyfp // f * 2^e
method diyfp (line 9735) | constexpr diyfp(uint64_t f_, int e_) noexcept : f(f_), e(e_) {}
method diyfp (line 9741) | static diyfp sub(const diyfp& x, const diyfp& y) noexcept
method diyfp (line 9753) | static diyfp mul(const diyfp& x, const diyfp& y) noexcept
method diyfp (line 9818) | static diyfp normalize(diyfp x) noexcept
method diyfp (line 9835) | static diyfp normalize_to(const diyfp& x, const int target_expon...
type boundaries (line 9846) | struct boundaries
function boundaries (line 9860) | boundaries compute_boundaries(FloatType value)
type cached_power (line 9985) | struct cached_power // c = f * 2^e ~= 10^k
function cached_power (line 9999) | inline cached_power get_cached_power_for_binary_exponent(int e)
function find_largest_pow10 (line 10163) | inline int find_largest_pow10(const uint32_t n, uint32_t& pow10)
function grisu2_round (line 10219) | inline void grisu2_round(char* buf, int len, uint64_t dist, uint64...
function grisu2_digit_gen (line 10260) | inline void grisu2_digit_gen(char* buffer, int& length, int& decim...
function grisu2 (line 10500) | inline void grisu2(char* buf, int& len, int& decimal_exponent,
function grisu2 (line 10559) | void grisu2(char* buf, int& len, int& decimal_exponent, FloatType ...
type error_handler_t (line 10798) | enum class error_handler_t
class serializer (line 10806) | class serializer
method serializer (line 10821) | serializer(output_adapter_t<char> s, const char ichar,
method serializer (line 10833) | serializer(const serializer&) = delete;
method serializer (line 10834) | serializer& operator=(const serializer&) = delete;
method serializer (line 10835) | serializer(serializer&&) = delete;
method serializer (line 10836) | serializer& operator=(serializer&&) = delete;
method dump (line 10856) | void dump(const BasicJsonType& val, const bool pretty_print,
method dump_escaped (line 11063) | void dump_escaped(const string_t& s, const bool ensure_ascii)
method dump_integer (line 11308) | void dump_integer(NumberType x)
method dump_float (line 11349) | void dump_float(number_float_t x)
method dump_float (line 11370) | void dump_float(number_float_t x, std::true_type /*is_ieee_single_...
method dump_float (line 11378) | void dump_float(number_float_t x, std::false_type /*is_ieee_single...
method decode (line 11448) | static uint8_t decode(uint8_t& state, uint32_t& codep, const uint8...
class json_ref (line 11522) | class json_ref
method json_ref (line 11527) | json_ref(value_type&& value)
method json_ref (line 11531) | json_ref(const value_type& value)
method json_ref (line 11535) | json_ref(std::initializer_list<json_ref> init)
method json_ref (line 11542) | json_ref(Args && ... args)
method json_ref (line 11547) | json_ref(json_ref&&) = default;
method json_ref (line 11548) | json_ref(const json_ref&) = delete;
method json_ref (line 11549) | json_ref& operator=(const json_ref&) = delete;
method json_ref (line 11550) | json_ref& operator=(json_ref&&) = delete;
method value_type (line 11553) | value_type moved_or_copied() const
method value_type (line 11562) | value_type const& operator*() const
method value_type (line 11567) | value_type const* operator->() const
type detail (line 339) | namespace detail
type index_sequence (line 273) | struct index_sequence
method size (line 277) | static constexpr std::size_t size() noexcept
type merge_and_renumber (line 284) | struct merge_and_renumber
type make_index_sequence (line 291) | struct make_index_sequence
type make_index_sequence<0> (line 295) | struct make_index_sequence<0> : index_sequence<> {}
type make_index_sequence<1> (line 296) | struct make_index_sequence<1> : index_sequence<0> {}
type priority_tag (line 302) | struct priority_tag : priority_tag < N - 1 > {}
type priority_tag<0> (line 303) | struct priority_tag<0> {}
type static_const (line 307) | struct static_const
type make_void (line 341) | struct make_void
type nonesuch (line 355) | struct nonesuch
method nonesuch (line 357) | nonesuch() = delete;
method nonesuch (line 359) | nonesuch(nonesuch const&) = delete;
type detector (line 367) | struct detector
type is_basic_json (line 429) | struct is_basic_json : std::false_type {}
type has_from_json (line 473) | struct has_from_json : std::false_type {}
type has_from_json<BasicJsonType, T,
enable_if_t<not is_basic_json<T>::value>> (line 476) | struct has_from_json<BasicJsonType, T,
type has_non_default_from_json (line 489) | struct has_non_default_from_json : std::false_type {}
type has_non_default_from_json<BasicJsonType, T, enable_if_t<not is_basic_json<T>::value>> (line 492) | struct has_non_default_from_json<BasicJsonType, T, enable_if_t<not i...
type has_to_json (line 504) | struct has_to_json : std::false_type {}
type has_to_json<BasicJsonType, T, enable_if_t<not is_basic_json<T>::value>> (line 507) | struct has_to_json<BasicJsonType, T, enable_if_t<not is_basic_json<T...
type is_iterator_traits (line 522) | struct is_iterator_traits : std::false_type {}
type is_iterator_traits<std::iterator_traits<T>> (line 525) | struct is_iterator_traits<std::iterator_traits<T>>
type is_complete_type (line 542) | struct is_complete_type : std::false_type {}
type is_complete_type<T, decltype(void(sizeof(T)))> (line 545) | struct is_complete_type<T, decltype(void(sizeof(T)))> : std::true_ty...
type is_compatible_object_type_impl (line 549) | struct is_compatible_object_type_impl : std::false_type {}
type is_compatible_object_type_impl <
BasicJsonType, CompatibleObjectType,
enable_if_t<is_detected<mapped_type_t, CompatibleObjectType>::value and
is_detected<key_type_t, CompatibleObjectType>::value >> (line 552) | struct is_compatible_object_type_impl <
type is_compatible_object_type (line 569) | struct is_compatible_object_type
type is_constructible_object_type_impl (line 574) | struct is_constructible_object_type_impl : std::false_type {}
type is_constructible_object_type_impl <
BasicJsonType, ConstructibleObjectType,
enable_if_t<is_detected<mapped_type_t, ConstructibleObjectType>::value and
is_detected<key_type_t, ConstructibleObjectType>::value >> (line 577) | struct is_constructible_object_type_impl <
type is_constructible_object_type (line 592) | struct is_constructible_object_type
type is_compatible_string_type_impl (line 598) | struct is_compatible_string_type_impl : std::false_type {}
type is_compatible_string_type_impl <
BasicJsonType, CompatibleStringType,
enable_if_t<is_detected_exact<typename BasicJsonType::string_t::value_type,
value_type_t, CompatibleStringType>::value >> (line 601) | struct is_compatible_string_type_impl <
type is_compatible_string_type (line 611) | struct is_compatible_string_type
type is_constructible_string_type_impl (line 616) | struct is_constructible_string_type_impl : std::false_type {}
type is_constructible_string_type_impl <
BasicJsonType, ConstructibleStringType,
enable_if_t<is_detected_exact<typename BasicJsonType::string_t::value_type,
value_type_t, ConstructibleStringType>::value >> (line 619) | struct is_constructible_string_type_impl <
type is_constructible_string_type (line 630) | struct is_constructible_string_type
type is_compatible_array_type_impl (line 634) | struct is_compatible_array_type_impl : std::false_type {}
type is_compatible_array_type (line 653) | struct is_compatible_array_type
type is_constructible_array_type_impl (line 657) | struct is_constructible_array_type_impl : std::false_type {}
type is_constructible_array_type_impl <
BasicJsonType, ConstructibleArrayType,
enable_if_t<std::is_same<ConstructibleArrayType,
typename BasicJsonType::value_type>::value >> (line 660) | struct is_constructible_array_type_impl <
type is_constructible_array_type_impl <
BasicJsonType, ConstructibleArrayType,
enable_if_t<not std::is_same<ConstructibleArrayType,
typename BasicJsonType::value_type>::value and
is_detected<value_type_t, ConstructibleArrayType>::value and
is_detected<iterator_t, ConstructibleArrayType>::value and
is_complete_type<
detected_t<value_type_t, ConstructibleArrayType>>::value >> (line 667) | struct is_constructible_array_type_impl <
type is_constructible_array_type (line 692) | struct is_constructible_array_type
type is_compatible_integer_type_impl (line 697) | struct is_compatible_integer_type_impl : std::false_type {}
type is_compatible_integer_type_impl <
RealIntegerType, CompatibleNumberIntegerType,
enable_if_t<std::is_integral<RealIntegerType>::value and
std::is_integral<CompatibleNumberIntegerType>::value and
not std::is_same<bool, CompatibleNumberIntegerType>::value >> (line 700) | struct is_compatible_integer_type_impl <
type is_compatible_integer_type (line 718) | struct is_compatible_integer_type
type is_compatible_type_impl (line 723) | struct is_compatible_type_impl: std::false_type {}
type is_compatible_type_impl <
BasicJsonType, CompatibleType,
enable_if_t<is_complete_type<CompatibleType>::value >> (line 726) | struct is_compatible_type_impl <
type is_compatible_type (line 735) | struct is_compatible_type
type position_t (line 757) | struct position_t
class exception (line 813) | class exception : public std::exception
method exception (line 826) | exception(int id_, const char* what_arg) : id(id_), m(what_arg) {}
method name (line 828) | static std::string name(const std::string& ename, int id_)
class parse_error (line 882) | class parse_error : public exception
method parse_error (line 894) | static parse_error create(int id_, const position_t& pos, const st...
method parse_error (line 901) | static parse_error create(int id_, std::size_t byte_, const std::s...
method parse_error (line 921) | parse_error(int id_, std::size_t byte_, const char* what_arg)
method position_string (line 924) | static std::string position_string(const position_t& pos)
class invalid_iterator (line 968) | class invalid_iterator : public exception
method invalid_iterator (line 971) | static invalid_iterator create(int id_, const std::string& what_arg)
method invalid_iterator (line 978) | invalid_iterator(int id_, const char* what_arg)
class type_error (line 1021) | class type_error : public exception
method type_error (line 1024) | static type_error create(int id_, const std::string& what_arg)
method type_error (line 1031) | type_error(int id_, const char* what_arg) : exception(id_, what_ar...
class out_of_range (line 1067) | class out_of_range : public exception
method out_of_range (line 1070) | static out_of_range create(int id_, const std::string& what_arg)
method out_of_range (line 1077) | out_of_range(int id_, const char* what_arg) : exception(id_, what_...
class other_error (line 1104) | class other_error : public exception
method other_error (line 1107) | static other_error create(int id_, const std::string& what_arg)
method other_error (line 1114) | other_error(int id_, const char* what_arg) : exception(id_, what_a...
type value_t (line 1159) | enum class value_t : std::uint8_t
function from_json (line 1229) | void from_json(const BasicJsonType& j, typename std::nullptr_t& n)
function get_arithmetic_value (line 1243) | void get_arithmetic_value(const BasicJsonType& j, ArithmeticType& val)
function from_json (line 1269) | void from_json(const BasicJsonType& j, typename BasicJsonType::boole...
function from_json (line 1279) | void from_json(const BasicJsonType& j, typename BasicJsonType::strin...
function from_json (line 1295) | void from_json(const BasicJsonType& j, ConstructibleStringType& s)
function from_json (line 1306) | void from_json(const BasicJsonType& j, typename BasicJsonType::numbe...
function from_json (line 1312) | void from_json(const BasicJsonType& j, typename BasicJsonType::numbe...
function from_json (line 1318) | void from_json(const BasicJsonType& j, typename BasicJsonType::numbe...
function from_json (line 1325) | void from_json(const BasicJsonType& j, EnumType& e)
function from_json (line 1335) | void from_json(const BasicJsonType& j, std::forward_list<T, Allocato...
function from_json (line 1351) | void from_json(const BasicJsonType& j, std::valarray<T>& l)
function from_json_array_impl (line 1362) | void from_json_array_impl(const BasicJsonType& j, typename BasicJson...
function from_json_array_impl (line 1368) | auto from_json_array_impl(const BasicJsonType& j, std::array<T, N>& ...
function from_json_array_impl (line 1379) | auto from_json_array_impl(const BasicJsonType& j, ConstructibleArray...
function from_json_array_impl (line 1398) | void from_json_array_impl(const BasicJsonType& j, ConstructibleArray...
function from_json (line 1421) | auto from_json(const BasicJsonType& j, ConstructibleArrayType& arr)
function from_json (line 1437) | void from_json(const BasicJsonType& j, ConstructibleObjectType& obj)
function from_json (line 1467) | void from_json(const BasicJsonType& j, ArithmeticType& val)
function from_json (line 1498) | void from_json(const BasicJsonType& j, std::pair<A1, A2>& p)
function from_json_tuple_impl (line 1504) | void from_json_tuple_impl(const BasicJsonType& j, Tuple& t, index_se...
function from_json (line 1510) | void from_json(const BasicJsonType& j, std::tuple<Args...>& t)
function from_json (line 1518) | void from_json(const BasicJsonType& j, std::map<Key, Value, Compare,...
function from_json (line 1537) | void from_json(const BasicJsonType& j, std::unordered_map<Key, Value...
type from_json_fn (line 1553) | struct from_json_fn
class iteration_proxy (line 1606) | class iteration_proxy
class iteration_proxy_internal (line 1610) | class iteration_proxy_internal
method iteration_proxy_internal (line 1632) | explicit iteration_proxy_internal(IteratorType it) noexcept : an...
method iteration_proxy_internal (line 1635) | iteration_proxy_internal& operator*()
method iteration_proxy_internal (line 1641) | iteration_proxy_internal& operator++()
method value (line 1690) | typename IteratorType::reference value() const
method iteration_proxy (line 1701) | explicit iteration_proxy(typename IteratorType::reference cont) no...
method iteration_proxy_internal (line 1705) | iteration_proxy_internal begin() noexcept
method iteration_proxy_internal (line 1632) | explicit iteration_proxy_internal(IteratorType it) noexcept : an...
method iteration_proxy_internal (line 1635) | iteration_proxy_internal& operator*()
method iteration_proxy_internal (line 1641) | iteration_proxy_internal& operator++()
method value (line 1690) | typename IteratorType::reference value() const
method iteration_proxy_internal (line 1711) | iteration_proxy_internal end() noexcept
method iteration_proxy_internal (line 1632) | explicit iteration_proxy_internal(IteratorType it) noexcept : an...
method iteration_proxy_internal (line 1635) | iteration_proxy_internal& operator*()
method iteration_proxy_internal (line 1641) | iteration_proxy_internal& operator++()
method value (line 1690) | typename IteratorType::reference value() const
type external_constructor (line 1728) | struct external_constructor
type external_constructor<value_t::boolean> (line 1731) | struct external_constructor<value_t::boolean>
method construct (line 1734) | static void construct(BasicJsonType& j, typename BasicJsonType::bo...
type external_constructor<value_t::string> (line 1743) | struct external_constructor<value_t::string>
method construct (line 1746) | static void construct(BasicJsonType& j, const typename BasicJsonTy...
method construct (line 1754) | static void construct(BasicJsonType& j, typename BasicJsonType::st...
method construct (line 1764) | static void construct(BasicJsonType& j, const CompatibleStringType...
type external_constructor<value_t::number_float> (line 1773) | struct external_constructor<value_t::number_float>
method construct (line 1776) | static void construct(BasicJsonType& j, typename BasicJsonType::nu...
type external_constructor<value_t::number_unsigned> (line 1785) | struct external_constructor<value_t::number_unsigned>
method construct (line 1788) | static void construct(BasicJsonType& j, typename BasicJsonType::nu...
type external_constructor<value_t::number_integer> (line 1797) | struct external_constructor<value_t::number_integer>
method construct (line 1800) | static void construct(BasicJsonType& j, typename BasicJsonType::nu...
type external_constructor<value_t::array> (line 1809) | struct external_constructor<value_t::array>
method construct (line 1812) | static void construct(BasicJsonType& j, const typename BasicJsonTy...
method construct (line 1820) | static void construct(BasicJsonType& j, typename BasicJsonType::ar...
method construct (line 1830) | static void construct(BasicJsonType& j, const CompatibleArrayType&...
method construct (line 1840) | static void construct(BasicJsonType& j, const std::vector<bool>& arr)
method construct (line 1854) | static void construct(BasicJsonType& j, const std::valarray<T>& arr)
type external_constructor<value_t::object> (line 1865) | struct external_constructor<value_t::object>
method construct (line 1868) | static void construct(BasicJsonType& j, const typename BasicJsonTy...
method construct (line 1876) | static void construct(BasicJsonType& j, typename BasicJsonType::ob...
method construct (line 1885) | static void construct(BasicJsonType& j, const CompatibleObjectType...
function to_json (line 1902) | void to_json(BasicJsonType& j, T b) noexcept
function to_json (line 1909) | void to_json(BasicJsonType& j, const CompatibleString& s)
function to_json (line 1915) | void to_json(BasicJsonType& j, typename BasicJsonType::string_t&& s)
function to_json (line 1922) | void to_json(BasicJsonType& j, FloatType val) noexcept
function to_json (line 1929) | void to_json(BasicJsonType& j, CompatibleNumberUnsignedType val) noe...
function to_json (line 1936) | void to_json(BasicJsonType& j, CompatibleNumberIntegerType val) noex...
function to_json (line 1943) | void to_json(BasicJsonType& j, EnumType e) noexcept
function to_json (line 1950) | void to_json(BasicJsonType& j, const std::vector<bool>& e)
function to_json (line 1963) | void to_json(BasicJsonType& j, const CompatibleArrayType& arr)
function to_json (line 1970) | void to_json(BasicJsonType& j, const std::valarray<T>& arr)
function to_json (line 1976) | void to_json(BasicJsonType& j, typename BasicJsonType::array_t&& arr)
function to_json (line 1983) | void to_json(BasicJsonType& j, const CompatibleObjectType& obj)
function to_json (line 1989) | void to_json(BasicJsonType& j, typename BasicJsonType::object_t&& obj)
function to_json (line 1999) | void to_json(BasicJsonType& j, const T (&arr)[N])
function to_json (line 2005) | void to_json(BasicJsonType& j, const std::pair<Args...>& p)
function to_json (line 2013) | void to_json(BasicJsonType& j, const T& b)
function to_json_tuple_impl (line 2019) | void to_json_tuple_impl(BasicJsonType& j, const Tuple& t, index_sequ...
function to_json (line 2025) | void to_json(BasicJsonType& j, const std::tuple<Args...>& t)
type to_json_fn (line 2030) | struct to_json_fn
type input_format_t (line 2070) | enum class input_format_t { json, cbor, msgpack, ubjson, bson }
type input_adapter_protocol (line 2087) | struct input_adapter_protocol
class input_stream_adapter (line 2106) | class input_stream_adapter : public input_adapter_protocol
method input_stream_adapter (line 2116) | explicit input_stream_adapter(std::istream& i)
method input_stream_adapter (line 2121) | input_stream_adapter(const input_stream_adapter&) = delete;
method input_stream_adapter (line 2122) | input_stream_adapter& operator=(input_stream_adapter&) = delete;
method input_stream_adapter (line 2123) | input_stream_adapter(input_stream_adapter&&) = delete;
method input_stream_adapter (line 2124) | input_stream_adapter& operator=(input_stream_adapter&&) = delete;
method get_character (line 2129) | std::char_traits<char>::int_type get_character() override
class input_buffer_adapter (line 2141) | class input_buffer_adapter : public input_adapter_protocol
method input_buffer_adapter (line 2144) | input_buffer_adapter(const char* b, const std::size_t l) noexcept
method input_buffer_adapter (line 2149) | input_buffer_adapter(const input_buffer_adapter&) = delete;
method input_buffer_adapter (line 2150) | input_buffer_adapter& operator=(input_buffer_adapter&) = delete;
method input_buffer_adapter (line 2151) | input_buffer_adapter(input_buffer_adapter&&) = delete;
method input_buffer_adapter (line 2152) | input_buffer_adapter& operator=(input_buffer_adapter&&) = delete;
method get_character (line 2155) | std::char_traits<char>::int_type get_character() noexcept override
type wide_string_input_helper (line 2173) | struct wide_string_input_helper
method fill_buffer (line 2176) | static void fill_buffer(const WideStringType& str, size_t& current...
type wide_string_input_helper<WideStringType, 2> (line 2228) | struct wide_string_input_helper<WideStringType, 2>
method fill_buffer (line 2231) | static void fill_buffer(const WideStringType& str, size_t& current...
class wide_string_input_adapter (line 2289) | class wide_string_input_adapter : public input_adapter_protocol
method wide_string_input_adapter (line 2292) | explicit wide_string_input_adapter(const WideStringType& w) noexcept
method get_character (line 2296) | std::char_traits<char>::int_type get_character() noexcept override
method fill_buffer (line 2315) | void fill_buffer()
class input_adapter (line 2335) | class input_adapter
method input_adapter (line 2341) | input_adapter(std::istream& i)
method input_adapter (line 2345) | input_adapter(std::istream&& i)
method input_adapter (line 2348) | input_adapter(const std::wstring& ws)
method input_adapter (line 2351) | input_adapter(const std::u16string& ws)
method input_adapter (line 2354) | input_adapter(const std::u32string& ws)
method input_adapter (line 2364) | input_adapter(CharT b, std::size_t l)
method input_adapter (line 2376) | input_adapter(CharT b)
method input_adapter (line 2385) | input_adapter(IteratorType first, IteratorType last)
method input_adapter (line 2420) | input_adapter(T (&array)[N])
method input_adapter (line 2428) | input_adapter(const ContiguousContainer& c)
class lexer (line 2475) | class lexer
type token_type (line 2484) | enum class token_type
method lexer (line 2549) | explicit lexer(detail::input_adapter_t&& adapter)
method lexer (line 2553) | lexer(const lexer&) = delete;
method lexer (line 2554) | lexer(lexer&&) = delete;
method lexer (line 2555) | lexer& operator=(lexer&) = delete;
method lexer (line 2556) | lexer& operator=(lexer&&) = delete;
method get_decimal_point (line 2565) | static char get_decimal_point() noexcept
method get_codepoint (line 2591) | int get_codepoint()
method next_byte_in_range (line 2639) | bool next_byte_in_range(std::initializer_list<int> ranges)
method token_type (line 2676) | token_type scan_string()
method strtof (line 3262) | static void strtof(float& f, const char* str, char** endptr) noexcept
method strtof (line 3267) | static void strtof(double& f, const char* str, char** endptr) noex...
method strtof (line 3272) | static void strtof(long double& f, const char* str, char** endptr)...
method token_type (line 3317) | token_type scan_number() // lgtm [cpp/use-of-goto]
method token_type (line 3651) | token_type scan_literal(const char* literal_text, const std::size_...
method reset (line 3671) | void reset() noexcept
method get (line 3688) | std::char_traits<char>::int_type get()
method unget (line 3725) | void unget()
method add (line 3752) | void add(int c)
method number_integer_t (line 3763) | constexpr number_integer_t get_number_integer() const noexcept
method number_unsigned_t (line 3769) | constexpr number_unsigned_t get_number_unsigned() const noexcept
method number_float_t (line 3775) | constexpr number_float_t get_number_float() const noexcept
method string_t (line 3781) | string_t& get_string()
method position_t (line 3791) | constexpr position_t get_position() const noexcept
method get_token_string (line 3799) | std::string get_token_string() const
method skip_bom (line 3836) | bool skip_bom()
method token_type (line 3850) | token_type scan()
type is_sax (line 4030) | struct is_sax
type is_sax_static_asserts (line 4062) | struct is_sax_static_asserts
class json_sax_dom_parser (line 4260) | class json_sax_dom_parser
method json_sax_dom_parser (line 4273) | explicit json_sax_dom_parser(BasicJsonType& r, const bool allow_ex...
method null (line 4277) | bool null()
method boolean (line 4283) | bool boolean(bool val)
method number_integer (line 4289) | bool number_integer(number_integer_t val)
method number_unsigned (line 4295) | bool number_unsigned(number_unsigned_t val)
method number_float (line 4301) | bool number_float(number_float_t val, const string_t& /*unused*/)
method string (line 4307) | bool string(string_t& val)
method start_object (line 4313) | bool start_object(std::size_t len)
method key (line 4326) | bool key(string_t& val)
method end_object (line 4333) | bool end_object()
method start_array (line 4339) | bool start_array(std::size_t len)
method end_array (line 4352) | bool end_array()
method parse_error (line 4358) | bool parse_error(std::size_t /*unused*/, const std::string& /*unus...
method is_errored (line 4386) | constexpr bool is_errored() const
method BasicJsonType (line 4399) | BasicJsonType* handle_value(Value&& v)
class json_sax_dom_callback_parser (line 4435) | class json_sax_dom_callback_parser
method json_sax_dom_callback_parser (line 4445) | json_sax_dom_callback_parser(BasicJsonType& r,
method null (line 4453) | bool null()
method boolean (line 4459) | bool boolean(bool val)
method number_integer (line 4465) | bool number_integer(number_integer_t val)
method number_unsigned (line 4471) | bool number_unsigned(number_unsigned_t val)
method number_float (line 4477) | bool number_float(number_float_t val, const string_t& /*unused*/)
method string (line 4483) | bool string(string_t& val)
method start_object (line 4489) | bool start_object(std::size_t len)
method key (line 4511) | bool key(string_t& val)
method end_object (line 4528) | bool end_object()
method start_array (line 4563) | bool start_array(std::size_t len)
method end_array (line 4584) | bool end_array()
method parse_error (line 4615) | bool parse_error(std::size_t /*unused*/, const std::string& /*unus...
method is_errored (line 4643) | constexpr bool is_errored() const
method handle_value (line 4665) | std::pair<bool, BasicJsonType*> handle_value(Value&& v, const bool...
class json_sax_acceptor (line 4748) | class json_sax_acceptor
method null (line 4756) | bool null()
method boolean (line 4761) | bool boolean(bool /*unused*/)
method number_integer (line 4766) | bool number_integer(number_integer_t /*unused*/)
method number_unsigned (line 4771) | bool number_unsigned(number_unsigned_t /*unused*/)
method number_float (line 4776) | bool number_float(number_float_t /*unused*/, const string_t& /*unu...
method string (line 4781) | bool string(string_t& /*unused*/)
method start_object (line 4786) | bool start_object(std::size_t /*unused*/ = std::size_t(-1))
method key (line 4791) | bool key(string_t& /*unused*/)
method end_object (line 4796) | bool end_object()
method start_array (line 4801) | bool start_array(std::size_t /*unused*/ = std::size_t(-1))
method end_array (line 4806) | bool end_array()
method parse_error (line 4811) | bool parse_error(std::size_t /*unused*/, const std::string& /*unus...
class parser (line 4839) | class parser
type parse_event_t (line 4849) | enum class parse_event_t : uint8_t
method parser (line 4869) | explicit parser(detail::input_adapter_t&& adapter,
method parse (line 4888) | void parse(const bool strict, BasicJsonType& result)
method accept (line 4949) | bool accept(const bool strict = true)
method sax_parse (line 4956) | bool sax_parse(SAX* sax, const bool strict = true)
method sax_parse_internal (line 4975) | bool sax_parse_internal(SAX* sax)
method token_type (line 5266) | token_type get_token()
method exception_message (line 5271) | std::string exception_message(const token_type expected, const std...
class primitive_iterator_t (line 5332) | class primitive_iterator_t
method difference_type (line 5343) | constexpr difference_type get_value() const noexcept
method set_begin (line 5349) | void set_begin() noexcept
method set_end (line 5355) | void set_end() noexcept
method is_begin (line 5361) | constexpr bool is_begin() const noexcept
method is_end (line 5367) | constexpr bool is_end() const noexcept
method primitive_iterator_t (line 5382) | primitive_iterator_t operator+(difference_type n) noexcept
method difference_type (line 5389) | constexpr difference_type operator-(primitive_iterator_t lhs, prim...
method primitive_iterator_t (line 5394) | primitive_iterator_t& operator++() noexcept
method primitive_iterator_t (line 5400) | primitive_iterator_t const operator++(int) noexcept
method primitive_iterator_t (line 5407) | primitive_iterator_t& operator--() noexcept
method primitive_iterator_t (line 5413) | primitive_iterator_t const operator--(int) noexcept
method primitive_iterator_t (line 5420) | primitive_iterator_t& operator+=(difference_type n) noexcept
method primitive_iterator_t (line 5426) | primitive_iterator_t& operator-=(difference_type n) noexcept
type internal_iterator (line 5451) | struct internal_iterator
class iteration_proxy (line 5488) | class iteration_proxy
class iteration_proxy_internal (line 1610) | class iteration_proxy_internal
method iteration_proxy_internal (line 1632) | explicit iteration_proxy_internal(IteratorType it) noexcept : an...
method iteration_proxy_internal (line 1635) | iteration_proxy_internal& operator*()
method iteration_proxy_internal (line 1641) | iteration_proxy_internal& operator++()
method value (line 1690) | typename IteratorType::reference value() const
method iteration_proxy (line 1701) | explicit iteration_proxy(typename IteratorType::reference cont) no...
method iteration_proxy_internal (line 1705) | iteration_proxy_internal begin() noexcept
method iteration_proxy_internal (line 1632) | explicit iteration_proxy_internal(IteratorType it) noexcept : an...
method iteration_proxy_internal (line 1635) | iteration_proxy_internal& operator*()
method iteration_proxy_internal (line 1641) | iteration_proxy_internal& operator++()
method value (line 1690) | typename IteratorType::reference value() const
method iteration_proxy_internal (line 1711) | iteration_proxy_internal end() noexcept
method iteration_proxy_internal (line 1632) | explicit iteration_proxy_internal(IteratorType it) noexcept : an...
method iteration_proxy_internal (line 1635) | iteration_proxy_internal& operator*()
method iteration_proxy_internal (line 1641) | iteration_proxy_internal& operator++()
method value (line 1690) | typename IteratorType::reference value() const
class iter_impl (line 5511) | class iter_impl
method iter_impl (line 5548) | iter_impl() = default;
method iter_impl (line 5556) | explicit iter_impl(pointer object) noexcept : m_object(object)
method iter_impl (line 5596) | iter_impl(const iter_impl<typename std::remove_const<BasicJsonType...
method iter_impl (line 5605) | iter_impl& operator=(const iter_impl<typename std::remove_const<Ba...
method set_begin (line 5617) | void set_begin() noexcept
method set_end (line 5654) | void set_end() noexcept
method reference (line 5685) | reference operator*() const
method pointer (line 5722) | pointer operator->() const
method iter_impl (line 5756) | iter_impl const operator++(int)
method iter_impl (line 5767) | iter_impl& operator++()
method iter_impl (line 5799) | iter_impl const operator--(int)
method iter_impl (line 5810) | iter_impl& operator--()
method iter_impl (line 5932) | iter_impl& operator+=(difference_type i)
method iter_impl (line 5961) | iter_impl& operator-=(difference_type i)
method iter_impl (line 5970) | iter_impl operator+(difference_type i) const
method iter_impl (line 5981) | iter_impl operator+(difference_type i, const iter_impl& it)
method iter_impl (line 5992) | iter_impl operator-(difference_type i) const
method difference_type (line 6003) | difference_type operator-(const iter_impl& other) const
method reference (line 6024) | reference operator[](difference_type n) const
method reference (line 6071) | reference value() const
class json_reverse_iterator (line 6121) | class json_reverse_iterator : public std::reverse_iterator<Base>
method json_reverse_iterator (line 6131) | explicit json_reverse_iterator(const typename base_iterator::itera...
method json_reverse_iterator (line 6135) | explicit json_reverse_iterator(const base_iterator& it) noexcept :...
method json_reverse_iterator (line 6138) | json_reverse_iterator const operator++(int)
method json_reverse_iterator (line 6144) | json_reverse_iterator& operator++()
method json_reverse_iterator (line 6150) | json_reverse_iterator const operator--(int)
method json_reverse_iterator (line 6156) | json_reverse_iterator& operator--()
method json_reverse_iterator (line 6162) | json_reverse_iterator& operator+=(difference_type i)
method json_reverse_iterator (line 6168) | json_reverse_iterator operator+(difference_type i) const
method json_reverse_iterator (line 6174) | json_reverse_iterator operator-(difference_type i) const
method difference_type (line 6180) | difference_type operator-(const json_reverse_iterator& other) const
method reference (line 6186) | reference operator[](difference_type n) const
method key (line 6192) | auto key() const -> decltype(std::declval<Base>().key())
method reference (line 6199) | reference value() const
type output_adapter_protocol (line 6225) | struct output_adapter_protocol
class output_vector_adapter (line 6238) | class output_vector_adapter : public output_adapter_protocol<CharType>
method output_vector_adapter (line 6241) | explicit output_vector_adapter(std::vector<CharType>& vec) noexcept
method write_character (line 6245) | void write_character(CharType c) override
method write_characters (line 6250) | void write_characters(const CharType* s, std::size_t length) override
class output_stream_adapter (line 6261) | class output_stream_adapter : public output_adapter_protocol<CharType>
method output_stream_adapter (line 6264) | explicit output_stream_adapter(std::basic_ostream<CharType>& s) no...
method write_character (line 6268) | void write_character(CharType c) override
method write_characters (line 6273) | void write_characters(const CharType* s, std::size_t length) override
class output_string_adapter (line 6284) | class output_string_adapter : public output_adapter_protocol<CharType>
method output_string_adapter (line 6287) | explicit output_string_adapter(StringType& s) noexcept
method write_character (line 6291) | void write_character(CharType c) override
method write_characters (line 6296) | void write_characters(const CharType* s, std::size_t length) override
class output_adapter (line 6306) | class output_adapter
method output_adapter (line 6309) | output_adapter(std::vector<CharType>& vec)
method output_adapter (line 6312) | output_adapter(std::basic_ostream<CharType>& s)
method output_adapter (line 6315) | output_adapter(StringType& s)
class binary_reader (line 6370) | class binary_reader
method binary_reader (line 6384) | explicit binary_reader(input_adapter_t adapter) : ia(std::move(ada...
method sax_parse (line 6397) | bool sax_parse(const input_format_t format,
method little_endianess (line 6457) | static constexpr bool little_endianess(int num = 1) noexcept
method parse_bson_internal (line 6471) | bool parse_bson_internal()
method get_bson_cstr (line 6496) | bool get_bson_cstr(string_t& result)
method get_bson_string (line 6528) | bool get_bson_string(const NumberType len, string_t& result)
method parse_bson_element_internal (line 6549) | bool parse_bson_element_internal(const int element_type,
method parse_bson_element_list (line 6620) | bool parse_bson_element_list(const bool is_array)
method parse_bson_array (line 6660) | bool parse_bson_array()
method parse_cbor_internal (line 6689) | bool parse_cbor_internal(const bool get_char = true)
method get_cbor_string (line 7031) | bool get_cbor_string(string_t& result)
method get_cbor_array (line 7120) | bool get_cbor_array(const std::size_t len)
method get_cbor_object (line 7156) | bool get_cbor_object(const std::size_t len)
method parse_msgpack_internal (line 7208) | bool parse_msgpack_internal()
method get_msgpack_string (line 7577) | bool get_msgpack_string(string_t& result)
method get_msgpack_array (line 7653) | bool get_msgpack_array(const std::size_t len)
method get_msgpack_object (line 7675) | bool get_msgpack_object(const std::size_t len)
method parse_ubjson_internal (line 7712) | bool parse_ubjson_internal(const bool get_char = true)
method get_ubjson_string (line 7731) | bool get_ubjson_string(string_t& result, const bool get_char = true)
method get_ubjson_size_value (line 7785) | bool get_ubjson_size_value(std::size_t& result)
method get_ubjson_size_type (line 7862) | bool get_ubjson_size_type(std::pair<std::size_t, int>& result)
method get_ubjson_value (line 7901) | bool get_ubjson_value(const int prefix)
method get_ubjson_array (line 7997) | bool get_ubjson_array()
method get_ubjson_object (line 8059) | bool get_ubjson_object()
method get (line 8144) | int get()
method get_ignore_noop (line 8153) | int get_ignore_noop()
method get_number (line 8178) | bool get_number(const input_format_t format, NumberType& result)
method get_string (line 8221) | bool get_string(const input_format_t format,
method unexpect_eof (line 8243) | bool unexpect_eof(const input_format_t format, const char* context...
method get_token_string (line 8256) | std::string get_token_string() const
method exception_message (line 8269) | std::string exception_message(const input_format_t format,
class binary_writer (line 8347) | class binary_writer
method binary_writer (line 8357) | explicit binary_writer(output_adapter_t<CharType> adapter) : oa(ad...
method write_bson (line 8366) | void write_bson(const BasicJsonType& j)
method write_cbor (line 8386) | void write_cbor(const BasicJsonType& j)
method write_msgpack (line 8630) | void write_msgpack(const BasicJsonType& j)
method write_ubjson (line 8872) | void write_ubjson(const BasicJsonType& j, const bool use_count,
method calc_bson_entry_header_size (line 9036) | static std::size_t calc_bson_entry_header_size(const string_t& name)
method write_bson_entry_header (line 9051) | void write_bson_entry_header(const string_t& name,
method write_bson_boolean (line 9063) | void write_bson_boolean(const string_t& name,
method write_bson_double (line 9073) | void write_bson_double(const string_t& name,
method calc_bson_string_size (line 9083) | static std::size_t calc_bson_string_size(const string_t& value)
method write_bson_string (line 9091) | void write_bson_string(const string_t& name,
method write_bson_null (line 9105) | void write_bson_null(const string_t& name)
method calc_bson_integer_size (line 9113) | static std::size_t calc_bson_integer_size(const std::int64_t value)
method write_bson_integer (line 9128) | void write_bson_integer(const string_t& name,
method calc_bson_unsigned_size (line 9146) | static constexpr std::size_t calc_bson_unsigned_size(const std::ui...
method write_bson_unsigned (line 9156) | void write_bson_unsigned(const string_t& name,
method write_bson_object_entry (line 9178) | void write_bson_object_entry(const string_t& name,
method calc_bson_array_size (line 9188) | static std::size_t calc_bson_array_size(const typename BasicJsonTy...
method write_bson_array (line 9204) | void write_bson_array(const string_t& name,
method calc_bson_element_size (line 9224) | static std::size_t calc_bson_element_size(const string_t& name,
method write_bson_element (line 9269) | void write_bson_element(const string_t& name,
method calc_bson_object_size (line 9312) | static std::size_t calc_bson_object_size(const typename BasicJsonT...
method write_bson_object (line 9327) | void write_bson_object(const typename BasicJsonType::object_t& value)
method CharType (line 9343) | static constexpr CharType get_cbor_float_prefix(float /*unused*/)
method CharType (line 9348) | static constexpr CharType get_cbor_float_prefix(double /*unused*/)
method CharType (line 9357) | static constexpr CharType get_msgpack_float_prefix(float /*unused*/)
method CharType (line 9362) | static constexpr CharType get_msgpack_float_prefix(double /*unused*/)
method write_number_with_ubjson_prefix (line 9374) | void write_number_with_ubjson_prefix(const NumberType n,
method write_number_with_ubjson_prefix (line 9387) | void write_number_with_ubjson_prefix(const NumberType n,
method write_number_with_ubjson_prefix (line 9440) | void write_number_with_ubjson_prefix(const NumberType n,
method CharType (line 9500) | CharType ubjson_prefix(const BasicJsonType& j) const noexcept
method CharType (line 9571) | static constexpr CharType get_ubjson_float_prefix(float /*unused*/)
method CharType (line 9576) | static constexpr CharType get_ubjson_float_prefix(double /*unused*/)
method write_number (line 9597) | void write_number(const NumberType n)
method CharType (line 9620) | static constexpr CharType to_char_type(std::uint8_t x) noexcept
method CharType (line 9627) | static CharType to_char_type(std::uint8_t x) noexcept
method CharType (line 9638) | static constexpr CharType to_char_type(std::uint8_t x) noexcept
method CharType (line 9649) | static constexpr CharType to_char_type(InputCharType x) noexcept
type dtoa_impl (line 9715) | namespace dtoa_impl
function Target (line 9719) | Target reinterpret_bits(const Source source)
type diyfp (line 9728) | struct diyfp // f * 2^e
method diyfp (line 9735) | constexpr diyfp(uint64_t f_, int e_) noexcept : f(f_), e(e_) {}
method diyfp (line 9741) | static diyfp sub(const diyfp& x, const diyfp& y) noexcept
method diyfp (line 9753) | static diyfp mul(const diyfp& x, const diyfp& y) noexcept
method diyfp (line 9818) | static diyfp normalize(diyfp x) noexcept
method diyfp (line 9835) | static diyfp normalize_to(const diyfp& x, const int target_expon...
type boundaries (line 9846) | struct boundaries
function boundaries (line 9860) | boundaries compute_boundaries(FloatType value)
type cached_power (line 9985) | struct cached_power // c = f * 2^e ~= 10^k
function cached_power (line 9999) | inline cached_power get_cached_power_for_binary_exponent(int e)
function find_largest_pow10 (line 10163) | inline int find_largest_pow10(const uint32_t n, uint32_t& pow10)
function grisu2_round (line 10219) | inline void grisu2_round(char* buf, int len, uint64_t dist, uint64...
function grisu2_digit_gen (line 10260) | inline void grisu2_digit_gen(char* buffer, int& length, int& decim...
function grisu2 (line 10500) | inline void grisu2(char* buf, int& len, int& decimal_exponent,
function grisu2 (line 10559) | void grisu2(char* buf, int& len, int& decimal_exponent, FloatType ...
type error_handler_t (line 10798) | enum class error_handler_t
class serializer (line 10806) | class serializer
method serializer (line 10821) | serializer(output_adapter_t<char> s, const char ichar,
method serializer (line 10833) | serializer(const serializer&) = delete;
method serializer (line 10834) | serializer& operator=(const serializer&) = delete;
method serializer (line 10835) | serializer(serializer&&) = delete;
method serializer (line 10836) | serializer& operator=(serializer&&) = delete;
method dump (line 10856) | void dump(const BasicJsonType& val, const bool pretty_print,
method dump_escaped (line 11063) | void dump_escaped(const string_t& s, const bool ensure_ascii)
method dump_integer (line 11308) | void dump_integer(NumberType x)
method dump_float (line 11349) | void dump_float(number_float_t x)
method dump_float (line 11370) | void dump_float(number_float_t x, std::true_type /*is_ieee_single_...
method dump_float (line 11378) | void dump_float(number_float_t x, std::false_type /*is_ieee_single...
method decode (line 11448) | static uint8_t decode(uint8_t& state, uint32_t& codep, const uint8...
class json_ref (line 11522) | class json_ref
method json_ref (line 11527) | json_ref(value_type&& value)
method json_ref (line 11531) | json_ref(const value_type& value)
method json_ref (line 11535) | json_ref(std::initializer_list<json_ref> init)
method json_ref (line 11542) | json_ref(Args && ... args)
method json_ref (line 11547) | json_ref(json_ref&&) = default;
method json_ref (line 11548) | json_ref(const json_ref&) = delete;
method json_ref (line 11549) | json_ref& operator=(const json_ref&) = delete;
method json_ref (line 11550) | json_ref& operator=(json_ref&&) = delete;
method value_type (line 11553) | value_type moved_or_copied() const
method value_type (line 11562) | value_type const& operator*() const
method value_type (line 11567) | value_type const* operator->() const
type detail (line 353) | namespace detail
type index_sequence (line 273) | struct index_sequence
method size (line 277) | static constexpr std::size_t size() noexcept
type merge_and_renumber (line 284) | struct merge_and_renumber
type make_index_sequence (line 291) | struct make_index_sequence
type make_index_sequence<0> (line 295) | struct make_index_sequence<0> : index_sequence<> {}
type make_index_sequence<1> (line 296) | struct make_index_sequence<1> : index_sequence<0> {}
type priority_tag (line 302) | struct priority_tag : priority_tag < N - 1 > {}
type priority_tag<0> (line 303) | struct priority_tag<0> {}
type static_const (line 307) | struct static_const
type make_void (line 341) | struct make_void
type nonesuch (line 355) | struct nonesuch
method nonesuch (line 357) | nonesuch() = delete;
method nonesuch (line 359) | nonesuch(nonesuch const&) = delete;
type detector (line 367) | struct detector
type is_basic_json (line 429) | struct is_basic_json : std::false_type {}
type has_from_json (line 473) | struct has_from_json : std::false_type {}
type has_from_json<BasicJsonType, T,
enable_if_t<not is_basic_json<T>::value>> (line 476) | struct has_from_json<BasicJsonType, T,
type has_non_default_from_json (line 489) | struct has_non_default_from_json : std::false_type {}
type has_non_default_from_json<BasicJsonType, T, enable_if_t<not is_basic_json<T>::value>> (line 492) | struct has_non_default_from_json<BasicJsonType, T, enable_if_t<not i...
type has_to_json (line 504) | struct has_to_json : std::false_type {}
type has_to_json<BasicJsonType, T, enable_if_t<not is_basic_json<T>::value>> (line 507) | struct has_to_json<BasicJsonType, T, enable_if_t<not is_basic_json<T...
type is_iterator_traits (line 522) | struct is_iterator_traits : std::false_type {}
type is_iterator_traits<std::iterator_traits<T>> (line 525) | struct is_iterator_traits<std::iterator_traits<T>>
type is_complete_type (line 542) | struct is_complete_type : std::false_type {}
type is_complete_type<T, decltype(void(sizeof(T)))> (line 545) | struct is_complete_type<T, decltype(void(sizeof(T)))> : std::true_ty...
type is_compatible_object_type_impl (line 549) | struct is_compatible_object_type_impl : std::false_type {}
type is_compatible_object_type_impl <
BasicJsonType, CompatibleObjectType,
enable_if_t<is_detected<mapped_type_t, CompatibleObjectType>::value and
is_detected<key_type_t, CompatibleObjectType>::value >> (line 552) | struct is_compatible_object_type_impl <
type is_compatible_object_type (line 569) | struct is_compatible_object_type
type is_constructible_object_type_impl (line 574) | struct is_constructible_object_type_impl : std::false_type {}
type is_constructible_object_type_impl <
BasicJsonType, ConstructibleObjectType,
enable_if_t<is_detected<mapped_type_t, ConstructibleObjectType>::value and
is_detected<key_type_t, ConstructibleObjectType>::value >> (line 577) | struct is_constructible_object_type_impl <
type is_constructible_object_type (line 592) | struct is_constructible_object_type
type is_compatible_string_type_impl (line 598) | struct is_compatible_string_type_impl : std::false_type {}
type is_compatible_string_type_impl <
BasicJsonType, CompatibleStringType,
enable_if_t<is_detected_exact<typename BasicJsonType::string_t::value_type,
value_type_t, CompatibleStringType>::value >> (line 601) | struct is_compatible_string_type_impl <
type is_compatible_string_type (line 611) | struct is_compatible_string_type
type is_constructible_string_type_impl (line 616) | struct is_constructible_string_type_impl : std::false_type {}
type is_constructible_string_type_impl <
BasicJsonType, ConstructibleStringType,
enable_if_t<is_detected_exact<typename BasicJsonType::string_t::value_type,
value_type_t, ConstructibleStringType>::value >> (line 619) | struct is_constructible_string_type_impl <
type is_constructible_string_type (line 630) | struct is_constructible_string_type
type is_compatible_array_type_impl (line 634) | struct is_compatible_array_type_impl : std::false_type {}
type is_compatible_array_type (line 653) | struct is_compatible_array_type
type is_constructible_array_type_impl (line 657) | struct is_constructible_array_type_impl : std::false_type {}
type is_constructible_array_type_impl <
BasicJsonType, ConstructibleArrayType,
enable_if_t<std::is_same<ConstructibleArrayType,
typename BasicJsonType::value_type>::value >> (line 660) | struct is_constructible_array_type_impl <
type is_constructible_array_type_impl <
BasicJsonType, ConstructibleArrayType,
enable_if_t<not std::is_same<ConstructibleArrayType,
typename BasicJsonType::value_type>::value and
is_detected<value_type_t, ConstructibleArrayType>::value and
is_detected<iterator_t, ConstructibleArrayType>::value and
is_complete_type<
detected_t<value_type_t, ConstructibleArrayType>>::value >> (line 667) | struct is_constructible_array_type_impl <
type is_constructible_array_type (line 692) | struct is_constructible_array_type
type is_compatible_integer_type_impl (line 697) | struct is_compatible_integer_type_impl : std::false_type {}
type is_compatible_integer_type_impl <
RealIntegerType, CompatibleNumberIntegerType,
enable_if_t<std::is_integral<RealIntegerType>::value and
std::is_integral<CompatibleNumberIntegerType>::value and
not std::is_same<bool, CompatibleNumberIntegerType>::value >> (line 700) | struct is_compatible_integer_type_impl <
type is_compatible_integer_type (line 718) | struct is_compatible_integer_type
type is_compatible_type_impl (line 723) | struct is_compatible_type_impl: std::false_type {}
type is_compatible_type_impl <
BasicJsonType, CompatibleType,
enable_if_t<is_complete_type<CompatibleType>::value >> (line 726) | struct is_compatible_type_impl <
type is_compatible_type (line 735) | struct is_compatible_type
type position_t (line 757) | struct position_t
class exception (line 813) | class exception : public std::exception
method exception (line 826) | exception(int id_, const char* what_arg) : id(id_), m(what_arg) {}
method name (line 828) | static std::string name(const std::string& ename, int id_)
class parse_error (line 882) | class parse_error : public exception
method parse_error (line 894) | static parse_error create(int id_, const position_t& pos, const st...
method parse_error (line 901) | static parse_error create(int id_, std::size_t byte_, const std::s...
method parse_error (line 921) | parse_error(int id_, std::size_t byte_, const char* what_arg)
method position_string (line 924) | static std::string position_string(const position_t& pos)
class invalid_iterator (line 968) | class invalid_iterator : public exception
method invalid_iterator (line 971) | static invalid_iterator create(int id_, const std::string& what_arg)
method invalid_iterator (line 978) | invalid_iterator(int id_, const char* what_arg)
class type_error (line 1021) | class type_error : public exception
method type_error (line 1024) | static type_error create(int id_, const std::string& what_arg)
method type_error (line 1031) | type_error(int id_, const char* what_arg) : exception(id_, what_ar...
class out_of_range (line 1067) | class out_of_range : public exception
method out_of_range (line 1070) | static out_of_range create(int id_, const std::string& what_arg)
method out_of_range (line 1077) | out_of_range(int id_, const char* what_arg) : exception(id_, what_...
class other_error (line 1104) | class other_error : public exception
method other_error (line 1107) | static other_error create(int id_, const std::string& what_arg)
method other_error (line 1114) | other_error(int id_, const char* what_arg) : exception(id_, what_a...
type value_t (line 1159) | enum class value_t : std::uint8_t
function from_json (line 1229) | void from_json(const BasicJsonType& j, typename std::nullptr_t& n)
function get_arithmetic_value (line 1243) | void get_arithmetic_value(const BasicJsonType& j, ArithmeticType& val)
function from_json (line 1269) | void from_json(const BasicJsonType& j, typename BasicJsonType::boole...
function from_json (line 1279) | void from_json(const BasicJsonType& j, typename BasicJsonType::strin...
function from_json (line 1295) | void from_json(const BasicJsonType& j, ConstructibleStringType& s)
function from_json (line 1306) | void from_json(const BasicJsonType& j, typename BasicJsonType::numbe...
function from_json (line 1312) | void from_json(const BasicJsonType& j, typename BasicJsonType::numbe...
function from_json (line 1318) | void from_json(const BasicJsonType& j, typename BasicJsonType::numbe...
function from_json (line 1325) | void from_json(const BasicJsonType& j, EnumType& e)
function from_json (line 1335) | void from_json(const BasicJsonType& j, std::forward_list<T, Allocato...
function from_json (line 1351) | void from_json(const BasicJsonType& j, std::valarray<T>& l)
function from_json_array_impl (line 1362) | void from_json_array_impl(const BasicJsonType& j, typename BasicJson...
function from_json_array_impl (line 1368) | auto from_json_array_impl(const BasicJsonType& j, std::array<T, N>& ...
function from_json_array_impl (line 1379) | auto from_json_array_impl(const BasicJsonType& j, ConstructibleArray...
function from_json_array_impl (line 1398) | void from_json_array_impl(const BasicJsonType& j, ConstructibleArray...
function from_json (line 1421) | auto from_json(const BasicJsonType& j, ConstructibleArrayType& arr)
function from_json (line 1437) | void from_json(const BasicJsonType& j, ConstructibleObjectType& obj)
function from_json (line 1467) | void from_json(const BasicJsonType& j, ArithmeticType& val)
function from_json (line 1498) | void from_json(const BasicJsonType& j, std::pair<A1, A2>& p)
function from_json_tuple_impl (line 1504) | void from_json_tuple_impl(const BasicJsonType& j, Tuple& t, index_se...
function from_json (line 1510) | void from_json(const BasicJsonType& j, std::tuple<Args...>& t)
function from_json (line 1518) | void from_json(const BasicJsonType& j, std::map<Key, Value, Compare,...
function from_json (line 1537) | void from_json(const BasicJsonType& j, std::unordered_map<Key, Value...
type from_json_fn (line 1553) | struct from_json_fn
class iteration_proxy (line 1606) | class iteration_proxy
class iteration_proxy_internal (line 1610) | class iteration_proxy_internal
method iteration_proxy_internal (line 1632) | explicit iteration_proxy_internal(IteratorType it) noexcept : an...
method iteration_proxy_internal (line 1635) | iteration_proxy_internal& operator*()
method iteration_proxy_internal (line 1641) | iteration_proxy_internal& operator++()
method value (line 1690) | typename IteratorType::reference value() const
method iteration_proxy (line 1701) | explicit iteration_proxy(typename IteratorType::reference cont) no...
method iteration_proxy_internal (line 1705) | iteration_proxy_internal begin() noexcept
method iteration_proxy_internal (line 1632) | explicit iteration_proxy_internal(IteratorType it) noexcept : an...
method iteration_proxy_internal (line 1635) | iteration_proxy_internal& operator*()
method iteration_proxy_internal (line 1641) | iteration_proxy_internal& operator++()
method value (line 1690) | typename IteratorType::reference value() const
method iteration_proxy_internal (line 1711) | iteration_proxy_internal end() noexcept
method iteration_proxy_internal (line 1632) | explicit iteration_proxy_internal(IteratorType it) noexcept : an...
method iteration_proxy_internal (line 1635) | iteration_proxy_internal& operator*()
method iteration_proxy_internal (line 1641) | iteration_proxy_internal& operator++()
method value (line 1690) | typename IteratorType::reference value() const
type external_constructor (line 1728) | struct external_constructor
type external_constructor<value_t::boolean> (line 1731) | struct external_constructor<value_t::boolean>
method construct (line 1734) | static void construct(BasicJsonType& j, typename BasicJsonType::bo...
type external_constructor<value_t::string> (line 1743) | struct external_constructor<value_t::string>
method construct (line 1746) | static void construct(BasicJsonType& j, const typename BasicJsonTy...
method construct (line 1754) | static void construct(BasicJsonType& j, typename BasicJsonType::st...
method construct (line 1764) | static void construct(BasicJsonType& j, const CompatibleStringType...
type external_constructor<value_t::number_float> (line 1773) | struct external_constructor<value_t::number_float>
method construct (line 1776) | static void construct(BasicJsonType& j, typename BasicJsonType::nu...
type external_constructor<value_t::number_unsigned> (line 1785) | struct external_constructor<value_t::number_unsigned>
method construct (line 1788) | static void construct(BasicJsonType& j, typename BasicJsonType::nu...
type external_constructor<value_t::number_integer> (line 1797) | struct external_constructor<value_t::number_integer>
method construct (line 1800) | static void construct(BasicJsonType& j, typename BasicJsonType::nu...
type external_constructor<value_t::array> (line 1809) | struct external_constructor<value_t::array>
method construct (line 1812) | static void construct(BasicJsonType& j, const typename BasicJsonTy...
method construct (line 1820) | static void construct(BasicJsonType& j, typename BasicJsonType::ar...
method construct (line 1830) | static void construct(BasicJsonType& j, const CompatibleArrayType&...
method construct (line 1840) | static void construct(BasicJsonType& j, const std::vector<bool>& arr)
method construct (line 1854) | static void construct(BasicJsonType& j, const std::valarray<T>& arr)
type external_constructor<value_t::object> (line 1865) | struct external_constructor<value_t::object>
method construct (line 1868) | static void construct(BasicJsonType& j, const typename BasicJsonTy...
method construct (line 1876) | static void construct(BasicJsonType& j, typename BasicJsonType::ob...
method construct (line 1885) | static void construct(BasicJsonType& j, const CompatibleObjectType...
function to_json (line 1902) | void to_json(BasicJsonType& j, T b) noexcept
function to_json (line 1909) | void to_json(BasicJsonType& j, const CompatibleString& s)
function to_json (line 1915) | void to_json(BasicJsonType& j, typename BasicJsonType::string_t&& s)
function to_json (line 1922) | void to_json(BasicJsonType& j, FloatType val) noexcept
function to_json (line 1929) | void to_json(BasicJsonType& j, CompatibleNumberUnsignedType val) noe...
function to_json (line 1936) | void to_json(BasicJsonType& j, CompatibleNumberIntegerType val) noex...
function to_json (line 1943) | void to_json(BasicJsonType& j, EnumType e) noexcept
function to_json (line 1950) | void to_json(BasicJsonType& j, const std::vector<bool>& e)
function to_json (line 1963) | void to_json(BasicJsonType& j, const CompatibleArrayType& arr)
function to_json (line 1970) | void to_json(BasicJsonType& j, const std::valarray<T>& arr)
function to_json (line 1976) | void to_json(BasicJsonType& j, typename BasicJsonType::array_t&& arr)
function to_json (line 1983) | void to_json(BasicJsonType& j, const CompatibleObjectType& obj)
function to_json (line 1989) | void to_json(BasicJsonType& j, typename BasicJsonType::object_t&& obj)
function to_json (line 1999) | void to_json(BasicJsonType& j, const T (&arr)[N])
function to_json (line 2005) | void to_json(BasicJsonType& j, const std::pair<Args...>& p)
function to_json (line 2013) | void to_json(BasicJsonType& j, const T& b)
function to_json_tuple_impl (line 2019) | void to_json_tuple_impl(BasicJsonType& j, const Tuple& t, index_sequ...
function to_json (line 2025) | void to_json(BasicJsonType& j, const std::tuple<Args...>& t)
type to_json_fn (line 2030) | struct to_json_fn
type input_format_t (line 2070) | enum class input_format_t { json, cbor, msgpack, ubjson, bson }
type input_adapter_protocol (line 2087) | struct input_adapter_protocol
class input_stream_adapter (line 2106) | class input_stream_adapter : public input_adapter_protocol
method input_stream_adapter (line 2116) | explicit input_stream_adapter(std::istream& i)
method input_stream_adapter (line 2121) | input_stream_adapter(const input_stream_adapter&) = delete;
method input_stream_adapter (line 2122) | input_stream_adapter& operator=(input_stream_adapter&) = delete;
method input_stream_adapter (line 2123) | input_stream_adapter(input_stream_adapter&&) = delete;
method input_stream_adapter (line 2124) | input_stream_adapter& operator=(input_stream_adapter&&) = delete;
method get_character (line 2129) | std::char_traits<char>::int_type get_character() override
class input_buffer_adapter (line 2141) | class input_buffer_adapter : public input_adapter_protocol
method input_buffer_adapter (line 2144) | input_buffer_adapter(const char* b, const std::size_t l) noexcept
method input_buffer_adapter (line 2149) | input_buffer_adapter(const input_buffer_adapter&) = delete;
method input_buffer_adapter (line 2150) | input_buffer_adapter& operator=(input_buffer_adapter&) = delete;
method input_buffer_adapter (line 2151) | input_buffer_adapter(input_buffer_adapter&&) = delete;
method input_buffer_adapter (line 2152) | input_buffer_adapter& operator=(input_buffer_adapter&&) = delete;
method get_character (line 2155) | std::char_traits<char>::int_type get_character() noexcept override
type wide_string_input_helper (line 2173) | struct wide_string_input_helper
method fill_buffer (line 2176) | static void fill_buffer(const WideStringType& str, size_t& current...
type wide_string_input_helper<WideStringType, 2> (line 2228) | struct wide_string_input_helper<WideStringType, 2>
method fill_buffer (line 2231) | static void fill_buffer(const WideStringType& str, size_t& current...
class wide_string_input_adapter (line 2289) | class wide_string_input_adapter : public input_adapter_protocol
method wide_string_input_adapter (line 2292) | explicit wide_string_input_adapter(const WideStringType& w) noexcept
method get_character (line 2296) | std::char_traits<char>::int_type get_character() noexcept override
method fill_buffer (line 2315) | void fill_buffer()
class input_adapter (line 2335) | class input_adapter
method input_adapter (line 2341) | input_adapter(std::istream& i)
method input_adapter (line 2345) | input_adapter(std::istream&& i)
method input_adapter (line 2348) | input_adapter(const std::wstring& ws)
method input_adapter (line 2351) | input_adapter(const std::u16string& ws)
method input_adapter (line 2354) | input_adapter(const std::u32string& ws)
method input_adapter (line 2364) | input_adapter(CharT b, std::size_t l)
method input_adapter (line 2376) | input_adapter(CharT b)
method input_adapter (line 2385) | input_adapter(IteratorType first, IteratorType last)
method input_adapter (line 2420) | input_adapter(T (&array)[N])
method input_adapter (line 2428) | input_adapter(const ContiguousContainer& c)
class lexer (line 2475) | class lexer
type token_type (line 2484) | enum class token_type
method lexer (line 2549) | explicit lexer(detail::input_adapter_t&& adapter)
method lexer (line 2553) | lexer(const lexer&) = delete;
method lexer (line 2554) | lexer(lexer&&) = delete;
method lexer (line 2555) | lexer& operator=(lexer&) = delete;
method lexer (line 2556) | lexer& operator=(lexer&&) = delete;
method get_decimal_point (line 2565) | static char get_decimal_point() noexcept
method get_codepoint (line 2591) | int get_codepoint()
method next_byte_in_range (line 2639) | bool next_byte_in_range(std::initializer_list<int> ranges)
method token_type (line 2676) | token_type scan_string()
method strtof (line 3262) | static void strtof(float& f, const char* str, char** endptr) noexcept
method strtof (line 3267) | static void strtof(double& f, const char* str, char** endptr) noex...
method strtof (line 3272) | static void strtof(long double& f, const char* str, char** endptr)...
method token_type (line 3317) | token_type scan_number() // lgtm [cpp/use-of-goto]
method token_type (line 3651) | token_type scan_literal(const char* literal_text, const std::size_...
method reset (line 3671) | void reset() noexcept
method get (line 3688) | std::char_traits<char>::int_type get()
method unget (line 3725) | void unget()
method add (line 3752) | void add(int c)
method number_integer_t (line 3763) | constexpr number_integer_t get_number_integer() const noexcept
method number_unsigned_t (line 3769) | constexpr number_unsigned_t get_number_unsigned() const noexcept
method number_float_t (line 3775) | constexpr number_float_t get_number_float() const noexcept
method string_t (line 3781) | string_t& get_string()
method position_t (line 3791) | constexpr position_t get_position() const noexcept
method get_token_string (line 3799) | std::string get_token_string() const
method skip_bom (line 3836) | bool skip_bom()
method token_type (line 3850) | token_type scan()
type is_sax (line 4030) | struct is_sax
type is_sax_static_asserts (line 4062) | struct is_sax_static_asserts
class json_sax_dom_parser (line 4260) | class json_sax_dom_parser
method json_sax_dom_parser (line 4273) | explicit json_sax_dom_parser(BasicJsonType& r, const bool allow_ex...
method null (line 4277) | bool null()
method boolean (line 4283) | bool boolean(bool val)
method number_integer (line 4289) | bool number_integer(number_integer_t val)
method number_unsigned (line 4295) | bool number_unsigned(number_unsigned_t val)
method number_float (line 4301) | bool number_float(number_float_t val, const string_t& /*unused*/)
method string (line 4307) | bool string(string_t& val)
method start_object (line 4313) | bool start_object(std::size_t len)
method key (line 4326) | bool key(string_t& val)
method end_object (line 4333) | bool end_object()
method start_array (line 4339) | bool start_array(std::size_t len)
method end_array (line 4352) | bool end_array()
method parse_error (line 4358) | bool parse_error(std::size_t /*unused*/, const std::string& /*unus...
method is_errored (line 4386) | constexpr bool is_errored() const
method BasicJsonType (line 4399) | BasicJsonType* handle_value(Value&& v)
class json_sax_dom_callback_parser (line 4435) | class json_sax_dom_callback_parser
method json_sax_dom_callback_parser (line 4445) | json_sax_dom_callback_parser(BasicJsonType& r,
method null (line 4453) | bool null()
method boolean (line 4459) | bool boolean(bool val)
method number_integer (line 4465) | bool number_integer(number_integer_t val)
method number_unsigned (line 4471) | bool number_unsigned(number_unsigned_t val)
method number_float (line 4477) | bool number_float(number_float_t val, const string_t& /*unused*/)
method string (line 4483) | bool string(string_t& val)
method start_object (line 4489) | bool start_object(std::size_t len)
method key (line 4511) | bool key(string_t& val)
method end_object (line 4528) | bool end_object()
method start_array (line 4563) | bool start_array(std::size_t len)
method end_array (line 4584) | bool end_array()
method parse_error (line 4615) | bool parse_error(std::size_t /*unused*/, const std::string& /*unus...
method is_errored (line 4643) | constexpr bool is_errored() const
method handle_value (line 4665) | std::pair<bool, BasicJsonType*> handle_value(Value&& v, const bool...
class json_sax_acceptor (line 4748) | class json_sax_acceptor
method null (line 4756) | bool null()
method boolean (line 4761) | bool boolean(bool /*unused*/)
method number_integer (line 4766) | bool number_integer(number_integer_t /*unused*/)
method number_unsigned (line 4771) | bool number_unsigned(number_unsigned_t /*unused*/)
method number_float (line 4776) | bool number_float(number_float_t /*unused*/, const string_t& /*unu...
method string (line 4781) | bool string(string_t& /*unused*/)
method start_object (line 4786) | bool start_object(std::size_t /*unused*/ = std::size_t(-1))
method key (line 4791) | bool key(string_t& /*unused*/)
method end_object (line 4796) | bool end_object()
method start_array (line 4801) | bool start_array(std::size_t /*unused*/ = std::size_t(-1))
method end_array (line 4806) | bool end_array()
method parse_error (line 4811) | bool parse_error(std::size_t /*unused*/, const std::string& /*unus...
class parser (line 4839) | class parser
type parse_event_t (line 4849) | enum class parse_event_t : uint8_t
method parser (line 4869) | explicit parser(detail::input_adapter_t&& adapter,
method parse (line 4888) | void parse(const bool strict, BasicJsonType& result)
method accept (line 4949) | bool accept(const bool strict = true)
method sax_parse (line 4956) | bool sax_parse(SAX* sax, const bool strict = true)
method sax_parse_internal (line 4975) | bool sax_parse_internal(SAX* sax)
method token_type (line 5266) | token_type get_token()
method exception_message (line 5271) | std::string exception_message(const token_type expected, const std...
class primitive_iterator_t (line 5332) | class primitive_iterator_t
method difference_type (line 5343) | constexpr difference_type get_value() const noexcept
method set_begin (line 5349) | void set_begin() noexcept
method set_end (line 5355) | void set_end() noexcept
method is_begin (line 5361) | constexpr bool is_begin() const noexcept
method is_end (line 5367) | constexpr bool is_end() const noexcept
method primitive_iterator_t (line 5382) | primitive_iterator_t operator+(difference_type n) noexcept
method difference_type (line 5389) | constexpr difference_type operator-(primitive_iterator_t lhs, prim...
method primitive_iterator_t (line 5394) | primitive_iterator_t& operator++() noexcept
method primitive_iterator_t (line 5400) | primitive_iterator_t const operator++(int) noexcept
method primitive_iterator_t (line 5407) | primitive_iterator_t& operator--() noexcept
method primitive_iterator_t (line 5413) | primitive_iterator_t const operator--(int) noexcept
method primitive_iterator_t (line 5420) | primitive_iterator_t& operator+=(difference_type n) noexcept
method primitive_iterator_t (line 5426) | primitive_iterator_t& operator-=(difference_type n) noexcept
type internal_iterator (line 5451) | struct internal_iterator
class iteration_proxy (line 5488) | class iteration_proxy
class iteration_proxy_internal (line 1610) | class iteration_proxy_internal
method iteration_proxy_internal (line 1632) | explicit iteration_proxy_internal(IteratorType it) noexcept : an...
method iteration_proxy_internal (line 1635) | iteration_proxy_internal& operator*()
method iteration_proxy_internal (line 1641) | iteration_proxy_internal& operator++()
method value (line 1690) | typename IteratorType::reference value() const
method iteration_proxy (line 1701) | explicit iteration_proxy(typename IteratorType::reference cont) no...
method iteration_proxy_internal (line 1705) | iteration_proxy_internal begin() noexcept
method iteration_proxy_internal (line 1632) | explicit iteration_proxy_internal(IteratorType it) noexcept : an...
method iteration_proxy_internal (line 1635) | iteration_proxy_internal& operator*()
method iteration_proxy_internal (line 1641) | iteration_proxy_internal& operator++()
method value (line 1690) | typename IteratorType::reference value() const
method iteration_proxy_internal (line 1711) | iteration_proxy_internal end() noexcept
method iteration_proxy_internal (line 1632) | explicit iteration_proxy_internal(IteratorType it) noexcept : an...
method iteration_proxy_internal (line 1635) | iteration_proxy_internal& operator*()
method iteration_proxy_internal (line 1641) | iteration_proxy_internal& operator++()
method value (line 1690) | typename IteratorType::reference value() const
class iter_impl (line 5511) | class iter_impl
method iter_impl (line 5548) | iter_impl() = default;
method iter_impl (line 5556) | explicit iter_impl(pointer object) noexcept : m_object(object)
method iter_impl (line 5596) | iter_impl(const iter_impl<typename std::remove_const<BasicJsonType...
method iter_impl (line 5605) | iter_impl& operator=(const iter_impl<typename std::remove_const<Ba...
method set_begin (line 5617) | void set_begin() noexcept
method set_end (line 5654) | void set_end() noexcept
method reference (line 5685) | reference operator*() const
method pointer (line 5722) | pointer operator->() const
method iter_impl (line 5756) | iter_impl const operator++(int)
method iter_impl (line 5767) | iter_impl& operator++()
method iter_impl (line 5799) | iter_impl const operator--(int)
method iter_impl (line 5810) | iter_impl& operator--()
method iter_impl (line 5932) | iter_impl& operator+=(difference_type i)
method iter_impl (line 5961) | iter_impl& operator-=(difference_type i)
method iter_impl (line 5970) | iter_impl operator+(difference_type i) const
method iter_impl (line 5981) | iter_impl operator+(difference_type i, const iter_impl& it)
method iter_impl (line 5992) | iter_impl operator-(difference_type i) const
method difference_type (line 6003) | difference_type operator-(const iter_impl& other) const
method reference (line 6024) | reference operator[](difference_type n) const
method reference (line 6071) | reference value() const
class json_reverse_iterator (line 6121) | class json_reverse_iterator : public std::reverse_iterator<Base>
method json_reverse_iterator (line 6131) | explicit json_reverse_iterator(const typename base_iterator::itera...
method json_reverse_iterator (line 6135) | explicit json_reverse_iterator(const base_iterator& it) noexcept :...
method json_reverse_iterator (line 6138) | json_reverse_iterator const operator++(int)
method json_reverse_iterator (line 6144) | json_reverse_iterator& operator++()
method json_reverse_iterator (line 6150) | json_reverse_iterator const operator--(int)
method json_reverse_iterator (line 6156) | json_reverse_iterator& operator--()
method json_reverse_iterator (line 6162) | json_reverse_iterator& operator+=(difference_type i)
method json_reverse_iterator (line 6168) | json_reverse_iterator operator+(difference_type i) const
method json_reverse_iterator (line 6174) | json_reverse_iterator operator-(difference_type i) const
method difference_type (line 6180) | difference_type operator-(const json_reverse_iterator& other) const
method reference (line 6186) | reference operator[](difference_type n) const
method key (line 6192) | auto key() const -> decltype(std::declval<Base>().key())
method reference (line 6199) | reference value() const
type output_adapter_protocol (line 6225) | struct output_adapter_protocol
class output_vector_adapter (line 6238) | class output_vector_adapter : public output_adapter_protocol<CharType>
method output_vector_adapter (line 6241) | explicit output_vector_adapter(std::vector<CharType>& vec) noexcept
method write_character (line 6245) | void write_character(CharType c) override
method write_characters (line 6250) | void write_characters(const CharType* s, std::size_t length) override
class output_stream_adapter (line 6261) | class output_stream_adapter : public output_adapter_protocol<CharType>
method output_stream_adapter (line 6264) | explicit output_stream_adapter(std::basic_ostream<CharType>& s) no...
method write_character (line 6268) | void write_character(CharType c) override
method write_characters (line 6273) | void write_characters(const CharType* s, std::size_t length) override
class output_string_adapter (line 6284) | class output_string_adapter : public output_adapter_protocol<CharType>
method output_string_adapter (line 6287) | explicit output_string_adapter(StringType& s) noexcept
method write_character (line 6291) | void write_character(CharType c) override
method write_characters (line 6296) | void write_characters(const CharType* s, std::size_t length) override
class output_adapter (line 6306) | class output_adapter
method output_adapter (line 6309) | output_adapter(std::vector<CharType>& vec)
method output_adapter (line 6312) | output_adapter(std::basic_ostream<CharType>& s)
method output_adapter (line 6315) | output_adapter(StringType& s)
class binary_reader (line 6370) | class binary_reader
method binary_reader (line 6384) | explicit binary_reader(input_adapter_t adapter) : ia(std::move(ada...
method sax_parse (line 6397) | bool sax_parse(const input_format_t format,
method little_endianess (line 6457) | static constexpr bool little_endianess(int num = 1) noexcept
method parse_bson_internal (line 6471) | bool parse_bson_internal()
method get_bson_cstr (line 6496) | bool get_bson_cstr(string_t& result)
method get_bson_string (line 6528) | bool get_bson_string(const NumberType len, string_t& result)
method parse_bson_element_internal (line 6549) | bool parse_bson_element_internal(const int element_type,
method parse_bson_element_list (line 6620) | bool parse_bson_element_list(const bool is_array)
method parse_bson_array (line 6660) | bool parse_bson_array()
method parse_cbor_internal (line 6689) | bool parse_cbor_internal(const bool get_char = true)
method get_cbor_string (line 7031) | bool get_cbor_string(string_t& result)
method get_cbor_array (line 7120) | bool get_cbor_array(const std::size_t len)
method get_cbor_object (line 7156) | bool get_cbor_object(const std::size_t len)
method parse_msgpack_internal (line 7208) | bool parse_msgpack_internal()
method get_msgpack_string (line 7577) | bool get_msgpack_string(string_t& result)
method get_msgpack_array (line 7653) | bool get_msgpack_array(const std::size_t len)
method get_msgpack_object (line 7675) | bool get_msgpack_object(const std::size_t len)
method parse_ubjson_internal (line 7712) | bool parse_ubjson_internal(const bool get_char = true)
method get_ubjson_string (line 7731) | bool get_ubjson_string(string_t& result, const bool get_char = true)
method get_ubjson_size_value (line 7785) | bool get_ubjson_size_value(std::size_t& result)
method get_ubjson_size_type (line 7862) | bool get_ubjson_size_type(std::pair<std::size_t, int>& result)
method get_ubjson_value (line 7901) | bool get_ubjson_value(const int prefix)
method get_ubjson_array (line 7997) | bool get_ubjson_array()
method get_ubjson_object (line 8059) | bool get_ubjson_object()
method get (line 8144) | int get()
method get_ignore_noop (line 8153) | int get_ignore_noop()
method get_number (line 8178) | bool get_number(const input_format_t format, NumberType& result)
method get_string (line 8221) | bool get_string(const input_format_t format,
method unexpect_eof (line 8243) | bool unexpect_eof(const input_format_t format, const char* context...
method get_token_string (line 8256) | std::string get_token_string() const
method exception_message (line 8269) | std::string exception_message(const input_format_t format,
class binary_writer (line 8347) | class binary_writer
method binary_writer (line 8357) | explicit binary_writer(output_adapter_t<CharType> adapter) : oa(ad...
method write_bson (line 8366) | void write_bson(const BasicJsonType& j)
method write_cbor (line 8386) | void write_cbor(const BasicJsonType& j)
method write_msgpack (line 8630) | void write_msgpack(const BasicJsonType& j)
method write_ubjson (line 8872) | void write_ubjson(const BasicJsonType& j, const bool use_count,
method calc_bson_entry_header_size (line 9036) | static std::size_t calc_bson_entry_header_size(const string_t& name)
method write_bson_entry_header (line 9051) | void write_bson_entry_header(const string_t& name,
method write_bson_boolean (line 9063) | void write_bson_boolean(const string_t& name,
method write_bson_double (line 9073) | void write_bson_double(const string_t& name,
method calc_bson_string_size (line 9083) | static std::size_t calc_bson_string_size(const string_t& value)
method write_bson_string (line 9091) | void write_bson_string(const string_t& name,
method write_bson_null (line 9105) | void write_bson_null(const string_t& name)
method calc_bson_integer_size (line 9113) | static std::size_t calc_bson_integer_size(const std::int64_t value)
method write_bson_integer (line 9128) | void write_bson_integer(const string_t& name,
method calc_bson_unsigned_size (line 9146) | static constexpr std::size_t calc_bson_unsigned_size(const std::ui...
method write_bson_unsigned (line 9156) | void write_bson_unsigned(const string_t& name,
method write_bson_object_entry (line 9178) | void write_bson_object_entry(const string_t& name,
method calc_bson_array_size (line 9188) | static std::size_t calc_bson_array_size(const typename BasicJsonTy...
method write_bson_array (line 9204) | void write_bson_array(const string_t& name,
method calc_bson_element_size (line 9224) | static std::size_t calc_bson_element_size(const string_t& name,
method write_bson_element (line 9269) | void write_bson_element(const string_t& name,
method calc_bson_object_size (line 9312) | static std::size_t calc_bson_object_size(const typename BasicJsonT...
method write_bson_object (line 9327) | void write_bson_object(const typename BasicJsonType::object_t& value)
method CharType (line 9343) | static constexpr CharType get_cbor_float_prefix(float /*unused*/)
method CharType (line 9348) | static constexpr CharType get_cbor_float_prefix(double /*unused*/)
method CharType (line 9357) | static constexpr CharType get_msgpack_float_prefix(float /*unused*/)
method CharType (line 9362) | static constexpr CharType get_msgpack_float_prefix(double /*unused*/)
method write_number_with_ubjson_prefix (line 9374) | void write_number_with_ubjson_prefix(const NumberType n,
method write_number_with_ubjson_prefix (line 9387) | void write_number_with_ubjson_prefix(const NumberType n,
method write_number_with_ubjson_prefix (line 9440) | void write_number_with_ubjson_prefix(const NumberType n,
method CharType (line 9500) | CharType ubjson_prefix(const BasicJsonType& j) const noexcept
method CharType (line 9571) | static constexpr CharType get_ubjson_float_prefix(float /*unused*/)
method CharType (line 9576) | static constexpr CharType get_ubjson_float_prefix(double /*unused*/)
method write_number (line 9597) | void write_number(const NumberType n)
method CharType (line 9620) | static constexpr CharType to_char_type(std::uint8_t x) noexcept
method CharType (line 9627) | static CharType to_char_type(std::uint8_t x) noexcept
method CharType (line 9638) | static constexpr CharType to_char_type(std::uint8_t x) noexcept
method CharType (line 9649) | static constexpr CharType to_char_type(InputCharType x) noexcept
type dtoa_impl (line 9715) | namespace dtoa_impl
function Target (line 9719) | Target reinterpret_bits(const Source source)
type diyfp (line 9728) | struct diyfp // f * 2^e
method diyfp (line 9735) | constexpr diyfp(uint64_t f_, int e_) noexcept : f(f_), e(e_) {}
method diyfp (line 9741) | static diyfp sub(const diyfp& x, const diyfp& y) noexcept
method diyfp (line 9753) | static diyfp mul(const diyfp& x, const diyfp& y) noexcept
method diyfp (line 9818) | static diyfp normalize(diyfp x) noexcept
method diyfp (line 9835) | static diyfp normalize_to(const diyfp& x, const int target_expon...
type boundaries (line 9846) | struct boundaries
function boundaries (line 9860) | boundaries compute_boundaries(FloatType value)
type cached_power (line 9985) | struct cached_power // c = f * 2^e ~= 10^k
function cached_power (line 9999) | inline cached_power get_cached_power_for_binary_exponent(int e)
function find_largest_pow10 (line 10163) | inline int find_largest_pow10(const uint32_t n, uint32_t& pow10)
function grisu2_round (line 10219) | inline void grisu2_round(char* buf, int len, uint64_t dist, uint64...
function grisu2_digit_gen (line 10260) | inline void grisu2_digit_gen(char* buffer, int& length, int& decim...
function grisu2 (line 10500) | inline void grisu2(char* buf, int& len, int& decimal_exponent,
function grisu2 (line 10559) | void grisu2(char* buf, int& len, int& decimal_exponent, FloatType ...
type error_handler_t (line 10798) | enum class error_handler_t
class serializer (line 10806) | class serializer
method serializer (line 10821) | serializer(output_adapter_t<char> s, const char ichar,
method serializer (line 10833) | serializer(const serializer&) = delete;
method serializer (line 10834) | serializer& operator=(const serializer&) = delete;
method serializer (line 10835) | serializer(serializer&&) = delete;
method serializer (line 10836) | serializer& operator=(serializer&&) = delete;
method dump (line 10856) | void dump(const BasicJsonType& val, const bool pretty_print,
method dump_escaped (line 11063) | void dump_escaped(const string_t& s, const bool ensure_ascii)
method dump_integer (line 11308) | void dump_integer(NumberType x)
method dump_float (line 11349) | void dump_float(number_float_t x)
method dump_float (line 11370) | void dump_float(number_float_t x, std::true_type /*is_ieee_single_...
method dump_float (line 11378) | void dump_float(number_float_t x, std::false_type /*is_ieee_single...
method decode (line 11448) | static uint8_t decode(uint8_t& state, uint32_t& codep, const uint8...
class json_ref (line 11522) | class json_ref
method json_ref (line 11527) | json_ref(value_type&& value)
method json_ref (line 11531) | json_ref(const value_type& value)
method json_ref (line 11535) | json_ref(std::initializer_list<json_ref> init)
method json_ref (line 11542) | json_ref(Args && ... args)
method json_ref (line 11547) | json_ref(json_ref&&) = default;
method json_ref (line 11548) | json_ref(const json_ref&) = delete;
method json_ref (line 11549) | json_ref& operator=(const json_ref&) = delete;
method json_ref (line 11550) | json_ref& operator=(json_ref&&) = delete;
method value_type (line 11553) | value_type moved_or_copied() const
method value_type (line 11562) | value_type const& operator*() const
method value_type (line 11567) | value_type const* operator->() const
type detail (line 414) | namespace detail
type index_sequence (line 273) | struct index_sequence
method size (line 277) | static constexpr std::size_t size() noexcept
type merge_and_renumber (line 284) | struct merge_and_renumber
type make_index_sequence (line 291) | struct make_index_sequence
type make_index_sequence<0> (line 295) | struct make_index_sequence<0> : index_sequence<> {}
type make_index_sequence<1> (line 296) | struct make_index_sequence<1> : index_sequence<0> {}
type priority_tag (line 302) | struct priority_tag : priority_tag < N - 1 > {}
type priority_tag<0> (line 303) | struct priority_tag<0> {}
type static_const (line 307) | struct static_const
type make_void (line 341) | struct make_void
type nonesuch (line 355) | struct nonesuch
method nonesuch (line 357) | nonesuch() = delete;
method nonesuch (line 359) | nonesuch(nonesuch const&) = delete;
type detector (line 367) | struct detector
type is_basic_json (line 429) | struct is_basic_json : std::false_type {}
type has_from_json (line 473) | struct has_from_json : std::false_type {}
type has_from_json<BasicJsonType, T,
enable_if_t<not is_basic_json<T>::value>> (line 476) | struct has_from_json<BasicJsonType, T,
type has_non_default_from_json (line 489) | struct has_non_default_from_json : std::false_type {}
type has_non_default_from_json<BasicJsonType, T, enable_if_t<not is_basic_json<T>::value>> (line 492) | struct has_non_default_from_json<BasicJsonType, T, enable_if_t<not i...
type has_to_json (line 504) | struct has_to_json : std::false_type {}
type has_to_json<BasicJsonType, T, enable_if_t<not is_basic_json<T>::value>> (line 507) | struct has_to_json<BasicJsonType, T, enable_if_t<not is_basic_json<T...
type is_iterator_traits (line 522) | struct is_iterator_traits : std::false_type {}
type is_iterator_traits<std::iterator_traits<T>> (line 525) | struct is_iterator_traits<std::iterator_traits<T>>
type is_complete_type (line 542) | struct is_complete_type : std::false_type {}
type is_complete_type<T, decltype(void(sizeof(T)))> (line 545) | struct is_complete_type<T, decltype(void(sizeof(T)))> : std::true_ty...
type is_compatible_object_type_impl (line 549) | struct is_compatible_object_type_impl : std::false_type {}
type is_compatible_object_type_impl <
BasicJsonType, CompatibleObjectType,
enable_if_t<is_detected<mapped_type_t, CompatibleObjectType>::value and
is_detected<key_type_t, CompatibleObjectType>::value >> (line 552) | struct is_compatible_object_type_impl <
type is_compatible_object_type (line 569) | struct is_compatible_object_type
type is_constructible_object_type_impl (line 574) | struct is_constructible_object_type_impl : std::false_type {}
type is_constructible_object_type_impl <
BasicJsonType, ConstructibleObjectType,
enable_if_t<is_detected<mapped_type_t, ConstructibleObjectType>::value and
is_detected<key_type_t, ConstructibleObjectType>::value >> (line 577) | struct is_constructible_object_type_impl <
type is_constructible_object_type (line 592) | struct is_constructible_object_type
type is_compatible_string_type_impl (line 598) | struct is_compatible_string_type_impl : std::false_type {}
type is_compatible_string_type_impl <
BasicJsonType, CompatibleStringType,
enable_if_t<is_detected_exact<typename BasicJsonType::string_t::value_type,
value_type_t, CompatibleStringType>::value >> (line 601) | struct is_compatible_string_type_impl <
type is_compatible_string_type (line 611) | struct is_compatible_string_type
type is_constructible_string_type_impl (line 616) | struct is_constructible_string_type_impl : std::false_type {}
type is_constructible_string_type_impl <
BasicJsonType, ConstructibleStringType,
enable_if_t<is_detected_exact<typename BasicJsonType::string_t::value_type,
value_type_t, ConstructibleStringType>::value >> (line 619) | struct is_constructible_string_type_impl <
type is_constructible_string_type (line 630) | struct is_constructible_string_type
type is_compatible_array_type_impl (line 634) | struct is_compatible_array_type_impl : std::false_type {}
type is_compatible_array_type (line 653) | struct is_compatible_array_type
type is_constructible_array_type_impl (line 657) | struct is_constructible_array_type_impl : std::false_type {}
type is_constructible_array_type_impl <
BasicJsonType, ConstructibleArrayType,
enable_if_t<std::is_same<ConstructibleArrayType,
typename BasicJsonType::value_type>::value >> (line 660) | struct is_constructible_array_type_impl <
type is_constructible_array_type_impl <
BasicJsonType, ConstructibleArrayType,
enable_if_t<not std::is_same<ConstructibleArrayType,
typename BasicJsonType::value_type>::value and
is_detected<value_type_t, ConstructibleArrayType>::value and
is_detected<iterator_t, ConstructibleArrayType>::value and
is_complete_type<
detected_t<value_type_t, ConstructibleArrayType>>::value >> (line 667) | struct is_constructible_array_type_impl <
type is_constructible_array_type (line 692) | struct is_constructible_array_type
type is_compatible_integer_type_impl (line 697) | struct is_compatible_integer_type_impl : std::false_type {}
type is_compatible_integer_type_impl <
RealIntegerType, CompatibleNumberIntegerType,
enable_if_t<std::is_integral<RealIntegerType>::value and
std::is_integral<CompatibleNumberIntegerType>::value and
not std::is_same<bool, CompatibleNumberIntegerType>::value >> (line 700) | struct is_compatible_integer_type_impl <
type is_compatible_integer_type (line 718) | struct is_compatible_integer_type
type is_compatible_type_impl (line 723) | struct is_compatible_type_impl: std::false_type {}
type is_compatible_type_impl <
BasicJsonType, CompatibleType,
enable_if_t<is_complete_type<CompatibleType>::value >> (line 726) | struct is_compatible_type_impl <
type is_compatible_type (line 735) | struct is_compatible_type
type position_t (line 757) | struct position_t
class exception (line 813) | class exception : public std::exception
method exception (line 826) | exception(int id_, const char* what_arg) : id(id_), m(what_arg) {}
method name (line 828) | static std::string name(const std::string& ename, int id_)
class parse_error (line 882) | class parse_error : public exception
method parse_error (line 894) | static parse_error create(int id_, const position_t& pos, const st...
method parse_error (line 901) | static parse_error create(int id_, std::size_t byte_, const std::s...
method parse_error (line 921) | parse_error(int id_, std::size_t byte_, const char* what_arg)
method position_string (line 924) | static std::string position_string(const position_t& pos)
class invalid_iterator (line 968) | class invalid_iterator : public exception
method invalid_iterator (line 971) | static invalid_iterator create(int id_, const std::string& what_arg)
method invalid_iterator (line 978) | invalid_iterator(int id_, const char* what_arg)
class type_error (line 1021) | class type_error : public exception
method type_error (line 1024) | static type_error create(int id_, const std::string& what_arg)
method type_error (line 1031) | type_error(int id_, const char* what_arg) : exception(id_, what_ar...
class out_of_range (line 1067) | class out_of_range : public exception
method out_of_range (line 1070) | static out_of_range create(int id_, const std::string& what_arg)
method out_of_range (line 1077) | out_of_range(int id_, const char* what_arg) : exception(id_, what_...
class other_error (line 1104) | class other_error : public exception
method other_error (line 1107) | static other_error create(int id_, const std::string& what_arg)
method other_error (line 1114) | other_error(int id_, const char* what_arg) : exception(id_, what_a...
type value_t (line 1159) | enum class value_t : std::uint8_t
function from_json (line 1229) | void from_json(const BasicJsonType& j, typename std::nullptr_t& n)
function get_arithmetic_value (line 1243) | void get_arithmetic_value(const BasicJsonType& j, ArithmeticType& val)
function from_json (line 1269) | void from_json(const BasicJsonType& j, typename BasicJsonType::boole...
function from_json (line 1279) | void from_json(const BasicJsonType& j, typename BasicJsonType::strin...
function from_json (line 1295) | void from_json(const BasicJsonType& j, ConstructibleStringType& s)
function from_json (line 1306) | void from_json(const BasicJsonType& j, typename BasicJsonType::numbe...
function from_json (line 1312) | void from_json(const BasicJsonType& j, typename BasicJsonType::numbe...
function from_json (line 1318) | void from_json(const BasicJsonType& j, typename BasicJsonType::numbe...
function from_json (line 1325) | void from_json(const BasicJsonType& j, EnumType& e)
function from_json (line 1335) | void from_json(const BasicJsonType& j, std::forward_list<T, Allocato...
function from_json (line 1351) | void from_json(const BasicJsonType& j, std::valarray<T>& l)
function from_json_array_impl (line 1362) | void from_json_array_impl(const BasicJsonType& j, typename BasicJson...
function from_json_array_impl (line 1368) | auto from_json_array_impl(const BasicJsonType& j, std::array<T, N>& ...
function from_json_array_impl (line 1379) | auto from_json_array_impl(const BasicJsonType& j, ConstructibleArray...
function from_json_array_impl (line 1398) | void from_json_array_impl(const BasicJsonType& j, ConstructibleArray...
function from_json (line 1421) | auto from_json(const BasicJsonType& j, ConstructibleArrayType& arr)
function from_json (line 1437) | void from_json(const BasicJsonType& j, ConstructibleObjectType& obj)
function from_json (line 1467) | void from_json(const BasicJsonType& j, ArithmeticType& val)
function from_json (line 1498) | void from_json(const BasicJsonType& j, std::pair<A1, A2>& p)
function from_json_tuple_impl (line 1504) | void from_json_tuple_impl(const BasicJsonType& j, Tuple& t, index_se...
function from_json (line 1510) | void from_json(const BasicJsonType& j, std::tuple<Args...>& t)
function from_json (line 1518) | void from_json(const BasicJsonType& j, std::map<Key, Value, Compare,...
function from_json (line 1537) | void from_json(const BasicJsonType& j, std::unordered_map<Key, Value...
type from_json_fn (line 1553) | struct from_json_fn
class iteration_proxy (line 1606) | class iteration_proxy
class iteration_proxy_internal (line 1610) | class iteration_proxy_internal
method iteration_proxy_internal (line 1632) | explicit iteration_proxy_internal(IteratorType it) noexcept : an...
method iteration_proxy_internal (line 1635) | iteration_proxy_internal& operator*()
method iteration_proxy_internal (line 1641) | iteration_proxy_internal& operator++()
method value (line 1690) | typename IteratorType::reference value() const
method iteration_proxy (line 1701) | explicit iteration_proxy(typename IteratorType::reference cont) no...
method iteration_proxy_internal (line 1705) | iteration_proxy_internal begin() noexcept
method iteration_proxy_internal (line 1632) | explicit iteration_proxy_internal(IteratorType it) noexcept : an...
method iteration_proxy_internal (line 1635) | iteration_proxy_internal& operator*()
method iteration_proxy_internal (line 1641) | iteration_proxy_internal& operator++()
method value (line 1690) | typename IteratorType::reference value() const
method iteration_proxy_internal (line 1711) | iteration_proxy_internal end() noexcept
method iteration_proxy_internal (line 1632) | explicit iteration_proxy_internal(IteratorType it) noexcept : an...
method iteration_proxy_internal (line 1635) | iteration_proxy_internal& operator*()
method iteration_proxy_internal (line 1641) | iteration_proxy_internal& operator++()
method value (line 1690) | typename IteratorType::reference value() const
type external_constructor (line 1728) | struct external_constructor
type external_constructor<value_t::boolean> (line 1731) | struct external_constructor<value_t::boolean>
method construct (line 1734) | static void construct(BasicJsonType& j, typename BasicJsonType::bo...
type external_constructor<value_t::string> (line 1743) | struct external_constructor<value_t::string>
method construct (line 1746) | static void construct(BasicJsonType& j, const typename BasicJsonTy...
method construct (line 1754) | static void construct(BasicJsonType& j, typename BasicJsonType::st...
method construct (line 1764) | static void construct(BasicJsonType& j, const CompatibleStringType...
type external_constructor<value_t::number_float> (line 1773) | struct external_constructor<value_t::number_float>
method construct (line 1776) | static void construct(BasicJsonType& j, typename BasicJsonType::nu...
type external_constructor<value_t::number_unsigned> (line 1785) | struct external_constructor<value_t::number_unsigned>
method construct (line 1788) | static void construct(BasicJsonType& j, typename BasicJsonType::nu...
type external_constructor<value_t::number_integer> (line 1797) | struct external_constructor<value_t::number_integer>
method construct (line 1800) | static void construct(BasicJsonType& j, typename BasicJsonType::nu...
type external_constructor<value_t::array> (line 1809) | struct external_constructor<value_t::array>
method construct (line 1812) | static void construct(BasicJsonType& j, const typename BasicJsonTy...
method construct (line 1820) | static void construct(BasicJsonType& j, typename BasicJsonType::ar...
method construct (line 1830) | static void construct(BasicJsonType& j, const CompatibleArrayType&...
method construct (line 1840) | static void construct(BasicJsonType& j, const std::vector<bool>& arr)
method construct (line 1854) | static void construct(BasicJsonType& j, const std::valarray<T>& arr)
type external_constructor<value_t::object> (line 1865) | struct external_constructor<value_t::object>
method construct (line 1868) | static void construct(BasicJsonType& j, const typename BasicJsonTy...
method construct (line 1876) | static void construct(BasicJsonType& j, typename BasicJsonType::ob...
method construct (line 1885) | static void construct(BasicJsonType& j, const CompatibleObjectType...
function to_json (line 1902) | void to_json(BasicJsonType& j, T b) noexcept
function to_json (line 1909) | void to_json(BasicJsonType& j, const CompatibleString& s)
function to_json (line 1915) | void to_json(BasicJsonType& j, typename BasicJsonType::string_t&& s)
function to_json (line 1922) | void to_json(BasicJsonType& j, FloatType val) noexcept
function to_json (line 1929) | void to_json(BasicJsonType& j, CompatibleNumberUnsignedType val) noe...
function to_json (line 1936) | void to_json(BasicJsonType& j, CompatibleNumberIntegerType val) noex...
function to_json (line 1943) | void to_json(BasicJsonType& j, EnumType e) noexcept
function to_json (line 1950) | void to_json(BasicJsonType& j, const std::vector<bool>& e)
function to_json (line 1963) | void to_json(BasicJsonType& j, const CompatibleArrayType& arr)
function to_json (line 1970) | void to_json(BasicJsonType& j, const std::valarray<T>& arr)
function to_json (line 1976) | void to_json(BasicJsonType& j, typename BasicJsonType::array_t&& arr)
function to_json (line 1983) | void to_json(BasicJsonType& j, const CompatibleObjectType& obj)
function to_json (line 1989) | void to_json(BasicJsonType& j, typename BasicJsonType::object_t&& obj)
function to_json (line 1999) | void to_json(BasicJsonType& j, const T (&arr)[N])
function to_json (line 2005) | void to_json(BasicJsonType& j, const std::pair<Args...>& p)
function to_json (line 2013) | void to_json(BasicJsonType& j, const T& b)
function to_json_tuple_impl (line 2019) | void to_json_tuple_impl(BasicJsonType& j, const Tuple& t, index_sequ...
function to_json (line 2025) | void to_json(BasicJsonType& j, const std::tuple<Args...>& t)
type to_json_fn (line 2030) | struct to_json_fn
type input_format_t (line 2070) | enum class input_format_t { json, cbor, msgpack, ubjson, bson }
type input_adapter_protocol (line 2087) | struct input_adapter_protocol
class input_stream_adapter (line 2106) | class input_stream_adapter : public input_adapter_protocol
method input_stream_adapter (line 2116) | explicit input_stream_adapter(std::istream& i)
method input_stream_adapter (line 2121) | input_stream_adapter(const input_stream_adapter&) = delete;
method input_stream_adapter (line 2122) | input_stream_adapter& operator=(input_stream_adapter&) = delete;
method input_stream_adapter (line 2123) | input_stream_adapter(input_stream_adapter&&) = delete;
method input_stream_adapter (line 2124) | input_stream_adapter& operator=(input_stream_adapter&&) = delete;
method get_character (line 2129) | std::char_traits<char>::int_type get_character() override
class input_buffer_adapter (line 2141) | class input_buffer_adapter : public input_adapter_protocol
method input_buffer_adapter (line 2144) | input_buffer_adapter(const char* b, const std::size_t l) noexcept
method input_buffer_adapter (line 2149) | input_buffer_adapter(const input_buffer_adapter&) = delete;
method input_buffer_adapter (line 2150) | input_buffer_adapter& operator=(input_buffer_adapter&) = delete;
method input_buffer_adapter (line 2151) | input_buffer_adapter(input_buffer_adapter&&) = delete;
method input_buffer_adapter (line 2152) | input_buffer_adapter& operator=(input_buffer_adapter&&) = delete;
method get_character (line 2155) | std::char_traits<char>::int_type get_character() noexcept override
type wide_string_input_helper (line 2173) | struct wide_string_input_helper
method fill_buffer (line 2176) | static void fill_buffer(const WideStringType& str, size_t& current...
type wide_string_input_helper<WideStringType, 2> (line 2228) | struct wide_string_input_helper<WideStringType, 2>
method fill_buffer (line 2231) | static void fill_buffer(const WideStringType& str, size_t& current...
class wide_string_input_adapter (line 2289) | class wide_string_input_adapter : public input_adapter_protocol
method wide_string_input_adapter (line 2292) | explicit wide_string_input_adapter(const WideStringType& w) noexcept
method get_character (line 2296) | std::char_traits<char>::int_type get_character() noexcept override
method fill_buffer (line 2315) | void fill_buffer()
class input_adapter (line 2335) | class input_adapter
method input_adapter (line 2341) | input_adapter(std::istream& i)
method input_adapter (line 2345) | input_adapter(std::istream&& i)
method input_adapter (line 2348) | input_adapter(const std::wstring& ws)
method input_adapter (line 2351) | input_adapter(const std::u16string& ws)
method input_adapter (line 2354) | input_adapter(const std::u32string& ws)
method input_adapter (line 2364) | input_adapter(CharT b, std::size_t l)
method input_adapter (line 2376) | input_adapter(CharT b)
method input_adapter (line 2385) | input_adapter(IteratorType first, IteratorType last)
method input_adapter (line 2420) | input_adapter(T (&array)[N])
method input_adapter (line 2428) | input_adapter(const ContiguousContainer& c)
class lexer (line 2475) | class lexer
type token_type (line 2484) | enum class token_type
method lexer (line 2549) | explicit lexer(detail::input_adapter_t&& adapter)
method lexer (line 2553) | lexer(const lexer&) = delete;
method lexer (line 2554) | lexer(lexer&&) = delete;
method lexer (line 2555) | lexer& operator=(lexer&) = delete;
method lexer (line 2556) | lexer& operator=(lexer&&) = delete;
method get_decimal_point (line 2565) | static char get_decimal_point() noexcept
method get_codepoint (line 2591) | int get_codepoint()
method next_byte_in_range (line 2639) | bool next_byte_in_range(std::initializer_list<int> ranges)
method token_type (line 2676) | token_type scan_string()
method strtof (line 3262) | static void strtof(float& f, const char* str, char** endptr) noexcept
method strtof (line 3267) | static void strtof(double& f, const char* str, char** endptr) noex...
method strtof (line 3272) | static void strtof(long double& f, const char* str, char** endptr)...
method token_type (line 3317) | token_type scan_number() // lgtm [cpp/use-of-goto]
method token_type (line 3651) | token_type scan_literal(const char* literal_text, const std::size_...
method reset (line 3671) | void reset() noexcept
method get (line 3688) | std::char_traits<char>::int_type get()
method unget (line 3725) | void unget()
method add (line 3752) | void add(int c)
method number_integer_t (line 3763) | constexpr number_integer_t get_number_integer() const noexcept
method number_unsigned_t (line 3769) | constexpr number_unsigned_t get_number_unsigned() const noexcept
method number_float_t (line 3775) | constexpr number_float_t get_number_float() const noexcept
method string_t (line 3781) | string_t& get_string()
method position_t (line 3791) | constexpr position_t get_position() const noexcept
method get_token_string (line 3799) | std::string get_token_string() const
method skip_bom (line 3836) | bool skip_bom()
method token_type (line 3850) | token_type scan()
type is_sax (line 4030) | struct is_sax
type is_sax_static_asserts (line 4062) | struct is_sax_static_asserts
class json_sax_dom_parser (line 4260) | class json_sax_dom_parser
method json_sax_dom_parser (line 4273) | explicit json_sax_dom_parser(BasicJsonType& r, const bool allow_ex...
method null (line 4277) | bool null()
method boolean (line 4283) | bool boolean(bool val)
method number_integer (line 4289) | bool number_integer(number_integer_t val)
method number_unsigned (line 4295) | bool number_unsigned(number_unsigned_t val)
method number_float (line 4301) | bool number_float(number_float_t val, const string_t& /*unused*/)
method string (line 4307) | bool string(string_t& val)
method start_object (line 4313) | bool start_object(std::size_t len)
method key (line 4326) | bool key(string_t& val)
method end_object (line 4333) | bool end_object()
method start_array (line 4339) | bool start_array(std::size_t len)
method end_array (line 4352) | bool end_array()
method parse_error (line 4358) | bool parse_error(std::size_t /*unused*/, const std::string& /*unus...
method is_errored (line 4386) | constexpr bool is_errored() const
method BasicJsonType (line 4399) | BasicJsonType* handle_value(Value&& v)
class json_sax_dom_callback_parser (line 4435) | class json_sax_dom_callback_parser
method json_sax_dom_callback_parser (line 4445) | json_sax_dom_callback_parser(BasicJsonType& r,
method null (line 4453) | bool null()
method boolean (line 4459) | bool boolean(bool val)
method number_integer (line 4465) | bool number_integer(number_integer_t val)
method number_unsigned (line 4471) | bool number_unsigned(number_unsigned_t val)
method number_float (line 4477) | bool number_float(number_float_t val, const string_t& /*unused*/)
method string (line 4483) | bool string(string_t& val)
method start_object (line 4489) | bool start_object(std::size_t len)
method key (line 4511) | bool key(string_t& val)
method end_object (line 4528) | bool end_object()
method start_array (line 4563) | bool start_array(std::size_t len)
method end_array (line 4584) | bool end_array()
method parse_error (line 4615) | bool parse_error(std::size_t /*unused*/, const std::string& /*unus...
method is_errored (line 4643) | constexpr bool is_errored() const
method handle_value (line 4665) | std::pair<bool, BasicJsonType*> handle_value(Value&& v, const bool...
class json_sax_acceptor (line 4748) | class json_sax_acceptor
method null (line 4756) | bool null()
method boolean (line 4761) | bool boolean(bool /*unused*/)
method number_integer (line 4766) | bool number_integer(number_integer_t /*unused*/)
method number_unsigned (line 4771) | bool number_unsigned(number_unsigned_t /*unused*/)
method number_float (line 4776) | bool number_float(number_float_t /*unused*/, const string_t& /*unu...
method string (line 4781) | bool string(string_t& /*unused*/)
method start_object (line 4786) | bool start_object(std::size_t /*unused*/ = std::size_t(-1))
method key (line 4791) | bool key(string_t& /*unused*/)
method end_object (line 4796) | bool end_object()
method start_array (line 4801) | bool start_array(std::size_t /*unused*/ = std::size_t(-1))
method end_array (line 4806) | bool end_array()
method parse_error (line 4811) | bool parse_error(std::size_t /*unused*/, const std::string& /*unus...
class parser (line 4839) | class parser
type parse_event_t (line 4849) | enum class parse_event_t : uint8_t
method parser (line 4869) | explicit parser(detail::input_adapter_t&& adapter,
method parse (line 4888) | void parse(const bool strict, BasicJsonType& result)
method accept (line 4949) | bool accept(const bool strict = true)
method sax_parse (line 4956) | bool sax_parse(SAX* sax, const bool strict = true)
method sax_parse_internal (line 4975) | bool sax_parse_internal(SAX* sax)
method token_type (line 5266) | token_type get_token()
method exception_message (line 5271) | std::string exception_message(const token_type expected, const std...
class primitive_iterator_t (line 5332) | class primitive_iterator_t
method difference_type (line 5343) | constexpr difference_type get_value() const noexcept
method set_begin (line 5349) | void set_begin() noexcept
method set_end (line 5355) | void set_end() noexcept
method is_begin (line 5361) | constexpr bool is_begin() const noexcept
method is_end (line 5367) | constexpr bool is_end() const noexcept
method primitive_iterator_t (line 5382) | primitive_iterator_t operator+(difference_type n) noexcept
method difference_type (line 5389) | constexpr difference_type operator-(primitive_iterator_t lhs, prim...
method primitive_iterator_t (line 5394) | primitive_iterator_t& operator++() noexcept
method primitive_iterator_t (line 5400) | primitive_iterator_t const operator++(int) noexcept
method primitive_iterator_t (line 5407) | primitive_iterator_t& operator--() noexcept
method primitive_iterator_t (line 5413) | primitive_iterator_t const operator--(int) noexcept
method primitive_iterator_t (line 5420) | primitive_iterator_t& operator+=(difference_type n) noexcept
method primitive_iterator_t (line 5426) | primitive_iterator_t& operator-=(difference_type n) noexcept
type internal_iterator (line 5451) | struct internal_iterator
class iteration_proxy (line 5488) | class iteration_proxy
class iteration_proxy_internal (line 1610) | class iteration_proxy_internal
method iteration_proxy_internal (line 1632) | explicit iteration_proxy_internal(IteratorType it) noexcept : an...
method iteration_proxy_internal (line 1635) | iteration_proxy_internal& operator*()
method iteration_proxy_internal (line 1641) | iteration_proxy_internal& operator++()
method value (line 1690) | typename IteratorType::reference value() const
method iteration_proxy (line 1701) | explicit iteration_proxy(typename IteratorType::reference cont) no...
method iteration_proxy_internal (line 1705) | iteration_proxy_internal begin() noexcept
method iteration_proxy_internal (line 1632) | explicit iteration_proxy_internal(IteratorType it) noexcept : an...
method iteration_proxy_internal (line 1635) | iteration_proxy_internal& operator*()
method iteration_proxy_internal (line 1641) | iteration_proxy_internal& operator++()
method value (line 1690) | typename IteratorType::reference value() const
method iteration_proxy_internal (line 1711) | iteration_proxy_internal end() noexcept
method iteration_proxy_internal (line 1632) | explicit iteration_proxy_internal(IteratorType it) noexcept : an...
method iteration_proxy_internal (line 1635) | iteration_proxy_internal& operator*()
method iteration_proxy_internal (line 1641) | iteration_proxy_internal& operator++()
method value (line 1690) | typename IteratorType::reference value() const
class iter_impl (line 5511) | class iter_impl
method iter_impl (line 5548) | iter_impl() = default;
method iter_impl (line 5556) | explicit iter_impl(pointer object) noexcept : m_object(object)
method iter_impl (line 5596) | iter_impl(const iter_impl<typename std::remove_const<BasicJsonType...
method iter_impl (line 5605) | iter_impl& operator=(const iter_impl<typename std::remove_const<Ba...
method set_begin (line 5617) | void set_begin() noexcept
method set_end (line 5654) | void set_end() noexcept
method reference (line 5685) | reference operator*() const
method pointer (line 5722) | pointer operator->() const
method iter_impl (line 5756) | iter_impl const operator++(int)
method iter_impl (line 5767) | iter_impl& operator++()
method iter_impl (line 5799) | iter_impl const operator--(int)
method iter_impl (line 5810) | iter_impl& operator--()
method iter_impl (line 5932) | iter_impl& operator+=(difference_type i)
method iter_impl (line 5961) | iter_impl& operator-=(difference_type i)
method iter_impl (line 5970) | iter_impl operator+(difference_type i) const
method iter_impl (line 5981) | iter_impl operator+(difference_type i, const iter_impl& it)
method iter_impl (line 5992) | iter_impl operator-(difference_type i) const
method difference_type (line 6003) | difference_type operator-(const iter_impl& other) const
method reference (line 6024) | reference operator[](difference_type n) const
method reference (line 6071) | reference value() const
class json_reverse_iterator (line 6121) | class json_reverse_iterator : public std::reverse_iterator<Base>
method json_reverse_iterator (line 6131) | explicit json_reverse_iterator(const typename base_iterator::itera...
method json_reverse_iterator (line 6135) | explicit json_reverse_iterator(const base_iterator& it) noexcept :...
method json_reverse_iterator (line 6138) | json_reverse_iterator const operator++(int)
method json_reverse_iterator (line 6144) | json_reverse_iterator& operator++()
method json_reverse_iterator (line 6150) | json_reverse_iterator const operator--(int)
method json_reverse_iterator (line 6156) | json_reverse_iterator& operator--()
method json_reverse_iterator (line 6162) | json_reverse_iterator& operator+=(difference_type i)
method json_reverse_iterator (line 6168) | json_reverse_iterator operator+(difference_type i) const
method json_reverse_iterator (line 6174) | json_reverse_iterator operator-(difference_type i) const
method difference_type (line 6180) | difference_type operator-(const json_reverse_iterator& other) const
method reference (line 6186) | reference operator[](difference_type n) const
method key (line 6192) | auto key() const -> decltype(std::declval<Base>().key())
method reference (line 6199) | reference value() const
type output_adapter_protocol (line 6225) | struct output_adapter_protocol
class output_vector_adapter (line 6238) | class output_vector_adapter : public output_adapter_protocol<CharType>
method output_vector_adapter (line 6241) | explicit output_vector_adapter(std::vector<CharType>& vec) noexcept
method write_character (line 6245) | void write_character(CharType c) override
method write_characters (line 6250) | void write_characters(const CharType* s, std::size_t length) override
class output_stream_adapter (line 6261) | class output_stream_adapter : public output_adapter_protocol<CharType>
method output_stream_adapter (line 6264) | explicit output_stream_adapter(std::basic_ostream<CharType>& s) no...
method write_character (line 6268) | void write_character(CharType c) override
method write_characters (line 6273) | void write_characters(const CharType* s, std::size_t length) override
class output_string_adapter (line 6284) | class output_string_adapter : public output_adapter_protocol<CharType>
method output_string_adapter (line 6287) | explicit output_string_adapter(StringType& s) noexcept
method write_character (line 6291) | void write_character(CharType c) override
method write_characters (line 6296) | void write_characters(const CharType* s, std::size_t length) override
class output_adapter (line 6306) | class output_adapter
method output_adapter (line 6309) | output_adapter(std::vector<CharType>& vec)
method output_adapter (line 6312) | output_adapter(std::basic_ostream<CharType>& s)
method output_adapter (line 6315) | output_adapter(StringType& s)
class binary_reader (line 6370) | class binary_reader
method binary_reader (line 6384) | explicit binary_reader(input_adapter_t adapter) : ia(std::move(ada...
method sax_parse (line 6397) | bool sax_parse(const input_format_t format,
method little_endianess (line 6457) | static constexpr bool little_endianess(int num = 1) noexcept
method parse_bson_internal (line 6471) | bool parse_bson_internal()
method get_bson_cstr (line 6496) | bool get_bson_cstr(string_t& result)
method get_bson_string (line 6528) | bool get_bson_string(const NumberType len, string_t& result)
method parse_bson_element_internal (line 6549) | bool parse_bson_element_internal(const int element_type,
method parse_bson_element_list (line 6620) | bool parse_bson_element_list(const bool is_array)
method parse_bson_array (line 6660) | bool parse_bson_array()
method parse_cbor_internal (line 6689) | bool parse_cbor_internal(const bool get_char = true)
method get_cbor_string (line 7031) | bool get_cbor_string(string_t& result)
method get_cbor_array (line 7120) | bool get_cbor_array(const std::size_t len)
method get_cbor_object (line 7156) | bool get_cbor_object(const std::size_t len)
method parse_msgpack_internal (line 7208) | bool parse_msgpack_internal()
method get_msgpack_string (line 7577) | bool get_msgpack_string(string_t& result)
method get_msgpack_array (line 7653) | bool get_msgpack_array(const std::size_t len)
method get_msgpack_object (line 7675) | bool get_msgpack_object(const std::size_t len)
method parse_ubjson_internal (line 7712) | bool parse_ubjson_internal(const bool get_char = true)
method get_ubjson_string (line 7731) | bool get_ubjson_string(string_t& result, const bool get_char = true)
method get_ubjson_size_value (line 7785) | bool get_ubjson_size_value(std::size_t& result)
method get_ubjson_size_type (line 7862) | bool get_ubjson_size_type(std::pair<std::size_t, int>& result)
method get_ubjson_value (line 7901) | bool get_ubjson_value(const int prefix)
method get_ubjson_array (line 7997) | bool get_ubjson_array()
method get_ubjson_object (line 8059) | bool get_ubjson_object()
method get (line 8144) | int get()
method get_ignore_noop (line 8153) | int get_ignore_noop()
method get_number (line 8178) | bool get_number(const input_format_t format, NumberType& result)
method get_string (line 8221) | bool get_string(const input_format_t format,
method unexpect_eof (line 8243) | bool unexpect_eof(
Condensed preview — 154 files, each showing path, character count, and a content snippet. Download the .json file or copy for the full structured content (2,102K chars).
[
{
"path": ".gitignore",
"chars": 37,
"preview": "*.data\n*.pyc\n*.npy\n*.npz\n*.pth\n*.bak\n"
},
{
"path": "CMakeLists.txt",
"chars": 9909,
"preview": "cmake_minimum_required(VERSION 2.8.3)\nproject(cerebro)\n\n# Catkin components\nfind_package(catkin REQUIRED COMPONENTS\n cv"
},
{
"path": "README.md",
"chars": 13018,
"preview": "# VINS-Fusion with Cerebro\nThis is the cerebro module for VINS-Fusion. The aim of this project\nis better loop detection "
},
{
"path": "config/echo__terminator_config_vins_fusion_cerebro",
"chars": 3597,
"preview": "[global_config]\n[keybindings]\n[layouts]\n [[default]]\n [[[child0]]]\n fullscreen = False\n last_active_term ="
},
{
"path": "config/euroc/euroc_config_no_extrinsic.yaml",
"chars": 3444,
"preview": "%YAML:1.0\n\n#common parameters\nimu_topic: \"/imu0\"\nimage_topic: \"/cam0/image_raw\"\noutput_path: \"/home/tony-ws1/output/\"\n\n#"
},
{
"path": "config/fly",
"chars": 4211,
"preview": "[global_config]\n[keybindings]\n[layouts]\n [[default]]\n [[[child0]]]\n fullscreen = False\n last_active_term ="
},
{
"path": "config/mynteye/camera_left.yaml",
"chars": 434,
"preview": "%YAML:1.0\n---\nmodel_type: MEI\ncamera_name: camera_left\nimage_width: 752\nimage_height: 480\nmirror_parameters:\n xi: 9.10"
},
{
"path": "config/mynteye/camera_right.yaml",
"chars": 436,
"preview": "%YAML:1.0\n---\nmodel_type: MEI\ncamera_name: camera_right\nimage_width: 752\nimage_height: 480\nmirror_parameters:\n xi: 1.0"
},
{
"path": "config/mynteye/extrinsics.yaml",
"chars": 246,
"preview": "%YAML:1.0\n---\ntransform:\n q_x: -1.8252509868889259e-04\n q_y: -1.6291774489779708e-03\n q_z: -1.2462127842978489e-03"
},
{
"path": "config/mynteye/mynteye_config.yaml",
"chars": 4629,
"preview": "%YAML:1.0\n\n#common parameters\nimu_topic: \"/mynteye/imu/data_raw\"\nimage_topic: \"/mynteye/left/image_raw\"\noutput_path: \"/B"
},
{
"path": "config/mynteye__terminator_config_vins_fusion_cerebro",
"chars": 4794,
"preview": "[global_config]\n[keybindings]\n[layouts]\n [[default]]\n [[[child0]]]\n fullscreen = False\n last_active_term ="
},
{
"path": "config/mynteye_kannala_brandt/camera_left.yaml",
"chars": 367,
"preview": "%YAML:1.0\n---\nmodel_type: KANNALA_BRANDT\ncamera_name: camera_left\nimage_width: 752\nimage_height: 480\nprojection_paramete"
},
{
"path": "config/mynteye_kannala_brandt/camera_right.yaml",
"chars": 368,
"preview": "%YAML:1.0\n---\nmodel_type: KANNALA_BRANDT\ncamera_name: camera_right\nimage_width: 752\nimage_height: 480\nprojection_paramet"
},
{
"path": "config/mynteye_kannala_brandt/extrinsics.yaml",
"chars": 247,
"preview": "%YAML:1.0\n---\ntransform:\n q_x: -7.0955103716253032e-04\n q_y: -1.5775578725333590e-03\n q_z: -1.2732644461763854e-03"
},
{
"path": "config/mynteye_kannala_brandt/mynteye_config.yaml",
"chars": 4617,
"preview": "%YAML:1.0\n\n#common parameters\nimu_topic: \"/mynteye/imu/data_raw\"\nimage_topic: \"/mynteye/left/image_raw\"\noutput_path: \"/B"
},
{
"path": "config/mynteye_pinhole/camera_left.yaml",
"chars": 382,
"preview": "%YAML:1.0\n---\nmodel_type: PINHOLE\ncamera_name: camera_left\nimage_width: 752\nimage_height: 480\ndistortion_parameters:\n "
},
{
"path": "config/mynteye_pinhole/camera_right.yaml",
"chars": 383,
"preview": "%YAML:1.0\n---\nmodel_type: PINHOLE\ncamera_name: camera_right\nimage_width: 752\nimage_height: 480\ndistortion_parameters:\n "
},
{
"path": "config/mynteye_pinhole/extrinsics.yaml",
"chars": 246,
"preview": "%YAML:1.0\n---\ntransform:\n q_x: -7.8278125678242136e-04\n q_y: 2.4666921736014214e-03\n q_z: -1.4477856356187120e-03\n"
},
{
"path": "config/mynteye_pinhole/mynteye_config.yaml",
"chars": 4574,
"preview": "%YAML:1.0\n\n#common parameters\nimu_topic: \"/mynteye/imu/data_raw\"\nimage_topic: \"/mynteye/left/image_raw\"\noutput_path: \"/B"
},
{
"path": "config/realsense__terminator_config_vins_fusion_cerebro",
"chars": 4463,
"preview": "[global_config]\n[keybindings]\n[layouts]\n [[default]]\n [[[child0]]]\n fullscreen = False\n last_active_term ="
},
{
"path": "config/vinsfusion/djirosimu_realsense_d435i/README.md",
"chars": 93,
"preview": "The configuration when using realsense stereo camera and djiros's imu (ie. imu data from N3)\n"
},
{
"path": "config/vinsfusion/djirosimu_realsense_d435i/extrinsics.yaml",
"chars": 218,
"preview": "%YAML:1.0\n---\ntransform:\n q_x: 0.\n q_y: 0.\n q_z: 0.\n q_w: 1.\n t_x: -49.8\n t_y: 0.\n t_z: 0.\n#4.98 cm for th"
},
{
"path": "config/vinsfusion/djirosimu_realsense_d435i/left.yaml",
"chars": 279,
"preview": "%YAML:1.0\n---\nmodel_type: PINHOLE\ncamera_name: camera\nimage_width: 640\nimage_height: 480\ndistortion_parameters:\n k1: 0"
},
{
"path": "config/vinsfusion/djirosimu_realsense_d435i/realsense_stereo_imu_config.yaml",
"chars": 3960,
"preview": "%YAML:1.0\n\n#common parameters\n#support: 1 imu 1 cam; 1 imu 2 cam: 2 cam;\nimu: 1\nnum_of_cam: 2\n\n# imu_topic: \"/camera/imu"
},
{
"path": "config/vinsfusion/djirosimu_realsense_d435i/right.yaml",
"chars": 279,
"preview": "%YAML:1.0\n---\nmodel_type: PINHOLE\ncamera_name: camera\nimage_width: 640\nimage_height: 480\ndistortion_parameters:\n k1: 0"
},
{
"path": "config/vinsfusion/euroc/cam0_pinhole.yaml",
"chars": 376,
"preview": "%YAML:1.0\n---\nmodel_type: PINHOLE\ncamera_name: camera\nimage_width: 752\nimage_height: 480\ndistortion_parameters:\n k1: -"
},
{
"path": "config/vinsfusion/euroc/cam1_pinhole.yaml",
"chars": 377,
"preview": "%YAML:1.0\n---\nmodel_type: PINHOLE\ncamera_name: camera\nimage_width: 752\nimage_height: 480\ndistortion_parameters:\n k1: -"
},
{
"path": "config/vinsfusion/euroc/euroc_stereo_imu_config.yaml",
"chars": 3690,
"preview": "%YAML:1.0\n\n#common parameters\n#support: 1 imu 1 cam; 1 imu 2 cam: 2 cam;\nimu: 1\nnum_of_cam: 2\n\nimu_topic: \"/imu0\"\nimage0"
},
{
"path": "config/vinsfusion/euroc/extrinsics.yaml",
"chars": 222,
"preview": "%YAML:1.0\n---\n # this is computed for euric using body_T_cam0 and body_T_cam1.\ntransform:\n q_x: -0.00704531\n q_y:"
},
{
"path": "config/vinsfusion/mynteye/camera_left.yaml",
"chars": 367,
"preview": "%YAML:1.0\n---\nmodel_type: KANNALA_BRANDT\ncamera_name: camera_left\nimage_width: 752\nimage_height: 480\nprojection_paramete"
},
{
"path": "config/vinsfusion/mynteye/camera_left_pinhole.yaml",
"chars": 382,
"preview": "%YAML:1.0\n---\nmodel_type: PINHOLE\ncamera_name: camera_left\nimage_width: 752\nimage_height: 480\ndistortion_parameters:\n "
},
{
"path": "config/vinsfusion/mynteye/camera_right.yaml",
"chars": 368,
"preview": "%YAML:1.0\n---\nmodel_type: KANNALA_BRANDT\ncamera_name: camera_right\nimage_width: 752\nimage_height: 480\nprojection_paramet"
},
{
"path": "config/vinsfusion/mynteye/camera_right_pinhole.yaml",
"chars": 383,
"preview": "%YAML:1.0\n---\nmodel_type: PINHOLE\ncamera_name: camera_right\nimage_width: 752\nimage_height: 480\ndistortion_parameters:\n "
},
{
"path": "config/vinsfusion/mynteye/extrinsics.yaml",
"chars": 247,
"preview": "%YAML:1.0\n---\ntransform:\n q_x: -7.0955103716253032e-04\n q_y: -1.5775578725333590e-03\n q_z: -1.2732644461763854e-03"
},
{
"path": "config/vinsfusion/mynteye/mynteye_stereo_imu_config.yaml",
"chars": 3920,
"preview": "%YAML:1.0\n\n#common parameters\n#support: 1 imu 1 cam; 1 imu 2 cam: 2 cam;\nimu: 1\nnum_of_cam: 2\n\nimu_topic: \"/mynteye/imu/"
},
{
"path": "config/vinsfusion/realsense_d435i/extrinsics.yaml",
"chars": 218,
"preview": "%YAML:1.0\n---\ntransform:\n q_x: 0.\n q_y: 0.\n q_z: 0.\n q_w: 1.\n t_x: -49.8\n t_y: 0.\n t_z: 0.\n#4.98 cm for th"
},
{
"path": "config/vinsfusion/realsense_d435i/left.yaml",
"chars": 279,
"preview": "%YAML:1.0\n---\nmodel_type: PINHOLE\ncamera_name: camera\nimage_width: 640\nimage_height: 480\ndistortion_parameters:\n k1: 0"
},
{
"path": "config/vinsfusion/realsense_d435i/realsense_stereo_imu_config.yaml",
"chars": 3947,
"preview": "%YAML:1.0\n\n#common parameters\n#support: 1 imu 1 cam; 1 imu 2 cam: 2 cam;\nimu: 1\nnum_of_cam: 2\n\n#imu_topic: \"/camera/imu\""
},
{
"path": "config/vinsfusion/realsense_d435i/right.yaml",
"chars": 279,
"preview": "%YAML:1.0\n---\nmodel_type: PINHOLE\ncamera_name: camera\nimage_width: 640\nimage_height: 480\ndistortion_parameters:\n k1: 0"
},
{
"path": "config/vinsmono_debug_config.yaml",
"chars": 4333,
"preview": "%YAML:1.0\n\n#######\n## This is config file for running vins-mono. We use this for imu_T_camera calibration.\n## Set the es"
},
{
"path": "launch/debugging_vinsmono.launch",
"chars": 1136,
"preview": "<launch>\n <arg name=\"config_path\" default = \"$(find cerebro)/config/vinsmono_debug_config.yaml\" />\n\t <arg name=\"vins"
},
{
"path": "launch/euroc_vinsfusion.launch",
"chars": 3678,
"preview": "<launch timeout=\"100.0\">\n\n <!-- CONFIG FILE -->\n <!-- <arg name=\"config_path\" default=\"$(find cerebro)/config/vins"
},
{
"path": "launch/keras_server.launch",
"chars": 1431,
"preview": "<launch>\n\n\n<!-- <arg name=\"config_path\" default=\"$(find cerebro)/config/euroc/euroc_config.yaml\" /> -->\n<!-- <arg name=\""
},
{
"path": "launch/mynteye_vinsfusion.launch",
"chars": 8492,
"preview": "<launch timeout=\"100.0\">\n\n <!-- CONFIG FILE -->\n <arg name=\"config_path\" default=\"$(find cerebro)/config/vinsfusio"
},
{
"path": "launch/mynteye_vinsfusion_loadstate.launch",
"chars": 10000,
"preview": "<launch timeout=\"100.0\">\n\n <!-- CONFIG FILE -->\n <arg name=\"config_path\" default=\"$(find cerebro)/config/vinsfusio"
},
{
"path": "launch/mynteye_vinsfusion_ondrone.launch",
"chars": 2987,
"preview": "<launch timeout=\"100.0\">\n\n <!-- CONFIG FILE -->\n <arg name=\"config_path\" default=\"$(find cerebro)/config/vinsfusio"
},
{
"path": "launch/mynteye_vinsfusion_savestate.launch",
"chars": 10000,
"preview": "<launch timeout=\"100.0\">\n\n <!-- CONFIG FILE -->\n <arg name=\"config_path\" default=\"$(find cerebro)/config/vinsfusio"
},
{
"path": "launch/realsense_camera.launch",
"chars": 5484,
"preview": "<launch>\n <arg name=\"serial_no\" default=\"\"/>\n <arg name=\"json_file_path\" default=\"\"/>\n <arg name=\"came"
},
{
"path": "launch/realsense_vinsfusion.launch",
"chars": 4328,
"preview": "<launch timeout=\"100.0\">\n\n <!-- CONFIG FILE -->\n <arg name=\"config_path\" default=\"$(find cerebro)/config/vinsfusio"
},
{
"path": "launch/realsense_vinsfusion_ondrone_repeat.launch",
"chars": 4351,
"preview": "<launch timeout=\"100.0\">\n\n <!-- CONFIG FILE -->\n <arg name=\"config_path\" default=\"$(find cerebro)/config/vinsfusio"
},
{
"path": "launch/realsense_vinsfusion_ondrone_teach.launch",
"chars": 4351,
"preview": "<launch timeout=\"100.0\">\n\n <!-- CONFIG FILE -->\n <arg name=\"config_path\" default=\"$(find cerebro)/config/vinsfusio"
},
{
"path": "msg/LoopEdge.msg",
"chars": 127,
"preview": "time timestamp0\ntime timestamp1\ngeometry_msgs/Pose pose_1T0 # pose of 0 as observed from 1. \nfloat32 weight\nstring descr"
},
{
"path": "package.xml",
"chars": 2545,
"preview": "<?xml version=\"1.0\"?>\n<package>\n <name>cerebro</name>\n <version>0.0.1</version>\n <description>The cerebro package. Th"
},
{
"path": "rviz/dev-config.rviz",
"chars": 17245,
"preview": "Panels:\n - Class: rviz/Displays\n Help Height: 78\n Name: Displays\n Property Tree Widget:\n Expanded:\n "
},
{
"path": "rviz/good-viz.rviz",
"chars": 18045,
"preview": "Panels:\n - Class: rviz/Displays\n Help Height: 78\n Name: Displays\n Property Tree Widget:\n Expanded:\n "
},
{
"path": "rviz/vins-fusion.rviz",
"chars": 18974,
"preview": "Panels:\n - Class: rviz/Displays\n Help Height: 78\n Name: Displays\n Property Tree Widget:\n Expanded:\n "
},
{
"path": "scripts/TerminalColors.py",
"chars": 344,
"preview": "class bcolors:\n HEADER = '\\033[95m'\n OKBLUE = '\\033[94m'\n OKGREEN = '\\033[92m'\n WARNING = '\\033[93m'\n FAI"
},
{
"path": "scripts/keras.models/.gitignore",
"chars": 0,
"preview": ""
},
{
"path": "scripts/keras.models/Apr2019/gray_conv6_K16__centeredinput/model.json",
"chars": 22061,
"preview": "\"{\\\"class_name\\\": \\\"Model\\\", \\\"keras_version\\\": \\\"2.2.4\\\", \\\"config\\\": {\\\"layers\\\": [{\\\"class_name\\\": \\\"InputLayer\\\", \\\""
},
{
"path": "scripts/keras.models/README.md",
"chars": 319,
"preview": "# Pretrained Models for Place Recognition.\n\nThis folder contains tested models for place recognition. The models have be"
},
{
"path": "scripts/keras.models/model.json",
"chars": 26571,
"preview": "\"{\\\"class_name\\\": \\\"Model\\\", \\\"keras_version\\\": \\\"2.2.4\\\", \\\"config\\\": {\\\"layers\\\": [{\\\"class_name\\\": \\\"InputLayer\\\", \\\""
},
{
"path": "scripts/keras_helpers.py",
"chars": 15386,
"preview": "from keras import backend as K\nfrom keras.engine.topology import Layer\nimport keras\nimport code\nimport numpy as np\n\nimpo"
},
{
"path": "scripts/predict_utils.py",
"chars": 7594,
"preview": "import keras\nimport json\nimport pprint\nimport numpy as np\nimport cv2\nimport code\nfrom keras import backend as K\nfrom ker"
},
{
"path": "scripts/unittest/demo_superpoint.py",
"chars": 29862,
"preview": "#!/usr/bin/env python\n#\n# %BANNER_BEGIN%\n# ---------------------------------------------------------------------\n# %COPY"
},
{
"path": "scripts/unittest/rtry_superpoint.py",
"chars": 8003,
"preview": "#!/usr/bin/env python\n\nimport numpy as np\nimport code\nimport cv2\nimport time\n\nimport json\n\nimport torch\n# Stub to warn a"
},
{
"path": "scripts/whole_image_desc_compute_client.py",
"chars": 656,
"preview": "#!/usr/bin/env python\n\n# Sample Client to call the `whole_image_descriptor_compute_server`\n\nfrom cerebro.srv import *\nim"
},
{
"path": "scripts/whole_image_desc_compute_server.py",
"chars": 30901,
"preview": "#!/usr/bin/env python\n\nfrom cerebro.srv import *\nimport rospy\n\nfrom cv_bridge import CvBridge, CvBridgeError\nimport cv2\n"
},
{
"path": "src/Cerebro.cpp",
"chars": 111011,
"preview": "#include \"Cerebro.h\"\n\n//-------------------------------------------------------------//\n//--- Setup Cerebro\n//----------"
},
{
"path": "src/Cerebro.h",
"chars": 8581,
"preview": "#pragma once\n\n/** Cerebro Class\n This class is suppose to be the main-brain of this package.\n It has to ru"
},
{
"path": "src/DataManager.cpp",
"chars": 57536,
"preview": "#include \"DataManager.h\"\n\nDataManager::DataManager(ros::NodeHandle &nh )\n//: out_stream(ofstream(\"/dev/pts/0\",ios::out) "
},
{
"path": "src/DataManager.h",
"chars": 8011,
"preview": "#pragma once\n\n/** DataManager - Inmemory database of data from VINS-estimator\n\n This attempts to store all the da"
},
{
"path": "src/DataNode.cpp",
"chars": 14195,
"preview": "#include \"DataNode.h\"\n\n#if 0\nvoid DataNode::setImageFromMsg( const sensor_msgs::ImageConstPtr msg )\n{\n std::lock_guar"
},
{
"path": "src/DataNode.h",
"chars": 5780,
"preview": "#pragma once\n\n/** This class holds data at 1 instance of time.\n\n Author : Manohar Kuse <mpkuse@connect.ust.hk>\n "
},
{
"path": "src/DlsPnpWithRansac.cpp",
"chars": 15298,
"preview": "\n#include \"DlsPnpWithRansac.h\"\n\n\n#ifdef __USE_THEIASFM\n// Theia's ICP\n// [Input]\n// uv_X: a 3d point cloud expresse"
},
{
"path": "src/DlsPnpWithRansac.h",
"chars": 6539,
"preview": "#pragma once\n\n/* This is a RanSAC wrapper for theia::DlsPnp. Based on sample code on theia-sfm website.\n The official"
},
{
"path": "src/HypothesisManager.cpp",
"chars": 3981,
"preview": "#include \"HypothesisManager.h\"\n\n\nHypothesisManager::HypothesisManager()\n{\n std::cout << \"HypothesisManager constructo"
},
{
"path": "src/HypothesisManager.h",
"chars": 4663,
"preview": "#pragma once\n// This class will manage all the loop hypothesis.\n// This is for implementing the heuristics for multi hyp"
},
{
"path": "src/ImageDataManager.cpp",
"chars": 21869,
"preview": "#include \"ImageDataManager.h\"\n\n\nImageDataManager::ImageDataManager()\n{\n cout << TermColor::iYELLOW() << \"Constructor "
},
{
"path": "src/ImageDataManager.h",
"chars": 3850,
"preview": "#pragma once\n\n// Getting lot of deallocation issues when storing images inside of DataNode.\n// This class now stores the"
},
{
"path": "src/PNPCeresCostFunctions.h",
"chars": 6361,
"preview": "#pragma once\n\n//ceres\n#include <ceres/ceres.h>\n\ntemplate <typename T>\nT NormalizeAngle(const T& angle_degrees) {\n if (a"
},
{
"path": "src/PinholeCamera.cpp",
"chars": 7423,
"preview": "#include \"PinholeCamera.h\"\n\n\nPinholeCamera::PinholeCamera( string config_file )\n{\n\n cv::FileStorage fs( config_file, cv"
},
{
"path": "src/PinholeCamera.h",
"chars": 2665,
"preview": "#pragma once\n/** Class to handle camera intrinsics\n\n Author : Manohar Kuse <mpkuse@connect.ust.hk>\n Created :"
},
{
"path": "src/ProcessedLoopCandidate.cpp",
"chars": 6928,
"preview": "#include \"ProcessedLoopCandidate.h\"\n\nProcessedLoopCandidate::ProcessedLoopCandidate( int idx_from_raw_candidates_list,\n "
},
{
"path": "src/ProcessedLoopCandidate.h",
"chars": 2568,
"preview": "#pragma once\n\n/** Stores info on the loop candidates. Also contains geometric info like\n number of pf-matches, how it"
},
{
"path": "src/Visualization.cpp",
"chars": 17822,
"preview": "#include \"Visualization.h\"\n\nVisualization::Visualization( ros::NodeHandle &nh )\n{\n b_run_thread = false;\n this->nh"
},
{
"path": "src/Visualization.h",
"chars": 1772,
"preview": "#pragma once\n\n/** Visualization class\n This holds a reference to the DataManager. Will publish messages\n "
},
{
"path": "src/cerebro_node.cpp",
"chars": 37220,
"preview": "/** Main for cerebro node.\n\n This contains the main for the cerebro. It subscribes to various topics\n from"
},
{
"path": "src/unittest/unittest_camera_geom_class_usage.cpp",
"chars": 4331,
"preview": "#include <iostream>\nusing namespace std;\n\n#include <iostream>\n#include <string>\n\n#include \"camodocal/camera_models/Camer"
},
{
"path": "src/unittest/unittest_camodocal_proj.cpp",
"chars": 3739,
"preview": "// A usage of my Stereo class.\n#include <iostream>\nusing namespace std;\n\n\n\n\n/** Experiments to project 3d points on imag"
},
{
"path": "src/unittest/unittest_plot2mat.cpp",
"chars": 838,
"preview": "#include <iostream>\nusing namespace std;\n\n#include \"../utils/Plot2Mat.h\"\nint demo()\n{\n cout << \"Hello\\n\";\n Plot2Ma"
},
{
"path": "src/unittest/unittest_pose_tester.cpp",
"chars": 16364,
"preview": "// This unittest will test and evaluate\n// ` StaticTheiaPoseCompute::P3P_ICP` and `StaticTheiaPoseCompute::PNP`\n// from "
},
{
"path": "src/unittest/unittest_rosservice_client.cpp",
"chars": 1470,
"preview": "#include <ros/ros.h>\n#include <cerebro/WholeImageDescriptorCompute.h>\n#include <iostream>\n\n#include <sensor_msgs/Image.h"
},
{
"path": "src/unittest/unittest_termcolor.cpp",
"chars": 1011,
"preview": "#include <iostream>\n\n#include \"../utils/TermColor.h\"\n// #include \"../utils/PoseManipUtils.h\"\n\nusing namespace std;\nint m"
},
{
"path": "src/unittest/unittest_theia.cpp",
"chars": 62871,
"preview": "// Opens the log.json file :\n// A) Plots the vio poses\n// B) plot loop candidates\n// c) at loop candidate compute relati"
},
{
"path": "src/unittest/unittest_theia_ransac.cpp",
"chars": 334,
"preview": "#include <iostream>\n#include <string>\n//opencv\n#include <opencv2/core/core.hpp>\n#include <opencv2/highgui/highgui.hpp>\n#"
},
{
"path": "src/utils/CameraGeometry.cpp",
"chars": 37276,
"preview": "#include \"CameraGeometry.h\"\n\nMonoGeometry::MonoGeometry(camodocal::CameraPtr _camera)\n{\n assert( _camera && \"Abstract"
},
{
"path": "src/utils/CameraGeometry.h",
"chars": 12973,
"preview": "#pragma once\n// This has 2 classes\n// A) MonoGeometry\n// B) StereoGeometry\n\n//opencv\n#include <opencv2/core/core.hpp>\n#i"
},
{
"path": "src/utils/ElapsedTime.h",
"chars": 1458,
"preview": "#pragma once\n\n#include <chrono>\n#include <iostream>\n#include <iomanip>\n#include <string>\n#include <sstream>\n\nclass Elaps"
},
{
"path": "src/utils/GMSMatcher/gms_matcher.cpp",
"chars": 3596,
"preview": "#include \"gms_matcher.h\"\n\n\n\nint gms_matcher::GetInlierMask(vector<bool> &vbInliers, bool WithScale, bool WithRotation) {"
},
{
"path": "src/utils/GMSMatcher/gms_matcher.h",
"chars": 5312,
"preview": "#pragma once\n#include <opencv2/opencv.hpp>\n#include <vector>\n#include <iostream>\n#include <ctime>\nusing namespace std;\nu"
},
{
"path": "src/utils/MiscUtils.cpp",
"chars": 22799,
"preview": "#include \"MiscUtils.h\"\n\nstring MiscUtils::type2str(int type) {\n string r;\n\n uchar depth = type & CV_MAT_DEPTH_MASK;\n "
},
{
"path": "src/utils/MiscUtils.h",
"chars": 8183,
"preview": "#pragma once\n\n#include <iostream>\n#include <string>\n#include <vector>\n#include <fstream>\n#include <queue>\n#include <ostr"
},
{
"path": "src/utils/Plot2Mat.cpp",
"chars": 3771,
"preview": "#include \"Plot2Mat.h\"\n\nPlot2Mat::Plot2Mat() {\n im_width = 640;\n im_height = 480;\n bg_color = cv::Scalar(80,80,8"
},
{
"path": "src/utils/Plot2Mat.h",
"chars": 4551,
"preview": "#pragma once\n/**\nA OpenCV based plotting. The idea is, given a vector (of floats) to\nplot them and make a cv::Mat out of"
},
{
"path": "src/utils/PointFeatureMatching.cpp",
"chars": 8753,
"preview": "#include \"PointFeatureMatching.h\"\n\n// #define ___StaticPointFeatureMatching__gms_point_feature_matches( msg ) msg;\n#defi"
},
{
"path": "src/utils/PointFeatureMatching.h",
"chars": 2810,
"preview": "#pragma once\n#include <iostream>\n#include <string>\n#include <vector>\n#include <fstream>\n#include <queue>\n#include <ostre"
},
{
"path": "src/utils/PoseManipUtils.cpp",
"chars": 6557,
"preview": "#include \"PoseManipUtils.h\"\n\nvoid PoseManipUtils::raw_to_eigenmat( const double * quat, const double * t, Matrix4d& dstT"
},
{
"path": "src/utils/PoseManipUtils.h",
"chars": 2258,
"preview": "#pragma once\n//\n// This provides utilities for pose manipulation.\n//\n// Author : Manohar Kuse <mpkuse@connect.ust.hk>\n//"
},
{
"path": "src/utils/RawFileIO.cpp",
"chars": 13279,
"preview": "#include \"RawFileIO.h\"\n\n\nvoid RawFileIO::write_image( string fname, const cv::Mat& img)\n{\n __RawFileIO__write_image_d"
},
{
"path": "src/utils/RawFileIO.h",
"chars": 3423,
"preview": "#pragma once\n\n\n#include <iostream>\n#include <string>\n#include <vector>\n#include <fstream>\n#include <queue>\n#include <ost"
},
{
"path": "src/utils/RosMarkerUtils.cpp",
"chars": 10161,
"preview": "#include \"RosMarkerUtils.h\"\n\n// cam_size = 1: means basic size. 1.5 will make it 50% bigger.\nvoid RosMarkerUtils::init_c"
},
{
"path": "src/utils/RosMarkerUtils.h",
"chars": 2553,
"preview": "#pragma once\n\n//\n// This provides utilities creating ros markers\n//\n// Author : Manohar Kuse <mpkuse@connect.ust.hk>\n// "
},
{
"path": "src/utils/SafeQueue.h",
"chars": 2123,
"preview": "#pragma once\n\n#include <queue>\n#include <mutex>\n#include <condition_variable>\n\n// A threadsafe-queue. - https://stackove"
},
{
"path": "src/utils/TermColor.h",
"chars": 3686,
"preview": "#pragma once\n\n/**\n\n// TODO Work in progress\n// https://stackoverflow.com/questions/2616906/how-do-i-output-coloured-text"
},
{
"path": "src/utils/camera_geometry_usage.cpp",
"chars": 28544,
"preview": "// Sample usage for class CameraGeometry.h/MonoGeometry and CameraGeometry.h/StereoGeometry\n// These classes abstractout"
},
{
"path": "src/utils/camodocal/README.md",
"chars": 1356,
"preview": "# Camodocal\n\nOriginal Implementation : https://github.com/hengli/camodocal\nMy (Manohar Kuse, mpkuse@connect.ust.hk) Adap"
},
{
"path": "src/utils/camodocal/include/camodocal/calib/CameraCalibration.h",
"chars": 2195,
"preview": "#ifndef CAMERACALIBRATION_H\n#define CAMERACALIBRATION_H\n\n#include <opencv2/core/core.hpp>\n\n#include \"camodocal/camera_mo"
},
{
"path": "src/utils/camodocal/include/camodocal/camera_models/Camera.h",
"chars": 5063,
"preview": "#ifndef CAMERA_H\n#define CAMERA_H\n\n#include <boost/shared_ptr.hpp>\n#include <eigen3/Eigen/Dense>\n#include <opencv2/core/"
},
{
"path": "src/utils/camodocal/include/camodocal/camera_models/CameraFactory.h",
"chars": 658,
"preview": "#ifndef CAMERAFACTORY_H\n#define CAMERAFACTORY_H\n\n#include <boost/shared_ptr.hpp>\n#include <opencv2/core/core.hpp>\n\n#incl"
},
{
"path": "src/utils/camodocal/include/camodocal/camera_models/CataCamera.h",
"chars": 6561,
"preview": "#ifndef CATACAMERA_H\r\n#define CATACAMERA_H\r\n\r\n#include <opencv2/core/core.hpp>\r\n#include <string>\r\n\r\n#include \"ceres/rot"
},
{
"path": "src/utils/camodocal/include/camodocal/camera_models/CostFunctionFactory.h",
"chars": 3444,
"preview": "#ifndef COSTFUNCTIONFACTORY_H\n#define COSTFUNCTIONFACTORY_H\n\n#include <boost/shared_ptr.hpp>\n#include <opencv2/core/core"
},
{
"path": "src/utils/camodocal/include/camodocal/camera_models/EquidistantCamera.h",
"chars": 6787,
"preview": "#ifndef EQUIDISTANTCAMERA_H\r\n#define EQUIDISTANTCAMERA_H\r\n\r\n#include <opencv2/core/core.hpp>\r\n#include <string>\r\n\r\n#incl"
},
{
"path": "src/utils/camodocal/include/camodocal/camera_models/PinholeCamera.h",
"chars": 5982,
"preview": "#ifndef PINHOLECAMERA_H\n#define PINHOLECAMERA_H\n\n#include <opencv2/core/core.hpp>\n#include <string>\n\n#include \"ceres/rot"
},
{
"path": "src/utils/camodocal/include/camodocal/camera_models/ScaramuzzaCamera.h",
"chars": 10407,
"preview": "#ifndef SCARAMUZZACAMERA_H\r\n#define SCARAMUZZACAMERA_H\r\n\r\n#include <opencv2/core/core.hpp>\r\n#include <string>\r\n\r\n#includ"
},
{
"path": "src/utils/camodocal/include/camodocal/chessboard/Chessboard.h",
"chars": 3058,
"preview": "#ifndef CHESSBOARD_H\n#define CHESSBOARD_H\n\n#include <boost/shared_ptr.hpp>\n#include <opencv2/core/core.hpp>\n\nnamespace c"
},
{
"path": "src/utils/camodocal/include/camodocal/chessboard/ChessboardCorner.h",
"chars": 1196,
"preview": "#ifndef CHESSBOARDCORNER_H\n#define CHESSBOARDCORNER_H\n\n#include <boost/shared_ptr.hpp>\n#include <opencv2/core/core.hpp>\n"
},
{
"path": "src/utils/camodocal/include/camodocal/chessboard/ChessboardQuad.h",
"chars": 773,
"preview": "#ifndef CHESSBOARDQUAD_H\n#define CHESSBOARDQUAD_H\n\n#include <boost/shared_ptr.hpp>\n\n#include \"camodocal/chessboard/Chess"
},
{
"path": "src/utils/camodocal/include/camodocal/chessboard/Spline.h",
"chars": 8626,
"preview": "/* dynamo:- Event driven molecular dynamics simulator\n http://www.marcusbannerman.co.uk/dynamo\n Copyright (C) 201"
},
{
"path": "src/utils/camodocal/include/camodocal/gpl/EigenQuaternionParameterization.h",
"chars": 1150,
"preview": "#ifndef EIGENQUATERNIONPARAMETERIZATION_H\n#define EIGENQUATERNIONPARAMETERIZATION_H\n\n#include \"ceres/local_parameterizat"
},
{
"path": "src/utils/camodocal/include/camodocal/gpl/EigenUtils.h",
"chars": 11621,
"preview": "#ifndef EIGENUTILS_H\n#define EIGENUTILS_H\n\n#include <eigen3/Eigen/Dense>\n\n#include \"ceres/rotation.h\"\n#include \"camodoca"
},
{
"path": "src/utils/camodocal/include/camodocal/gpl/gpl.h",
"chars": 2414,
"preview": "#ifndef GPL_H\r\n#define GPL_H\r\n\r\n#include <algorithm>\r\n#include <cmath>\r\n#include <opencv2/core/core.hpp>\r\n\r\nnamespace ca"
},
{
"path": "src/utils/camodocal/include/camodocal/sparse_graph/Transform.h",
"chars": 744,
"preview": "#ifndef TRANSFORM_H\n#define TRANSFORM_H\n\n#include <boost/shared_ptr.hpp>\n#include <eigen3/Eigen/Dense>\n#include <stdint."
},
{
"path": "src/utils/camodocal/src/calib/CameraCalibration.cc",
"chars": 16543,
"preview": "#include \"camodocal/calib/CameraCalibration.h\"\n\n#include <cstdio>\n#include <eigen3/Eigen/Dense>\n#include <iomanip>\n#incl"
},
{
"path": "src/utils/camodocal/src/camera_models/Camera.cc",
"chars": 5759,
"preview": "#include \"camodocal/camera_models/Camera.h\"\n#include \"camodocal/camera_models/ScaramuzzaCamera.h\"\n\n#include <opencv2/cal"
},
{
"path": "src/utils/camodocal/src/camera_models/CameraFactory.cc",
"chars": 4440,
"preview": "#include \"camodocal/camera_models/CameraFactory.h\"\n\n#include <boost/algorithm/string.hpp>\n\n\n#include \"camodocal/camera_m"
},
{
"path": "src/utils/camodocal/src/camera_models/CataCamera.cc",
"chars": 26012,
"preview": "#include \"camodocal/camera_models/CataCamera.h\"\n\n#include <cmath>\n#include <cstdio>\n#include <eigen3/Eigen/Dense>\n#inclu"
},
{
"path": "src/utils/camodocal/src/camera_models/CostFunctionFactory.cc",
"chars": 45514,
"preview": "#include \"camodocal/camera_models/CostFunctionFactory.h\"\n\n#include \"ceres/ceres.h\"\n#include \"camodocal/camera_models/Cat"
},
{
"path": "src/utils/camodocal/src/camera_models/EquidistantCamera.cc",
"chars": 20449,
"preview": "#include \"camodocal/camera_models/EquidistantCamera.h\"\n\n#include <cmath>\n#include <cstdio>\n#include <eigen3/Eigen/Dense>"
},
{
"path": "src/utils/camodocal/src/camera_models/PinholeCamera.cc",
"chars": 22110,
"preview": "#include \"camodocal/camera_models/PinholeCamera.h\"\n\n#include <cmath>\n#include <cstdio>\n#include <eigen3/Eigen/Dense>\n#in"
},
{
"path": "src/utils/camodocal/src/camera_models/ScaramuzzaCamera.cc",
"chars": 25873,
"preview": "#include \"camodocal/camera_models/ScaramuzzaCamera.h\"\n\n#include <cmath>\n#include <cstdio>\n#include <eigen3/Eigen/Dense>\n"
},
{
"path": "src/utils/camodocal/src/chessboard/Chessboard.cc",
"chars": 70141,
"preview": "#include \"camodocal/chessboard/Chessboard.h\"\n\n#include <opencv2/calib3d/calib3d.hpp>\n#include <opencv2/imgproc/imgproc.h"
},
{
"path": "src/utils/camodocal/src/gpl/EigenQuaternionParameterization.cc",
"chars": 1409,
"preview": "#include \"camodocal/gpl/EigenQuaternionParameterization.h\"\n\n#include <cmath>\n\nnamespace camodocal\n{\n\nbool\nEigenQuaternio"
},
{
"path": "src/utils/camodocal/src/gpl/gpl.cc",
"chars": 25657,
"preview": "#include \"camodocal/gpl/gpl.h\"\r\n\r\n#include <set>\r\n#ifdef _WIN32\r\n#include <winsock.h>\r\n#else\r\n#include <time.h>\r\n#endif\r"
},
{
"path": "src/utils/camodocal/src/intrinsic_calib.cc",
"chars": 8500,
"preview": "#include <boost/algorithm/string.hpp>\n#include <boost/filesystem.hpp>\n#include <boost/program_options.hpp>\n#include <iom"
},
{
"path": "src/utils/camodocal/src/sparse_graph/Transform.cc",
"chars": 1075,
"preview": "#include <camodocal/sparse_graph/Transform.h>\n\nnamespace camodocal\n{\n\nTransform::Transform()\n{\n m_q.setIdentity();\n "
},
{
"path": "src/utils/nlohmann/json.hpp",
"chars": 706034,
"preview": "/*\n __ _____ _____ _____\n __| | __| | | | JSON for Modern C++\n| | |__ | | | | | | version 3.4.0\n|___"
},
{
"path": "srv/WholeImageDescriptorCompute.srv",
"chars": 67,
"preview": "sensor_msgs/Image ima\nint64 a\n---\nfloat64[] desc\nstring model_type\n"
}
]
// ... and 7 more files (download for full content)
About this extraction
This page contains the full source code of the mpkuse/cerebro GitHub repository, extracted and formatted as plain text for AI agents and large language models (LLMs). The extraction includes 154 files (1.9 MB), approximately 543.1k tokens, and a symbol index with 989 extracted functions, classes, methods, constants, and types. Use this with OpenClaw, Claude, ChatGPT, Cursor, Windsurf, or any other AI tool that accepts text input. You can copy the full output to your clipboard or download it as a .txt file.
Extracted by GitExtract — free GitHub repo to text converter for AI. Built by Nikandr Surkov.