diff --git a/.github/workflows/ubuntu.yml b/.github/workflows/ubuntu.yml index 9dc78ef..5fa7516 100644 --- a/.github/workflows/ubuntu.yml +++ b/.github/workflows/ubuntu.yml @@ -51,7 +51,7 @@ jobs: run: | echo "/usr/local/cuda-11.0/bin" >> $GITHUB_PATH echo "$HOME/.local/bin" >> $GITHUB_PATH - - name: local dependencies cache + - name: cache local dependencies id: cache-local uses: actions/cache@v2 with: @@ -134,6 +134,12 @@ jobs: - name: format check run: make check-format working-directory: build + - name: cache third party build + id: cache-third-party + uses: actions/cache@v2 + with: + path: ${{ github.workspace }}/build/third_party + key: third-party-build-v1.0 - name: build run: make -j3 working-directory: build diff --git a/third_party/CMakeLists.txt b/third_party/CMakeLists.txt index ccd8389..0c6af06 100644 --- a/third_party/CMakeLists.txt +++ b/third_party/CMakeLists.txt @@ -2,5 +2,8 @@ add_library(popl INTERFACE) target_include_directories(popl SYSTEM INTERFACE ${CMAKE_CURRENT_SOURCE_DIR}/popl/include) add_subdirectory(imgui-1.77) -#add_subdirectory(spdlog-1.6.1) add_subdirectory(googletest-1.10.0) +add_subdirectory(ORB_SLAM3) + +# NOTE(alvin): add back when OpenVSLAM is removed +# add_subdirectory(spdlog-1.6.1) diff --git a/third_party/ORB_SLAM3/.gitignore b/third_party/ORB_SLAM3/.gitignore new file mode 100644 index 0000000..c3d1361 --- /dev/null +++ b/third_party/ORB_SLAM3/.gitignore @@ -0,0 +1,49 @@ +CMakeLists.txt.user +CMakeLists_modified.txt + +Examples/RGB-D/rgbd_tum + +Examples/Monocular/mono_euroc +Examples/Monocular/mono_kitti +Examples/Monocular/mono_tum +Examples/Monocular/mono_tum_vi + +Examples/Stereo/stereo_euroc +Examples/Stereo/stereo_kitti +Examples/Stereo/stereo_tum_vi + +Examples/Monocular-Inertial/mono_inertial_euroc +Examples/Monocular-Inertial/mono_inertial_tum_vi + +Examples/Stereo-Inertial/stereo_inertial_euroc +Examples/Stereo-Inertial/stereo_inertial_tum_vi + +Examples/ROS/ORB_SLAM3/Mono +Examples/ROS/ORB_SLAM3/Mono_Inertial +Examples/ROS/ORB_SLAM3/MonoAR +Examples/ROS/ORB_SLAM3/RGBD +Examples/ROS/ORB_SLAM3/Stereo +Examples/ROS/ORB_SLAM3/Stereo_Inertial + +Examples/ROS/ORB_SLAM3/CMakeLists.txt.user +Examples/ROS/ORB_SLAM3/build/ + +KeyFrameTrajectory.txt +CameraTrajectory.txt +kf_*.txt +f_*.txt +Thirdparty/DBoW2/build/ +Thirdparty/DBoW2/lib/ +Thirdparty/g2o/build/ +Thirdparty/g2o/config.h +Thirdparty/g2o/lib/ +Vocabulary/ORBvoc.txt +build/ + +lib/ + +cmake_modules/ +cmake-build-debug/ + +*.pyc +*.osa diff --git a/third_party/ORB_SLAM3/CMakeLists.txt b/third_party/ORB_SLAM3/CMakeLists.txt new file mode 100644 index 0000000..09e43a0 --- /dev/null +++ b/third_party/ORB_SLAM3/CMakeLists.txt @@ -0,0 +1,120 @@ +cmake_minimum_required(VERSION 2.8) +project(ORB_SLAM3) + +IF(NOT CMAKE_BUILD_TYPE) + SET(CMAKE_BUILD_TYPE Release) +ENDIF() + +MESSAGE("Build type: " ${CMAKE_BUILD_TYPE}) + +set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wall -O3") +set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -O3") +set(CMAKE_C_FLAGS_RELEASE "${CMAKE_C_FLAGS_RELEASE} -march=native") +set(CMAKE_CXX_FLAGS_RELEASE "${CMAKE_CXX_FLAGS_RELEASE} -march=native") + +set(CMAKE_CXX_STANDARD 17) +set(CMAKE_CXX_STANDARD_REQUIRED ON) + +LIST(APPEND CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake_modules) + +find_package(OpenCV REQUIRED) + +MESSAGE("OPENCV VERSION:") +MESSAGE(${OpenCV_VERSION}) + +find_package(Eigen3 3.3 REQUIRED) +find_package(Pangolin REQUIRED) + +add_library(${PROJECT_NAME} SHARED +src/System.cc +src/Tracking.cc +src/LocalMapping.cc +src/LoopClosing.cc +src/ORBextractor.cc +src/ORBmatcher.cc +src/FrameDrawer.cc +src/Converter.cc +src/MapPoint.cc +src/KeyFrame.cc +src/Atlas.cc +src/Map.cc +src/MapDrawer.cc +src/Optimizer.cc +src/PnPsolver.cc +src/Frame.cc +src/KeyFrameDatabase.cc +src/Sim3Solver.cc +src/Initializer.cc +src/Viewer.cc +src/ImuTypes.cc +src/G2oTypes.cc +src/CameraModels/Pinhole.cpp +src/CameraModels/KannalaBrandt8.cpp +src/OptimizableTypes.cpp +src/MLPnPsolver.cpp +include/System.h +include/Tracking.h +include/LocalMapping.h +include/LoopClosing.h +include/ORBextractor.h +include/ORBmatcher.h +include/FrameDrawer.h +include/Converter.h +include/MapPoint.h +include/KeyFrame.h +include/Atlas.h +include/Map.h +include/MapDrawer.h +include/Optimizer.h +include/PnPsolver.h +include/Frame.h +include/KeyFrameDatabase.h +include/Sim3Solver.h +include/Initializer.h +include/Viewer.h +include/ImuTypes.h +include/G2oTypes.h +include/CameraModels/GeometricCamera.h +include/CameraModels/Pinhole.h +include/CameraModels/KannalaBrandt8.h +include/OptimizableTypes.h +include/MLPnPsolver.h +include/TwoViewReconstruction.h +src/TwoViewReconstruction.cc) + +add_subdirectory(Thirdparty/DBoW2) +add_subdirectory(Thirdparty/g2o) + +target_include_directories(${PROJECT_NAME} PUBLIC + ${PROJECT_SOURCE_DIR} + ${PROJECT_SOURCE_DIR}/include + ${PROJECT_SOURCE_DIR}/include/CameraModels + ${Pangolin_INCLUDE_DIRS} +) + + +target_link_libraries(${PROJECT_NAME} PUBLIC + ${OpenCV_LIBS} + ${Pangolin_LIBRARIES} + Eigen3::Eigen + DBoW2 + g2o +) + +target_compile_definitions(${PROJECT_NAME} PRIVATE COMPILEDWITHC11) + +target_compile_options(${PROJECT_NAME} PRIVATE + -Wno-deprecated-declarations + -Wno-deprecated + -Wno-dangling-else + -Wno-sign-compare + -Wno-unused-variable + -Wno-unused-but-set-variable + -Wno-unused-local-typedefs + -Wno-unused-result + -Wno-maybe-uninitialized + -Wno-conversion-null + -Wno-comment + -Wno-reorder +) + diff --git a/third_party/ORB_SLAM3/Changelog.md b/third_party/ORB_SLAM3/Changelog.md new file mode 100644 index 0000000..1d19d80 --- /dev/null +++ b/third_party/ORB_SLAM3/Changelog.md @@ -0,0 +1,26 @@ +# ORB-SLAM3 +Details of changes between the different versions. + +### V0.3: Beta version, 4 Sep 2020 + +- RGB-D compatibility, the RGB-D examples had been adapted to the new version. + +- Kitti and TUM dataset compatibility, these examples had been adapted to the new version. + +- ROS compatibility, It had been updated the old references in the code to work with this version. + +- Config file parser, the YAML file contains the session configuration, a wrong parametrization may break the execution without any information to solve it. This version parses the file to read all the fields and give a proper answer if one of the fields have been wrong deffined or don't exist. + +- Fixed minor bugs. + + +### V0.2: Beta version, 7 Aug 2020 +Initial release. It has these capabilities: + +- Multiple-Maps capabilities, it is able to handle multiple maps in the same session and merge them when a common area is detected with a seamless fussion. + +- Inertial sensor, the IMU initialization takes a 2 seconds to achieve a scale error less than 5\% and it is reffined in the next 10 seconds until is around 1\%. Inertial measures are integrated at frame rate to estimate the scale, gravity and velocity in order to improve the visual features detection and make the system robust to temporal occlusions. + +- Fisheye sensor, the fisheye sensors are now fully supported in monocular and stereo. + + diff --git a/third_party/ORB_SLAM3/Dependencies.md b/third_party/ORB_SLAM3/Dependencies.md new file mode 100644 index 0000000..c194d26 --- /dev/null +++ b/third_party/ORB_SLAM3/Dependencies.md @@ -0,0 +1,48 @@ +##List of Known Dependencies +###ORB-SLAM3 version 0.3 + +In this document we list all the pieces of code included by ORB-SLAM3 and linked libraries which are not property of the authors of ORB-SLAM3. + + +#####Code in **src** and **include** folders + +* *ORBextractor.cc*. +This is a modified version of orb.cpp of OpenCV library. The original code is BSD licensed. + +* *PnPsolver.h, PnPsolver.cc*. +This is a modified version of the epnp.h and epnp.cc of Vincent Lepetit. +This code can be found in popular BSD licensed computer vision libraries as [OpenCV](https://github.com/Itseez/opencv/blob/master/modules/calib3d/src/epnp.cpp) and [OpenGV](https://github.com/laurentkneip/opengv/blob/master/src/absolute_pose/modules/Epnp.cpp). The original code is FreeBSD. + +* *MLPnPsolver.h, MLPnPsolver.cc*. +This is a modified version of the MLPnP of Steffen Urban from [here](https://github.com/urbste/opengv). +The original code is BSD licensed. + +* Function *ORBmatcher::DescriptorDistance* in *ORBmatcher.cc*. +The code is from: http://graphics.stanford.edu/~seander/bithacks.html#CountBitsSetParallel. +The code is in the public domain. + +#####Code in Thirdparty folder + +* All code in **DBoW2** folder. +This is a modified version of [DBoW2](https://github.com/dorian3d/DBoW2) and [DLib](https://github.com/dorian3d/DLib) library. All files included are BSD licensed. + +* All code in **g2o** folder. +This is a modified version of [g2o](https://github.com/RainerKuemmerle/g2o). All files included are BSD licensed. + +#####Library dependencies + +* **Pangolin (visualization and user interface)**. +[MIT license](https://en.wikipedia.org/wiki/MIT_License). + +* **OpenCV**. +BSD license. + +* **Eigen3**. +For versions greater than 3.1.1 is MPL2, earlier versions are LGPLv3. + +* **ROS (Optional, only if you build Examples/ROS)**. +BSD license. In the manifest.xml the only declared package dependencies are roscpp, tf, sensor_msgs, image_transport, cv_bridge, which are all BSD licensed. + + + + diff --git a/third_party/ORB_SLAM3/LICENSE b/third_party/ORB_SLAM3/LICENSE new file mode 100644 index 0000000..9cecc1d --- /dev/null +++ b/third_party/ORB_SLAM3/LICENSE @@ -0,0 +1,674 @@ + GNU GENERAL PUBLIC LICENSE + Version 3, 29 June 2007 + + Copyright (C) 2007 Free Software Foundation, Inc. + Everyone is permitted to copy and distribute verbatim copies + of this license document, but changing it is not allowed. + + Preamble + + The GNU General Public License is a free, copyleft license for +software and other kinds of works. + + The licenses for most software and other practical works are designed +to take away your freedom to share and change the works. By contrast, +the GNU General Public License is intended to guarantee your freedom to +share and change all versions of a program--to make sure it remains free +software for all its users. We, the Free Software Foundation, use the +GNU General Public License for most of our software; it applies also to +any other work released this way by its authors. You can apply it to +your programs, too. + + When we speak of free software, we are referring to freedom, not +price. Our General Public Licenses are designed to make sure that you +have the freedom to distribute copies of free software (and charge for +them if you wish), that you receive source code or can get it if you +want it, that you can change the software or use pieces of it in new +free programs, and that you know you can do these things. + + To protect your rights, we need to prevent others from denying you +these rights or asking you to surrender the rights. Therefore, you have +certain responsibilities if you distribute copies of the software, or if +you modify it: responsibilities to respect the freedom of others. + + For example, if you distribute copies of such a program, whether +gratis or for a fee, you must pass on to the recipients the same +freedoms that you received. You must make sure that they, too, receive +or can get the source code. And you must show them these terms so they +know their rights. + + Developers that use the GNU GPL protect your rights with two steps: +(1) assert copyright on the software, and (2) offer you this License +giving you legal permission to copy, distribute and/or modify it. + + For the developers' and authors' protection, the GPL clearly explains +that there is no warranty for this free software. For both users' and +authors' sake, the GPL requires that modified versions be marked as +changed, so that their problems will not be attributed erroneously to +authors of previous versions. + + Some devices are designed to deny users access to install or run +modified versions of the software inside them, although the manufacturer +can do so. This is fundamentally incompatible with the aim of +protecting users' freedom to change the software. The systematic +pattern of such abuse occurs in the area of products for individuals to +use, which is precisely where it is most unacceptable. Therefore, we +have designed this version of the GPL to prohibit the practice for those +products. If such problems arise substantially in other domains, we +stand ready to extend this provision to those domains in future versions +of the GPL, as needed to protect the freedom of users. + + Finally, every program is threatened constantly by software patents. +States should not allow patents to restrict development and use of +software on general-purpose computers, but in those that do, we wish to +avoid the special danger that patents applied to a free program could +make it effectively proprietary. To prevent this, the GPL assures that +patents cannot be used to render the program non-free. + + The precise terms and conditions for copying, distribution and +modification follow. + + TERMS AND CONDITIONS + + 0. Definitions. + + "This License" refers to version 3 of the GNU General Public License. + + "Copyright" also means copyright-like laws that apply to other kinds of +works, such as semiconductor masks. + + "The Program" refers to any copyrightable work licensed under this +License. Each licensee is addressed as "you". "Licensees" and +"recipients" may be individuals or organizations. + + To "modify" a work means to copy from or adapt all or part of the work +in a fashion requiring copyright permission, other than the making of an +exact copy. The resulting work is called a "modified version" of the +earlier work or a work "based on" the earlier work. + + A "covered work" means either the unmodified Program or a work based +on the Program. + + To "propagate" a work means to do anything with it that, without +permission, would make you directly or secondarily liable for +infringement under applicable copyright law, except executing it on a +computer or modifying a private copy. Propagation includes copying, +distribution (with or without modification), making available to the +public, and in some countries other activities as well. + + To "convey" a work means any kind of propagation that enables other +parties to make or receive copies. Mere interaction with a user through +a computer network, with no transfer of a copy, is not conveying. + + An interactive user interface displays "Appropriate Legal Notices" +to the extent that it includes a convenient and prominently visible +feature that (1) displays an appropriate copyright notice, and (2) +tells the user that there is no warranty for the work (except to the +extent that warranties are provided), that licensees may convey the +work under this License, and how to view a copy of this License. If +the interface presents a list of user commands or options, such as a +menu, a prominent item in the list meets this criterion. + + 1. Source Code. + + The "source code" for a work means the preferred form of the work +for making modifications to it. "Object code" means any non-source +form of a work. + + A "Standard Interface" means an interface that either is an official +standard defined by a recognized standards body, or, in the case of +interfaces specified for a particular programming language, one that +is widely used among developers working in that language. + + The "System Libraries" of an executable work include anything, other +than the work as a whole, that (a) is included in the normal form of +packaging a Major Component, but which is not part of that Major +Component, and (b) serves only to enable use of the work with that +Major Component, or to implement a Standard Interface for which an +implementation is available to the public in source code form. A +"Major Component", in this context, means a major essential component +(kernel, window system, and so on) of the specific operating system +(if any) on which the executable work runs, or a compiler used to +produce the work, or an object code interpreter used to run it. + + The "Corresponding Source" for a work in object code form means all +the source code needed to generate, install, and (for an executable +work) run the object code and to modify the work, including scripts to +control those activities. However, it does not include the work's +System Libraries, or general-purpose tools or generally available free +programs which are used unmodified in performing those activities but +which are not part of the work. For example, Corresponding Source +includes interface definition files associated with source files for +the work, and the source code for shared libraries and dynamically +linked subprograms that the work is specifically designed to require, +such as by intimate data communication or control flow between those +subprograms and other parts of the work. + + The Corresponding Source need not include anything that users +can regenerate automatically from other parts of the Corresponding +Source. + + The Corresponding Source for a work in source code form is that +same work. + + 2. Basic Permissions. + + All rights granted under this License are granted for the term of +copyright on the Program, and are irrevocable provided the stated +conditions are met. This License explicitly affirms your unlimited +permission to run the unmodified Program. The output from running a +covered work is covered by this License only if the output, given its +content, constitutes a covered work. This License acknowledges your +rights of fair use or other equivalent, as provided by copyright law. + + You may make, run and propagate covered works that you do not +convey, without conditions so long as your license otherwise remains +in force. You may convey covered works to others for the sole purpose +of having them make modifications exclusively for you, or provide you +with facilities for running those works, provided that you comply with +the terms of this License in conveying all material for which you do +not control copyright. Those thus making or running the covered works +for you must do so exclusively on your behalf, under your direction +and control, on terms that prohibit them from making any copies of +your copyrighted material outside their relationship with you. + + Conveying under any other circumstances is permitted solely under +the conditions stated below. Sublicensing is not allowed; section 10 +makes it unnecessary. + + 3. Protecting Users' Legal Rights From Anti-Circumvention Law. + + No covered work shall be deemed part of an effective technological +measure under any applicable law fulfilling obligations under article +11 of the WIPO copyright treaty adopted on 20 December 1996, or +similar laws prohibiting or restricting circumvention of such +measures. + + When you convey a covered work, you waive any legal power to forbid +circumvention of technological measures to the extent such circumvention +is effected by exercising rights under this License with respect to +the covered work, and you disclaim any intention to limit operation or +modification of the work as a means of enforcing, against the work's +users, your or third parties' legal rights to forbid circumvention of +technological measures. + + 4. Conveying Verbatim Copies. + + You may convey verbatim copies of the Program's source code as you +receive it, in any medium, provided that you conspicuously and +appropriately publish on each copy an appropriate copyright notice; +keep intact all notices stating that this License and any +non-permissive terms added in accord with section 7 apply to the code; +keep intact all notices of the absence of any warranty; and give all +recipients a copy of this License along with the Program. + + You may charge any price or no price for each copy that you convey, +and you may offer support or warranty protection for a fee. + + 5. Conveying Modified Source Versions. + + You may convey a work based on the Program, or the modifications to +produce it from the Program, in the form of source code under the +terms of section 4, provided that you also meet all of these conditions: + + a) The work must carry prominent notices stating that you modified + it, and giving a relevant date. + + b) The work must carry prominent notices stating that it is + released under this License and any conditions added under section + 7. This requirement modifies the requirement in section 4 to + "keep intact all notices". + + c) You must license the entire work, as a whole, under this + License to anyone who comes into possession of a copy. This + License will therefore apply, along with any applicable section 7 + additional terms, to the whole of the work, and all its parts, + regardless of how they are packaged. This License gives no + permission to license the work in any other way, but it does not + invalidate such permission if you have separately received it. + + d) If the work has interactive user interfaces, each must display + Appropriate Legal Notices; however, if the Program has interactive + interfaces that do not display Appropriate Legal Notices, your + work need not make them do so. + + A compilation of a covered work with other separate and independent +works, which are not by their nature extensions of the covered work, +and which are not combined with it such as to form a larger program, +in or on a volume of a storage or distribution medium, is called an +"aggregate" if the compilation and its resulting copyright are not +used to limit the access or legal rights of the compilation's users +beyond what the individual works permit. Inclusion of a covered work +in an aggregate does not cause this License to apply to the other +parts of the aggregate. + + 6. Conveying Non-Source Forms. + + You may convey a covered work in object code form under the terms +of sections 4 and 5, provided that you also convey the +machine-readable Corresponding Source under the terms of this License, +in one of these ways: + + a) Convey the object code in, or embodied in, a physical product + (including a physical distribution medium), accompanied by the + Corresponding Source fixed on a durable physical medium + customarily used for software interchange. + + b) Convey the object code in, or embodied in, a physical product + (including a physical distribution medium), accompanied by a + written offer, valid for at least three years and valid for as + long as you offer spare parts or customer support for that product + model, to give anyone who possesses the object code either (1) a + copy of the Corresponding Source for all the software in the + product that is covered by this License, on a durable physical + medium customarily used for software interchange, for a price no + more than your reasonable cost of physically performing this + conveying of source, or (2) access to copy the + Corresponding Source from a network server at no charge. + + c) Convey individual copies of the object code with a copy of the + written offer to provide the Corresponding Source. This + alternative is allowed only occasionally and noncommercially, and + only if you received the object code with such an offer, in accord + with subsection 6b. + + d) Convey the object code by offering access from a designated + place (gratis or for a charge), and offer equivalent access to the + Corresponding Source in the same way through the same place at no + further charge. You need not require recipients to copy the + Corresponding Source along with the object code. If the place to + copy the object code is a network server, the Corresponding Source + may be on a different server (operated by you or a third party) + that supports equivalent copying facilities, provided you maintain + clear directions next to the object code saying where to find the + Corresponding Source. Regardless of what server hosts the + Corresponding Source, you remain obligated to ensure that it is + available for as long as needed to satisfy these requirements. + + e) Convey the object code using peer-to-peer transmission, provided + you inform other peers where the object code and Corresponding + Source of the work are being offered to the general public at no + charge under subsection 6d. + + A separable portion of the object code, whose source code is excluded +from the Corresponding Source as a System Library, need not be +included in conveying the object code work. + + A "User Product" is either (1) a "consumer product", which means any +tangible personal property which is normally used for personal, family, +or household purposes, or (2) anything designed or sold for incorporation +into a dwelling. In determining whether a product is a consumer product, +doubtful cases shall be resolved in favor of coverage. For a particular +product received by a particular user, "normally used" refers to a +typical or common use of that class of product, regardless of the status +of the particular user or of the way in which the particular user +actually uses, or expects or is expected to use, the product. A product +is a consumer product regardless of whether the product has substantial +commercial, industrial or non-consumer uses, unless such uses represent +the only significant mode of use of the product. + + "Installation Information" for a User Product means any methods, +procedures, authorization keys, or other information required to install +and execute modified versions of a covered work in that User Product from +a modified version of its Corresponding Source. The information must +suffice to ensure that the continued functioning of the modified object +code is in no case prevented or interfered with solely because +modification has been made. + + If you convey an object code work under this section in, or with, or +specifically for use in, a User Product, and the conveying occurs as +part of a transaction in which the right of possession and use of the +User Product is transferred to the recipient in perpetuity or for a +fixed term (regardless of how the transaction is characterized), the +Corresponding Source conveyed under this section must be accompanied +by the Installation Information. But this requirement does not apply +if neither you nor any third party retains the ability to install +modified object code on the User Product (for example, the work has +been installed in ROM). + + The requirement to provide Installation Information does not include a +requirement to continue to provide support service, warranty, or updates +for a work that has been modified or installed by the recipient, or for +the User Product in which it has been modified or installed. Access to a +network may be denied when the modification itself materially and +adversely affects the operation of the network or violates the rules and +protocols for communication across the network. + + Corresponding Source conveyed, and Installation Information provided, +in accord with this section must be in a format that is publicly +documented (and with an implementation available to the public in +source code form), and must require no special password or key for +unpacking, reading or copying. + + 7. Additional Terms. + + "Additional permissions" are terms that supplement the terms of this +License by making exceptions from one or more of its conditions. +Additional permissions that are applicable to the entire Program shall +be treated as though they were included in this License, to the extent +that they are valid under applicable law. If additional permissions +apply only to part of the Program, that part may be used separately +under those permissions, but the entire Program remains governed by +this License without regard to the additional permissions. + + When you convey a copy of a covered work, you may at your option +remove any additional permissions from that copy, or from any part of +it. (Additional permissions may be written to require their own +removal in certain cases when you modify the work.) You may place +additional permissions on material, added by you to a covered work, +for which you have or can give appropriate copyright permission. + + Notwithstanding any other provision of this License, for material you +add to a covered work, you may (if authorized by the copyright holders of +that material) supplement the terms of this License with terms: + + a) Disclaiming warranty or limiting liability differently from the + terms of sections 15 and 16 of this License; or + + b) Requiring preservation of specified reasonable legal notices or + author attributions in that material or in the Appropriate Legal + Notices displayed by works containing it; or + + c) Prohibiting misrepresentation of the origin of that material, or + requiring that modified versions of such material be marked in + reasonable ways as different from the original version; or + + d) Limiting the use for publicity purposes of names of licensors or + authors of the material; or + + e) Declining to grant rights under trademark law for use of some + trade names, trademarks, or service marks; or + + f) Requiring indemnification of licensors and authors of that + material by anyone who conveys the material (or modified versions of + it) with contractual assumptions of liability to the recipient, for + any liability that these contractual assumptions directly impose on + those licensors and authors. + + All other non-permissive additional terms are considered "further +restrictions" within the meaning of section 10. If the Program as you +received it, or any part of it, contains a notice stating that it is +governed by this License along with a term that is a further +restriction, you may remove that term. If a license document contains +a further restriction but permits relicensing or conveying under this +License, you may add to a covered work material governed by the terms +of that license document, provided that the further restriction does +not survive such relicensing or conveying. + + If you add terms to a covered work in accord with this section, you +must place, in the relevant source files, a statement of the +additional terms that apply to those files, or a notice indicating +where to find the applicable terms. + + Additional terms, permissive or non-permissive, may be stated in the +form of a separately written license, or stated as exceptions; +the above requirements apply either way. + + 8. Termination. + + You may not propagate or modify a covered work except as expressly +provided under this License. Any attempt otherwise to propagate or +modify it is void, and will automatically terminate your rights under +this License (including any patent licenses granted under the third +paragraph of section 11). + + However, if you cease all violation of this License, then your +license from a particular copyright holder is reinstated (a) +provisionally, unless and until the copyright holder explicitly and +finally terminates your license, and (b) permanently, if the copyright +holder fails to notify you of the violation by some reasonable means +prior to 60 days after the cessation. + + Moreover, your license from a particular copyright holder is +reinstated permanently if the copyright holder notifies you of the +violation by some reasonable means, this is the first time you have +received notice of violation of this License (for any work) from that +copyright holder, and you cure the violation prior to 30 days after +your receipt of the notice. + + Termination of your rights under this section does not terminate the +licenses of parties who have received copies or rights from you under +this License. If your rights have been terminated and not permanently +reinstated, you do not qualify to receive new licenses for the same +material under section 10. + + 9. Acceptance Not Required for Having Copies. + + You are not required to accept this License in order to receive or +run a copy of the Program. Ancillary propagation of a covered work +occurring solely as a consequence of using peer-to-peer transmission +to receive a copy likewise does not require acceptance. However, +nothing other than this License grants you permission to propagate or +modify any covered work. These actions infringe copyright if you do +not accept this License. Therefore, by modifying or propagating a +covered work, you indicate your acceptance of this License to do so. + + 10. Automatic Licensing of Downstream Recipients. + + Each time you convey a covered work, the recipient automatically +receives a license from the original licensors, to run, modify and +propagate that work, subject to this License. You are not responsible +for enforcing compliance by third parties with this License. + + An "entity transaction" is a transaction transferring control of an +organization, or substantially all assets of one, or subdividing an +organization, or merging organizations. If propagation of a covered +work results from an entity transaction, each party to that +transaction who receives a copy of the work also receives whatever +licenses to the work the party's predecessor in interest had or could +give under the previous paragraph, plus a right to possession of the +Corresponding Source of the work from the predecessor in interest, if +the predecessor has it or can get it with reasonable efforts. + + You may not impose any further restrictions on the exercise of the +rights granted or affirmed under this License. For example, you may +not impose a license fee, royalty, or other charge for exercise of +rights granted under this License, and you may not initiate litigation +(including a cross-claim or counterclaim in a lawsuit) alleging that +any patent claim is infringed by making, using, selling, offering for +sale, or importing the Program or any portion of it. + + 11. Patents. + + A "contributor" is a copyright holder who authorizes use under this +License of the Program or a work on which the Program is based. The +work thus licensed is called the contributor's "contributor version". + + A contributor's "essential patent claims" are all patent claims +owned or controlled by the contributor, whether already acquired or +hereafter acquired, that would be infringed by some manner, permitted +by this License, of making, using, or selling its contributor version, +but do not include claims that would be infringed only as a +consequence of further modification of the contributor version. For +purposes of this definition, "control" includes the right to grant +patent sublicenses in a manner consistent with the requirements of +this License. + + Each contributor grants you a non-exclusive, worldwide, royalty-free +patent license under the contributor's essential patent claims, to +make, use, sell, offer for sale, import and otherwise run, modify and +propagate the contents of its contributor version. + + In the following three paragraphs, a "patent license" is any express +agreement or commitment, however denominated, not to enforce a patent +(such as an express permission to practice a patent or covenant not to +sue for patent infringement). To "grant" such a patent license to a +party means to make such an agreement or commitment not to enforce a +patent against the party. + + If you convey a covered work, knowingly relying on a patent license, +and the Corresponding Source of the work is not available for anyone +to copy, free of charge and under the terms of this License, through a +publicly available network server or other readily accessible means, +then you must either (1) cause the Corresponding Source to be so +available, or (2) arrange to deprive yourself of the benefit of the +patent license for this particular work, or (3) arrange, in a manner +consistent with the requirements of this License, to extend the patent +license to downstream recipients. "Knowingly relying" means you have +actual knowledge that, but for the patent license, your conveying the +covered work in a country, or your recipient's use of the covered work +in a country, would infringe one or more identifiable patents in that +country that you have reason to believe are valid. + + If, pursuant to or in connection with a single transaction or +arrangement, you convey, or propagate by procuring conveyance of, a +covered work, and grant a patent license to some of the parties +receiving the covered work authorizing them to use, propagate, modify +or convey a specific copy of the covered work, then the patent license +you grant is automatically extended to all recipients of the covered +work and works based on it. + + A patent license is "discriminatory" if it does not include within +the scope of its coverage, prohibits the exercise of, or is +conditioned on the non-exercise of one or more of the rights that are +specifically granted under this License. You may not convey a covered +work if you are a party to an arrangement with a third party that is +in the business of distributing software, under which you make payment +to the third party based on the extent of your activity of conveying +the work, and under which the third party grants, to any of the +parties who would receive the covered work from you, a discriminatory +patent license (a) in connection with copies of the covered work +conveyed by you (or copies made from those copies), or (b) primarily +for and in connection with specific products or compilations that +contain the covered work, unless you entered into that arrangement, +or that patent license was granted, prior to 28 March 2007. + + Nothing in this License shall be construed as excluding or limiting +any implied license or other defenses to infringement that may +otherwise be available to you under applicable patent law. + + 12. No Surrender of Others' Freedom. + + If conditions are imposed on you (whether by court order, agreement or +otherwise) that contradict the conditions of this License, they do not +excuse you from the conditions of this License. If you cannot convey a +covered work so as to satisfy simultaneously your obligations under this +License and any other pertinent obligations, then as a consequence you may +not convey it at all. For example, if you agree to terms that obligate you +to collect a royalty for further conveying from those to whom you convey +the Program, the only way you could satisfy both those terms and this +License would be to refrain entirely from conveying the Program. + + 13. Use with the GNU Affero General Public License. + + Notwithstanding any other provision of this License, you have +permission to link or combine any covered work with a work licensed +under version 3 of the GNU Affero General Public License into a single +combined work, and to convey the resulting work. The terms of this +License will continue to apply to the part which is the covered work, +but the special requirements of the GNU Affero General Public License, +section 13, concerning interaction through a network will apply to the +combination as such. + + 14. Revised Versions of this License. + + The Free Software Foundation may publish revised and/or new versions of +the GNU General Public License from time to time. Such new versions will +be similar in spirit to the present version, but may differ in detail to +address new problems or concerns. + + Each version is given a distinguishing version number. If the +Program specifies that a certain numbered version of the GNU General +Public License "or any later version" applies to it, you have the +option of following the terms and conditions either of that numbered +version or of any later version published by the Free Software +Foundation. If the Program does not specify a version number of the +GNU General Public License, you may choose any version ever published +by the Free Software Foundation. + + If the Program specifies that a proxy can decide which future +versions of the GNU General Public License can be used, that proxy's +public statement of acceptance of a version permanently authorizes you +to choose that version for the Program. + + Later license versions may give you additional or different +permissions. However, no additional obligations are imposed on any +author or copyright holder as a result of your choosing to follow a +later version. + + 15. Disclaimer of Warranty. + + THERE IS NO WARRANTY FOR THE PROGRAM, TO THE EXTENT PERMITTED BY +APPLICABLE LAW. EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT +HOLDERS AND/OR OTHER PARTIES PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY +OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, +THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR +PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE PROGRAM +IS WITH YOU. SHOULD THE PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF +ALL NECESSARY SERVICING, REPAIR OR CORRECTION. + + 16. Limitation of Liability. + + IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING +WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MODIFIES AND/OR CONVEYS +THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY +GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING OUT OF THE +USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED TO LOSS OF +DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD +PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER PROGRAMS), +EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF +SUCH DAMAGES. + + 17. Interpretation of Sections 15 and 16. + + If the disclaimer of warranty and limitation of liability provided +above cannot be given local legal effect according to their terms, +reviewing courts shall apply local law that most closely approximates +an absolute waiver of all civil liability in connection with the +Program, unless a warranty or assumption of liability accompanies a +copy of the Program in return for a fee. + + END OF TERMS AND CONDITIONS + + How to Apply These Terms to Your New Programs + + If you develop a new program, and you want it to be of the greatest +possible use to the public, the best way to achieve this is to make it +free software which everyone can redistribute and change under these terms. + + To do so, attach the following notices to the program. It is safest +to attach them to the start of each source file to most effectively +state the exclusion of warranty; and each file should have at least +the "copyright" line and a pointer to where the full notice is found. + + {one line to give the program's name and a brief idea of what it does.} + Copyright (C) {year} {name of author} + + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + +Also add information on how to contact you by electronic and paper mail. + + If the program does terminal interaction, make it output a short +notice like this when it starts in an interactive mode: + + {project} Copyright (C) {year} {fullname} + This program comes with ABSOLUTELY NO WARRANTY; for details type `show w'. + This is free software, and you are welcome to redistribute it + under certain conditions; type `show c' for details. + +The hypothetical commands `show w' and `show c' should show the appropriate +parts of the General Public License. Of course, your program's commands +might be different; for a GUI interface, you would use an "about box". + + You should also get your employer (if you work as a programmer) or school, +if any, to sign a "copyright disclaimer" for the program, if necessary. +For more information on this, and how to apply and follow the GNU GPL, see +. + + The GNU General Public License does not permit incorporating your program +into proprietary programs. If your program is a subroutine library, you +may consider it more useful to permit linking proprietary applications with +the library. If this is what you want to do, use the GNU Lesser General +Public License instead of this License. But first, please read +. diff --git a/third_party/ORB_SLAM3/README.md b/third_party/ORB_SLAM3/README.md new file mode 100644 index 0000000..ee177df --- /dev/null +++ b/third_party/ORB_SLAM3/README.md @@ -0,0 +1,213 @@ +# ORB-SLAM3 + +### V0.3: Beta version, 4 Sep 2020 +**Authors:** Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, [José M. M. Montiel](http://webdiis.unizar.es/~josemari/), [Juan D. Tardos](http://webdiis.unizar.es/~jdtardos/). + +The [Changelog](https://github.com/UZ-SLAMLab/ORB_SLAM3/Changelog.md) describes the features of each version. + +ORB-SLAM3 is the first real-time SLAM library able to perform **Visual, Visual-Inertial and Multi-Map SLAM** with **monocular, stereo and RGB-D** cameras, using **pin-hole and fisheye** lens models. In all sensor configurations, ORB-SLAM3 is as robust as the best systems available in the literature, and significantly more accurate. + +We provide examples to run ORB-SLAM3 in the [EuRoC dataset](http://projects.asl.ethz.ch/datasets/doku.php?id=kmavvisualinertialdatasets) using stereo or monocular, with or without IMU, and in the [TUM-VI dataset](https://vision.in.tum.de/data/datasets/visual-inertial-dataset) using fisheye stereo or monocular, with or without IMU. Videos of some example executions can be found at [ORB-SLAM3 channel](https://www.youtube.com/channel/UCXVt-kXG6T95Z4tVaYlU80Q). + +This software is based on [ORB-SLAM2](https://github.com/raulmur/ORB_SLAM2) developed by [Raul Mur-Artal](http://webdiis.unizar.es/~raulmur/), [Juan D. Tardos](http://webdiis.unizar.es/~jdtardos/), [J. M. M. Montiel](http://webdiis.unizar.es/~josemari/) and [Dorian Galvez-Lopez](http://doriangalvez.com/) ([DBoW2](https://github.com/dorian3d/DBoW2)). + + + +### Related Publications: + +[ORB-SLAM3] Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M. M. Montiel and Juan D. Tardós, **ORB-SLAM3: An Accurate Open-Source Library for Visual, Visual-Inertial and Multi-Map SLAM**, Under review. **[PDF](https://arxiv.org/pdf/2007.11898.pdf)**. + +[IMU-Initialization] Carlos Campos, J. M. M. Montiel and Juan D. Tardós, **Inertial-Only Optimization for Visual-Inertial Initialization**, *ICRA 2020*. **[PDF](https://arxiv.org/pdf/2003.05766.pdf)** + +[ORBSLAM-Atlas] Richard Elvira, J. M. M. Montiel and Juan D. Tardós, **ORBSLAM-Atlas: a robust and accurate multi-map system**, *IROS 2019*. **[PDF](https://arxiv.org/pdf/1908.11585.pdf)**. + +[ORBSLAM-VI] Raúl Mur-Artal, and Juan D. Tardós, **Visual-inertial monocular SLAM with map reuse**, IEEE Robotics and Automation Letters, vol. 2 no. 2, pp. 796-803, 2017. **[PDF](https://arxiv.org/pdf/1610.05949.pdf)**. + +[Stereo and RGB-D] Raúl Mur-Artal and Juan D. Tardós. **ORB-SLAM2: an Open-Source SLAM System for Monocular, Stereo and RGB-D Cameras**. *IEEE Transactions on Robotics,* vol. 33, no. 5, pp. 1255-1262, 2017. **[PDF](https://arxiv.org/pdf/1610.06475.pdf)**. + +[Monocular] Raúl Mur-Artal, José M. M. Montiel and Juan D. Tardós. **ORB-SLAM: A Versatile and Accurate Monocular SLAM System**. *IEEE Transactions on Robotics,* vol. 31, no. 5, pp. 1147-1163, 2015. (**2015 IEEE Transactions on Robotics Best Paper Award**). **[PDF](https://arxiv.org/pdf/1502.00956.pdf)**. + +[DBoW2 Place Recognition] Dorian Gálvez-López and Juan D. Tardós. **Bags of Binary Words for Fast Place Recognition in Image Sequences**. *IEEE Transactions on Robotics,* vol. 28, no. 5, pp. 1188-1197, 2012. **[PDF](http://doriangalvez.com/php/dl.php?dlp=GalvezTRO12.pdf)** + +# 1. License + +ORB-SLAM3 is released under [GPLv3 license](https://github.com/UZ-SLAMLab/ORB_SLAM3/LICENSE). For a list of all code/library dependencies (and associated licenses), please see [Dependencies.md](https://github.com/UZ-SLAMLab/ORB_SLAM3/blob/master/Dependencies.md). + +For a closed-source version of ORB-SLAM3 for commercial purposes, please contact the authors: orbslam (at) unizar (dot) es. + +If you use ORB-SLAM3 in an academic work, please cite: + + @article{ORBSLAM3_2020, + title={{ORB-SLAM3}: An Accurate Open-Source Library for Visual, Visual-Inertial + and Multi-Map {SLAM}}, + author={Campos, Carlos AND Elvira, Richard AND G\´omez, Juan J. AND Montiel, + Jos\'e M. M. AND Tard\'os, Juan D.}, + journal={arXiv preprint arXiv:2007.11898}, + year={2020} + } + +# 2. Prerequisites +We have tested the library in **Ubuntu 16.04** and **18.04**, but it should be easy to compile in other platforms. A powerful computer (e.g. i7) will ensure real-time performance and provide more stable and accurate results. + +## C++11 or C++0x Compiler +We use the new thread and chrono functionalities of C++11. + +## Pangolin +We use [Pangolin](https://github.com/stevenlovegrove/Pangolin) for visualization and user interface. Dowload and install instructions can be found at: https://github.com/stevenlovegrove/Pangolin. + +## OpenCV +We use [OpenCV](http://opencv.org) to manipulate images and features. Dowload and install instructions can be found at: http://opencv.org. **Required at leat 3.0. Tested with OpenCV 3.2.0**. + +## Eigen3 +Required by g2o (see below). Download and install instructions can be found at: http://eigen.tuxfamily.org. **Required at least 3.1.0**. + +## DBoW2 and g2o (Included in Thirdparty folder) +We use modified versions of the [DBoW2](https://github.com/dorian3d/DBoW2) library to perform place recognition and [g2o](https://github.com/RainerKuemmerle/g2o) library to perform non-linear optimizations. Both modified libraries (which are BSD) are included in the *Thirdparty* folder. + +## Python +Required to calculate the alignment of the trajectory with the ground truth. **Required Numpy module**. + +* (win) http://www.python.org/downloads/windows +* (deb) `sudo apt install libpython2.7-dev` +* (mac) preinstalled with osx + +## ROS (optional) + +We provide some examples to process input of a monocular, monocular-inertial, stereo, stereo-inertial or RGB-D camera using ROS. Building these examples is optional. These have been tested with ROS Melodic under Ubuntu 18.04. + +# 3. Building ORB-SLAM3 library and examples + +Clone the repository: +``` +git clone https://github.com/UZ-SLAMLab/ORB_SLAM3.git ORB_SLAM3 +``` + +We provide a script `build.sh` to build the *Thirdparty* libraries and *ORB-SLAM3*. Please make sure you have installed all required dependencies (see section 2). Execute: +``` +cd ORB_SLAM3 +chmod +x build.sh +./build.sh +``` + +This will create **libORB_SLAM3.so** at *lib* folder and the executables in *Examples* folder. + +# 4. EuRoC Examples +[EuRoC dataset](http://projects.asl.ethz.ch/datasets/doku.php?id=kmavvisualinertialdatasets) was recorded with two pinhole cameras and an inertial sensor. We provide an example script to launch EuRoC sequences in all the sensor configurations. + +1. Download a sequence (ASL format) from http://projects.asl.ethz.ch/datasets/doku.php?id=kmavvisualinertialdatasets + +2. Open the script "euroc_examples.sh" in the root of the project. Change **pathDatasetEuroc** variable to point to the directory where the dataset has been uncompressed. + +3. Execute the following script to process all the sequences with all sensor configurations: +``` +./euroc_examples +``` + +## Evaluation +EuRoC provides ground truth for each sequence in the IMU body reference. As pure visual executions report trajectories centered in the left camera, we provide in the "evaluation" folder the transformation of the ground truth to the left camera reference. Visual-inertial trajectories use the ground truth from the dataset. + +Execute the following script to process sequences and compute the RMS ATE: +``` +./euroc_eval_examples +``` + +# 5. TUM-VI Examples +[TUM-VI dataset](https://vision.in.tum.de/data/datasets/visual-inertial-dataset) was recorded with two fisheye cameras and an inertial sensor. + +1. Download a sequence from https://vision.in.tum.de/data/datasets/visual-inertial-dataset and uncompress it. + +2. Open the script "tum_vi_examples.sh" in the root of the project. Change **pathDatasetTUM_VI** variable to point to the directory where the dataset has been uncompressed. + +3. Execute the following script to process all the sequences with all sensor configurations: +``` +./tum_vi_examples +``` + +## Evaluation +In TUM-VI ground truth is only available in the room where all sequences start and end. As a result the error measures the drift at the end of the sequence. + +Execute the following script to process sequences and compute the RMS ATE: +``` +./tum_vi_eval_examples +``` + +# 6. ROS Examples + +### Building the nodes for mono, mono-inertial, stereo, stereo-inertial and RGB-D +Tested with ROS Melodic and ubuntu 18.04. + +1. Add the path including *Examples/ROS/ORB_SLAM3* to the ROS_PACKAGE_PATH environment variable. Open .bashrc file: + ``` + gedit ~/.bashrc + ``` +and add at the end the following line. Replace PATH by the folder where you cloned ORB_SLAM3: + + ``` + export ROS_PACKAGE_PATH=${ROS_PACKAGE_PATH}:PATH/ORB_SLAM3/Examples/ROS + ``` + +2. Execute `build_ros.sh` script: + + ``` + chmod +x build_ros.sh + ./build_ros.sh + ``` + +### Running Monocular Node +For a monocular input from topic `/camera/image_raw` run node ORB_SLAM3/Mono. You will need to provide the vocabulary file and a settings file. See the monocular examples above. + + ``` + rosrun ORB_SLAM3 Mono PATH_TO_VOCABULARY PATH_TO_SETTINGS_FILE + ``` + +### Running Monocular-Inertial Node +For a monocular input from topic `/camera/image_raw` and an inertial input from topic `/imu`, run node ORB_SLAM3/Mono_Inertial. Setting the optional third argument to true will apply CLAHE equalization to images (Mainly for TUM-VI dataset). + + ``` + rosrun ORB_SLAM3 Mono PATH_TO_VOCABULARY PATH_TO_SETTINGS_FILE [EQUALIZATION] + ``` + +### Running Stereo Node +For a stereo input from topic `/camera/left/image_raw` and `/camera/right/image_raw` run node ORB_SLAM3/Stereo. You will need to provide the vocabulary file and a settings file. For Pinhole camera model, if you **provide rectification matrices** (see Examples/Stereo/EuRoC.yaml example), the node will recitify the images online, **otherwise images must be pre-rectified**. For FishEye camera model, rectification is not required since system works with original images: + + ``` + rosrun ORB_SLAM3 Stereo PATH_TO_VOCABULARY PATH_TO_SETTINGS_FILE ONLINE_RECTIFICATION + ``` + +### Running Stereo-Inertial Node +For a stereo input from topics `/camera/left/image_raw` and `/camera/right/image_raw`, and an inertial input from topic `/imu`, run node ORB_SLAM3/Stereo_Inertial. You will need to provide the vocabulary file and a settings file, including rectification matrices if required in a similar way to Stereo case: + + ``` + rosrun ORB_SLAM3 Stereo_Inertial PATH_TO_VOCABULARY PATH_TO_SETTINGS_FILE ONLINE_RECTIFICATION [EQUALIZATION] + ``` + +### Running RGB_D Node +For an RGB-D input from topics `/camera/rgb/image_raw` and `/camera/depth_registered/image_raw`, run node ORB_SLAM3/RGBD. You will need to provide the vocabulary file and a settings file. See the RGB-D example above. + + ``` + rosrun ORB_SLAM3 RGBD PATH_TO_VOCABULARY PATH_TO_SETTINGS_FILE + ``` + +**Running ROS example:** Download a rosbag (e.g. V1_02_medium.bag) from the EuRoC dataset (http://projects.asl.ethz.ch/datasets/doku.php?id=kmavvisualinertialdatasets). Open 3 tabs on the terminal and run the following command at each tab for a Stereo-Inertial configuration: + ``` + roscore + ``` + + ``` + rosrun ORB_SLAM3 Stereo_Inertial Vocabulary/ORBvoc.txt Examples/Stereo-Inertial/EuRoC.yaml true + ``` + + ``` + rosbag play --pause V1_02_medium.bag /cam0/image_raw:=/camera/left/image_raw /cam1/image_raw:=/camera/right/image_raw /imu0:=/imu + ``` + +Once ORB-SLAM3 has loaded the vocabulary, press space in the rosbag tab. + +**Remark:** For rosbags from TUM-VI dataset, some play issue may appear due to chunk size. One possible solution is to rebag them with the default chunk size, for example: + ``` + rosrun rosbag fastrebag.py dataset-room1_512_16.bag dataset-room1_512_16_small_chunks.bag + ``` + + + diff --git a/third_party/ORB_SLAM3/Thirdparty/DBoW2/CMakeLists.txt b/third_party/ORB_SLAM3/Thirdparty/DBoW2/CMakeLists.txt new file mode 100644 index 0000000..db38ee5 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/DBoW2/CMakeLists.txt @@ -0,0 +1,31 @@ +cmake_minimum_required(VERSION 2.8) +project(DBoW2) + +set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wall -O3 -march=native ") +set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -O3 -march=native") + +set(HDRS_DBOW2 + DBoW2/BowVector.h + DBoW2/FORB.h + DBoW2/FClass.h + DBoW2/FeatureVector.h + DBoW2/ScoringObject.h + DBoW2/TemplatedVocabulary.h) +set(SRCS_DBOW2 + DBoW2/BowVector.cpp + DBoW2/FORB.cpp + DBoW2/FeatureVector.cpp + DBoW2/ScoringObject.cpp) + +set(HDRS_DUTILS + DUtils/Random.h + DUtils/Timestamp.h) +set(SRCS_DUTILS + DUtils/Random.cpp + DUtils/Timestamp.cpp) + +find_package(OpenCV REQUIRED) + +add_library(DBoW2 SHARED ${SRCS_DBOW2} ${SRCS_DUTILS}) +target_link_libraries(DBoW2 ${OpenCV_LIBS}) + diff --git a/third_party/ORB_SLAM3/Thirdparty/DBoW2/DBoW2/BowVector.cpp b/third_party/ORB_SLAM3/Thirdparty/DBoW2/DBoW2/BowVector.cpp new file mode 100644 index 0000000..1337fa3 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/DBoW2/DBoW2/BowVector.cpp @@ -0,0 +1,130 @@ +/** + * File: BowVector.cpp + * Date: March 2011 + * Author: Dorian Galvez-Lopez + * Description: bag of words vector + * License: see the LICENSE.txt file + * + */ + +#include +#include +#include +#include +#include + +#include "BowVector.h" + +namespace DBoW2 { + +// -------------------------------------------------------------------------- + +BowVector::BowVector(void) +{ +} + +// -------------------------------------------------------------------------- + +BowVector::~BowVector(void) +{ +} + +// -------------------------------------------------------------------------- + +void BowVector::addWeight(WordId id, WordValue v) +{ + BowVector::iterator vit = this->lower_bound(id); + + if(vit != this->end() && !(this->key_comp()(id, vit->first))) + { + vit->second += v; + } + else + { + this->insert(vit, BowVector::value_type(id, v)); + } +} + +// -------------------------------------------------------------------------- + +void BowVector::addIfNotExist(WordId id, WordValue v) +{ + BowVector::iterator vit = this->lower_bound(id); + + if(vit == this->end() || (this->key_comp()(id, vit->first))) + { + this->insert(vit, BowVector::value_type(id, v)); + } +} + +// -------------------------------------------------------------------------- + +void BowVector::normalize(LNorm norm_type) +{ + double norm = 0.0; + BowVector::iterator it; + + if(norm_type == DBoW2::L1) + { + for(it = begin(); it != end(); ++it) + norm += fabs(it->second); + } + else + { + for(it = begin(); it != end(); ++it) + norm += it->second * it->second; + norm = sqrt(norm); + } + + if(norm > 0.0) + { + for(it = begin(); it != end(); ++it) + it->second /= norm; + } +} + +// -------------------------------------------------------------------------- + +std::ostream& operator<< (std::ostream &out, const BowVector &v) +{ + BowVector::const_iterator vit; + std::vector::const_iterator iit; + unsigned int i = 0; + const unsigned int N = v.size(); + for(vit = v.begin(); vit != v.end(); ++vit, ++i) + { + out << "<" << vit->first << ", " << vit->second << ">"; + + if(i < N-1) out << ", "; + } + return out; +} + +// -------------------------------------------------------------------------- + +void BowVector::saveM(const std::string &filename, size_t W) const +{ + std::fstream f(filename.c_str(), std::ios::out); + + WordId last = 0; + BowVector::const_iterator bit; + for(bit = this->begin(); bit != this->end(); ++bit) + { + for(; last < bit->first; ++last) + { + f << "0 "; + } + f << bit->second << " "; + + last = bit->first + 1; + } + for(; last < (WordId)W; ++last) + f << "0 "; + + f.close(); +} + +// -------------------------------------------------------------------------- + +} // namespace DBoW2 + diff --git a/third_party/ORB_SLAM3/Thirdparty/DBoW2/DBoW2/BowVector.h b/third_party/ORB_SLAM3/Thirdparty/DBoW2/DBoW2/BowVector.h new file mode 100644 index 0000000..a7a12a9 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/DBoW2/DBoW2/BowVector.h @@ -0,0 +1,119 @@ +/** + * File: BowVector.h + * Date: March 2011 + * Author: Dorian Galvez-Lopez + * Description: bag of words vector + * License: see the LICENSE.txt file + * + */ + +#ifndef __D_T_BOW_VECTOR__ +#define __D_T_BOW_VECTOR__ + +#include +#include +#include + +#include +#include + +namespace DBoW2 { + +/// Id of words +typedef unsigned int WordId; + +/// Value of a word +typedef double WordValue; + +/// Id of nodes in the vocabulary treee +typedef unsigned int NodeId; + +/// L-norms for normalization +enum LNorm +{ + L1, + L2 +}; + +/// Weighting type +enum WeightingType +{ + TF_IDF, + TF, + IDF, + BINARY +}; + +/// Scoring type +enum ScoringType +{ + L1_NORM, + L2_NORM, + CHI_SQUARE, + KL, + BHATTACHARYYA, + DOT_PRODUCT, +}; + +/// Vector of words to represent images +class BowVector: + public std::map +{ + friend class boost::serialization::access; + template + void serialize(Archive& ar, const int version) + { + ar & boost::serialization::base_object >(*this); + } + +public: + + /** + * Constructor + */ + BowVector(void); + + /** + * Destructor + */ + ~BowVector(void); + + /** + * Adds a value to a word value existing in the vector, or creates a new + * word with the given value + * @param id word id to look for + * @param v value to create the word with, or to add to existing word + */ + void addWeight(WordId id, WordValue v); + + /** + * Adds a word with a value to the vector only if this does not exist yet + * @param id word id to look for + * @param v value to give to the word if this does not exist + */ + void addIfNotExist(WordId id, WordValue v); + + /** + * L1-Normalizes the values in the vector + * @param norm_type norm used + */ + void normalize(LNorm norm_type); + + /** + * Prints the content of the bow vector + * @param out stream + * @param v + */ + friend std::ostream& operator<<(std::ostream &out, const BowVector &v); + + /** + * Saves the bow vector as a vector in a matlab file + * @param filename + * @param W number of words in the vocabulary + */ + void saveM(const std::string &filename, size_t W) const; +}; + +} // namespace DBoW2 + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/DBoW2/DBoW2/FClass.h b/third_party/ORB_SLAM3/Thirdparty/DBoW2/DBoW2/FClass.h new file mode 100644 index 0000000..13be53d --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/DBoW2/DBoW2/FClass.h @@ -0,0 +1,71 @@ +/** + * File: FClass.h + * Date: November 2011 + * Author: Dorian Galvez-Lopez + * Description: generic FClass to instantiate templated classes + * License: see the LICENSE.txt file + * + */ + +#ifndef __D_T_FCLASS__ +#define __D_T_FCLASS__ + +#include +#include +#include + +namespace DBoW2 { + +/// Generic class to encapsulate functions to manage descriptors. +/** + * This class must be inherited. Derived classes can be used as the + * parameter F when creating Templated structures + * (TemplatedVocabulary, TemplatedDatabase, ...) + */ +class FClass +{ + class TDescriptor; + typedef const TDescriptor *pDescriptor; + + /** + * Calculates the mean value of a set of descriptors + * @param descriptors + * @param mean mean descriptor + */ + virtual void meanValue(const std::vector &descriptors, + TDescriptor &mean) = 0; + + /** + * Calculates the distance between two descriptors + * @param a + * @param b + * @return distance + */ + static double distance(const TDescriptor &a, const TDescriptor &b); + + /** + * Returns a string version of the descriptor + * @param a descriptor + * @return string version + */ + static std::string toString(const TDescriptor &a); + + /** + * Returns a descriptor from a string + * @param a descriptor + * @param s string version + */ + static void fromString(TDescriptor &a, const std::string &s); + + /** + * Returns a mat with the descriptors in float format + * @param descriptors + * @param mat (out) NxL 32F matrix + */ + static void toMat32F(const std::vector &descriptors, + cv::Mat &mat); +}; + +} // namespace DBoW2 + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/DBoW2/DBoW2/FORB.cpp b/third_party/ORB_SLAM3/Thirdparty/DBoW2/DBoW2/FORB.cpp new file mode 100644 index 0000000..1f1990c --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/DBoW2/DBoW2/FORB.cpp @@ -0,0 +1,193 @@ +/** + * File: FORB.cpp + * Date: June 2012 + * Author: Dorian Galvez-Lopez + * Description: functions for ORB descriptors + * License: see the LICENSE.txt file + * + * Distance function has been modified + * + */ + + +#include +#include +#include +#include + +#include "FORB.h" + +using namespace std; + +namespace DBoW2 { + +// -------------------------------------------------------------------------- + +const int FORB::L=32; + +void FORB::meanValue(const std::vector &descriptors, + FORB::TDescriptor &mean) +{ + if(descriptors.empty()) + { + mean.release(); + return; + } + else if(descriptors.size() == 1) + { + mean = descriptors[0]->clone(); + } + else + { + vector sum(FORB::L * 8, 0); + + for(size_t i = 0; i < descriptors.size(); ++i) + { + const cv::Mat &d = *descriptors[i]; + const unsigned char *p = d.ptr(); + + for(int j = 0; j < d.cols; ++j, ++p) + { + if(*p & (1 << 7)) ++sum[ j*8 ]; + if(*p & (1 << 6)) ++sum[ j*8 + 1 ]; + if(*p & (1 << 5)) ++sum[ j*8 + 2 ]; + if(*p & (1 << 4)) ++sum[ j*8 + 3 ]; + if(*p & (1 << 3)) ++sum[ j*8 + 4 ]; + if(*p & (1 << 2)) ++sum[ j*8 + 5 ]; + if(*p & (1 << 1)) ++sum[ j*8 + 6 ]; + if(*p & (1)) ++sum[ j*8 + 7 ]; + } + } + + mean = cv::Mat::zeros(1, FORB::L, CV_8U); + unsigned char *p = mean.ptr(); + + const int N2 = (int)descriptors.size() / 2 + descriptors.size() % 2; + for(size_t i = 0; i < sum.size(); ++i) + { + if(sum[i] >= N2) + { + // set bit + *p |= 1 << (7 - (i % 8)); + } + + if(i % 8 == 7) ++p; + } + } +} + +// -------------------------------------------------------------------------- + +int FORB::distance(const FORB::TDescriptor &a, + const FORB::TDescriptor &b) +{ + // Bit set count operation from + // http://graphics.stanford.edu/~seander/bithacks.html#CountBitsSetParallel + + const int *pa = a.ptr(); + const int *pb = b.ptr(); + + int dist=0; + + for(int i=0; i<8; i++, pa++, pb++) + { + unsigned int v = *pa ^ *pb; + v = v - ((v >> 1) & 0x55555555); + v = (v & 0x33333333) + ((v >> 2) & 0x33333333); + dist += (((v + (v >> 4)) & 0xF0F0F0F) * 0x1010101) >> 24; + } + + return dist; +} + +// -------------------------------------------------------------------------- + +std::string FORB::toString(const FORB::TDescriptor &a) +{ + stringstream ss; + const unsigned char *p = a.ptr(); + + for(int i = 0; i < a.cols; ++i, ++p) + { + ss << (int)*p << " "; + } + + return ss.str(); +} + +// -------------------------------------------------------------------------- + +void FORB::fromString(FORB::TDescriptor &a, const std::string &s) +{ + a.create(1, FORB::L, CV_8U); + unsigned char *p = a.ptr(); + + stringstream ss(s); + for(int i = 0; i < FORB::L; ++i, ++p) + { + int n; + ss >> n; + + if(!ss.fail()) + *p = (unsigned char)n; + } + +} + +// -------------------------------------------------------------------------- + +void FORB::toMat32F(const std::vector &descriptors, + cv::Mat &mat) +{ + if(descriptors.empty()) + { + mat.release(); + return; + } + + const size_t N = descriptors.size(); + + mat.create(N, FORB::L*8, CV_32F); + float *p = mat.ptr(); + + for(size_t i = 0; i < N; ++i) + { + const int C = descriptors[i].cols; + const unsigned char *desc = descriptors[i].ptr(); + + for(int j = 0; j < C; ++j, p += 8) + { + p[0] = (desc[j] & (1 << 7) ? 1 : 0); + p[1] = (desc[j] & (1 << 6) ? 1 : 0); + p[2] = (desc[j] & (1 << 5) ? 1 : 0); + p[3] = (desc[j] & (1 << 4) ? 1 : 0); + p[4] = (desc[j] & (1 << 3) ? 1 : 0); + p[5] = (desc[j] & (1 << 2) ? 1 : 0); + p[6] = (desc[j] & (1 << 1) ? 1 : 0); + p[7] = desc[j] & (1); + } + } +} + +// -------------------------------------------------------------------------- + +void FORB::toMat8U(const std::vector &descriptors, + cv::Mat &mat) +{ + mat.create(descriptors.size(), 32, CV_8U); + + unsigned char *p = mat.ptr(); + + for(size_t i = 0; i < descriptors.size(); ++i, p += 32) + { + const unsigned char *d = descriptors[i].ptr(); + std::copy(d, d+32, p); + } + +} + +// -------------------------------------------------------------------------- + +} // namespace DBoW2 + + diff --git a/third_party/ORB_SLAM3/Thirdparty/DBoW2/DBoW2/FORB.h b/third_party/ORB_SLAM3/Thirdparty/DBoW2/DBoW2/FORB.h new file mode 100644 index 0000000..a39599f --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/DBoW2/DBoW2/FORB.h @@ -0,0 +1,79 @@ +/** + * File: FORB.h + * Date: June 2012 + * Author: Dorian Galvez-Lopez + * Description: functions for ORB descriptors + * License: see the LICENSE.txt file + * + */ + +#ifndef __D_T_F_ORB__ +#define __D_T_F_ORB__ + +#include +#include +#include + +#include "FClass.h" + +namespace DBoW2 { + +/// Functions to manipulate ORB descriptors +class FORB: protected FClass +{ +public: + + /// Descriptor type + typedef cv::Mat TDescriptor; // CV_8U + /// Pointer to a single descriptor + typedef const TDescriptor *pDescriptor; + /// Descriptor length (in bytes) + static const int L; + + /** + * Calculates the mean value of a set of descriptors + * @param descriptors + * @param mean mean descriptor + */ + static void meanValue(const std::vector &descriptors, + TDescriptor &mean); + + /** + * Calculates the distance between two descriptors + * @param a + * @param b + * @return distance + */ + static int distance(const TDescriptor &a, const TDescriptor &b); + + /** + * Returns a string version of the descriptor + * @param a descriptor + * @return string version + */ + static std::string toString(const TDescriptor &a); + + /** + * Returns a descriptor from a string + * @param a descriptor + * @param s string version + */ + static void fromString(TDescriptor &a, const std::string &s); + + /** + * Returns a mat with the descriptors in float format + * @param descriptors + * @param mat (out) NxL 32F matrix + */ + static void toMat32F(const std::vector &descriptors, + cv::Mat &mat); + + static void toMat8U(const std::vector &descriptors, + cv::Mat &mat); + +}; + +} // namespace DBoW2 + +#endif + diff --git a/third_party/ORB_SLAM3/Thirdparty/DBoW2/DBoW2/FeatureVector.cpp b/third_party/ORB_SLAM3/Thirdparty/DBoW2/DBoW2/FeatureVector.cpp new file mode 100644 index 0000000..c055a15 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/DBoW2/DBoW2/FeatureVector.cpp @@ -0,0 +1,85 @@ +/** + * File: FeatureVector.cpp + * Date: November 2011 + * Author: Dorian Galvez-Lopez + * Description: feature vector + * License: see the LICENSE.txt file + * + */ + +#include "FeatureVector.h" +#include +#include +#include + +namespace DBoW2 { + +// --------------------------------------------------------------------------- + +FeatureVector::FeatureVector(void) +{ +} + +// --------------------------------------------------------------------------- + +FeatureVector::~FeatureVector(void) +{ +} + +// --------------------------------------------------------------------------- + +void FeatureVector::addFeature(NodeId id, unsigned int i_feature) +{ + FeatureVector::iterator vit = this->lower_bound(id); + + if(vit != this->end() && vit->first == id) + { + vit->second.push_back(i_feature); + } + else + { + vit = this->insert(vit, FeatureVector::value_type(id, + std::vector() )); + vit->second.push_back(i_feature); + } +} + +// --------------------------------------------------------------------------- + +std::ostream& operator<<(std::ostream &out, + const FeatureVector &v) +{ + if(!v.empty()) + { + FeatureVector::const_iterator vit = v.begin(); + + const std::vector* f = &vit->second; + + out << "<" << vit->first << ": ["; + if(!f->empty()) out << (*f)[0]; + for(unsigned int i = 1; i < f->size(); ++i) + { + out << ", " << (*f)[i]; + } + out << "]>"; + + for(++vit; vit != v.end(); ++vit) + { + f = &vit->second; + + out << ", <" << vit->first << ": ["; + if(!f->empty()) out << (*f)[0]; + for(unsigned int i = 1; i < f->size(); ++i) + { + out << ", " << (*f)[i]; + } + out << "]>"; + } + } + + return out; +} + +// --------------------------------------------------------------------------- + +} // namespace DBoW2 diff --git a/third_party/ORB_SLAM3/Thirdparty/DBoW2/DBoW2/FeatureVector.h b/third_party/ORB_SLAM3/Thirdparty/DBoW2/DBoW2/FeatureVector.h new file mode 100644 index 0000000..426f36d --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/DBoW2/DBoW2/FeatureVector.h @@ -0,0 +1,66 @@ +/** + * File: FeatureVector.h + * Date: November 2011 + * Author: Dorian Galvez-Lopez + * Description: feature vector + * License: see the LICENSE.txt file + * + */ + +#ifndef __D_T_FEATURE_VECTOR__ +#define __D_T_FEATURE_VECTOR__ + +#include "BowVector.h" +#include +#include +#include + +#include +#include + +namespace DBoW2 { + +/// Vector of nodes with indexes of local features +class FeatureVector: + public std::map > +{ + friend class boost::serialization::access; + template + void serialize(Archive& ar, const int version) + { + ar & boost::serialization::base_object > >(*this); + } + +public: + + /** + * Constructor + */ + FeatureVector(void); + + /** + * Destructor + */ + ~FeatureVector(void); + + /** + * Adds a feature to an existing node, or adds a new node with an initial + * feature + * @param id node id to add or to modify + * @param i_feature index of feature to add to the given node + */ + void addFeature(NodeId id, unsigned int i_feature); + + /** + * Sends a string versions of the feature vector through the stream + * @param out stream + * @param v feature vector + */ + friend std::ostream& operator<<(std::ostream &out, const FeatureVector &v); + +}; + +} // namespace DBoW2 + +#endif + diff --git a/third_party/ORB_SLAM3/Thirdparty/DBoW2/DBoW2/ScoringObject.cpp b/third_party/ORB_SLAM3/Thirdparty/DBoW2/DBoW2/ScoringObject.cpp new file mode 100644 index 0000000..063a96e --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/DBoW2/DBoW2/ScoringObject.cpp @@ -0,0 +1,315 @@ +/** + * File: ScoringObject.cpp + * Date: November 2011 + * Author: Dorian Galvez-Lopez + * Description: functions to compute bow scores + * License: see the LICENSE.txt file + * + */ + +#include +#include "TemplatedVocabulary.h" +#include "BowVector.h" + +using namespace DBoW2; + +// If you change the type of WordValue, make sure you change also the +// epsilon value (this is needed by the KL method) +const double GeneralScoring::LOG_EPS = log(DBL_EPSILON); // FLT_EPSILON + +// --------------------------------------------------------------------------- +// --------------------------------------------------------------------------- + +double L1Scoring::score(const BowVector &v1, const BowVector &v2) const +{ + BowVector::const_iterator v1_it, v2_it; + const BowVector::const_iterator v1_end = v1.end(); + const BowVector::const_iterator v2_end = v2.end(); + + v1_it = v1.begin(); + v2_it = v2.begin(); + + double score = 0; + + while(v1_it != v1_end && v2_it != v2_end) + { + const WordValue& vi = v1_it->second; + const WordValue& wi = v2_it->second; + + if(v1_it->first == v2_it->first) + { + score += fabs(vi - wi) - fabs(vi) - fabs(wi); + + // move v1 and v2 forward + ++v1_it; + ++v2_it; + } + else if(v1_it->first < v2_it->first) + { + // move v1 forward + v1_it = v1.lower_bound(v2_it->first); + // v1_it = (first element >= v2_it.id) + } + else + { + // move v2 forward + v2_it = v2.lower_bound(v1_it->first); + // v2_it = (first element >= v1_it.id) + } + } + + // ||v - w||_{L1} = 2 + Sum(|v_i - w_i| - |v_i| - |w_i|) + // for all i | v_i != 0 and w_i != 0 + // (Nister, 2006) + // scaled_||v - w||_{L1} = 1 - 0.5 * ||v - w||_{L1} + score = -score/2.0; + + return score; // [0..1] +} + +// --------------------------------------------------------------------------- +// --------------------------------------------------------------------------- + +double L2Scoring::score(const BowVector &v1, const BowVector &v2) const +{ + BowVector::const_iterator v1_it, v2_it; + const BowVector::const_iterator v1_end = v1.end(); + const BowVector::const_iterator v2_end = v2.end(); + + v1_it = v1.begin(); + v2_it = v2.begin(); + + double score = 0; + + while(v1_it != v1_end && v2_it != v2_end) + { + const WordValue& vi = v1_it->second; + const WordValue& wi = v2_it->second; + + if(v1_it->first == v2_it->first) + { + score += vi * wi; + + // move v1 and v2 forward + ++v1_it; + ++v2_it; + } + else if(v1_it->first < v2_it->first) + { + // move v1 forward + v1_it = v1.lower_bound(v2_it->first); + // v1_it = (first element >= v2_it.id) + } + else + { + // move v2 forward + v2_it = v2.lower_bound(v1_it->first); + // v2_it = (first element >= v1_it.id) + } + } + + // ||v - w||_{L2} = sqrt( 2 - 2 * Sum(v_i * w_i) ) + // for all i | v_i != 0 and w_i != 0 ) + // (Nister, 2006) + if(score >= 1) // rounding errors + score = 1.0; + else + score = 1.0 - sqrt(1.0 - score); // [0..1] + + return score; +} + +// --------------------------------------------------------------------------- +// --------------------------------------------------------------------------- + +double ChiSquareScoring::score(const BowVector &v1, const BowVector &v2) + const +{ + BowVector::const_iterator v1_it, v2_it; + const BowVector::const_iterator v1_end = v1.end(); + const BowVector::const_iterator v2_end = v2.end(); + + v1_it = v1.begin(); + v2_it = v2.begin(); + + double score = 0; + + // all the items are taken into account + + while(v1_it != v1_end && v2_it != v2_end) + { + const WordValue& vi = v1_it->second; + const WordValue& wi = v2_it->second; + + if(v1_it->first == v2_it->first) + { + // (v-w)^2/(v+w) - v - w = -4 vw/(v+w) + // we move the -4 out + if(vi + wi != 0.0) score += vi * wi / (vi + wi); + + // move v1 and v2 forward + ++v1_it; + ++v2_it; + } + else if(v1_it->first < v2_it->first) + { + // move v1 forward + v1_it = v1.lower_bound(v2_it->first); + } + else + { + // move v2 forward + v2_it = v2.lower_bound(v1_it->first); + } + } + + // this takes the -4 into account + score = 2. * score; // [0..1] + + return score; +} + +// --------------------------------------------------------------------------- +// --------------------------------------------------------------------------- + +double KLScoring::score(const BowVector &v1, const BowVector &v2) const +{ + BowVector::const_iterator v1_it, v2_it; + const BowVector::const_iterator v1_end = v1.end(); + const BowVector::const_iterator v2_end = v2.end(); + + v1_it = v1.begin(); + v2_it = v2.begin(); + + double score = 0; + + // all the items or v are taken into account + + while(v1_it != v1_end && v2_it != v2_end) + { + const WordValue& vi = v1_it->second; + const WordValue& wi = v2_it->second; + + if(v1_it->first == v2_it->first) + { + if(vi != 0 && wi != 0) score += vi * log(vi/wi); + + // move v1 and v2 forward + ++v1_it; + ++v2_it; + } + else if(v1_it->first < v2_it->first) + { + // move v1 forward + score += vi * (log(vi) - LOG_EPS); + ++v1_it; + } + else + { + // move v2_it forward, do not add any score + v2_it = v2.lower_bound(v1_it->first); + // v2_it = (first element >= v1_it.id) + } + } + + // sum rest of items of v + for(; v1_it != v1_end; ++v1_it) + if(v1_it->second != 0) + score += v1_it->second * (log(v1_it->second) - LOG_EPS); + + return score; // cannot be scaled +} + +// --------------------------------------------------------------------------- +// --------------------------------------------------------------------------- + +double BhattacharyyaScoring::score(const BowVector &v1, + const BowVector &v2) const +{ + BowVector::const_iterator v1_it, v2_it; + const BowVector::const_iterator v1_end = v1.end(); + const BowVector::const_iterator v2_end = v2.end(); + + v1_it = v1.begin(); + v2_it = v2.begin(); + + double score = 0; + + while(v1_it != v1_end && v2_it != v2_end) + { + const WordValue& vi = v1_it->second; + const WordValue& wi = v2_it->second; + + if(v1_it->first == v2_it->first) + { + score += sqrt(vi * wi); + + // move v1 and v2 forward + ++v1_it; + ++v2_it; + } + else if(v1_it->first < v2_it->first) + { + // move v1 forward + v1_it = v1.lower_bound(v2_it->first); + // v1_it = (first element >= v2_it.id) + } + else + { + // move v2 forward + v2_it = v2.lower_bound(v1_it->first); + // v2_it = (first element >= v1_it.id) + } + } + + return score; // already scaled +} + +// --------------------------------------------------------------------------- +// --------------------------------------------------------------------------- + +double DotProductScoring::score(const BowVector &v1, + const BowVector &v2) const +{ + BowVector::const_iterator v1_it, v2_it; + const BowVector::const_iterator v1_end = v1.end(); + const BowVector::const_iterator v2_end = v2.end(); + + v1_it = v1.begin(); + v2_it = v2.begin(); + + double score = 0; + + while(v1_it != v1_end && v2_it != v2_end) + { + const WordValue& vi = v1_it->second; + const WordValue& wi = v2_it->second; + + if(v1_it->first == v2_it->first) + { + score += vi * wi; + + // move v1 and v2 forward + ++v1_it; + ++v2_it; + } + else if(v1_it->first < v2_it->first) + { + // move v1 forward + v1_it = v1.lower_bound(v2_it->first); + // v1_it = (first element >= v2_it.id) + } + else + { + // move v2 forward + v2_it = v2.lower_bound(v1_it->first); + // v2_it = (first element >= v1_it.id) + } + } + + return score; // cannot scale +} + +// --------------------------------------------------------------------------- +// --------------------------------------------------------------------------- + diff --git a/third_party/ORB_SLAM3/Thirdparty/DBoW2/DBoW2/ScoringObject.h b/third_party/ORB_SLAM3/Thirdparty/DBoW2/DBoW2/ScoringObject.h new file mode 100644 index 0000000..8d5b821 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/DBoW2/DBoW2/ScoringObject.h @@ -0,0 +1,96 @@ +/** + * File: ScoringObject.h + * Date: November 2011 + * Author: Dorian Galvez-Lopez + * Description: functions to compute bow scores + * License: see the LICENSE.txt file + * + */ + +#ifndef __D_T_SCORING_OBJECT__ +#define __D_T_SCORING_OBJECT__ + +#include "BowVector.h" + +namespace DBoW2 { + +/// Base class of scoring functions +class GeneralScoring +{ +public: + /** + * Computes the score between two vectors. Vectors must be sorted and + * normalized if necessary + * @param v (in/out) + * @param w (in/out) + * @return score + */ + virtual double score(const BowVector &v, const BowVector &w) const = 0; + + /** + * Returns whether a vector must be normalized before scoring according + * to the scoring scheme + * @param norm norm to use + * @return true iff must normalize + */ + virtual bool mustNormalize(LNorm &norm) const = 0; + + /// Log of epsilon + static const double LOG_EPS; + // If you change the type of WordValue, make sure you change also the + // epsilon value (this is needed by the KL method) + + virtual ~GeneralScoring() {} //!< Required for virtual base classes + +}; + +/** + * Macro for defining Scoring classes + * @param NAME name of class + * @param MUSTNORMALIZE if vectors must be normalized to compute the score + * @param NORM type of norm to use when MUSTNORMALIZE + */ +#define __SCORING_CLASS(NAME, MUSTNORMALIZE, NORM) \ + NAME: public GeneralScoring \ + { public: \ + /** \ + * Computes score between two vectors \ + * @param v \ + * @param w \ + * @return score between v and w \ + */ \ + virtual double score(const BowVector &v, const BowVector &w) const; \ + \ + /** \ + * Says if a vector must be normalized according to the scoring function \ + * @param norm (out) if true, norm to use + * @return true iff vectors must be normalized \ + */ \ + virtual inline bool mustNormalize(LNorm &norm) const \ + { norm = NORM; return MUSTNORMALIZE; } \ + } + +/// L1 Scoring object +class __SCORING_CLASS(L1Scoring, true, L1); + +/// L2 Scoring object +class __SCORING_CLASS(L2Scoring, true, L2); + +/// Chi square Scoring object +class __SCORING_CLASS(ChiSquareScoring, true, L1); + +/// KL divergence Scoring object +class __SCORING_CLASS(KLScoring, true, L1); + +/// Bhattacharyya Scoring object +class __SCORING_CLASS(BhattacharyyaScoring, true, L1); + +/// Dot product Scoring object +class __SCORING_CLASS(DotProductScoring, false, L1); + +#undef __SCORING_CLASS + +} // namespace DBoW2 + +#endif + diff --git a/third_party/ORB_SLAM3/Thirdparty/DBoW2/DBoW2/TemplatedVocabulary.h b/third_party/ORB_SLAM3/Thirdparty/DBoW2/DBoW2/TemplatedVocabulary.h new file mode 100644 index 0000000..0195934 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/DBoW2/DBoW2/TemplatedVocabulary.h @@ -0,0 +1,1665 @@ +/** + * This is a modified version of TemplatedVocabulary.h from DBoW2 (see below). + * Added functions: Save and Load from text files without using cv::FileStorage. + * Date: August 2015 + * Raúl Mur-Artal + */ + +/** + * File: TemplatedVocabulary.h + * Date: February 2011 + * Author: Dorian Galvez-Lopez + * Description: templated vocabulary + * License: see the LICENSE.txt file + * + */ + +#ifndef __D_T_TEMPLATED_VOCABULARY__ +#define __D_T_TEMPLATED_VOCABULARY__ + +#include + +#include +#include +#include +#include +#include +#include +#include + +#include "FeatureVector.h" +#include "BowVector.h" +#include "ScoringObject.h" + +#include "../DUtils/Random.h" + +using namespace std; + +namespace DBoW2 { + +/// @param TDescriptor class of descriptor +/// @param F class of descriptor functions +template +/// Generic Vocabulary +class TemplatedVocabulary +{ +public: + + /** + * Initiates an empty vocabulary + * @param k branching factor + * @param L depth levels + * @param weighting weighting type + * @param scoring scoring type + */ + TemplatedVocabulary(int k = 10, int L = 5, + WeightingType weighting = TF_IDF, ScoringType scoring = L1_NORM); + + /** + * Creates the vocabulary by loading a file + * @param filename + */ + TemplatedVocabulary(const std::string &filename); + + /** + * Creates the vocabulary by loading a file + * @param filename + */ + TemplatedVocabulary(const char *filename); + + /** + * Copy constructor + * @param voc + */ + TemplatedVocabulary(const TemplatedVocabulary &voc); + + /** + * Destructor + */ + virtual ~TemplatedVocabulary(); + + /** + * Assigns the given vocabulary to this by copying its data and removing + * all the data contained by this vocabulary before + * @param voc + * @return reference to this vocabulary + */ + TemplatedVocabulary& operator=( + const TemplatedVocabulary &voc); + + /** + * Creates a vocabulary from the training features with the already + * defined parameters + * @param training_features + */ + virtual void create + (const std::vector > &training_features); + + /** + * Creates a vocabulary from the training features, setting the branching + * factor and the depth levels of the tree + * @param training_features + * @param k branching factor + * @param L depth levels + */ + virtual void create + (const std::vector > &training_features, + int k, int L); + + /** + * Creates a vocabulary from the training features, setting the branching + * factor nad the depth levels of the tree, and the weighting and scoring + * schemes + */ + virtual void create + (const std::vector > &training_features, + int k, int L, WeightingType weighting, ScoringType scoring); + + /** + * Returns the number of words in the vocabulary + * @return number of words + */ + virtual inline unsigned int size() const; + + /** + * Returns whether the vocabulary is empty (i.e. it has not been trained) + * @return true iff the vocabulary is empty + */ + virtual inline bool empty() const; + + /** + * Transforms a set of descriptores into a bow vector + * @param features + * @param v (out) bow vector of weighted words + */ + virtual void transform(const std::vector& features, BowVector &v) + const; + + /** + * Transform a set of descriptors into a bow vector and a feature vector + * @param features + * @param v (out) bow vector + * @param fv (out) feature vector of nodes and feature indexes + * @param levelsup levels to go up the vocabulary tree to get the node index + */ + virtual void transform(const std::vector& features, + BowVector &v, FeatureVector &fv, int levelsup) const; + + /** + * Transforms a single feature into a word (without weight) + * @param feature + * @return word id + */ + virtual WordId transform(const TDescriptor& feature) const; + + /** + * Returns the score of two vectors + * @param a vector + * @param b vector + * @return score between vectors + * @note the vectors must be already sorted and normalized if necessary + */ + inline double score(const BowVector &a, const BowVector &b) const; + + /** + * Returns the id of the node that is "levelsup" levels from the word given + * @param wid word id + * @param levelsup 0..L + * @return node id. if levelsup is 0, returns the node id associated to the + * word id + */ + virtual NodeId getParentNode(WordId wid, int levelsup) const; + + /** + * Returns the ids of all the words that are under the given node id, + * by traversing any of the branches that goes down from the node + * @param nid starting node id + * @param words ids of words + */ + void getWordsFromNode(NodeId nid, std::vector &words) const; + + /** + * Returns the branching factor of the tree (k) + * @return k + */ + inline int getBranchingFactor() const { return m_k; } + + /** + * Returns the depth levels of the tree (L) + * @return L + */ + inline int getDepthLevels() const { return m_L; } + + /** + * Returns the real depth levels of the tree on average + * @return average of depth levels of leaves + */ + float getEffectiveLevels() const; + + /** + * Returns the descriptor of a word + * @param wid word id + * @return descriptor + */ + virtual inline TDescriptor getWord(WordId wid) const; + + /** + * Returns the weight of a word + * @param wid word id + * @return weight + */ + virtual inline WordValue getWordWeight(WordId wid) const; + + /** + * Returns the weighting method + * @return weighting method + */ + inline WeightingType getWeightingType() const { return m_weighting; } + + /** + * Returns the scoring method + * @return scoring method + */ + inline ScoringType getScoringType() const { return m_scoring; } + + /** + * Changes the weighting method + * @param type new weighting type + */ + inline void setWeightingType(WeightingType type); + + /** + * Changes the scoring method + * @param type new scoring type + */ + void setScoringType(ScoringType type); + + /** + * Loads the vocabulary from a text file + * @param filename + */ + bool loadFromTextFile(const std::string &filename); + + /** + * Saves the vocabulary into a text file + * @param filename + */ + void saveToTextFile(const std::string &filename) const; + + /** + * Saves the vocabulary into a file + * @param filename + */ + void save(const std::string &filename) const; + + /** + * Loads the vocabulary from a file + * @param filename + */ + void load(const std::string &filename); + + /** + * Saves the vocabulary to a file storage structure + * @param fn node in file storage + */ + virtual void save(cv::FileStorage &fs, + const std::string &name = "vocabulary") const; + + /** + * Loads the vocabulary from a file storage node + * @param fn first node + * @param subname name of the child node of fn where the tree is stored. + * If not given, the fn node is used instead + */ + virtual void load(const cv::FileStorage &fs, + const std::string &name = "vocabulary"); + + /** + * Stops those words whose weight is below minWeight. + * Words are stopped by setting their weight to 0. There are not returned + * later when transforming image features into vectors. + * Note that when using IDF or TF_IDF, the weight is the idf part, which + * is equivalent to -log(f), where f is the frequency of the word + * (f = Ni/N, Ni: number of training images where the word is present, + * N: number of training images). + * Note that the old weight is forgotten, and subsequent calls to this + * function with a lower minWeight have no effect. + * @return number of words stopped now + */ + virtual int stopWords(double minWeight); + +protected: + + /// Pointer to descriptor + typedef const TDescriptor *pDescriptor; + + /// Tree node + struct Node + { + /// Node id + NodeId id; + /// Weight if the node is a word + WordValue weight; + /// Children + vector children; + /// Parent node (undefined in case of root) + NodeId parent; + /// Node descriptor + TDescriptor descriptor; + + /// Word id if the node is a word + WordId word_id; + + /** + * Empty constructor + */ + Node(): id(0), weight(0), parent(0), word_id(0){} + + /** + * Constructor + * @param _id node id + */ + Node(NodeId _id): id(_id), weight(0), parent(0), word_id(0){} + + /** + * Returns whether the node is a leaf node + * @return true iff the node is a leaf + */ + inline bool isLeaf() const { return children.empty(); } + }; + +protected: + + /** + * Creates an instance of the scoring object accoring to m_scoring + */ + void createScoringObject(); + + /** + * Returns a set of pointers to descriptores + * @param training_features all the features + * @param features (out) pointers to the training features + */ + void getFeatures( + const vector > &training_features, + vector &features) const; + + /** + * Returns the word id associated to a feature + * @param feature + * @param id (out) word id + * @param weight (out) word weight + * @param nid (out) if given, id of the node "levelsup" levels up + * @param levelsup + */ + virtual void transform(const TDescriptor &feature, + WordId &id, WordValue &weight, NodeId* nid = NULL, int levelsup = 0) const; + + /** + * Returns the word id associated to a feature + * @param feature + * @param id (out) word id + */ + virtual void transform(const TDescriptor &feature, WordId &id) const; + + /** + * Creates a level in the tree, under the parent, by running kmeans with + * a descriptor set, and recursively creates the subsequent levels too + * @param parent_id id of parent node + * @param descriptors descriptors to run the kmeans on + * @param current_level current level in the tree + */ + void HKmeansStep(NodeId parent_id, const vector &descriptors, + int current_level); + + /** + * Creates k clusters from the given descriptors with some seeding algorithm. + * @note In this class, kmeans++ is used, but this function should be + * overriden by inherited classes. + */ + virtual void initiateClusters(const vector &descriptors, + vector &clusters) const; + + /** + * Creates k clusters from the given descriptor sets by running the + * initial step of kmeans++ + * @param descriptors + * @param clusters resulting clusters + */ + void initiateClustersKMpp(const vector &descriptors, + vector &clusters) const; + + /** + * Create the words of the vocabulary once the tree has been built + */ + void createWords(); + + /** + * Sets the weights of the nodes of tree according to the given features. + * Before calling this function, the nodes and the words must be already + * created (by calling HKmeansStep and createWords) + * @param features + */ + void setNodeWeights(const vector > &features); + +protected: + + /// Branching factor + int m_k; + + /// Depth levels + int m_L; + + /// Weighting method + WeightingType m_weighting; + + /// Scoring method + ScoringType m_scoring; + + /// Object for computing scores + GeneralScoring* m_scoring_object; + + /// Tree nodes + std::vector m_nodes; + + /// Words of the vocabulary (tree leaves) + /// this condition holds: m_words[wid]->word_id == wid + std::vector m_words; + +}; + +// -------------------------------------------------------------------------- + +template +TemplatedVocabulary::TemplatedVocabulary + (int k, int L, WeightingType weighting, ScoringType scoring) + : m_k(k), m_L(L), m_weighting(weighting), m_scoring(scoring), + m_scoring_object(NULL) +{ + createScoringObject(); +} + +// -------------------------------------------------------------------------- + +template +TemplatedVocabulary::TemplatedVocabulary + (const std::string &filename): m_scoring_object(NULL) +{ + load(filename); +} + +// -------------------------------------------------------------------------- + +template +TemplatedVocabulary::TemplatedVocabulary + (const char *filename): m_scoring_object(NULL) +{ + load(filename); +} + +// -------------------------------------------------------------------------- + +template +void TemplatedVocabulary::createScoringObject() +{ + delete m_scoring_object; + m_scoring_object = NULL; + + switch(m_scoring) + { + case L1_NORM: + m_scoring_object = new L1Scoring; + break; + + case L2_NORM: + m_scoring_object = new L2Scoring; + break; + + case CHI_SQUARE: + m_scoring_object = new ChiSquareScoring; + break; + + case KL: + m_scoring_object = new KLScoring; + break; + + case BHATTACHARYYA: + m_scoring_object = new BhattacharyyaScoring; + break; + + case DOT_PRODUCT: + m_scoring_object = new DotProductScoring; + break; + + } +} + +// -------------------------------------------------------------------------- + +template +void TemplatedVocabulary::setScoringType(ScoringType type) +{ + m_scoring = type; + createScoringObject(); +} + +// -------------------------------------------------------------------------- + +template +void TemplatedVocabulary::setWeightingType(WeightingType type) +{ + this->m_weighting = type; +} + +// -------------------------------------------------------------------------- + +template +TemplatedVocabulary::TemplatedVocabulary( + const TemplatedVocabulary &voc) + : m_scoring_object(NULL) +{ + *this = voc; +} + +// -------------------------------------------------------------------------- + +template +TemplatedVocabulary::~TemplatedVocabulary() +{ + delete m_scoring_object; +} + +// -------------------------------------------------------------------------- + +template +TemplatedVocabulary& +TemplatedVocabulary::operator= + (const TemplatedVocabulary &voc) +{ + this->m_k = voc.m_k; + this->m_L = voc.m_L; + this->m_scoring = voc.m_scoring; + this->m_weighting = voc.m_weighting; + + this->createScoringObject(); + + this->m_nodes.clear(); + this->m_words.clear(); + + this->m_nodes = voc.m_nodes; + this->createWords(); + + return *this; +} + +// -------------------------------------------------------------------------- + +template +void TemplatedVocabulary::create( + const std::vector > &training_features) +{ + m_nodes.clear(); + m_words.clear(); + + // expected_nodes = Sum_{i=0..L} ( k^i ) + int expected_nodes = + (int)((pow((double)m_k, (double)m_L + 1) - 1)/(m_k - 1)); + + m_nodes.reserve(expected_nodes); // avoid allocations when creating the tree + + + vector features; + getFeatures(training_features, features); + + + // create root + m_nodes.push_back(Node(0)); // root + + // create the tree + HKmeansStep(0, features, 1); + + // create the words + createWords(); + + // and set the weight of each node of the tree + setNodeWeights(training_features); + +} + +// -------------------------------------------------------------------------- + +template +void TemplatedVocabulary::create( + const std::vector > &training_features, + int k, int L) +{ + m_k = k; + m_L = L; + + create(training_features); +} + +// -------------------------------------------------------------------------- + +template +void TemplatedVocabulary::create( + const std::vector > &training_features, + int k, int L, WeightingType weighting, ScoringType scoring) +{ + m_k = k; + m_L = L; + m_weighting = weighting; + m_scoring = scoring; + createScoringObject(); + + create(training_features); +} + +// -------------------------------------------------------------------------- + +template +void TemplatedVocabulary::getFeatures( + const vector > &training_features, + vector &features) const +{ + features.resize(0); + + typename vector >::const_iterator vvit; + typename vector::const_iterator vit; + for(vvit = training_features.begin(); vvit != training_features.end(); ++vvit) + { + features.reserve(features.size() + vvit->size()); + for(vit = vvit->begin(); vit != vvit->end(); ++vit) + { + features.push_back(&(*vit)); + } + } +} + +// -------------------------------------------------------------------------- + +template +void TemplatedVocabulary::HKmeansStep(NodeId parent_id, + const vector &descriptors, int current_level) +{ + if(descriptors.empty()) return; + + // features associated to each cluster + vector clusters; + vector > groups; // groups[i] = [j1, j2, ...] + // j1, j2, ... indices of descriptors associated to cluster i + + clusters.reserve(m_k); + groups.reserve(m_k); + + //const int msizes[] = { m_k, descriptors.size() }; + //cv::SparseMat assoc(2, msizes, CV_8U); + //cv::SparseMat last_assoc(2, msizes, CV_8U); + //// assoc.row(cluster_idx).col(descriptor_idx) = 1 iif associated + + if((int)descriptors.size() <= m_k) + { + // trivial case: one cluster per feature + groups.resize(descriptors.size()); + + for(unsigned int i = 0; i < descriptors.size(); i++) + { + groups[i].push_back(i); + clusters.push_back(*descriptors[i]); + } + } + else + { + // select clusters and groups with kmeans + + bool first_time = true; + bool goon = true; + + // to check if clusters move after iterations + vector last_association, current_association; + + while(goon) + { + // 1. Calculate clusters + + if(first_time) + { + // random sample + initiateClusters(descriptors, clusters); + } + else + { + // calculate cluster centres + + for(unsigned int c = 0; c < clusters.size(); ++c) + { + vector cluster_descriptors; + cluster_descriptors.reserve(groups[c].size()); + + /* + for(unsigned int d = 0; d < descriptors.size(); ++d) + { + if( assoc.find(c, d) ) + { + cluster_descriptors.push_back(descriptors[d]); + } + } + */ + + vector::const_iterator vit; + for(vit = groups[c].begin(); vit != groups[c].end(); ++vit) + { + cluster_descriptors.push_back(descriptors[*vit]); + } + + + F::meanValue(cluster_descriptors, clusters[c]); + } + + } // if(!first_time) + + // 2. Associate features with clusters + + // calculate distances to cluster centers + groups.clear(); + groups.resize(clusters.size(), vector()); + current_association.resize(descriptors.size()); + + //assoc.clear(); + + typename vector::const_iterator fit; + //unsigned int d = 0; + for(fit = descriptors.begin(); fit != descriptors.end(); ++fit)//, ++d) + { + double best_dist = F::distance(*(*fit), clusters[0]); + unsigned int icluster = 0; + + for(unsigned int c = 1; c < clusters.size(); ++c) + { + double dist = F::distance(*(*fit), clusters[c]); + if(dist < best_dist) + { + best_dist = dist; + icluster = c; + } + } + + //assoc.ref(icluster, d) = 1; + + groups[icluster].push_back(fit - descriptors.begin()); + current_association[ fit - descriptors.begin() ] = icluster; + } + + // kmeans++ ensures all the clusters has any feature associated with them + + // 3. check convergence + if(first_time) + { + first_time = false; + } + else + { + //goon = !eqUChar(last_assoc, assoc); + + goon = false; + for(unsigned int i = 0; i < current_association.size(); i++) + { + if(current_association[i] != last_association[i]){ + goon = true; + break; + } + } + } + + if(goon) + { + // copy last feature-cluster association + last_association = current_association; + //last_assoc = assoc.clone(); + } + + } // while(goon) + + } // if must run kmeans + + // create nodes + for(unsigned int i = 0; i < clusters.size(); ++i) + { + NodeId id = m_nodes.size(); + m_nodes.push_back(Node(id)); + m_nodes.back().descriptor = clusters[i]; + m_nodes.back().parent = parent_id; + m_nodes[parent_id].children.push_back(id); + } + + // go on with the next level + if(current_level < m_L) + { + // iterate again with the resulting clusters + const vector &children_ids = m_nodes[parent_id].children; + for(unsigned int i = 0; i < clusters.size(); ++i) + { + NodeId id = children_ids[i]; + + vector child_features; + child_features.reserve(groups[i].size()); + + vector::const_iterator vit; + for(vit = groups[i].begin(); vit != groups[i].end(); ++vit) + { + child_features.push_back(descriptors[*vit]); + } + + if(child_features.size() > 1) + { + HKmeansStep(id, child_features, current_level + 1); + } + } + } +} + +// -------------------------------------------------------------------------- + +template +void TemplatedVocabulary::initiateClusters + (const vector &descriptors, vector &clusters) const +{ + initiateClustersKMpp(descriptors, clusters); +} + +// -------------------------------------------------------------------------- + +template +void TemplatedVocabulary::initiateClustersKMpp( + const vector &pfeatures, vector &clusters) const +{ + // Implements kmeans++ seeding algorithm + // Algorithm: + // 1. Choose one center uniformly at random from among the data points. + // 2. For each data point x, compute D(x), the distance between x and the nearest + // center that has already been chosen. + // 3. Add one new data point as a center. Each point x is chosen with probability + // proportional to D(x)^2. + // 4. Repeat Steps 2 and 3 until k centers have been chosen. + // 5. Now that the initial centers have been chosen, proceed using standard k-means + // clustering. + + DUtils::Random::SeedRandOnce(); + + clusters.resize(0); + clusters.reserve(m_k); + vector min_dists(pfeatures.size(), std::numeric_limits::max()); + + // 1. + + int ifeature = DUtils::Random::RandomInt(0, pfeatures.size()-1); + + // create first cluster + clusters.push_back(*pfeatures[ifeature]); + + // compute the initial distances + typename vector::const_iterator fit; + vector::iterator dit; + dit = min_dists.begin(); + for(fit = pfeatures.begin(); fit != pfeatures.end(); ++fit, ++dit) + { + *dit = F::distance(*(*fit), clusters.back()); + } + + while((int)clusters.size() < m_k) + { + // 2. + dit = min_dists.begin(); + for(fit = pfeatures.begin(); fit != pfeatures.end(); ++fit, ++dit) + { + if(*dit > 0) + { + double dist = F::distance(*(*fit), clusters.back()); + if(dist < *dit) *dit = dist; + } + } + + // 3. + double dist_sum = std::accumulate(min_dists.begin(), min_dists.end(), 0.0); + + if(dist_sum > 0) + { + double cut_d; + do + { + cut_d = DUtils::Random::RandomValue(0, dist_sum); + } while(cut_d == 0.0); + + double d_up_now = 0; + for(dit = min_dists.begin(); dit != min_dists.end(); ++dit) + { + d_up_now += *dit; + if(d_up_now >= cut_d) break; + } + + if(dit == min_dists.end()) + ifeature = pfeatures.size()-1; + else + ifeature = dit - min_dists.begin(); + + clusters.push_back(*pfeatures[ifeature]); + + } // if dist_sum > 0 + else + break; + + } // while(used_clusters < m_k) + +} + +// -------------------------------------------------------------------------- + +template +void TemplatedVocabulary::createWords() +{ + m_words.resize(0); + + if(!m_nodes.empty()) + { + m_words.reserve( (int)pow((double)m_k, (double)m_L) ); + + typename vector::iterator nit; + + nit = m_nodes.begin(); // ignore root + for(++nit; nit != m_nodes.end(); ++nit) + { + if(nit->isLeaf()) + { + nit->word_id = m_words.size(); + m_words.push_back( &(*nit) ); + } + } + } +} + +// -------------------------------------------------------------------------- + +template +void TemplatedVocabulary::setNodeWeights + (const vector > &training_features) +{ + const unsigned int NWords = m_words.size(); + const unsigned int NDocs = training_features.size(); + + if(m_weighting == TF || m_weighting == BINARY) + { + // idf part must be 1 always + for(unsigned int i = 0; i < NWords; i++) + m_words[i]->weight = 1; + } + else if(m_weighting == IDF || m_weighting == TF_IDF) + { + // IDF and TF-IDF: we calculte the idf path now + + // Note: this actually calculates the idf part of the tf-idf score. + // The complete tf-idf score is calculated in ::transform + + vector Ni(NWords, 0); + vector counted(NWords, false); + + typename vector >::const_iterator mit; + typename vector::const_iterator fit; + + for(mit = training_features.begin(); mit != training_features.end(); ++mit) + { + fill(counted.begin(), counted.end(), false); + + for(fit = mit->begin(); fit < mit->end(); ++fit) + { + WordId word_id; + transform(*fit, word_id); + + if(!counted[word_id]) + { + Ni[word_id]++; + counted[word_id] = true; + } + } + } + + // set ln(N/Ni) + for(unsigned int i = 0; i < NWords; i++) + { + if(Ni[i] > 0) + { + m_words[i]->weight = log((double)NDocs / (double)Ni[i]); + }// else // This cannot occur if using kmeans++ + } + + } + +} + +// -------------------------------------------------------------------------- + +template +inline unsigned int TemplatedVocabulary::size() const +{ + return m_words.size(); +} + +// -------------------------------------------------------------------------- + +template +inline bool TemplatedVocabulary::empty() const +{ + return m_words.empty(); +} + +// -------------------------------------------------------------------------- + +template +float TemplatedVocabulary::getEffectiveLevels() const +{ + long sum = 0; + typename std::vector::const_iterator wit; + for(wit = m_words.begin(); wit != m_words.end(); ++wit) + { + const Node *p = *wit; + + for(; p->id != 0; sum++) p = &m_nodes[p->parent]; + } + + return (float)((double)sum / (double)m_words.size()); +} + +// -------------------------------------------------------------------------- + +template +TDescriptor TemplatedVocabulary::getWord(WordId wid) const +{ + return m_words[wid]->descriptor; +} + +// -------------------------------------------------------------------------- + +template +WordValue TemplatedVocabulary::getWordWeight(WordId wid) const +{ + return m_words[wid]->weight; +} + +// -------------------------------------------------------------------------- + +template +WordId TemplatedVocabulary::transform + (const TDescriptor& feature) const +{ + if(empty()) + { + return 0; + } + + WordId wid; + transform(feature, wid); + return wid; +} + +// -------------------------------------------------------------------------- + +template +void TemplatedVocabulary::transform( + const std::vector& features, BowVector &v) const +{ + v.clear(); + + if(empty()) + { + return; + } + + // normalize + LNorm norm; + bool must = m_scoring_object->mustNormalize(norm); + + typename vector::const_iterator fit; + + if(m_weighting == TF || m_weighting == TF_IDF) + { + for(fit = features.begin(); fit < features.end(); ++fit) + { + WordId id; + WordValue w; + // w is the idf value if TF_IDF, 1 if TF + + transform(*fit, id, w); + + // not stopped + if(w > 0) v.addWeight(id, w); + } + + if(!v.empty() && !must) + { + // unnecessary when normalizing + const double nd = v.size(); + for(BowVector::iterator vit = v.begin(); vit != v.end(); vit++) + vit->second /= nd; + } + + } + else // IDF || BINARY + { + for(fit = features.begin(); fit < features.end(); ++fit) + { + WordId id; + WordValue w; + // w is idf if IDF, or 1 if BINARY + + transform(*fit, id, w); + + // not stopped + if(w > 0) v.addIfNotExist(id, w); + + } // if add_features + } // if m_weighting == ... + + if(must) v.normalize(norm); +} + +// -------------------------------------------------------------------------- + +template +void TemplatedVocabulary::transform( + const std::vector& features, + BowVector &v, FeatureVector &fv, int levelsup) const +{ + v.clear(); + fv.clear(); + + if(empty()) // safe for subclasses + { + return; + } + + // normalize + LNorm norm; + bool must = m_scoring_object->mustNormalize(norm); + + typename vector::const_iterator fit; + + if(m_weighting == TF || m_weighting == TF_IDF) + { + unsigned int i_feature = 0; + for(fit = features.begin(); fit < features.end(); ++fit, ++i_feature) + { + WordId id; + NodeId nid; + WordValue w; + // w is the idf value if TF_IDF, 1 if TF + + transform(*fit, id, w, &nid, levelsup); + + if(w > 0) // not stopped + { + v.addWeight(id, w); + fv.addFeature(nid, i_feature); + } + } + + if(!v.empty() && !must) + { + // unnecessary when normalizing + const double nd = v.size(); + for(BowVector::iterator vit = v.begin(); vit != v.end(); vit++) + vit->second /= nd; + } + + } + else // IDF || BINARY + { + unsigned int i_feature = 0; + for(fit = features.begin(); fit < features.end(); ++fit, ++i_feature) + { + WordId id; + NodeId nid; + WordValue w; + // w is idf if IDF, or 1 if BINARY + + transform(*fit, id, w, &nid, levelsup); + + if(w > 0) // not stopped + { + v.addIfNotExist(id, w); + fv.addFeature(nid, i_feature); + } + } + } // if m_weighting == ... + + if(must) v.normalize(norm); +} + +// -------------------------------------------------------------------------- + +template +inline double TemplatedVocabulary::score + (const BowVector &v1, const BowVector &v2) const +{ + return m_scoring_object->score(v1, v2); +} + +// -------------------------------------------------------------------------- + +template +void TemplatedVocabulary::transform + (const TDescriptor &feature, WordId &id) const +{ + WordValue weight; + transform(feature, id, weight); +} + +// -------------------------------------------------------------------------- + +template +void TemplatedVocabulary::transform(const TDescriptor &feature, + WordId &word_id, WordValue &weight, NodeId *nid, int levelsup) const +{ + // propagate the feature down the tree + vector nodes; + typename vector::const_iterator nit; + + // level at which the node must be stored in nid, if given + const int nid_level = m_L - levelsup; + if(nid_level <= 0 && nid != NULL) *nid = 0; // root + + NodeId final_id = 0; // root + int current_level = 0; + + do + { + ++current_level; + nodes = m_nodes[final_id].children; + final_id = nodes[0]; + + double best_d = F::distance(feature, m_nodes[final_id].descriptor); + + for(nit = nodes.begin() + 1; nit != nodes.end(); ++nit) + { + NodeId id = *nit; + double d = F::distance(feature, m_nodes[id].descriptor); + if(d < best_d) + { + best_d = d; + final_id = id; + } + } + + if(nid != NULL && current_level == nid_level) + *nid = final_id; + + } while( !m_nodes[final_id].isLeaf() ); + + // turn node id into word id + word_id = m_nodes[final_id].word_id; + weight = m_nodes[final_id].weight; +} + +// -------------------------------------------------------------------------- + +template +NodeId TemplatedVocabulary::getParentNode + (WordId wid, int levelsup) const +{ + NodeId ret = m_words[wid]->id; // node id + while(levelsup > 0 && ret != 0) // ret == 0 --> root + { + --levelsup; + ret = m_nodes[ret].parent; + } + return ret; +} + +// -------------------------------------------------------------------------- + +template +void TemplatedVocabulary::getWordsFromNode + (NodeId nid, std::vector &words) const +{ + words.clear(); + + if(m_nodes[nid].isLeaf()) + { + words.push_back(m_nodes[nid].word_id); + } + else + { + words.reserve(m_k); // ^1, ^2, ... + + vector parents; + parents.push_back(nid); + + while(!parents.empty()) + { + NodeId parentid = parents.back(); + parents.pop_back(); + + const vector &child_ids = m_nodes[parentid].children; + vector::const_iterator cit; + + for(cit = child_ids.begin(); cit != child_ids.end(); ++cit) + { + const Node &child_node = m_nodes[*cit]; + + if(child_node.isLeaf()) + words.push_back(child_node.word_id); + else + parents.push_back(*cit); + + } // for each child + } // while !parents.empty + } +} + +// -------------------------------------------------------------------------- + +template +int TemplatedVocabulary::stopWords(double minWeight) +{ + int c = 0; + typename vector::iterator wit; + for(wit = m_words.begin(); wit != m_words.end(); ++wit) + { + if((*wit)->weight < minWeight) + { + ++c; + (*wit)->weight = 0; + } + } + return c; +} + +// -------------------------------------------------------------------------- + +template +bool TemplatedVocabulary::loadFromTextFile(const std::string &filename) +{ + ifstream f; + f.open(filename.c_str()); + + if(f.eof()) + return false; + + m_words.clear(); + m_nodes.clear(); + + string s; + getline(f,s); + stringstream ss; + ss << s; + ss >> m_k; + ss >> m_L; + int n1, n2; + ss >> n1; + ss >> n2; + + if(m_k<0 || m_k>20 || m_L<1 || m_L>10 || n1<0 || n1>5 || n2<0 || n2>3) + { + std::cerr << "Vocabulary loading failure: This is not a correct text file!" << endl; + return false; + } + + m_scoring = (ScoringType)n1; + m_weighting = (WeightingType)n2; + createScoringObject(); + + // nodes + int expected_nodes = + (int)((pow((double)m_k, (double)m_L + 1) - 1)/(m_k - 1)); + m_nodes.reserve(expected_nodes); + + m_words.reserve(pow((double)m_k, (double)m_L + 1)); + + m_nodes.resize(1); + m_nodes[0].id = 0; + while(!f.eof()) + { + string snode; + getline(f,snode); + stringstream ssnode; + ssnode << snode; + + int nid = m_nodes.size(); + m_nodes.resize(m_nodes.size()+1); + m_nodes[nid].id = nid; + + int pid ; + ssnode >> pid; + m_nodes[nid].parent = pid; + m_nodes[pid].children.push_back(nid); + + int nIsLeaf; + ssnode >> nIsLeaf; + + stringstream ssd; + for(int iD=0;iD> sElement; + ssd << sElement << " "; + } + F::fromString(m_nodes[nid].descriptor, ssd.str()); + + ssnode >> m_nodes[nid].weight; + + if(nIsLeaf>0) + { + int wid = m_words.size(); + m_words.resize(wid+1); + + m_nodes[nid].word_id = wid; + m_words[wid] = &m_nodes[nid]; + } + else + { + m_nodes[nid].children.reserve(m_k); + } + } + + return true; + +} + +// -------------------------------------------------------------------------- + +template +void TemplatedVocabulary::saveToTextFile(const std::string &filename) const +{ + fstream f; + f.open(filename.c_str(),ios_base::out); + f << m_k << " " << m_L << " " << " " << m_scoring << " " << m_weighting << endl; + + for(size_t i=1; i +void TemplatedVocabulary::save(const std::string &filename) const +{ + cv::FileStorage fs(filename.c_str(), cv::FileStorage::WRITE); + if(!fs.isOpened()) throw string("Could not open file ") + filename; + + save(fs); +} + +// -------------------------------------------------------------------------- + +template +void TemplatedVocabulary::load(const std::string &filename) +{ + cv::FileStorage fs(filename.c_str(), cv::FileStorage::READ); + if(!fs.isOpened()) throw string("Could not open file ") + filename; + + this->load(fs); +} + +// -------------------------------------------------------------------------- + +template +void TemplatedVocabulary::save(cv::FileStorage &f, + const std::string &name) const +{ + // Format YAML: + // vocabulary + // { + // k: + // L: + // scoringType: + // weightingType: + // nodes + // [ + // { + // nodeId: + // parentId: + // weight: + // descriptor: + // } + // ] + // words + // [ + // { + // wordId: + // nodeId: + // } + // ] + // } + // + // The root node (index 0) is not included in the node vector + // + + f << name << "{"; + + f << "k" << m_k; + f << "L" << m_L; + f << "scoringType" << m_scoring; + f << "weightingType" << m_weighting; + + // tree + f << "nodes" << "["; + vector parents, children; + vector::const_iterator pit; + + parents.push_back(0); // root + + while(!parents.empty()) + { + NodeId pid = parents.back(); + parents.pop_back(); + + const Node& parent = m_nodes[pid]; + children = parent.children; + + for(pit = children.begin(); pit != children.end(); pit++) + { + const Node& child = m_nodes[*pit]; + + // save node data + f << "{:"; + f << "nodeId" << (int)child.id; + f << "parentId" << (int)pid; + f << "weight" << (double)child.weight; + f << "descriptor" << F::toString(child.descriptor); + f << "}"; + + // add to parent list + if(!child.isLeaf()) + { + parents.push_back(*pit); + } + } + } + + f << "]"; // nodes + + // words + f << "words" << "["; + + typename vector::const_iterator wit; + for(wit = m_words.begin(); wit != m_words.end(); wit++) + { + WordId id = wit - m_words.begin(); + f << "{:"; + f << "wordId" << (int)id; + f << "nodeId" << (int)(*wit)->id; + f << "}"; + } + + f << "]"; // words + + f << "}"; + +} + +// -------------------------------------------------------------------------- + +template +void TemplatedVocabulary::load(const cv::FileStorage &fs, + const std::string &name) +{ + m_words.clear(); + m_nodes.clear(); + + cv::FileNode fvoc = fs[name]; + + m_k = (int)fvoc["k"]; + m_L = (int)fvoc["L"]; + m_scoring = (ScoringType)((int)fvoc["scoringType"]); + m_weighting = (WeightingType)((int)fvoc["weightingType"]); + + createScoringObject(); + + // nodes + cv::FileNode fn = fvoc["nodes"]; + + m_nodes.resize(fn.size() + 1); // +1 to include root + m_nodes[0].id = 0; + + for(unsigned int i = 0; i < fn.size(); ++i) + { + NodeId nid = (int)fn[i]["nodeId"]; + NodeId pid = (int)fn[i]["parentId"]; + WordValue weight = (WordValue)fn[i]["weight"]; + string d = (string)fn[i]["descriptor"]; + + m_nodes[nid].id = nid; + m_nodes[nid].parent = pid; + m_nodes[nid].weight = weight; + m_nodes[pid].children.push_back(nid); + + F::fromString(m_nodes[nid].descriptor, d); + } + + // words + fn = fvoc["words"]; + + m_words.resize(fn.size()); + + for(unsigned int i = 0; i < fn.size(); ++i) + { + NodeId wid = (int)fn[i]["wordId"]; + NodeId nid = (int)fn[i]["nodeId"]; + + m_nodes[nid].word_id = wid; + m_words[wid] = &m_nodes[nid]; + } +} + +// -------------------------------------------------------------------------- + +/** + * Writes printable information of the vocabulary + * @param os stream to write to + * @param voc + */ +template +std::ostream& operator<<(std::ostream &os, + const TemplatedVocabulary &voc) +{ + os << "Vocabulary: k = " << voc.getBranchingFactor() + << ", L = " << voc.getDepthLevels() + << ", Weighting = "; + + switch(voc.getWeightingType()) + { + case TF_IDF: os << "tf-idf"; break; + case TF: os << "tf"; break; + case IDF: os << "idf"; break; + case BINARY: os << "binary"; break; + } + + os << ", Scoring = "; + switch(voc.getScoringType()) + { + case L1_NORM: os << "L1-norm"; break; + case L2_NORM: os << "L2-norm"; break; + case CHI_SQUARE: os << "Chi square distance"; break; + case KL: os << "KL-divergence"; break; + case BHATTACHARYYA: os << "Bhattacharyya coefficient"; break; + case DOT_PRODUCT: os << "Dot product"; break; + } + + os << ", Number of words = " << voc.size(); + + return os; +} + +} // namespace DBoW2 + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/DBoW2/DUtils/Random.cpp b/third_party/ORB_SLAM3/Thirdparty/DBoW2/DUtils/Random.cpp new file mode 100644 index 0000000..1d78273 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/DBoW2/DUtils/Random.cpp @@ -0,0 +1,129 @@ +/* + * File: Random.cpp + * Project: DUtils library + * Author: Dorian Galvez-Lopez + * Date: April 2010 + * Description: manages pseudo-random numbers + * License: see the LICENSE.txt file + * + */ + +#include "Random.h" +#include "Timestamp.h" +#include +using namespace std; + +bool DUtils::Random::m_already_seeded = false; + +void DUtils::Random::SeedRand(){ + Timestamp time; + time.setToCurrentTime(); + srand((unsigned)time.getFloatTime()); +} + +void DUtils::Random::SeedRandOnce() +{ + if(!m_already_seeded) + { + DUtils::Random::SeedRand(); + m_already_seeded = true; + } +} + +void DUtils::Random::SeedRand(int seed) +{ + srand(seed); +} + +void DUtils::Random::SeedRandOnce(int seed) +{ + if(!m_already_seeded) + { + DUtils::Random::SeedRand(seed); + m_already_seeded = true; + } +} + +int DUtils::Random::RandomInt(int min, int max){ + int d = max - min + 1; + return int(((double)rand()/((double)RAND_MAX + 1.0)) * d) + min; +} + +// --------------------------------------------------------------------------- +// --------------------------------------------------------------------------- + +DUtils::Random::UnrepeatedRandomizer::UnrepeatedRandomizer(int min, int max) +{ + if(min <= max) + { + m_min = min; + m_max = max; + } + else + { + m_min = max; + m_max = min; + } + + createValues(); +} + +// --------------------------------------------------------------------------- + +DUtils::Random::UnrepeatedRandomizer::UnrepeatedRandomizer + (const DUtils::Random::UnrepeatedRandomizer& rnd) +{ + *this = rnd; +} + +// --------------------------------------------------------------------------- + +int DUtils::Random::UnrepeatedRandomizer::get() +{ + if(empty()) createValues(); + + DUtils::Random::SeedRandOnce(); + + int k = DUtils::Random::RandomInt(0, m_values.size()-1); + int ret = m_values[k]; + m_values[k] = m_values.back(); + m_values.pop_back(); + + return ret; +} + +// --------------------------------------------------------------------------- + +void DUtils::Random::UnrepeatedRandomizer::createValues() +{ + int n = m_max - m_min + 1; + + m_values.resize(n); + for(int i = 0; i < n; ++i) m_values[i] = m_min + i; +} + +// --------------------------------------------------------------------------- + +void DUtils::Random::UnrepeatedRandomizer::reset() +{ + if((int)m_values.size() != m_max - m_min + 1) createValues(); +} + +// --------------------------------------------------------------------------- + +DUtils::Random::UnrepeatedRandomizer& +DUtils::Random::UnrepeatedRandomizer::operator= + (const DUtils::Random::UnrepeatedRandomizer& rnd) +{ + if(this != &rnd) + { + this->m_min = rnd.m_min; + this->m_max = rnd.m_max; + this->m_values = rnd.m_values; + } + return *this; +} + +// --------------------------------------------------------------------------- + + diff --git a/third_party/ORB_SLAM3/Thirdparty/DBoW2/DUtils/Random.h b/third_party/ORB_SLAM3/Thirdparty/DBoW2/DUtils/Random.h new file mode 100644 index 0000000..5115dc4 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/DBoW2/DUtils/Random.h @@ -0,0 +1,184 @@ +/* + * File: Random.h + * Project: DUtils library + * Author: Dorian Galvez-Lopez + * Date: April 2010, November 2011 + * Description: manages pseudo-random numbers + * License: see the LICENSE.txt file + * + */ + +#pragma once +#ifndef __D_RANDOM__ +#define __D_RANDOM__ + +#include +#include + +namespace DUtils { + +/// Functions to generate pseudo-random numbers +class Random +{ +public: + class UnrepeatedRandomizer; + +public: + /** + * Sets the random number seed to the current time + */ + static void SeedRand(); + + /** + * Sets the random number seed to the current time only the first + * time this function is called + */ + static void SeedRandOnce(); + + /** + * Sets the given random number seed + * @param seed + */ + static void SeedRand(int seed); + + /** + * Sets the given random number seed only the first time this function + * is called + * @param seed + */ + static void SeedRandOnce(int seed); + + /** + * Returns a random number in the range [0..1] + * @return random T number in [0..1] + */ + template + static T RandomValue(){ + return (T)rand()/(T)RAND_MAX; + } + + /** + * Returns a random number in the range [min..max] + * @param min + * @param max + * @return random T number in [min..max] + */ + template + static T RandomValue(T min, T max){ + return Random::RandomValue() * (max - min) + min; + } + + /** + * Returns a random int in the range [min..max] + * @param min + * @param max + * @return random int in [min..max] + */ + static int RandomInt(int min, int max); + + /** + * Returns a random number from a gaussian distribution + * @param mean + * @param sigma standard deviation + */ + template + static T RandomGaussianValue(T mean, T sigma) + { + // Box-Muller transformation + T x1, x2, w, y1; + + do { + x1 = (T)2. * RandomValue() - (T)1.; + x2 = (T)2. * RandomValue() - (T)1.; + w = x1 * x1 + x2 * x2; + } while ( w >= (T)1. || w == (T)0. ); + + w = sqrt( ((T)-2.0 * log( w ) ) / w ); + y1 = x1 * w; + + return( mean + y1 * sigma ); + } + +private: + + /// If SeedRandOnce() or SeedRandOnce(int) have already been called + static bool m_already_seeded; + +}; + +// --------------------------------------------------------------------------- + +/// Provides pseudo-random numbers with no repetitions +class Random::UnrepeatedRandomizer +{ +public: + + /** + * Creates a randomizer that returns numbers in the range [min, max] + * @param min + * @param max + */ + UnrepeatedRandomizer(int min, int max); + ~UnrepeatedRandomizer(){} + + /** + * Copies a randomizer + * @param rnd + */ + UnrepeatedRandomizer(const UnrepeatedRandomizer& rnd); + + /** + * Copies a randomizer + * @param rnd + */ + UnrepeatedRandomizer& operator=(const UnrepeatedRandomizer& rnd); + + /** + * Returns a random number not given before. If all the possible values + * were already given, the process starts again + * @return unrepeated random number + */ + int get(); + + /** + * Returns whether all the possible values between min and max were + * already given. If get() is called when empty() is true, the behaviour + * is the same than after creating the randomizer + * @return true iff all the values were returned + */ + inline bool empty() const { return m_values.empty(); } + + /** + * Returns the number of values still to be returned + * @return amount of values to return + */ + inline unsigned int left() const { return m_values.size(); } + + /** + * Resets the randomizer as it were just created + */ + void reset(); + +protected: + + /** + * Creates the vector with available values + */ + void createValues(); + +protected: + + /// Min of range of values + int m_min; + /// Max of range of values + int m_max; + + /// Available values + std::vector m_values; + +}; + +} + +#endif + diff --git a/third_party/ORB_SLAM3/Thirdparty/DBoW2/DUtils/Timestamp.cpp b/third_party/ORB_SLAM3/Thirdparty/DBoW2/DUtils/Timestamp.cpp new file mode 100644 index 0000000..497304a --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/DBoW2/DUtils/Timestamp.cpp @@ -0,0 +1,246 @@ +/* + * File: Timestamp.cpp + * Author: Dorian Galvez-Lopez + * Date: March 2009 + * Description: timestamping functions + * + * Note: in windows, this class has a 1ms resolution + * + * License: see the LICENSE.txt file + * + */ + +#include +#include +#include +#include +#include +#include + +#ifdef _WIN32 +#ifndef WIN32 +#define WIN32 +#endif +#endif + +#ifdef WIN32 +#include +#define sprintf sprintf_s +#else +#include +#endif + +#include "Timestamp.h" + +using namespace std; + +using namespace DUtils; + +Timestamp::Timestamp(Timestamp::tOptions option) +{ + if(option & CURRENT_TIME) + setToCurrentTime(); + else if(option & ZERO) + setTime(0.); +} + +Timestamp::~Timestamp(void) +{ +} + +bool Timestamp::empty() const +{ + return m_secs == 0 && m_usecs == 0; +} + +void Timestamp::setToCurrentTime(){ + +#ifdef WIN32 + struct __timeb32 timebuffer; + _ftime32_s( &timebuffer ); // C4996 + // Note: _ftime is deprecated; consider using _ftime_s instead + m_secs = timebuffer.time; + m_usecs = timebuffer.millitm * 1000; +#else + struct timeval now; + gettimeofday(&now, NULL); + m_secs = now.tv_sec; + m_usecs = now.tv_usec; +#endif + +} + +void Timestamp::setTime(const string &stime){ + string::size_type p = stime.find('.'); + if(p == string::npos){ + m_secs = atol(stime.c_str()); + m_usecs = 0; + }else{ + m_secs = atol(stime.substr(0, p).c_str()); + + string s_usecs = stime.substr(p+1, 6); + m_usecs = atol(stime.substr(p+1).c_str()); + m_usecs *= (unsigned long)pow(10.0, double(6 - s_usecs.length())); + } +} + +void Timestamp::setTime(double s) +{ + m_secs = (unsigned long)s; + m_usecs = (s - (double)m_secs) * 1e6; +} + +double Timestamp::getFloatTime() const { + return double(m_secs) + double(m_usecs)/1000000.0; +} + +string Timestamp::getStringTime() const { + char buf[32]; + sprintf(buf, "%.6lf", this->getFloatTime()); + return string(buf); +} + +double Timestamp::operator- (const Timestamp &t) const { + return this->getFloatTime() - t.getFloatTime(); +} + +Timestamp& Timestamp::operator+= (double s) +{ + *this = *this + s; + return *this; +} + +Timestamp& Timestamp::operator-= (double s) +{ + *this = *this - s; + return *this; +} + +Timestamp Timestamp::operator+ (double s) const +{ + unsigned long secs = (long)floor(s); + unsigned long usecs = (long)((s - (double)secs) * 1e6); + + return this->plus(secs, usecs); +} + +Timestamp Timestamp::plus(unsigned long secs, unsigned long usecs) const +{ + Timestamp t; + + const unsigned long max = 1000000ul; + + if(m_usecs + usecs >= max) + t.setTime(m_secs + secs + 1, m_usecs + usecs - max); + else + t.setTime(m_secs + secs, m_usecs + usecs); + + return t; +} + +Timestamp Timestamp::operator- (double s) const +{ + unsigned long secs = (long)floor(s); + unsigned long usecs = (long)((s - (double)secs) * 1e6); + + return this->minus(secs, usecs); +} + +Timestamp Timestamp::minus(unsigned long secs, unsigned long usecs) const +{ + Timestamp t; + + const unsigned long max = 1000000ul; + + if(m_usecs < usecs) + t.setTime(m_secs - secs - 1, max - (usecs - m_usecs)); + else + t.setTime(m_secs - secs, m_usecs - usecs); + + return t; +} + +bool Timestamp::operator> (const Timestamp &t) const +{ + if(m_secs > t.m_secs) return true; + else if(m_secs == t.m_secs) return m_usecs > t.m_usecs; + else return false; +} + +bool Timestamp::operator>= (const Timestamp &t) const +{ + if(m_secs > t.m_secs) return true; + else if(m_secs == t.m_secs) return m_usecs >= t.m_usecs; + else return false; +} + +bool Timestamp::operator< (const Timestamp &t) const +{ + if(m_secs < t.m_secs) return true; + else if(m_secs == t.m_secs) return m_usecs < t.m_usecs; + else return false; +} + +bool Timestamp::operator<= (const Timestamp &t) const +{ + if(m_secs < t.m_secs) return true; + else if(m_secs == t.m_secs) return m_usecs <= t.m_usecs; + else return false; +} + +bool Timestamp::operator== (const Timestamp &t) const +{ + return(m_secs == t.m_secs && m_usecs == t.m_usecs); +} + + +string Timestamp::Format(bool machine_friendly) const +{ + struct tm tm_time; + + time_t t = (time_t)getFloatTime(); + +#ifdef WIN32 + localtime_s(&tm_time, &t); +#else + localtime_r(&t, &tm_time); +#endif + + char buffer[128]; + + if(machine_friendly) + { + strftime(buffer, 128, "%Y%m%d_%H%M%S", &tm_time); + } + else + { + strftime(buffer, 128, "%c", &tm_time); // Thu Aug 23 14:55:02 2001 + } + + return string(buffer); +} + +string Timestamp::Format(double s) { + int days = int(s / (24. * 3600.0)); + s -= days * (24. * 3600.0); + int hours = int(s / 3600.0); + s -= hours * 3600; + int minutes = int(s / 60.0); + s -= minutes * 60; + int seconds = int(s); + int ms = int((s - seconds)*1e6); + + stringstream ss; + ss.fill('0'); + bool b; + if((b = (days > 0))) ss << days << "d "; + if((b = (b || hours > 0))) ss << setw(2) << hours << ":"; + if((b = (b || minutes > 0))) ss << setw(2) << minutes << ":"; + if(b) ss << setw(2); + ss << seconds; + if(!b) ss << "." << setw(6) << ms; + + return ss.str(); +} + + diff --git a/third_party/ORB_SLAM3/Thirdparty/DBoW2/DUtils/Timestamp.h b/third_party/ORB_SLAM3/Thirdparty/DBoW2/DUtils/Timestamp.h new file mode 100644 index 0000000..b92f89f --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/DBoW2/DUtils/Timestamp.h @@ -0,0 +1,204 @@ +/* + * File: Timestamp.h + * Author: Dorian Galvez-Lopez + * Date: March 2009 + * Description: timestamping functions + * License: see the LICENSE.txt file + * + */ + +#ifndef __D_TIMESTAMP__ +#define __D_TIMESTAMP__ + +#include +using namespace std; + +namespace DUtils { + +/// Timestamp +class Timestamp +{ +public: + + /// Options to initiate a timestamp + enum tOptions + { + NONE = 0, + CURRENT_TIME = 0x1, + ZERO = 0x2 + }; + +public: + + /** + * Creates a timestamp + * @param option option to set the initial time stamp + */ + Timestamp(Timestamp::tOptions option = NONE); + + /** + * Destructor + */ + virtual ~Timestamp(void); + + /** + * Says if the timestamp is "empty": seconds and usecs are both 0, as + * when initiated with the ZERO flag + * @return true iif secs == usecs == 0 + */ + bool empty() const; + + /** + * Sets this instance to the current time + */ + void setToCurrentTime(); + + /** + * Sets the timestamp from seconds and microseconds + * @param secs: seconds + * @param usecs: microseconds + */ + inline void setTime(unsigned long secs, unsigned long usecs){ + m_secs = secs; + m_usecs = usecs; + } + + /** + * Returns the timestamp in seconds and microseconds + * @param secs seconds + * @param usecs microseconds + */ + inline void getTime(unsigned long &secs, unsigned long &usecs) const + { + secs = m_secs; + usecs = m_usecs; + } + + /** + * Sets the timestamp from a string with the time in seconds + * @param stime: string such as "1235603336.036609" + */ + void setTime(const string &stime); + + /** + * Sets the timestamp from a number of seconds from the epoch + * @param s seconds from the epoch + */ + void setTime(double s); + + /** + * Returns this timestamp as the number of seconds in (long) float format + */ + double getFloatTime() const; + + /** + * Returns this timestamp as the number of seconds in fixed length string format + */ + string getStringTime() const; + + /** + * Returns the difference in seconds between this timestamp (greater) and t (smaller) + * If the order is swapped, a negative number is returned + * @param t: timestamp to subtract from this timestamp + * @return difference in seconds + */ + double operator- (const Timestamp &t) const; + + /** + * Returns a copy of this timestamp + s seconds + us microseconds + * @param s seconds + * @param us microseconds + */ + Timestamp plus(unsigned long s, unsigned long us) const; + + /** + * Returns a copy of this timestamp - s seconds - us microseconds + * @param s seconds + * @param us microseconds + */ + Timestamp minus(unsigned long s, unsigned long us) const; + + /** + * Adds s seconds to this timestamp and returns a reference to itself + * @param s seconds + * @return reference to this timestamp + */ + Timestamp& operator+= (double s); + + /** + * Substracts s seconds to this timestamp and returns a reference to itself + * @param s seconds + * @return reference to this timestamp + */ + Timestamp& operator-= (double s); + + /** + * Returns a copy of this timestamp + s seconds + * @param s: seconds + */ + Timestamp operator+ (double s) const; + + /** + * Returns a copy of this timestamp - s seconds + * @param s: seconds + */ + Timestamp operator- (double s) const; + + /** + * Returns whether this timestamp is at the future of t + * @param t + */ + bool operator> (const Timestamp &t) const; + + /** + * Returns whether this timestamp is at the future of (or is the same as) t + * @param t + */ + bool operator>= (const Timestamp &t) const; + + /** + * Returns whether this timestamp and t represent the same instant + * @param t + */ + bool operator== (const Timestamp &t) const; + + /** + * Returns whether this timestamp is at the past of t + * @param t + */ + bool operator< (const Timestamp &t) const; + + /** + * Returns whether this timestamp is at the past of (or is the same as) t + * @param t + */ + bool operator<= (const Timestamp &t) const; + + /** + * Returns the timestamp in a human-readable string + * @param machine_friendly if true, the returned string is formatted + * to yyyymmdd_hhmmss, without weekday or spaces + * @note This has not been tested under Windows + * @note The timestamp is truncated to seconds + */ + string Format(bool machine_friendly = false) const; + + /** + * Returns a string version of the elapsed time in seconds, with the format + * xd hh:mm:ss, hh:mm:ss, mm:ss or s.us + * @param s: elapsed seconds (given by getFloatTime) to format + */ + static string Format(double s); + + +protected: + /// Seconds + unsigned long m_secs; // seconds + /// Microseconds + unsigned long m_usecs; // microseconds +}; + +} + +#endif + diff --git a/third_party/ORB_SLAM3/Thirdparty/DBoW2/README.txt b/third_party/ORB_SLAM3/Thirdparty/DBoW2/README.txt new file mode 100644 index 0000000..71827f0 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/DBoW2/README.txt @@ -0,0 +1,7 @@ +You should have received this DBoW2 version along with ORB-SLAM2 (https://github.com/raulmur/ORB_SLAM2). +See the original DBoW2 library at: https://github.com/dorian3d/DBoW2 +All files included in this version are BSD, see LICENSE.txt + +We also use Random.h, Random.cpp, Timestamp.pp and Timestamp.h from DLib/DUtils. +See the original DLib library at: https://github.com/dorian3d/DLib +All files included in this version are BSD, see LICENSE.txt diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/CMakeLists.txt b/third_party/ORB_SLAM3/Thirdparty/g2o/CMakeLists.txt new file mode 100644 index 0000000..e85b9cf --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/CMakeLists.txt @@ -0,0 +1,164 @@ +CMAKE_MINIMUM_REQUIRED(VERSION 2.6) +SET(CMAKE_LEGACY_CYGWIN_WIN32 0) + +PROJECT(g2o) + +SET(g2o_C_FLAGS) +SET(g2o_CXX_FLAGS) + +# default built type +IF(NOT CMAKE_BUILD_TYPE) + SET(CMAKE_BUILD_TYPE Release) +ENDIF() + +MESSAGE(STATUS "BUILD TYPE:" ${CMAKE_BUILD_TYPE}) + +SET (G2O_LIB_TYPE SHARED) + +# There seems to be an issue with MSVC8 +# see http://eigen.tuxfamily.org/bz/show_bug.cgi?id=83 +if(MSVC90) + add_definitions(-DEIGEN_DONT_ALIGN_STATICALLY=1) + message(STATUS "Disabling memory alignment for MSVC8") +endif(MSVC90) + +# Set search directory for looking for our custom CMake scripts to +# look for SuiteSparse, QGLViewer, and Eigen3. +LIST(APPEND CMAKE_MODULE_PATH ${g2o_SOURCE_DIR}/cmake_modules) + +# Detect OS and define macros appropriately +IF(UNIX) + ADD_DEFINITIONS(-DUNIX) + MESSAGE(STATUS "Compiling on Unix") +ENDIF(UNIX) + +# Eigen library parallelise itself, though, presumably due to performance issues +# OPENMP is experimental. We experienced some slowdown with it +FIND_PACKAGE(OpenMP) +SET(G2O_USE_OPENMP OFF CACHE BOOL "Build g2o with OpenMP support (EXPERIMENTAL)") +IF(OPENMP_FOUND AND G2O_USE_OPENMP) + SET (G2O_OPENMP 1) + SET(g2o_C_FLAGS "${g2o_C_FLAGS} ${OpenMP_C_FLAGS}") + SET(g2o_CXX_FLAGS "${g2o_CXX_FLAGS} -DEIGEN_DONT_PARALLELIZE ${OpenMP_CXX_FLAGS}") + MESSAGE(STATUS "Compiling with OpenMP support") +ENDIF(OPENMP_FOUND AND G2O_USE_OPENMP) + +# Compiler specific options for gcc +SET(CMAKE_CXX_FLAGS_RELEASE "${CMAKE_CXX_FLAGS_RELEASE} -O3 -march=native") +SET(CMAKE_C_FLAGS_RELEASE "${CMAKE_C_FLAGS_RELEASE} -O3 -march=native") +# SET(CMAKE_CXX_FLAGS_RELEASE "${CMAKE_CXX_FLAGS_RELEASE} -O3") +# SET(CMAKE_C_FLAGS_RELEASE "${CMAKE_C_FLAGS_RELEASE} -O3") + +# activate warnings !!! +SET(g2o_C_FLAGS "${g2o_C_FLAGS} -Wall -W") +SET(g2o_CXX_FLAGS "${g2o_CXX_FLAGS} -Wall -W") + +# specifying compiler flags +SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${g2o_CXX_FLAGS}") +SET(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${g2o_C_FLAGS}") + +# Find Eigen3 +FIND_PACKAGE(Eigen3 3.3 REQUIRED) + +# Generate config.h +SET(G2O_CXX_COMPILER "${CMAKE_CXX_COMPILER_ID} ${CMAKE_CXX_COMPILER}") +configure_file(config.h.in ${g2o_SOURCE_DIR}/config.h) + +# Include the subdirectories +ADD_LIBRARY(g2o ${G2O_LIB_TYPE} +#types +g2o/types/types_sba.h +g2o/types/types_six_dof_expmap.h +g2o/types/types_sba.cpp +g2o/types/types_six_dof_expmap.cpp +g2o/types/types_seven_dof_expmap.cpp +g2o/types/types_seven_dof_expmap.h +g2o/types/se3quat.h +g2o/types/se3_ops.h +g2o/types/se3_ops.hpp +#core +g2o/core/base_edge.h +g2o/core/base_binary_edge.h +g2o/core/hyper_graph_action.cpp +g2o/core/base_binary_edge.hpp +g2o/core/hyper_graph_action.h +g2o/core/base_multi_edge.h +g2o/core/hyper_graph.cpp +g2o/core/base_multi_edge.hpp +g2o/core/hyper_graph.h +g2o/core/base_unary_edge.h +g2o/core/linear_solver.h +g2o/core/base_unary_edge.hpp +g2o/core/marginal_covariance_cholesky.cpp +g2o/core/base_vertex.h +g2o/core/marginal_covariance_cholesky.h +g2o/core/base_vertex.hpp +g2o/core/matrix_structure.cpp +g2o/core/batch_stats.cpp +g2o/core/matrix_structure.h +g2o/core/batch_stats.h +g2o/core/openmp_mutex.h +g2o/core/block_solver.h +g2o/core/block_solver.hpp +g2o/core/parameter.cpp +g2o/core/parameter.h +g2o/core/cache.cpp +g2o/core/cache.h +g2o/core/optimizable_graph.cpp +g2o/core/optimizable_graph.h +g2o/core/solver.cpp +g2o/core/solver.h +g2o/core/creators.h +g2o/core/optimization_algorithm_factory.cpp +g2o/core/estimate_propagator.cpp +g2o/core/optimization_algorithm_factory.h +g2o/core/estimate_propagator.h +g2o/core/factory.cpp +g2o/core/optimization_algorithm_property.h +g2o/core/factory.h +g2o/core/sparse_block_matrix.h +g2o/core/sparse_optimizer.cpp +g2o/core/sparse_block_matrix.hpp +g2o/core/sparse_optimizer.h +g2o/core/hyper_dijkstra.cpp +g2o/core/hyper_dijkstra.h +g2o/core/parameter_container.cpp +g2o/core/parameter_container.h +g2o/core/optimization_algorithm.cpp +g2o/core/optimization_algorithm.h +g2o/core/optimization_algorithm_with_hessian.cpp +g2o/core/optimization_algorithm_with_hessian.h +g2o/core/optimization_algorithm_levenberg.cpp +g2o/core/optimization_algorithm_levenberg.h +g2o/core/optimization_algorithm_gauss_newton.cpp +g2o/core/optimization_algorithm_gauss_newton.h +g2o/core/jacobian_workspace.cpp +g2o/core/jacobian_workspace.h +g2o/core/robust_kernel.cpp +g2o/core/robust_kernel.h +g2o/core/robust_kernel_factory.cpp +g2o/core/robust_kernel_factory.h +g2o/core/robust_kernel_impl.cpp +g2o/core/robust_kernel_impl.h +#stuff +g2o/stuff/string_tools.h +g2o/stuff/color_macros.h +g2o/stuff/macros.h +g2o/stuff/timeutil.cpp +g2o/stuff/misc.h +g2o/stuff/timeutil.h +g2o/stuff/os_specific.c +g2o/stuff/os_specific.h +g2o/stuff/string_tools.cpp +g2o/stuff/property.cpp +g2o/stuff/property.h +) + +TARGET_INCLUDE_DIRECTORIES(g2o PUBLIC + ${g2o_SOURCE_DIR}/core + ${g2o_SOURCE_DIR}/types + ${g2o_SOURCE_DIR}/stuff) + +TARGET_LINK_LIBRARIES(g2o PUBLIC Eigen3::Eigen) + +TARGET_COMPILE_OPTIONS(g2o PRIVATE -Wno-deprecated-declarations) diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/README.txt b/third_party/ORB_SLAM3/Thirdparty/g2o/README.txt new file mode 100644 index 0000000..82641a8 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/README.txt @@ -0,0 +1,3 @@ +You should have received this g2o version along with ORB-SLAM2 (https://github.com/raulmur/ORB_SLAM2). +See the original g2o library at: https://github.com/RainerKuemmerle/g2o +All files included in this g2o version are BSD, see license-bsd.txt diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/config.h.in b/third_party/ORB_SLAM3/Thirdparty/g2o/config.h.in new file mode 100644 index 0000000..49c686b --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/config.h.in @@ -0,0 +1,13 @@ +#ifndef G2O_CONFIG_H +#define G2O_CONFIG_H + +#cmakedefine G2O_OPENMP 1 +#cmakedefine G2O_SHARED_LIBS 1 + +// give a warning if Eigen defaults to row-major matrices. +// We internally assume column-major matrices throughout the code. +#ifdef EIGEN_DEFAULT_TO_ROW_MAJOR +# error "g2o requires column major Eigen matrices (see http://eigen.tuxfamily.org/bz/show_bug.cgi?id=422)" +#endif + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/base_binary_edge.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/base_binary_edge.h new file mode 100644 index 0000000..660e83a --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/base_binary_edge.h @@ -0,0 +1,119 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, H. Strasdat, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_BASE_BINARY_EDGE_H +#define G2O_BASE_BINARY_EDGE_H + +#include +#include + +#include "base_edge.h" +#include "robust_kernel.h" +#include "../../config.h" + +namespace g2o { + + using namespace Eigen; + + template + class BaseBinaryEdge : public BaseEdge + { + public: + + typedef VertexXi VertexXiType; + typedef VertexXj VertexXjType; + + static const int Di = VertexXiType::Dimension; + static const int Dj = VertexXjType::Dimension; + + static const int Dimension = BaseEdge::Dimension; + typedef typename BaseEdge::Measurement Measurement; + typedef typename Matrix::AlignedMapType JacobianXiOplusType; + typedef typename Matrix::AlignedMapType JacobianXjOplusType; + typedef typename BaseEdge::ErrorVector ErrorVector; + typedef typename BaseEdge::InformationType InformationType; + + typedef Eigen::Map, Matrix::Flags & AlignedBit ? Aligned : Unaligned > HessianBlockType; + typedef Eigen::Map, Matrix::Flags & AlignedBit ? Aligned : Unaligned > HessianBlockTransposedType; + + BaseBinaryEdge() : BaseEdge(), + _hessianRowMajor(false), + _hessian(0, VertexXiType::Dimension, VertexXjType::Dimension), // HACK we map to the null pointer for initializing the Maps + _hessianTransposed(0, VertexXjType::Dimension, VertexXiType::Dimension), + _jacobianOplusXi(0, D, Di), _jacobianOplusXj(0, D, Dj) + { + _vertices.resize(2); + } + + virtual OptimizableGraph::Vertex* createFrom(); + virtual OptimizableGraph::Vertex* createTo(); + + virtual void resize(size_t size); + + virtual bool allVerticesFixed() const; + + virtual void linearizeOplus(JacobianWorkspace& jacobianWorkspace); + + /** + * Linearizes the oplus operator in the vertex, and stores + * the result in temporary variables _jacobianOplusXi and _jacobianOplusXj + */ + virtual void linearizeOplus(); + + //! returns the result of the linearization in the manifold space for the node xi + const JacobianXiOplusType& jacobianOplusXi() const { return _jacobianOplusXi;} + //! returns the result of the linearization in the manifold space for the node xj + const JacobianXjOplusType& jacobianOplusXj() const { return _jacobianOplusXj;} + + virtual void constructQuadraticForm() ; + + virtual void mapHessianMemory(double* d, int i, int j, bool rowMajor); + + using BaseEdge::resize; + using BaseEdge::computeError; + + protected: + using BaseEdge::_measurement; + using BaseEdge::_information; + using BaseEdge::_error; + using BaseEdge::_vertices; + using BaseEdge::_dimension; + + bool _hessianRowMajor; + HessianBlockType _hessian; + HessianBlockTransposedType _hessianTransposed; + JacobianXiOplusType _jacobianOplusXi; + JacobianXjOplusType _jacobianOplusXj; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + +#include "base_binary_edge.hpp" + +} // end namespace g2o + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/base_binary_edge.hpp b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/base_binary_edge.hpp new file mode 100644 index 0000000..7542a9f --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/base_binary_edge.hpp @@ -0,0 +1,218 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, H. Strasdat, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +template +OptimizableGraph::Vertex* BaseBinaryEdge::createFrom(){ + return new VertexXiType(); +} + +template +OptimizableGraph::Vertex* BaseBinaryEdge::createTo(){ + return new VertexXjType(); +} + + +template +void BaseBinaryEdge::resize(size_t size) +{ + if (size != 2) { + std::cerr << "WARNING, attempting to resize binary edge " << BaseEdge::id() << " to " << size << std::endl; + } + BaseEdge::resize(size); +} + +template +bool BaseBinaryEdge::allVerticesFixed() const +{ + return (static_cast (_vertices[0])->fixed() && + static_cast (_vertices[1])->fixed()); +} + +template +void BaseBinaryEdge::constructQuadraticForm() +{ + VertexXiType* from = static_cast(_vertices[0]); + VertexXjType* to = static_cast(_vertices[1]); + + // get the Jacobian of the nodes in the manifold domain + const JacobianXiOplusType& A = jacobianOplusXi(); + const JacobianXjOplusType& B = jacobianOplusXj(); + + + bool fromNotFixed = !(from->fixed()); + bool toNotFixed = !(to->fixed()); + + if (fromNotFixed || toNotFixed) { +#ifdef G2O_OPENMP + from->lockQuadraticForm(); + to->lockQuadraticForm(); +#endif + const InformationType& omega = _information; + Matrix omega_r = - omega * _error; + if (this->robustKernel() == 0) { + if (fromNotFixed) { + Matrix AtO = A.transpose() * omega; + from->b().noalias() += A.transpose() * omega_r; + from->A().noalias() += AtO*A; + if (toNotFixed ) { + if (_hessianRowMajor) // we have to write to the block as transposed + _hessianTransposed.noalias() += B.transpose() * AtO.transpose(); + else + _hessian.noalias() += AtO * B; + } + } + if (toNotFixed) { + to->b().noalias() += B.transpose() * omega_r; + to->A().noalias() += B.transpose() * omega * B; + } + } else { // robust (weighted) error according to some kernel + double error = this->chi2(); + Eigen::Vector3d rho; + this->robustKernel()->robustify(error, rho); + InformationType weightedOmega = this->robustInformation(rho); + //std::cout << PVAR(rho.transpose()) << std::endl; + //std::cout << PVAR(weightedOmega) << std::endl; + + omega_r *= rho[1]; + if (fromNotFixed) { + from->b().noalias() += A.transpose() * omega_r; + from->A().noalias() += A.transpose() * weightedOmega * A; + if (toNotFixed ) { + if (_hessianRowMajor) // we have to write to the block as transposed + _hessianTransposed.noalias() += B.transpose() * weightedOmega * A; + else + _hessian.noalias() += A.transpose() * weightedOmega * B; + } + } + if (toNotFixed) { + to->b().noalias() += B.transpose() * omega_r; + to->A().noalias() += B.transpose() * weightedOmega * B; + } + } +#ifdef G2O_OPENMP + to->unlockQuadraticForm(); + from->unlockQuadraticForm(); +#endif + } +} + +template +void BaseBinaryEdge::linearizeOplus(JacobianWorkspace& jacobianWorkspace) +{ + new (&_jacobianOplusXi) JacobianXiOplusType(jacobianWorkspace.workspaceForVertex(0), D, Di); + new (&_jacobianOplusXj) JacobianXjOplusType(jacobianWorkspace.workspaceForVertex(1), D, Dj); + linearizeOplus(); +} + +template +void BaseBinaryEdge::linearizeOplus() +{ + VertexXiType* vi = static_cast(_vertices[0]); + VertexXjType* vj = static_cast(_vertices[1]); + + bool iNotFixed = !(vi->fixed()); + bool jNotFixed = !(vj->fixed()); + + if (!iNotFixed && !jNotFixed) + return; + +#ifdef G2O_OPENMP + vi->lockQuadraticForm(); + vj->lockQuadraticForm(); +#endif + + const double delta = 1e-9; + const double scalar = 1.0 / (2*delta); + ErrorVector errorBak; + ErrorVector errorBeforeNumeric = _error; + + if (iNotFixed) { + //Xi - estimate the jacobian numerically + double add_vi[VertexXiType::Dimension]; + std::fill(add_vi, add_vi + VertexXiType::Dimension, 0.0); + // add small step along the unit vector in each dimension + for (int d = 0; d < VertexXiType::Dimension; ++d) { + vi->push(); + add_vi[d] = delta; + vi->oplus(add_vi); + computeError(); + errorBak = _error; + vi->pop(); + vi->push(); + add_vi[d] = -delta; + vi->oplus(add_vi); + computeError(); + errorBak -= _error; + vi->pop(); + add_vi[d] = 0.0; + + _jacobianOplusXi.col(d) = scalar * errorBak; + } // end dimension + } + + if (jNotFixed) { + //Xj - estimate the jacobian numerically + double add_vj[VertexXjType::Dimension]; + std::fill(add_vj, add_vj + VertexXjType::Dimension, 0.0); + // add small step along the unit vector in each dimension + for (int d = 0; d < VertexXjType::Dimension; ++d) { + vj->push(); + add_vj[d] = delta; + vj->oplus(add_vj); + computeError(); + errorBak = _error; + vj->pop(); + vj->push(); + add_vj[d] = -delta; + vj->oplus(add_vj); + computeError(); + errorBak -= _error; + vj->pop(); + add_vj[d] = 0.0; + + _jacobianOplusXj.col(d) = scalar * errorBak; + } + } // end dimension + + _error = errorBeforeNumeric; +#ifdef G2O_OPENMP + vj->unlockQuadraticForm(); + vi->unlockQuadraticForm(); +#endif +} + +template +void BaseBinaryEdge::mapHessianMemory(double* d, int i, int j, bool rowMajor) +{ + (void) i; (void) j; + //assert(i == 0 && j == 1); + if (rowMajor) { + new (&_hessianTransposed) HessianBlockTransposedType(d, VertexXjType::Dimension, VertexXiType::Dimension); + } else { + new (&_hessian) HessianBlockType(d, VertexXiType::Dimension, VertexXjType::Dimension); + } + _hessianRowMajor = rowMajor; +} diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/base_edge.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/base_edge.h new file mode 100644 index 0000000..91139e4 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/base_edge.h @@ -0,0 +1,110 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, H. Strasdat, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_BASE_EDGE_H +#define G2O_BASE_EDGE_H + +#include +#include + +#include + +#include "optimizable_graph.h" + +namespace g2o { + + using namespace Eigen; + + template + class BaseEdge : public OptimizableGraph::Edge + { + public: + + static const int Dimension = D; + typedef E Measurement; + typedef Matrix ErrorVector; + typedef Matrix InformationType; + + BaseEdge() : OptimizableGraph::Edge() + { + _dimension = D; + } + + virtual ~BaseEdge() {} + + virtual double chi2() const + { + return _error.dot(information()*_error); + } + + virtual const double* errorData() const { return _error.data();} + virtual double* errorData() { return _error.data();} + const ErrorVector& error() const { return _error;} + ErrorVector& error() { return _error;} + + //! information matrix of the constraint + const InformationType& information() const { return _information;} + InformationType& information() { return _information;} + void setInformation(const InformationType& information) { _information = information;} + + virtual const double* informationData() const { return _information.data();} + virtual double* informationData() { return _information.data();} + + //! accessor functions for the measurement represented by the edge + const Measurement& measurement() const { return _measurement;} + virtual void setMeasurement(const Measurement& m) { _measurement = m;} + + virtual int rank() const {return _dimension;} + + virtual void initialEstimate(const OptimizableGraph::VertexSet&, OptimizableGraph::Vertex*) + { + std::cerr << "inititialEstimate() is not implemented, please give implementation in your derived class" << std::endl; + } + + protected: + + Measurement _measurement; + InformationType _information; + ErrorVector _error; + + /** + * calculate the robust information matrix by updating the information matrix of the error + */ + InformationType robustInformation(const Eigen::Vector3d& rho) + { + InformationType result = rho[1] * _information; + //ErrorVector weightedErrror = _information * _error; + //result.noalias() += 2 * rho[2] * (weightedErrror * weightedErrror.transpose()); + return result; + } + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + +} // end namespace g2o + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/base_multi_edge.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/base_multi_edge.h new file mode 100644 index 0000000..dd2261f --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/base_multi_edge.h @@ -0,0 +1,113 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, H. Strasdat, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_BASE_MULTI_EDGE_H +#define G2O_BASE_MULTI_EDGE_H + +#include +#include +#include + +#include + +#include "base_edge.h" +#include "robust_kernel.h" +#include "../../config.h" + +namespace g2o { + + using namespace Eigen; + + /** + * \brief base class to represent an edge connecting an arbitrary number of nodes + * + * D - Dimension of the measurement + * E - type to represent the measurement + */ + template + class BaseMultiEdge : public BaseEdge + { + public: + /** + * \brief helper for mapping the Hessian memory of the upper triangular block + */ + struct HessianHelper { + Eigen::Map matrix; ///< the mapped memory + bool transposed; ///< the block has to be transposed + HessianHelper() : matrix(0, 0, 0), transposed(false) {} + }; + + public: + static const int Dimension = BaseEdge::Dimension; + typedef typename BaseEdge::Measurement Measurement; + typedef MatrixXd::MapType JacobianType; + typedef typename BaseEdge::ErrorVector ErrorVector; + typedef typename BaseEdge::InformationType InformationType; + typedef Eigen::Map HessianBlockType; + + BaseMultiEdge() : BaseEdge() + { + } + + virtual void linearizeOplus(JacobianWorkspace& jacobianWorkspace); + + /** + * Linearizes the oplus operator in the vertex, and stores + * the result in temporary variable vector _jacobianOplus + */ + virtual void linearizeOplus(); + + virtual void resize(size_t size); + + virtual bool allVerticesFixed() const; + + virtual void constructQuadraticForm() ; + + virtual void mapHessianMemory(double* d, int i, int j, bool rowMajor); + + using BaseEdge::computeError; + + protected: + using BaseEdge::_measurement; + using BaseEdge::_information; + using BaseEdge::_error; + using BaseEdge::_vertices; + using BaseEdge::_dimension; + + std::vector _hessian; + std::vector > _jacobianOplus; ///< jacobians of the edge (w.r.t. oplus) + + void computeQuadraticForm(const InformationType& omega, const ErrorVector& weightedError); + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + +#include "base_multi_edge.hpp" + +} // end namespace g2o + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/base_multi_edge.hpp b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/base_multi_edge.hpp new file mode 100644 index 0000000..a2fa66d --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/base_multi_edge.hpp @@ -0,0 +1,222 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, H. Strasdat, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +namespace internal { + inline int computeUpperTriangleIndex(int i, int j) + { + int elemsUpToCol = ((j-1) * j) / 2; + return elemsUpToCol + i; + } +} + +template +void BaseMultiEdge::constructQuadraticForm() +{ + if (this->robustKernel()) { + double error = this->chi2(); + Eigen::Vector3d rho; + this->robustKernel()->robustify(error, rho); + Matrix omega_r = - _information * _error; + omega_r *= rho[1]; + computeQuadraticForm(this->robustInformation(rho), omega_r); + } else { + computeQuadraticForm(_information, - _information * _error); + } +} + + +template +void BaseMultiEdge::linearizeOplus(JacobianWorkspace& jacobianWorkspace) +{ + for (size_t i = 0; i < _vertices.size(); ++i) { + OptimizableGraph::Vertex* v = static_cast(_vertices[i]); + assert(v->dimension() >= 0); + new (&_jacobianOplus[i]) JacobianType(jacobianWorkspace.workspaceForVertex(i), D, v->dimension()); + } + linearizeOplus(); +} + +template +void BaseMultiEdge::linearizeOplus() +{ +#ifdef G2O_OPENMP + for (size_t i = 0; i < _vertices.size(); ++i) { + OptimizableGraph::Vertex* v = static_cast(_vertices[i]); + v->lockQuadraticForm(); + } +#endif + + const double delta = 1e-9; + const double scalar = 1.0 / (2*delta); + ErrorVector errorBak; + ErrorVector errorBeforeNumeric = _error; + + for (size_t i = 0; i < _vertices.size(); ++i) { + //Xi - estimate the jacobian numerically + OptimizableGraph::Vertex* vi = static_cast(_vertices[i]); + + if (vi->fixed()) + continue; + + const int vi_dim = vi->dimension(); + assert(vi_dim >= 0); +#ifdef _MSC_VER + double* add_vi = new double[vi_dim]; +#else + double add_vi[vi_dim]; +#endif + std::fill(add_vi, add_vi + vi_dim, 0.0); + assert(_dimension >= 0); + assert(_jacobianOplus[i].rows() == _dimension && _jacobianOplus[i].cols() == vi_dim && "jacobian cache dimension does not match"); + _jacobianOplus[i].resize(_dimension, vi_dim); + // add small step along the unit vector in each dimension + for (int d = 0; d < vi_dim; ++d) { + vi->push(); + add_vi[d] = delta; + vi->oplus(add_vi); + computeError(); + errorBak = _error; + vi->pop(); + vi->push(); + add_vi[d] = -delta; + vi->oplus(add_vi); + computeError(); + errorBak -= _error; + vi->pop(); + add_vi[d] = 0.0; + + _jacobianOplus[i].col(d) = scalar * errorBak; + } // end dimension +#ifdef _MSC_VER + delete[] add_vi; +#endif + } + _error = errorBeforeNumeric; + +#ifdef G2O_OPENMP + for (int i = (int)(_vertices.size()) - 1; i >= 0; --i) { + OptimizableGraph::Vertex* v = static_cast(_vertices[i]); + v->unlockQuadraticForm(); + } +#endif + +} + +template +void BaseMultiEdge::mapHessianMemory(double* d, int i, int j, bool rowMajor) +{ + int idx = internal::computeUpperTriangleIndex(i, j); + assert(idx < (int)_hessian.size()); + OptimizableGraph::Vertex* vi = static_cast(HyperGraph::Edge::vertex(i)); + OptimizableGraph::Vertex* vj = static_cast(HyperGraph::Edge::vertex(j)); + assert(vi->dimension() >= 0); + assert(vj->dimension() >= 0); + HessianHelper& h = _hessian[idx]; + if (rowMajor) { + if (h.matrix.data() != d || h.transposed != rowMajor) + new (&h.matrix) HessianBlockType(d, vj->dimension(), vi->dimension()); + } else { + if (h.matrix.data() != d || h.transposed != rowMajor) + new (&h.matrix) HessianBlockType(d, vi->dimension(), vj->dimension()); + } + h.transposed = rowMajor; +} + +template +void BaseMultiEdge::resize(size_t size) +{ + BaseEdge::resize(size); + int n = (int)_vertices.size(); + int maxIdx = (n * (n-1))/2; + assert(maxIdx >= 0); + _hessian.resize(maxIdx); + _jacobianOplus.resize(size, JacobianType(0,0,0)); +} + +template +bool BaseMultiEdge::allVerticesFixed() const +{ + for (size_t i = 0; i < _vertices.size(); ++i) { + if (!static_cast (_vertices[i])->fixed()) { + return false; + } + } + return true; +} + +template +void BaseMultiEdge::computeQuadraticForm(const InformationType& omega, const ErrorVector& weightedError) +{ + for (size_t i = 0; i < _vertices.size(); ++i) { + OptimizableGraph::Vertex* from = static_cast(_vertices[i]); + bool istatus = !(from->fixed()); + + if (istatus) { + const MatrixXd& A = _jacobianOplus[i]; + + MatrixXd AtO = A.transpose() * omega; + int fromDim = from->dimension(); + assert(fromDim >= 0); + Eigen::Map fromMap(from->hessianData(), fromDim, fromDim); + Eigen::Map fromB(from->bData(), fromDim); + + // ii block in the hessian +#ifdef G2O_OPENMP + from->lockQuadraticForm(); +#endif + fromMap.noalias() += AtO * A; + fromB.noalias() += A.transpose() * weightedError; + + // compute the off-diagonal blocks ij for all j + for (size_t j = i+1; j < _vertices.size(); ++j) { + OptimizableGraph::Vertex* to = static_cast(_vertices[j]); +#ifdef G2O_OPENMP + to->lockQuadraticForm(); +#endif + bool jstatus = !(to->fixed()); + if (jstatus) { + const MatrixXd& B = _jacobianOplus[j]; + int idx = internal::computeUpperTriangleIndex(i, j); + assert(idx < (int)_hessian.size()); + HessianHelper& hhelper = _hessian[idx]; + if (hhelper.transposed) { // we have to write to the block as transposed + hhelper.matrix.noalias() += B.transpose() * AtO.transpose(); + } else { + hhelper.matrix.noalias() += AtO * B; + } + } +#ifdef G2O_OPENMP + to->unlockQuadraticForm(); +#endif + } + +#ifdef G2O_OPENMP + from->unlockQuadraticForm(); +#endif + } + + } +} diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/base_unary_edge.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/base_unary_edge.h new file mode 100644 index 0000000..28df8a5 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/base_unary_edge.h @@ -0,0 +1,100 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, H. Strasdat, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_BASE_UNARY_EDGE_H +#define G2O_BASE_UNARY_EDGE_H + +#include +#include +#include + +#include "base_edge.h" +#include "robust_kernel.h" +#include "../../config.h" + +namespace g2o { + + using namespace Eigen; + + template + class BaseUnaryEdge : public BaseEdge + { + public: + static const int Dimension = BaseEdge::Dimension; + typedef typename BaseEdge::Measurement Measurement; + typedef VertexXi VertexXiType; + typedef typename Matrix::AlignedMapType JacobianXiOplusType; + typedef typename BaseEdge::ErrorVector ErrorVector; + typedef typename BaseEdge::InformationType InformationType; + + BaseUnaryEdge() : BaseEdge(), + _jacobianOplusXi(0, D, VertexXiType::Dimension) + { + _vertices.resize(1); + } + + virtual void resize(size_t size); + + virtual bool allVerticesFixed() const; + + virtual void linearizeOplus(JacobianWorkspace& jacobianWorkspace); + + /** + * Linearizes the oplus operator in the vertex, and stores + * the result in temporary variables _jacobianOplusXi and _jacobianOplusXj + */ + virtual void linearizeOplus(); + + //! returns the result of the linearization in the manifold space for the node xi + const JacobianXiOplusType& jacobianOplusXi() const { return _jacobianOplusXi;} + + virtual void constructQuadraticForm(); + + virtual void initialEstimate(const OptimizableGraph::VertexSet& from, OptimizableGraph::Vertex* to); + + virtual void mapHessianMemory(double*, int, int, bool) {assert(0 && "BaseUnaryEdge does not map memory of the Hessian");} + + using BaseEdge::resize; + using BaseEdge::computeError; + + protected: + using BaseEdge::_measurement; + using BaseEdge::_information; + using BaseEdge::_error; + using BaseEdge::_vertices; + using BaseEdge::_dimension; + + JacobianXiOplusType _jacobianOplusXi; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + +#include "base_unary_edge.hpp" + +} // end namespace g2o + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/base_unary_edge.hpp b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/base_unary_edge.hpp new file mode 100644 index 0000000..464900f --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/base_unary_edge.hpp @@ -0,0 +1,129 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, H. Strasdat, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +template +void BaseUnaryEdge::resize(size_t size) +{ + if (size != 1) { + std::cerr << "WARNING, attempting to resize unary edge " << BaseEdge::id() << " to " << size << std::endl; + } + BaseEdge::resize(size); +} + +template +bool BaseUnaryEdge::allVerticesFixed() const +{ + return static_cast (_vertices[0])->fixed(); +} + +template +void BaseUnaryEdge::constructQuadraticForm() +{ + VertexXiType* from=static_cast(_vertices[0]); + + // chain rule to get the Jacobian of the nodes in the manifold domain + const JacobianXiOplusType& A = jacobianOplusXi(); + const InformationType& omega = _information; + + bool istatus = !from->fixed(); + if (istatus) { +#ifdef G2O_OPENMP + from->lockQuadraticForm(); +#endif + if (this->robustKernel()) { + double error = this->chi2(); + Eigen::Vector3d rho; + this->robustKernel()->robustify(error, rho); + InformationType weightedOmega = this->robustInformation(rho); + + from->b().noalias() -= rho[1] * A.transpose() * omega * _error; + from->A().noalias() += A.transpose() * weightedOmega * A; + } else { + from->b().noalias() -= A.transpose() * omega * _error; + from->A().noalias() += A.transpose() * omega * A; + } +#ifdef G2O_OPENMP + from->unlockQuadraticForm(); +#endif + } +} + +template +void BaseUnaryEdge::linearizeOplus(JacobianWorkspace& jacobianWorkspace) +{ + new (&_jacobianOplusXi) JacobianXiOplusType(jacobianWorkspace.workspaceForVertex(0), D, VertexXiType::Dimension); + linearizeOplus(); +} + +template +void BaseUnaryEdge::linearizeOplus() +{ + //Xi - estimate the jacobian numerically + VertexXiType* vi = static_cast(_vertices[0]); + + if (vi->fixed()) + return; + +#ifdef G2O_OPENMP + vi->lockQuadraticForm(); +#endif + + const double delta = 1e-9; + const double scalar = 1.0 / (2*delta); + ErrorVector error1; + ErrorVector errorBeforeNumeric = _error; + + double add_vi[VertexXiType::Dimension]; + std::fill(add_vi, add_vi + VertexXiType::Dimension, 0.0); + // add small step along the unit vector in each dimension + for (int d = 0; d < VertexXiType::Dimension; ++d) { + vi->push(); + add_vi[d] = delta; + vi->oplus(add_vi); + computeError(); + error1 = _error; + vi->pop(); + vi->push(); + add_vi[d] = -delta; + vi->oplus(add_vi); + computeError(); + vi->pop(); + add_vi[d] = 0.0; + + _jacobianOplusXi.col(d) = scalar * (error1 - _error); + } // end dimension + + _error = errorBeforeNumeric; +#ifdef G2O_OPENMP + vi->unlockQuadraticForm(); +#endif +} + +template +void BaseUnaryEdge::initialEstimate(const OptimizableGraph::VertexSet&, OptimizableGraph::Vertex*) +{ + std::cerr << __PRETTY_FUNCTION__ << " is not implemented, please give implementation in your derived class" << std::endl; +} diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/base_vertex.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/base_vertex.h new file mode 100644 index 0000000..e375fde --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/base_vertex.h @@ -0,0 +1,120 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_BASE_VERTEX_H +#define G2O_BASE_VERTEX_H + +#include "optimizable_graph.h" +#include "creators.h" +#include "../stuff/macros.h" + +#include +#include +#include +#include +#include + +namespace g2o { + + using namespace Eigen; + + +/** + * \brief Templatized BaseVertex + * + * Templatized BaseVertex + * D : minimal dimension of the vertex, e.g., 3 for rotation in 3D + * T : internal type to represent the estimate, e.g., Quaternion for rotation in 3D + */ + template + class BaseVertex : public OptimizableGraph::Vertex { + public: + typedef T EstimateType; + typedef std::stack > > + BackupStackType; + + static const int Dimension = D; ///< dimension of the estimate (minimal) in the manifold space + + typedef Eigen::Map, Matrix::Flags & AlignedBit ? Aligned : Unaligned > HessianBlockType; + + public: + BaseVertex(); + + virtual const double& hessian(int i, int j) const { assert(i(_hessian.data());} + + virtual void mapHessianMemory(double* d); + + virtual int copyB(double* b_) const { + memcpy(b_, _b.data(), Dimension * sizeof(double)); + return Dimension; + } + + virtual const double& b(int i) const { assert(i < D); return _b(i);} + virtual double& b(int i) { assert(i < D); return _b(i);} + virtual double* bData() { return _b.data();} + + virtual void clearQuadraticForm(); + + //! updates the current vertex with the direct solution x += H_ii\b_ii + //! @returns the determinant of the inverted hessian + virtual double solveDirect(double lambda=0); + + //! return right hand side b of the constructed linear system + Matrix& b() { return _b;} + const Matrix& b() const { return _b;} + //! return the hessian block associated with the vertex + HessianBlockType& A() { return _hessian;} + const HessianBlockType& A() const { return _hessian;} + + virtual void push() { _backup.push(_estimate);} + virtual void pop() { assert(!_backup.empty()); _estimate = _backup.top(); _backup.pop(); updateCache();} + virtual void discardTop() { assert(!_backup.empty()); _backup.pop();} + virtual int stackSize() const {return _backup.size();} + + //! return the current estimate of the vertex + const EstimateType& estimate() const { return _estimate;} + //! set the estimate for the vertex also calls updateCache() + void setEstimate(const EstimateType& et) { _estimate = et; updateCache();} + + protected: + HessianBlockType _hessian; + Matrix _b; + EstimateType _estimate; + BackupStackType _backup; + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + +#include "base_vertex.hpp" + +} // end namespace g2o + + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/base_vertex.hpp b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/base_vertex.hpp new file mode 100644 index 0000000..f21ff16 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/base_vertex.hpp @@ -0,0 +1,55 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +template +BaseVertex::BaseVertex() : + OptimizableGraph::Vertex(), + _hessian(0, D, D) +{ + _dimension = D; +} + +template +double BaseVertex::solveDirect(double lambda) { + Matrix tempA=_hessian + Matrix ::Identity()*lambda; + double det=tempA.determinant(); + if (g2o_isnan(det) || det < std::numeric_limits::epsilon()) + return det; + Matrix dx=tempA.llt().solve(_b); + oplus(&dx[0]); + return det; +} + +template +void BaseVertex::clearQuadraticForm() { + _b.setZero(); +} + +template +void BaseVertex::mapHessianMemory(double* d) +{ + new (&_hessian) HessianBlockType(d, D, D); +} diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/batch_stats.cpp b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/batch_stats.cpp new file mode 100644 index 0000000..a6beb69 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/batch_stats.cpp @@ -0,0 +1,90 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#include "batch_stats.h" +#include + +namespace g2o { + using namespace std; + + G2OBatchStatistics* G2OBatchStatistics::_globalStats=0; + + #ifndef PTHING + #define PTHING(s) \ + #s << "= " << (st.s) << "\t " + #endif + + G2OBatchStatistics::G2OBatchStatistics(){ + // zero all. + memset (this, 0, sizeof(G2OBatchStatistics)); + + // set the iteration to -1 to show that it isn't valid + iteration = -1; + } + + std::ostream& operator << (std::ostream& os , const G2OBatchStatistics& st) + { + os << PTHING(iteration); + + os << PTHING( numVertices ); // how many vertices are involved + os << PTHING( numEdges ); // hoe many edges + os << PTHING( chi2 ); // total chi2 + + /** timings **/ + // nonlinear part + os << PTHING( timeResiduals ); + os << PTHING( timeLinearize ); // jacobians + os << PTHING( timeQuadraticForm ); // construct the quadratic form in the graph + + // block_solver (constructs Ax=b, plus maybe schur); + os << PTHING( timeSchurComplement ); // compute schur complement (0 if not done); + + // linear solver (computes Ax=b); ); + os << PTHING( timeSymbolicDecomposition ); // symbolic decomposition (0 if not done); + os << PTHING( timeNumericDecomposition ); // numeric decomposition (0 if not done); + os << PTHING( timeLinearSolution ); // total time for solving Ax=b + os << PTHING( iterationsLinearSolver ); // iterations of PCG + os << PTHING( timeUpdate ); // oplus + os << PTHING( timeIteration ); // total time ); + + os << PTHING( levenbergIterations ); + os << PTHING( timeLinearSolver); + + os << PTHING(hessianDimension); + os << PTHING(hessianPoseDimension); + os << PTHING(hessianLandmarkDimension); + os << PTHING(choleskyNNZ); + os << PTHING(timeMarginals); + + return os; + }; + + void G2OBatchStatistics::setGlobalStats(G2OBatchStatistics* b) + { + _globalStats = b; + } + +} // end namespace diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/batch_stats.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/batch_stats.h new file mode 100644 index 0000000..d039f65 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/batch_stats.h @@ -0,0 +1,83 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_BATCH_STATS_H_ +#define G2O_BATCH_STATS_H_ + +#include +#include + + +namespace g2o { + + /** + * \brief statistics about the optimization + */ + struct G2OBatchStatistics { + G2OBatchStatistics(); + int iteration; ///< which iteration + int numVertices; ///< how many vertices are involved + int numEdges; ///< how many edges + double chi2; ///< total chi2 + + /** timings **/ + // nonlinear part + double timeResiduals; ///< residuals + double timeLinearize; ///< jacobians + double timeQuadraticForm; ///< construct the quadratic form in the graph + int levenbergIterations; ///< number of iterations performed by LM + // block_solver (constructs Ax=b, plus maybe schur) + double timeSchurComplement; ///< compute schur complement (0 if not done) + + // linear solver (computes Ax=b); + double timeSymbolicDecomposition; ///< symbolic decomposition (0 if not done) + double timeNumericDecomposition; ///< numeric decomposition (0 if not done) + double timeLinearSolution; ///< total time for solving Ax=b (including detup for schur) + double timeLinearSolver; ///< time for solving, excluding Schur setup + int iterationsLinearSolver; ///< iterations of PCG, (0 if not used, i.e., Cholesky) + double timeUpdate; ///< time to apply the update + double timeIteration; ///< total time; + + double timeMarginals; ///< computing the inverse elements (solve blocks) and thus the marginal covariances + + // information about the Hessian matrix + size_t hessianDimension; ///< rows / cols of the Hessian + size_t hessianPoseDimension; ///< dimension of the pose matrix in Schur + size_t hessianLandmarkDimension; ///< dimension of the landmark matrix in Schur + size_t choleskyNNZ; ///< number of non-zeros in the cholesky factor + + static G2OBatchStatistics* globalStats() {return _globalStats;} + static void setGlobalStats(G2OBatchStatistics* b); + protected: + static G2OBatchStatistics* _globalStats; + }; + + std::ostream& operator<<(std::ostream&, const G2OBatchStatistics&); + + typedef std::vector BatchStatisticsContainer; +} + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/block_solver.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/block_solver.h new file mode 100644 index 0000000..a393398 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/block_solver.h @@ -0,0 +1,193 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_BLOCK_SOLVER_H +#define G2O_BLOCK_SOLVER_H +#include +#include "solver.h" +#include "linear_solver.h" +#include "sparse_block_matrix.h" +#include "sparse_block_matrix_diagonal.h" +#include "openmp_mutex.h" +#include "../../config.h" + +namespace g2o { + using namespace Eigen; + + /** + * \brief traits to summarize the properties of the fixed size optimization problem + */ + template + struct BlockSolverTraits + { + static const int PoseDim = _PoseDim; + static const int LandmarkDim = _LandmarkDim; + typedef Matrix PoseMatrixType; + typedef Matrix LandmarkMatrixType; + typedef Matrix PoseLandmarkMatrixType; + typedef Matrix PoseVectorType; + typedef Matrix LandmarkVectorType; + + typedef SparseBlockMatrix PoseHessianType; + typedef SparseBlockMatrix LandmarkHessianType; + typedef SparseBlockMatrix PoseLandmarkHessianType; + typedef LinearSolver LinearSolverType; + }; + + /** + * \brief traits to summarize the properties of the dynamic size optimization problem + */ + template <> + struct BlockSolverTraits + { + static const int PoseDim = Eigen::Dynamic; + static const int LandmarkDim = Eigen::Dynamic; + typedef MatrixXd PoseMatrixType; + typedef MatrixXd LandmarkMatrixType; + typedef MatrixXd PoseLandmarkMatrixType; + typedef VectorXd PoseVectorType; + typedef VectorXd LandmarkVectorType; + + typedef SparseBlockMatrix PoseHessianType; + typedef SparseBlockMatrix LandmarkHessianType; + typedef SparseBlockMatrix PoseLandmarkHessianType; + typedef LinearSolver LinearSolverType; + }; + + /** + * \brief base for the block solvers with some basic function interfaces + */ + class BlockSolverBase : public Solver + { + public: + virtual ~BlockSolverBase() {} + /** + * compute dest = H * src + */ + virtual void multiplyHessian(double* dest, const double* src) const = 0; + }; + + /** + * \brief Implementation of a solver operating on the blocks of the Hessian + */ + template + class BlockSolver: public BlockSolverBase { + public: + + static const int PoseDim = Traits::PoseDim; + static const int LandmarkDim = Traits::LandmarkDim; + typedef typename Traits::PoseMatrixType PoseMatrixType; + typedef typename Traits::LandmarkMatrixType LandmarkMatrixType; + typedef typename Traits::PoseLandmarkMatrixType PoseLandmarkMatrixType; + typedef typename Traits::PoseVectorType PoseVectorType; + typedef typename Traits::LandmarkVectorType LandmarkVectorType; + + typedef typename Traits::PoseHessianType PoseHessianType; + typedef typename Traits::LandmarkHessianType LandmarkHessianType; + typedef typename Traits::PoseLandmarkHessianType PoseLandmarkHessianType; + typedef typename Traits::LinearSolverType LinearSolverType; + + public: + + /** + * allocate a block solver ontop of the underlying linear solver. + * NOTE: The BlockSolver assumes exclusive access to the linear solver and will therefore free the pointer + * in its destructor. + */ + BlockSolver(LinearSolverType* linearSolver); + ~BlockSolver(); + + virtual bool init(SparseOptimizer* optmizer, bool online = false); + virtual bool buildStructure(bool zeroBlocks = false); + virtual bool updateStructure(const std::vector& vset, const HyperGraph::EdgeSet& edges); + virtual bool buildSystem(); + virtual bool solve(); + virtual bool computeMarginals(SparseBlockMatrix& spinv, const std::vector >& blockIndices); + virtual bool setLambda(double lambda, bool backup = false); + virtual void restoreDiagonal(); + virtual bool supportsSchur() {return true;} + virtual bool schur() { return _doSchur;} + virtual void setSchur(bool s) { _doSchur = s;} + + LinearSolver* linearSolver() const { return _linearSolver;} + + virtual void setWriteDebug(bool writeDebug); + virtual bool writeDebug() const {return _linearSolver->writeDebug();} + + virtual bool saveHessian(const std::string& fileName) const; + + virtual void multiplyHessian(double* dest, const double* src) const { _Hpp->multiplySymmetricUpperTriangle(dest, src);} + + protected: + void resize(int* blockPoseIndices, int numPoseBlocks, + int* blockLandmarkIndices, int numLandmarkBlocks, int totalDim); + + void deallocate(); + + SparseBlockMatrix* _Hpp; + SparseBlockMatrix* _Hll; + SparseBlockMatrix* _Hpl; + + SparseBlockMatrix* _Hschur; + SparseBlockMatrixDiagonal* _DInvSchur; + + SparseBlockMatrixCCS* _HplCCS; + SparseBlockMatrixCCS* _HschurTransposedCCS; + + LinearSolver* _linearSolver; + + std::vector > _diagonalBackupPose; + std::vector > _diagonalBackupLandmark; + +# ifdef G2O_OPENMP + std::vector _coefficientsMutex; +# endif + + bool _doSchur; + + double* _coefficients; + double* _bschur; + + int _numPoses, _numLandmarks; + int _sizePoses, _sizeLandmarks; + }; + + + //variable size solver + typedef BlockSolver< BlockSolverTraits > BlockSolverX; + // solver for BA/3D SLAM + typedef BlockSolver< BlockSolverTraits<6, 3> > BlockSolver_6_3; + // solver fo BA with scale + typedef BlockSolver< BlockSolverTraits<7, 3> > BlockSolver_7_3; + // 2Dof landmarks 3Dof poses + typedef BlockSolver< BlockSolverTraits<3, 2> > BlockSolver_3_2; + +} // end namespace + +#include "block_solver.hpp" + + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/block_solver.hpp b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/block_solver.hpp new file mode 100644 index 0000000..f8b032e --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/block_solver.hpp @@ -0,0 +1,634 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#include "sparse_optimizer.h" +#include +#include +#include + +#include "../stuff/timeutil.h" +#include "../stuff/macros.h" +#include "../stuff/misc.h" + +namespace g2o { + +using namespace std; +using namespace Eigen; + +template +BlockSolver::BlockSolver(LinearSolverType* linearSolver) : + BlockSolverBase(), + _linearSolver(linearSolver) +{ + // workspace + _Hpp=0; + _Hll=0; + _Hpl=0; + _HplCCS = 0; + _HschurTransposedCCS = 0; + _Hschur=0; + _DInvSchur=0; + _coefficients=0; + _bschur = 0; + _xSize=0; + _numPoses=0; + _numLandmarks=0; + _sizePoses=0; + _sizeLandmarks=0; + _doSchur=true; +} + +template +void BlockSolver::resize(int* blockPoseIndices, int numPoseBlocks, + int* blockLandmarkIndices, int numLandmarkBlocks, + int s) +{ + deallocate(); + + resizeVector(s); + + if (_doSchur) { + // the following two are only used in schur + assert(_sizePoses > 0 && "allocating with wrong size"); + _coefficients = new double [s]; + _bschur = new double[_sizePoses]; + } + + _Hpp=new PoseHessianType(blockPoseIndices, blockPoseIndices, numPoseBlocks, numPoseBlocks); + if (_doSchur) { + _Hschur=new PoseHessianType(blockPoseIndices, blockPoseIndices, numPoseBlocks, numPoseBlocks); + _Hll=new LandmarkHessianType(blockLandmarkIndices, blockLandmarkIndices, numLandmarkBlocks, numLandmarkBlocks); + _DInvSchur = new SparseBlockMatrixDiagonal(_Hll->colBlockIndices()); + _Hpl=new PoseLandmarkHessianType(blockPoseIndices, blockLandmarkIndices, numPoseBlocks, numLandmarkBlocks); + _HplCCS = new SparseBlockMatrixCCS(_Hpl->rowBlockIndices(), _Hpl->colBlockIndices()); + _HschurTransposedCCS = new SparseBlockMatrixCCS(_Hschur->colBlockIndices(), _Hschur->rowBlockIndices()); +#ifdef G2O_OPENMP + _coefficientsMutex.resize(numPoseBlocks); +#endif + } +} + +template +void BlockSolver::deallocate() +{ + if (_Hpp){ + delete _Hpp; + _Hpp=0; + } + if (_Hll){ + delete _Hll; + _Hll=0; + } + if (_Hpl){ + delete _Hpl; + _Hpl = 0; + } + if (_Hschur){ + delete _Hschur; + _Hschur=0; + } + if (_DInvSchur){ + delete _DInvSchur; + _DInvSchur=0; + } + if (_coefficients) { + delete[] _coefficients; + _coefficients = 0; + } + if (_bschur) { + delete[] _bschur; + _bschur = 0; + } + if (_HplCCS) { + delete _HplCCS; + _HplCCS = 0; + } + if (_HschurTransposedCCS) { + delete _HschurTransposedCCS; + _HschurTransposedCCS = 0; + } +} + +template +BlockSolver::~BlockSolver() +{ + delete _linearSolver; + deallocate(); +} + +template +bool BlockSolver::buildStructure(bool zeroBlocks) +{ + assert(_optimizer); + + size_t sparseDim = 0; + _numPoses=0; + _numLandmarks=0; + _sizePoses=0; + _sizeLandmarks=0; + int* blockPoseIndices = new int[_optimizer->indexMapping().size()]; + int* blockLandmarkIndices = new int[_optimizer->indexMapping().size()]; + + for (size_t i = 0; i < _optimizer->indexMapping().size(); ++i) { + OptimizableGraph::Vertex* v = _optimizer->indexMapping()[i]; + int dim = v->dimension(); + if (! v->marginalized()){ + v->setColInHessian(_sizePoses); + _sizePoses+=dim; + blockPoseIndices[_numPoses]=_sizePoses; + ++_numPoses; + } else { + v->setColInHessian(_sizeLandmarks); + _sizeLandmarks+=dim; + blockLandmarkIndices[_numLandmarks]=_sizeLandmarks; + ++_numLandmarks; + } + sparseDim += dim; + } + resize(blockPoseIndices, _numPoses, blockLandmarkIndices, _numLandmarks, sparseDim); + delete[] blockLandmarkIndices; + delete[] blockPoseIndices; + + // allocate the diagonal on Hpp and Hll + int poseIdx = 0; + int landmarkIdx = 0; + for (size_t i = 0; i < _optimizer->indexMapping().size(); ++i) { + OptimizableGraph::Vertex* v = _optimizer->indexMapping()[i]; + if (! v->marginalized()){ + //assert(poseIdx == v->hessianIndex()); + PoseMatrixType* m = _Hpp->block(poseIdx, poseIdx, true); + if (zeroBlocks) + m->setZero(); + v->mapHessianMemory(m->data()); + ++poseIdx; + } else { + LandmarkMatrixType* m = _Hll->block(landmarkIdx, landmarkIdx, true); + if (zeroBlocks) + m->setZero(); + v->mapHessianMemory(m->data()); + ++landmarkIdx; + } + } + assert(poseIdx == _numPoses && landmarkIdx == _numLandmarks); + + // temporary structures for building the pattern of the Schur complement + SparseBlockMatrixHashMap* schurMatrixLookup = 0; + if (_doSchur) { + schurMatrixLookup = new SparseBlockMatrixHashMap(_Hschur->rowBlockIndices(), _Hschur->colBlockIndices()); + schurMatrixLookup->blockCols().resize(_Hschur->blockCols().size()); + } + + // here we assume that the landmark indices start after the pose ones + // create the structure in Hpp, Hll and in Hpl + for (SparseOptimizer::EdgeContainer::const_iterator it=_optimizer->activeEdges().begin(); it!=_optimizer->activeEdges().end(); ++it){ + OptimizableGraph::Edge* e = *it; + + for (size_t viIdx = 0; viIdx < e->vertices().size(); ++viIdx) { + OptimizableGraph::Vertex* v1 = (OptimizableGraph::Vertex*) e->vertex(viIdx); + int ind1 = v1->hessianIndex(); + if (ind1 == -1) + continue; + int indexV1Bak = ind1; + for (size_t vjIdx = viIdx + 1; vjIdx < e->vertices().size(); ++vjIdx) { + OptimizableGraph::Vertex* v2 = (OptimizableGraph::Vertex*) e->vertex(vjIdx); + int ind2 = v2->hessianIndex(); + if (ind2 == -1) + continue; + ind1 = indexV1Bak; + bool transposedBlock = ind1 > ind2; + if (transposedBlock){ // make sure, we allocate the upper triangle block + swap(ind1, ind2); + } + if (! v1->marginalized() && !v2->marginalized()){ + PoseMatrixType* m = _Hpp->block(ind1, ind2, true); + if (zeroBlocks) + m->setZero(); + e->mapHessianMemory(m->data(), viIdx, vjIdx, transposedBlock); + if (_Hschur) {// assume this is only needed in case we solve with the schur complement + schurMatrixLookup->addBlock(ind1, ind2); + } + } else if (v1->marginalized() && v2->marginalized()){ + // RAINER hmm.... should we ever reach this here???? + LandmarkMatrixType* m = _Hll->block(ind1-_numPoses, ind2-_numPoses, true); + if (zeroBlocks) + m->setZero(); + e->mapHessianMemory(m->data(), viIdx, vjIdx, false); + } else { + if (v1->marginalized()){ + PoseLandmarkMatrixType* m = _Hpl->block(v2->hessianIndex(),v1->hessianIndex()-_numPoses, true); + if (zeroBlocks) + m->setZero(); + e->mapHessianMemory(m->data(), viIdx, vjIdx, true); // transpose the block before writing to it + } else { + PoseLandmarkMatrixType* m = _Hpl->block(v1->hessianIndex(),v2->hessianIndex()-_numPoses, true); + if (zeroBlocks) + m->setZero(); + e->mapHessianMemory(m->data(), viIdx, vjIdx, false); // directly the block + } + } + } + } + } + + if (! _doSchur) + return true; + + _DInvSchur->diagonal().resize(landmarkIdx); + _Hpl->fillSparseBlockMatrixCCS(*_HplCCS); + + for (size_t i = 0; i < _optimizer->indexMapping().size(); ++i) { + OptimizableGraph::Vertex* v = _optimizer->indexMapping()[i]; + if (v->marginalized()){ + const HyperGraph::EdgeSet& vedges=v->edges(); + for (HyperGraph::EdgeSet::const_iterator it1=vedges.begin(); it1!=vedges.end(); ++it1){ + for (size_t i=0; i<(*it1)->vertices().size(); ++i) + { + OptimizableGraph::Vertex* v1= (OptimizableGraph::Vertex*) (*it1)->vertex(i); + if (v1->hessianIndex()==-1 || v1==v) + continue; + for (HyperGraph::EdgeSet::const_iterator it2=vedges.begin(); it2!=vedges.end(); ++it2){ + for (size_t j=0; j<(*it2)->vertices().size(); ++j) + { + OptimizableGraph::Vertex* v2= (OptimizableGraph::Vertex*) (*it2)->vertex(j); + if (v2->hessianIndex()==-1 || v2==v) + continue; + int i1=v1->hessianIndex(); + int i2=v2->hessianIndex(); + if (i1<=i2) { + schurMatrixLookup->addBlock(i1, i2); + } + } + } + } + } + } + } + + _Hschur->takePatternFromHash(*schurMatrixLookup); + delete schurMatrixLookup; + _Hschur->fillSparseBlockMatrixCCSTransposed(*_HschurTransposedCCS); + + return true; +} + +template +bool BlockSolver::updateStructure(const std::vector& vset, const HyperGraph::EdgeSet& edges) +{ + for (std::vector::const_iterator vit = vset.begin(); vit != vset.end(); ++vit) { + OptimizableGraph::Vertex* v = static_cast(*vit); + int dim = v->dimension(); + if (! v->marginalized()){ + v->setColInHessian(_sizePoses); + _sizePoses+=dim; + _Hpp->rowBlockIndices().push_back(_sizePoses); + _Hpp->colBlockIndices().push_back(_sizePoses); + _Hpp->blockCols().push_back(typename SparseBlockMatrix::IntBlockMap()); + ++_numPoses; + int ind = v->hessianIndex(); + PoseMatrixType* m = _Hpp->block(ind, ind, true); + v->mapHessianMemory(m->data()); + } else { + std::cerr << "updateStructure(): Schur not supported" << std::endl; + abort(); + } + } + resizeVector(_sizePoses + _sizeLandmarks); + + for (HyperGraph::EdgeSet::const_iterator it = edges.begin(); it != edges.end(); ++it) { + OptimizableGraph::Edge* e = static_cast(*it); + + for (size_t viIdx = 0; viIdx < e->vertices().size(); ++viIdx) { + OptimizableGraph::Vertex* v1 = (OptimizableGraph::Vertex*) e->vertex(viIdx); + int ind1 = v1->hessianIndex(); + int indexV1Bak = ind1; + if (ind1 == -1) + continue; + for (size_t vjIdx = viIdx + 1; vjIdx < e->vertices().size(); ++vjIdx) { + OptimizableGraph::Vertex* v2 = (OptimizableGraph::Vertex*) e->vertex(vjIdx); + int ind2 = v2->hessianIndex(); + if (ind2 == -1) + continue; + ind1 = indexV1Bak; + bool transposedBlock = ind1 > ind2; + if (transposedBlock) // make sure, we allocate the upper triangular block + swap(ind1, ind2); + + if (! v1->marginalized() && !v2->marginalized()) { + PoseMatrixType* m = _Hpp->block(ind1, ind2, true); + e->mapHessianMemory(m->data(), viIdx, vjIdx, transposedBlock); + } else { + std::cerr << __PRETTY_FUNCTION__ << ": not supported" << std::endl; + } + } + } + + } + + return true; +} + +template +bool BlockSolver::solve(){ + //cerr << __PRETTY_FUNCTION__ << endl; + if (! _doSchur){ + double t=get_monotonic_time(); + bool ok = _linearSolver->solve(*_Hpp, _x, _b); + G2OBatchStatistics* globalStats = G2OBatchStatistics::globalStats(); + if (globalStats) { + globalStats->timeLinearSolver = get_monotonic_time() - t; + globalStats->hessianDimension = globalStats->hessianPoseDimension = _Hpp->cols(); + } + return ok; + } + + // schur thing + + // backup the coefficient matrix + double t=get_monotonic_time(); + + // _Hschur = _Hpp, but keeping the pattern of _Hschur + _Hschur->clear(); + _Hpp->add(_Hschur); + + //_DInvSchur->clear(); + memset (_coefficients, 0, _sizePoses*sizeof(double)); +# ifdef G2O_OPENMP +# pragma omp parallel for default (shared) schedule(dynamic, 10) +# endif + for (int landmarkIndex = 0; landmarkIndex < static_cast(_Hll->blockCols().size()); ++landmarkIndex) { + const typename SparseBlockMatrix::IntBlockMap& marginalizeColumn = _Hll->blockCols()[landmarkIndex]; + assert(marginalizeColumn.size() == 1 && "more than one block in _Hll column"); + + // calculate inverse block for the landmark + const LandmarkMatrixType * D = marginalizeColumn.begin()->second; + assert (D && D->rows()==D->cols() && "Error in landmark matrix"); + LandmarkMatrixType& Dinv = _DInvSchur->diagonal()[landmarkIndex]; + Dinv = D->inverse(); + + LandmarkVectorType db(D->rows()); + for (int j=0; jrows(); ++j) { + db[j]=_b[_Hll->rowBaseOfBlock(landmarkIndex) + _sizePoses + j]; + } + db=Dinv*db; + + assert((size_t)landmarkIndex < _HplCCS->blockCols().size() && "Index out of bounds"); + const typename SparseBlockMatrixCCS::SparseColumn& landmarkColumn = _HplCCS->blockCols()[landmarkIndex]; + + for (typename SparseBlockMatrixCCS::SparseColumn::const_iterator it_outer = landmarkColumn.begin(); + it_outer != landmarkColumn.end(); ++it_outer) { + int i1 = it_outer->row; + + const PoseLandmarkMatrixType* Bi = it_outer->block; + assert(Bi); + + PoseLandmarkMatrixType BDinv = (*Bi)*(Dinv); + assert(_HplCCS->rowBaseOfBlock(i1) < _sizePoses && "Index out of bounds"); + typename PoseVectorType::MapType Bb(&_coefficients[_HplCCS->rowBaseOfBlock(i1)], Bi->rows()); +# ifdef G2O_OPENMP + ScopedOpenMPMutex mutexLock(&_coefficientsMutex[i1]); +# endif + Bb.noalias() += (*Bi)*db; + + assert(i1 >= 0 && i1 < static_cast(_HschurTransposedCCS->blockCols().size()) && "Index out of bounds"); + typename SparseBlockMatrixCCS::SparseColumn::iterator targetColumnIt = _HschurTransposedCCS->blockCols()[i1].begin(); + + typename SparseBlockMatrixCCS::RowBlock aux(i1, 0); + typename SparseBlockMatrixCCS::SparseColumn::const_iterator it_inner = lower_bound(landmarkColumn.begin(), landmarkColumn.end(), aux); + for (; it_inner != landmarkColumn.end(); ++it_inner) { + int i2 = it_inner->row; + const PoseLandmarkMatrixType* Bj = it_inner->block; + assert(Bj); + while (targetColumnIt->row < i2 /*&& targetColumnIt != _HschurTransposedCCS->blockCols()[i1].end()*/) + ++targetColumnIt; + assert(targetColumnIt != _HschurTransposedCCS->blockCols()[i1].end() && targetColumnIt->row == i2 && "invalid iterator, something wrong with the matrix structure"); + PoseMatrixType* Hi1i2 = targetColumnIt->block;//_Hschur->block(i1,i2); + assert(Hi1i2); + (*Hi1i2).noalias() -= BDinv*Bj->transpose(); + } + } + } + //cerr << "Solve [marginalize] = " << get_monotonic_time()-t << endl; + + // _bschur = _b for calling solver, and not touching _b + memcpy(_bschur, _b, _sizePoses * sizeof(double)); + for (int i=0; i<_sizePoses; ++i){ + _bschur[i]-=_coefficients[i]; + } + + G2OBatchStatistics* globalStats = G2OBatchStatistics::globalStats(); + if (globalStats){ + globalStats->timeSchurComplement = get_monotonic_time() - t; + } + + t=get_monotonic_time(); + bool solvedPoses = _linearSolver->solve(*_Hschur, _x, _bschur); + if (globalStats) { + globalStats->timeLinearSolver = get_monotonic_time() - t; + globalStats->hessianPoseDimension = _Hpp->cols(); + globalStats->hessianLandmarkDimension = _Hll->cols(); + globalStats->hessianDimension = globalStats->hessianPoseDimension + globalStats->hessianLandmarkDimension; + } + //cerr << "Solve [decompose and solve] = " << get_monotonic_time()-t << endl; + + if (! solvedPoses) + return false; + + // _x contains the solution for the poses, now applying it to the landmarks to get the new part of the + // solution; + double* xp = _x; + double* cp = _coefficients; + + double* xl=_x+_sizePoses; + double* cl=_coefficients + _sizePoses; + double* bl=_b+_sizePoses; + + // cp = -xp + for (int i=0; i<_sizePoses; ++i) + cp[i]=-xp[i]; + + // cl = bl + memcpy(cl,bl,_sizeLandmarks*sizeof(double)); + + // cl = bl - Bt * xp + //Bt->multiply(cl, cp); + _HplCCS->rightMultiply(cl, cp); + + // xl = Dinv * cl + memset(xl,0, _sizeLandmarks*sizeof(double)); + _DInvSchur->multiply(xl,cl); + //_DInvSchur->rightMultiply(xl,cl); + //cerr << "Solve [landmark delta] = " << get_monotonic_time()-t << endl; + + return true; +} + + +template +bool BlockSolver::computeMarginals(SparseBlockMatrix& spinv, const std::vector >& blockIndices) +{ + double t = get_monotonic_time(); + bool ok = _linearSolver->solvePattern(spinv, blockIndices, *_Hpp); + G2OBatchStatistics* globalStats = G2OBatchStatistics::globalStats(); + if (globalStats) { + globalStats->timeMarginals = get_monotonic_time() - t; + } + return ok; +} + +template +bool BlockSolver::buildSystem() +{ + // clear b vector +# ifdef G2O_OPENMP +# pragma omp parallel for default (shared) if (_optimizer->indexMapping().size() > 1000) +# endif + for (int i = 0; i < static_cast(_optimizer->indexMapping().size()); ++i) { + OptimizableGraph::Vertex* v=_optimizer->indexMapping()[i]; + assert(v); + v->clearQuadraticForm(); + } + _Hpp->clear(); + if (_doSchur) { + _Hll->clear(); + _Hpl->clear(); + } + + // resetting the terms for the pairwise constraints + // built up the current system by storing the Hessian blocks in the edges and vertices +# ifndef G2O_OPENMP + // no threading, we do not need to copy the workspace + JacobianWorkspace& jacobianWorkspace = _optimizer->jacobianWorkspace(); +# else + // if running with threads need to produce copies of the workspace for each thread + JacobianWorkspace jacobianWorkspace = _optimizer->jacobianWorkspace(); +# pragma omp parallel for default (shared) firstprivate(jacobianWorkspace) if (_optimizer->activeEdges().size() > 100) +# endif + for (int k = 0; k < static_cast(_optimizer->activeEdges().size()); ++k) { + OptimizableGraph::Edge* e = _optimizer->activeEdges()[k]; + e->linearizeOplus(jacobianWorkspace); // jacobian of the nodes' oplus (manifold) + e->constructQuadraticForm(); +# ifndef NDEBUG + for (size_t i = 0; i < e->vertices().size(); ++i) { + const OptimizableGraph::Vertex* v = static_cast(e->vertex(i)); + if (! v->fixed()) { + bool hasANan = arrayHasNaN(jacobianWorkspace.workspaceForVertex(i), e->dimension() * v->dimension()); + if (hasANan) { + cerr << "buildSystem(): NaN within Jacobian for edge " << e << " for vertex " << i << endl; + break; + } + } + } +# endif + } + + // flush the current system in a sparse block matrix +# ifdef G2O_OPENMP +# pragma omp parallel for default (shared) if (_optimizer->indexMapping().size() > 1000) +# endif + for (int i = 0; i < static_cast(_optimizer->indexMapping().size()); ++i) { + OptimizableGraph::Vertex* v=_optimizer->indexMapping()[i]; + int iBase = v->colInHessian(); + if (v->marginalized()) + iBase+=_sizePoses; + v->copyB(_b+iBase); + } + + return 0; +} + + +template +bool BlockSolver::setLambda(double lambda, bool backup) +{ + if (backup) { + _diagonalBackupPose.resize(_numPoses); + _diagonalBackupLandmark.resize(_numLandmarks); + } +# ifdef G2O_OPENMP +# pragma omp parallel for default (shared) if (_numPoses > 100) +# endif + for (int i = 0; i < _numPoses; ++i) { + PoseMatrixType *b=_Hpp->block(i,i); + if (backup) + _diagonalBackupPose[i] = b->diagonal(); + b->diagonal().array() += lambda; + } +# ifdef G2O_OPENMP +# pragma omp parallel for default (shared) if (_numLandmarks > 100) +# endif + for (int i = 0; i < _numLandmarks; ++i) { + LandmarkMatrixType *b=_Hll->block(i,i); + if (backup) + _diagonalBackupLandmark[i] = b->diagonal(); + b->diagonal().array() += lambda; + } + return true; +} + +template +void BlockSolver::restoreDiagonal() +{ + assert((int) _diagonalBackupPose.size() == _numPoses && "Mismatch in dimensions"); + assert((int) _diagonalBackupLandmark.size() == _numLandmarks && "Mismatch in dimensions"); + for (int i = 0; i < _numPoses; ++i) { + PoseMatrixType *b=_Hpp->block(i,i); + b->diagonal() = _diagonalBackupPose[i]; + } + for (int i = 0; i < _numLandmarks; ++i) { + LandmarkMatrixType *b=_Hll->block(i,i); + b->diagonal() = _diagonalBackupLandmark[i]; + } +} + +template +bool BlockSolver::init(SparseOptimizer* optimizer, bool online) +{ + _optimizer = optimizer; + if (! online) { + if (_Hpp) + _Hpp->clear(); + if (_Hpl) + _Hpl->clear(); + if (_Hll) + _Hll->clear(); + } + _linearSolver->init(); + return true; +} + +template +void BlockSolver::setWriteDebug(bool writeDebug) +{ + _linearSolver->setWriteDebug(writeDebug); +} + +template +bool BlockSolver::saveHessian(const std::string& fileName) const +{ + return _Hpp->writeOctave(fileName.c_str(), true); +} + +} // end namespace diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/cache.cpp b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/cache.cpp new file mode 100644 index 0000000..89f9c24 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/cache.cpp @@ -0,0 +1,183 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 G. Grisetti, R. Kuemmerle, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#include "cache.h" +#include "optimizable_graph.h" +#include "factory.h" + +#include + +namespace g2o { + using namespace std; + + Cache::CacheKey::CacheKey() : + _type(), _parameters() + { + } + + Cache::CacheKey::CacheKey(const std::string& type_, const ParameterVector& parameters_) : + _type(type_), _parameters(parameters_) + { + } + + Cache::Cache(CacheContainer* container_, const ParameterVector& parameters_) : + _updateNeeded(true), _parameters(parameters_), _container(container_) + { + } + + bool Cache::CacheKey::operator<(const Cache::CacheKey& c) const{ + if (_type < c._type) + return true; + return std::lexicographical_compare (_parameters.begin( ), _parameters.end( ), + c._parameters.begin( ), c._parameters.end( ) ); + } + + + OptimizableGraph::Vertex* Cache::vertex() { + if (container() ) + return container()->vertex(); + return 0; + } + + OptimizableGraph* Cache::graph() { + if (container()) + return container()->graph(); + return 0; + } + + CacheContainer* Cache::container() { + return _container; + } + + ParameterVector& Cache::parameters() { + return _parameters; + } + + Cache::CacheKey Cache::key() const { + Factory* factory=Factory::instance(); + return CacheKey(factory->tag(this), _parameters); + }; + + + void Cache::update(){ + if (! _updateNeeded) + return; + for(std::vector::iterator it=_parentCaches.begin(); it!=_parentCaches.end(); it++){ + (*it)->update(); + } + updateImpl(); + _updateNeeded=false; + } + + Cache* Cache::installDependency(const std::string& type_, const std::vector& parameterIndices){ + ParameterVector pv(parameterIndices.size()); + for (size_t i=0; i=(int)_parameters.size()) + return 0; + pv[i]=_parameters[ parameterIndices[i] ]; + } + CacheKey k(type_, pv); + if (!container()) + return 0; + Cache* c=container()->findCache(k); + if (!c) { + c = container()->createCache(k); + } + if (c) + _parentCaches.push_back(c); + return c; + } + + bool Cache::resolveDependancies(){ + return true; + } + + CacheContainer::CacheContainer(OptimizableGraph::Vertex* vertex_) { + _vertex = vertex_; + } + + Cache* CacheContainer::findCache(const Cache::CacheKey& key) { + iterator it=find(key); + if (it==end()) + return 0; + return it->second; + } + + Cache* CacheContainer::createCache(const Cache::CacheKey& key){ + Factory* f = Factory::instance(); + HyperGraph::HyperGraphElement* e = f->construct(key.type()); + if (!e) { + cerr << __PRETTY_FUNCTION__ << endl; + cerr << "fatal error in creating cache of type " << key.type() << endl; + return 0; + } + Cache* c = dynamic_cast(e); + if (! c){ + cerr << __PRETTY_FUNCTION__ << endl; + cerr << "fatal error in creating cache of type " << key.type() << endl; + return 0; + } + c->_container = this; + c->_parameters = key._parameters; + if (c->resolveDependancies()){ + insert(make_pair(key,c)); + c->update(); + return c; + } + return 0; + } + + OptimizableGraph::Vertex* CacheContainer::vertex() { + return _vertex; + } + + OptimizableGraph* CacheContainer::graph(){ + if (_vertex) + return _vertex->graph(); + return 0; + } + + void CacheContainer::update() { + for (iterator it=begin(); it!=end(); it++){ + (it->second)->update(); + } + _updateNeeded=false; + } + + void CacheContainer::setUpdateNeeded(bool needUpdate) { + _updateNeeded=needUpdate; + for (iterator it=begin(); it!=end(); ++it){ + (it->second)->_updateNeeded = needUpdate; + } + } + + CacheContainer::~CacheContainer(){ + for (iterator it=begin(); it!=end(); ++it){ + delete (it->second); + } + } + +} // end namespace diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/cache.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/cache.h new file mode 100644 index 0000000..c5b00a4 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/cache.h @@ -0,0 +1,140 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_CACHE_HH_ +#define G2O_CACHE_HH_ + +#include + +#include "optimizable_graph.h" + +namespace g2o { + + class CacheContainer; + + class Cache: public HyperGraph::HyperGraphElement + { + public: + friend class CacheContainer; + class CacheKey + { + public: + friend class CacheContainer; + CacheKey(); + CacheKey(const std::string& type_, const ParameterVector& parameters_); + + bool operator<(const CacheKey& c) const; + + const std::string& type() const { return _type;} + const ParameterVector& parameters() const { return _parameters;} + + protected: + std::string _type; + ParameterVector _parameters; + }; + + Cache(CacheContainer* container_ = 0, const ParameterVector& parameters_ = ParameterVector()); + + CacheKey key() const; + + OptimizableGraph::Vertex* vertex(); + OptimizableGraph* graph(); + CacheContainer* container(); + ParameterVector& parameters(); + + void update(); + + virtual HyperGraph::HyperGraphElementType elementType() const { return HyperGraph::HGET_CACHE;} + + protected: + //! redefine this to do the update + virtual void updateImpl() = 0; + + /** + * this function installs and satisfies a cache + * @param type_: the typename of the dependency + * @param parameterIndices: a vector containing the indices if the parameters + * in _parameters that will be used to assemble the Key of the cache being created + * For example if I have a cache of type C2, having parameters "A, B, and C", + * and it depends on a cache of type C1 that depends on the parameters A and C, + * the parameterIndices should contain "0, 2", since they are the positions in the + * parameter vector of C2 of the parameters needed to construct C1. + * @returns the newly created cache + */ + Cache* installDependency(const std::string& type_, const std::vector& parameterIndices); + + /** + * Function to be called from a cache that has dependencies. It just invokes a + * sequence of installDependency(). + * Although the caches returned are stored in the _parentCache vector, + * it is better that you redefine your own cache member variables, for better readability + */ + virtual bool resolveDependancies(); + + bool _updateNeeded; + ParameterVector _parameters; + std::vector _parentCaches; + CacheContainer* _container; + }; + + class CacheContainer: public std::map + { + public: + CacheContainer(OptimizableGraph::Vertex* vertex_); + virtual ~CacheContainer(); + OptimizableGraph::Vertex* vertex(); + OptimizableGraph* graph(); + Cache* findCache(const Cache::CacheKey& key); + Cache* createCache(const Cache::CacheKey& key); + void setUpdateNeeded(bool needUpdate=true); + void update(); + protected: + OptimizableGraph::Vertex* _vertex; + bool _updateNeeded; + }; + + + template + void OptimizableGraph::Edge::resolveCache(CacheType*& cache, + OptimizableGraph::Vertex* v, + const std::string& type_, + const ParameterVector& parameters_) + { + cache = 0; + CacheContainer* container= v->cacheContainer(); + Cache::CacheKey key(type_, parameters_); + Cache* c = container->findCache(key); + if (!c) { + c = container->createCache(key); + } + if (c) { + cache = dynamic_cast(c); + } + } + +} // end namespace + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/creators.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/creators.h new file mode 100644 index 0000000..9ca9967 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/creators.h @@ -0,0 +1,75 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_CREATORS_H +#define G2O_CREATORS_H + +#include "hyper_graph.h" + +#include +#include + +namespace g2o +{ + + /** + * \brief Abstract interface for allocating HyperGraphElement + */ + class AbstractHyperGraphElementCreator + { + public: + /** + * create a hyper graph element. Has to implemented in derived class. + */ + virtual HyperGraph::HyperGraphElement* construct() = 0; + /** + * name of the class to be created. Has to implemented in derived class. + */ + virtual const std::string& name() const = 0; + + virtual ~AbstractHyperGraphElementCreator() { } + }; + + /** + * \brief templatized creator class which creates graph elements + */ + template + class HyperGraphElementCreator : public AbstractHyperGraphElementCreator + { + public: + HyperGraphElementCreator() : _name(typeid(T).name()) {} +#if defined (WINDOWS) && defined(__GNUC__) // force stack alignment on Windows with GCC + __attribute__((force_align_arg_pointer)) +#endif + HyperGraph::HyperGraphElement* construct() { return new T;} + virtual const std::string& name() const { return _name;} + protected: + std::string _name; + }; + +} // end namespace + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/eigen_types.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/eigen_types.h new file mode 100644 index 0000000..f2c6856 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/eigen_types.h @@ -0,0 +1,73 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_EIGEN_TYPES_H +#define G2O_EIGEN_TYPES_H + +#include +#include + +namespace g2o { + + typedef Eigen::Matrix Vector2I; + typedef Eigen::Matrix Vector3I; + typedef Eigen::Matrix Vector4I; + typedef Eigen::Matrix VectorXI; + + typedef Eigen::Matrix Vector2F; + typedef Eigen::Matrix Vector3F; + typedef Eigen::Matrix Vector4F; + typedef Eigen::Matrix VectorXF; + + typedef Eigen::Matrix Vector2D; + typedef Eigen::Matrix Vector3D; + typedef Eigen::Matrix Vector4D; + typedef Eigen::Matrix VectorXD; + + typedef Eigen::Matrix Matrix2I; + typedef Eigen::Matrix Matrix3I; + typedef Eigen::Matrix Matrix4I; + typedef Eigen::Matrix MatrixXI; + + typedef Eigen::Matrix Matrix2F; + typedef Eigen::Matrix Matrix3F; + typedef Eigen::Matrix Matrix4F; + typedef Eigen::Matrix MatrixXF; + + typedef Eigen::Matrix Matrix2D; + typedef Eigen::Matrix Matrix3D; + typedef Eigen::Matrix Matrix4D; + typedef Eigen::Matrix MatrixXD; + + typedef Eigen::Transform Isometry2D; + typedef Eigen::Transform Isometry3D; + + typedef Eigen::Transform Affine2D; + typedef Eigen::Transform Affine3D; + +} // end namespace g2o + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/estimate_propagator.cpp b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/estimate_propagator.cpp new file mode 100644 index 0000000..010dac1 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/estimate_propagator.cpp @@ -0,0 +1,267 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#include "estimate_propagator.h" + +#include +#include +#include +#include +#include +#include + +//#define DEBUG_ESTIMATE_PROPAGATOR + +using namespace std; + +namespace g2o { + +# ifdef DEBUG_ESTIMATE_PROPAGATOR + struct FrontierLevelCmp { + bool operator()(EstimatePropagator::AdjacencyMapEntry* e1, EstimatePropagator::AdjacencyMapEntry* e2) const + { + return e1->frontierLevel() < e2->frontierLevel(); + } + }; +# endif + + EstimatePropagator::AdjacencyMapEntry::AdjacencyMapEntry() + { + reset(); + } + + void EstimatePropagator::AdjacencyMapEntry::reset() + { + _child = 0; + _parent.clear(); + _edge = 0; + _distance = numeric_limits::max(); + _frontierLevel = -1; + inQueue = false; + } + + EstimatePropagator::EstimatePropagator(OptimizableGraph* g): _graph(g) + { + for (OptimizableGraph::VertexIDMap::const_iterator it=_graph->vertices().begin(); it!=_graph->vertices().end(); ++it){ + AdjacencyMapEntry entry; + entry._child = static_cast(it->second); + _adjacencyMap.insert(make_pair(entry.child(), entry)); + } + } + + void EstimatePropagator::reset() + { + for (OptimizableGraph::VertexSet::iterator it=_visited.begin(); it!=_visited.end(); ++it){ + OptimizableGraph::Vertex* v = static_cast(*it); + AdjacencyMap::iterator at = _adjacencyMap.find(v); + assert(at != _adjacencyMap.end()); + at->second.reset(); + } + _visited.clear(); + } + + void EstimatePropagator::propagate(OptimizableGraph::Vertex* v, + const EstimatePropagator::PropagateCost& cost, + const EstimatePropagator::PropagateAction& action, + double maxDistance, + double maxEdgeCost) + { + OptimizableGraph::VertexSet vset; + vset.insert(v); + propagate(vset, cost, action, maxDistance, maxEdgeCost); + } + + void EstimatePropagator::propagate(OptimizableGraph::VertexSet& vset, + const EstimatePropagator::PropagateCost& cost, + const EstimatePropagator::PropagateAction& action, + double maxDistance, + double maxEdgeCost) + { + reset(); + + PriorityQueue frontier; + for (OptimizableGraph::VertexSet::iterator vit=vset.begin(); vit!=vset.end(); ++vit){ + OptimizableGraph::Vertex* v = static_cast(*vit); + AdjacencyMap::iterator it = _adjacencyMap.find(v); + assert(it != _adjacencyMap.end()); + it->second._distance = 0.; + it->second._parent.clear(); + it->second._frontierLevel = 0; + frontier.push(&it->second); + } + + while(! frontier.empty()){ + AdjacencyMapEntry* entry = frontier.pop(); + OptimizableGraph::Vertex* u = entry->child(); + double uDistance = entry->distance(); + //cerr << "uDistance " << uDistance << endl; + + // initialize the vertex + if (entry->_frontierLevel > 0) { + action(entry->edge(), entry->parent(), u); + } + + /* std::pair< OptimizableGraph::VertexSet::iterator, bool> insertResult = */ _visited.insert(u); + OptimizableGraph::EdgeSet::iterator et = u->edges().begin(); + while (et != u->edges().end()){ + OptimizableGraph::Edge* edge = static_cast(*et); + ++et; + + int maxFrontier = -1; + OptimizableGraph::VertexSet initializedVertices; + for (size_t i = 0; i < edge->vertices().size(); ++i) { + OptimizableGraph::Vertex* z = static_cast(edge->vertex(i)); + AdjacencyMap::iterator ot = _adjacencyMap.find(z); + if (ot->second._distance != numeric_limits::max()) { + initializedVertices.insert(z); + maxFrontier = (max)(maxFrontier, ot->second._frontierLevel); + } + } + assert(maxFrontier >= 0); + + for (size_t i = 0; i < edge->vertices().size(); ++i) { + OptimizableGraph::Vertex* z = static_cast(edge->vertex(i)); + if (z == u) + continue; + + size_t wasInitialized = initializedVertices.erase(z); + + double edgeDistance = cost(edge, initializedVertices, z); + if (edgeDistance > 0. && edgeDistance != std::numeric_limits::max() && edgeDistance < maxEdgeCost) { + double zDistance = uDistance + edgeDistance; + //cerr << z->id() << " " << zDistance << endl; + + AdjacencyMap::iterator ot = _adjacencyMap.find(z); + assert(ot!=_adjacencyMap.end()); + + if (zDistance < ot->second.distance() && zDistance < maxDistance){ + //if (ot->second.inQueue) + //cerr << "Updating" << endl; + ot->second._distance = zDistance; + ot->second._parent = initializedVertices; + ot->second._edge = edge; + ot->second._frontierLevel = maxFrontier + 1; + frontier.push(&ot->second); + } + } + + if (wasInitialized > 0) + initializedVertices.insert(z); + + } + } + } + + // writing debug information like cost for reaching each vertex and the parent used to initialize +#ifdef DEBUG_ESTIMATE_PROPAGATOR + cerr << "Writing cost.dat" << endl; + ofstream costStream("cost.dat"); + for (AdjacencyMap::const_iterator it = _adjacencyMap.begin(); it != _adjacencyMap.end(); ++it) { + HyperGraph::Vertex* u = it->second.child(); + costStream << "vertex " << u->id() << " cost " << it->second._distance << endl; + } + cerr << "Writing init.dat" << endl; + ofstream initStream("init.dat"); + vector frontierLevels; + for (AdjacencyMap::iterator it = _adjacencyMap.begin(); it != _adjacencyMap.end(); ++it) { + if (it->second._frontierLevel > 0) + frontierLevels.push_back(&it->second); + } + sort(frontierLevels.begin(), frontierLevels.end(), FrontierLevelCmp()); + for (vector::const_iterator it = frontierLevels.begin(); it != frontierLevels.end(); ++it) { + AdjacencyMapEntry* entry = *it; + OptimizableGraph::Vertex* to = entry->child(); + + initStream << "calling init level = " << entry->_frontierLevel << "\t ("; + for (OptimizableGraph::VertexSet::iterator pit = entry->parent().begin(); pit != entry->parent().end(); ++pit) { + initStream << " " << (*pit)->id(); + } + initStream << " ) -> " << to->id() << endl; + } +#endif + + } + + void EstimatePropagator::PriorityQueue::push(AdjacencyMapEntry* entry) + { + assert(entry != NULL); + if (entry->inQueue) { + assert(entry->queueIt->second == entry); + erase(entry->queueIt); + } + + entry->queueIt = insert(std::make_pair(entry->distance(), entry)); + assert(entry->queueIt != end()); + entry->inQueue = true; + } + + EstimatePropagator::AdjacencyMapEntry* EstimatePropagator::PriorityQueue::pop() + { + assert(!empty()); + iterator it = begin(); + AdjacencyMapEntry* entry = it->second; + erase(it); + + assert(entry != NULL); + entry->queueIt = end(); + entry->inQueue = false; + return entry; + } + + EstimatePropagatorCost::EstimatePropagatorCost (SparseOptimizer* graph) : + _graph(graph) + { + } + + double EstimatePropagatorCost::operator()(OptimizableGraph::Edge* edge, const OptimizableGraph::VertexSet& from, OptimizableGraph::Vertex* to_) const + { + OptimizableGraph::Edge* e = dynamic_cast(edge); + OptimizableGraph::Vertex* to = dynamic_cast(to_); + SparseOptimizer::EdgeContainer::const_iterator it = _graph->findActiveEdge(e); + if (it == _graph->activeEdges().end()) // it has to be an active edge + return std::numeric_limits::max(); + return e->initialEstimatePossible(from, to); + } + + EstimatePropagatorCostOdometry::EstimatePropagatorCostOdometry(SparseOptimizer* graph) : + EstimatePropagatorCost(graph) + { + } + + double EstimatePropagatorCostOdometry::operator()(OptimizableGraph::Edge* edge, const OptimizableGraph::VertexSet& from_, OptimizableGraph::Vertex* to_) const + { + OptimizableGraph::Edge* e = dynamic_cast(edge); + OptimizableGraph::Vertex* from = dynamic_cast(*from_.begin()); + OptimizableGraph::Vertex* to = dynamic_cast(to_); + if (std::abs(from->id() - to->id()) != 1) // simple method to identify odometry edges in a pose graph + return std::numeric_limits::max(); + SparseOptimizer::EdgeContainer::const_iterator it = _graph->findActiveEdge(e); + if (it == _graph->activeEdges().end()) // it has to be an active edge + return std::numeric_limits::max(); + return e->initialEstimatePossible(from_, to); + } + +} // end namespace diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/estimate_propagator.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/estimate_propagator.h new file mode 100644 index 0000000..6a16d11 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/estimate_propagator.h @@ -0,0 +1,175 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_ESTIMATE_PROPAGATOR_H +#define G2O_ESTIMATE_PROPAGATOR_H + +#include "optimizable_graph.h" +#include "sparse_optimizer.h" + +#include +#include +#include + +#ifdef _MSC_VER +#include +#else +#include +#endif + +namespace g2o { + + /** + * \brief cost for traversing along active edges in the optimizer + * + * You may derive an own one, if necessary. The default is to return initialEstimatePossible(from, to) for the edge. + */ + class EstimatePropagatorCost { + public: + EstimatePropagatorCost (SparseOptimizer* graph); + virtual double operator()(OptimizableGraph::Edge* edge, const OptimizableGraph::VertexSet& from, OptimizableGraph::Vertex* to_) const; + virtual const char* name() const { return "spanning tree";} + protected: + SparseOptimizer* _graph; + }; + + /** + * \brief cost for traversing only odometry edges. + * + * Initialize your graph along odometry edges. An odometry edge is assumed to connect vertices + * whose IDs only differs by one. + */ + class EstimatePropagatorCostOdometry : public EstimatePropagatorCost { + public: + EstimatePropagatorCostOdometry(SparseOptimizer* graph); + virtual double operator()(OptimizableGraph::Edge* edge, const OptimizableGraph::VertexSet& from_, OptimizableGraph::Vertex* to_) const; + virtual const char* name() const { return "odometry";} + }; + + /** + * \brief propagation of an initial guess + */ + class EstimatePropagator { + public: + + /** + * \brief Applying the action for propagating. + * + * You may derive an own one, if necessary. The default is to call initialEstimate(from, to) for the edge. + */ + struct PropagateAction { + virtual void operator()(OptimizableGraph::Edge* e, const OptimizableGraph::VertexSet& from, OptimizableGraph::Vertex* to) const + { + if (! to->fixed()) + e->initialEstimate(from, to); + } + }; + + typedef EstimatePropagatorCost PropagateCost; + + class AdjacencyMapEntry; + + /** + * \brief priority queue for AdjacencyMapEntry + */ + class PriorityQueue : public std::multimap { + public: + void push(AdjacencyMapEntry* entry); + AdjacencyMapEntry* pop(); + }; + + /** + * \brief data structure for loopuk during Dijkstra + */ + class AdjacencyMapEntry { + public: + friend class EstimatePropagator; + friend class PriorityQueue; + AdjacencyMapEntry(); + void reset(); + OptimizableGraph::Vertex* child() const {return _child;} + const OptimizableGraph::VertexSet& parent() const {return _parent;} + OptimizableGraph::Edge* edge() const {return _edge;} + double distance() const {return _distance;} + int frontierLevel() const { return _frontierLevel;} + + protected: + OptimizableGraph::Vertex* _child; + OptimizableGraph::VertexSet _parent; + OptimizableGraph::Edge* _edge; + double _distance; + int _frontierLevel; + private: // for PriorityQueue + bool inQueue; + PriorityQueue::iterator queueIt; + }; + + /** + * \brief hash function for a vertex + */ + class VertexIDHashFunction { + public: + size_t operator ()(const OptimizableGraph::Vertex* v) const { return v->id();} + }; + + typedef std::tr1::unordered_map AdjacencyMap; + + public: + EstimatePropagator(OptimizableGraph* g); + OptimizableGraph::VertexSet& visited() {return _visited; } + AdjacencyMap& adjacencyMap() {return _adjacencyMap; } + OptimizableGraph* graph() {return _graph;} + + /** + * propagate an initial guess starting from v. The function computes a spanning tree + * whereas the cost for each edge is determined by calling cost() and the action applied to + * each vertex is action(). + */ + void propagate(OptimizableGraph::Vertex* v, + const EstimatePropagator::PropagateCost& cost, + const EstimatePropagator::PropagateAction& action = PropagateAction(), + double maxDistance=std::numeric_limits::max(), + double maxEdgeCost=std::numeric_limits::max()); + + /** + * same as above but starting to propagate from a set of vertices instead of just a single one. + */ + void propagate(OptimizableGraph::VertexSet& vset, + const EstimatePropagator::PropagateCost& cost, + const EstimatePropagator::PropagateAction& action = PropagateAction(), + double maxDistance=std::numeric_limits::max(), + double maxEdgeCost=std::numeric_limits::max()); + + protected: + void reset(); + + AdjacencyMap _adjacencyMap; + OptimizableGraph::VertexSet _visited; + OptimizableGraph* _graph; + }; + +} +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/factory.cpp b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/factory.cpp new file mode 100644 index 0000000..6263ae2 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/factory.cpp @@ -0,0 +1,217 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#include "factory.h" + +#include "creators.h" +#include "parameter.h" +#include "cache.h" +#include "optimizable_graph.h" +#include "../stuff/color_macros.h" + +#include +#include +#include + +using namespace std; + +namespace g2o { + +Factory* Factory::factoryInstance = 0; + +Factory::Factory() +{ +} + +Factory::~Factory() +{ +# ifdef G2O_DEBUG_FACTORY + cerr << "# Factory destroying " << (void*)this << endl; +# endif + for (CreatorMap::iterator it = _creator.begin(); it != _creator.end(); ++it) { + delete it->second->creator; + } + _creator.clear(); + _tagLookup.clear(); +} + +Factory* Factory::instance() +{ + if (factoryInstance == 0) { + factoryInstance = new Factory; +# ifdef G2O_DEBUG_FACTORY + cerr << "# Factory allocated " << (void*)factoryInstance << endl; +# endif + } + + return factoryInstance; +} + +void Factory::registerType(const std::string& tag, AbstractHyperGraphElementCreator* c) +{ + CreatorMap::const_iterator foundIt = _creator.find(tag); + if (foundIt != _creator.end()) { + cerr << "FACTORY WARNING: Overwriting Vertex tag " << tag << endl; + assert(0); + } + TagLookup::const_iterator tagIt = _tagLookup.find(c->name()); + if (tagIt != _tagLookup.end()) { + cerr << "FACTORY WARNING: Registering same class for two tags " << c->name() << endl; + assert(0); + } + + CreatorInformation* ci = new CreatorInformation(); + ci->creator = c; + +#ifdef G2O_DEBUG_FACTORY + cerr << "# Factory " << (void*)this << " constructing type " << tag << " "; +#endif + // construct an element once to figure out its type + HyperGraph::HyperGraphElement* element = c->construct(); + ci->elementTypeBit = element->elementType(); + +#ifdef G2O_DEBUG_FACTORY + cerr << "done." << endl; + cerr << "# Factory " << (void*)this << " registering " << tag; + cerr << " " << (void*) c << " "; + switch (element->elementType()) { + case HyperGraph::HGET_VERTEX: + cerr << " -> Vertex"; + break; + case HyperGraph::HGET_EDGE: + cerr << " -> Edge"; + break; + case HyperGraph::HGET_PARAMETER: + cerr << " -> Parameter"; + break; + case HyperGraph::HGET_CACHE: + cerr << " -> Cache"; + break; + case HyperGraph::HGET_DATA: + cerr << " -> Data"; + break; + default: + assert(0 && "Unknown element type occured, fix elementTypes"); + break; + } + cerr << endl; +#endif + + _creator[tag] = ci; + _tagLookup[c->name()] = tag; + delete element; +} + + void Factory::unregisterType(const std::string& tag) + { + // Look for the tag + CreatorMap::iterator tagPosition = _creator.find(tag); + + if (tagPosition != _creator.end()) { + + AbstractHyperGraphElementCreator* c = tagPosition->second->creator; + + // If we found it, remove the creator from the tag lookup map + TagLookup::iterator classPosition = _tagLookup.find(c->name()); + if (classPosition != _tagLookup.end()) + { + _tagLookup.erase(classPosition); + } + _creator.erase(tagPosition); + } + } + +HyperGraph::HyperGraphElement* Factory::construct(const std::string& tag) const +{ + CreatorMap::const_iterator foundIt = _creator.find(tag); + if (foundIt != _creator.end()) { + //cerr << "tag " << tag << " -> " << (void*) foundIt->second->creator << " " << foundIt->second->creator->name() << endl; + return foundIt->second->creator->construct(); + } + return 0; +} + +const std::string& Factory::tag(const HyperGraph::HyperGraphElement* e) const +{ + static std::string emptyStr(""); + TagLookup::const_iterator foundIt = _tagLookup.find(typeid(*e).name()); + if (foundIt != _tagLookup.end()) + return foundIt->second; + return emptyStr; +} + +void Factory::fillKnownTypes(std::vector& types) const +{ + types.clear(); + for (CreatorMap::const_iterator it = _creator.begin(); it != _creator.end(); ++it) + types.push_back(it->first); +} + +bool Factory::knowsTag(const std::string& tag, int* elementType) const +{ + CreatorMap::const_iterator foundIt = _creator.find(tag); + if (foundIt == _creator.end()) { + if (elementType) + *elementType = -1; + return false; + } + if (elementType) + *elementType = foundIt->second->elementTypeBit; + return true; +} + +void Factory::destroy() +{ + delete factoryInstance; + factoryInstance = 0; +} + +void Factory::printRegisteredTypes(std::ostream& os, bool comment) const +{ + if (comment) + os << "# "; + os << "types:" << endl; + for (CreatorMap::const_iterator it = _creator.begin(); it != _creator.end(); ++it) { + if (comment) + os << "#"; + cerr << "\t" << it->first << endl; + } +} + +HyperGraph::HyperGraphElement* Factory::construct(const std::string& tag, const HyperGraph::GraphElemBitset& elemsToConstruct) const +{ + if (elemsToConstruct.none()) { + return construct(tag); + } + CreatorMap::const_iterator foundIt = _creator.find(tag); + if (foundIt != _creator.end() && foundIt->second->elementTypeBit >= 0 && elemsToConstruct.test(foundIt->second->elementTypeBit)) { + return foundIt->second->creator->construct(); + } + return 0; +} + +} // end namespace + diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/factory.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/factory.h new file mode 100644 index 0000000..0e189ae --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/factory.h @@ -0,0 +1,179 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_FACTORY_H +#define G2O_FACTORY_H + +#include "../../config.h" +#include "../stuff/misc.h" +#include "hyper_graph.h" +#include "creators.h" + +#include +#include +#include + +// define to get some verbose output +//#define G2O_DEBUG_FACTORY + +namespace g2o { + + class AbstractHyperGraphElementCreator; + + /** + * \brief create vertices and edges based on TAGs in, for example, a file + */ + class Factory + { + public: + + //! return the instance + static Factory* instance(); + + //! free the instance + static void destroy(); + + /** + * register a tag for a specific creator + */ + void registerType(const std::string& tag, AbstractHyperGraphElementCreator* c); + + /** + * unregister a tag for a specific creator + */ + void unregisterType(const std::string& tag); + + /** + * construct a graph element based on its tag + */ + HyperGraph::HyperGraphElement* construct(const std::string& tag) const; + + /** + * construct a graph element based on its tag, but only if it's type (a bitmask) matches. A bitmask without any + * bit set will construct any item. Otherwise a bit has to be set to allow construction of a graph element. + */ + HyperGraph::HyperGraphElement* construct(const std::string& tag, const HyperGraph::GraphElemBitset& elemsToConstruct) const; + + /** + * return whether the factory knows this tag or not + */ + bool knowsTag(const std::string& tag, int* elementType = 0) const; + + //! return the TAG given a vertex + const std::string& tag(const HyperGraph::HyperGraphElement* v) const; + + /** + * get a list of all known types + */ + void fillKnownTypes(std::vector& types) const; + + /** + * print a list of the known registered types to the given stream + */ + void printRegisteredTypes(std::ostream& os, bool comment = false) const; + + protected: + class CreatorInformation + { + public: + AbstractHyperGraphElementCreator* creator; + int elementTypeBit; + CreatorInformation() + { + creator = 0; + elementTypeBit = -1; + } + + ~CreatorInformation() + { + std::cout << "Deleting " << (void*) creator << std::endl; + + delete creator; + } + }; + + typedef std::map CreatorMap; + typedef std::map TagLookup; + Factory(); + ~Factory(); + + CreatorMap _creator; ///< look-up map for the existing creators + TagLookup _tagLookup; ///< reverse look-up, class name to tag + + private: + static Factory* factoryInstance; + }; + + template + class RegisterTypeProxy + { + public: + RegisterTypeProxy(const std::string& name) : _name(name) + { +#ifdef G2O_DEBUG_FACTORY + std::cout << __FUNCTION__ << ": Registering " << _name << " of type " << typeid(T).name() << std::endl; +#endif + Factory::instance()->registerType(_name, new HyperGraphElementCreator()); + } + + ~RegisterTypeProxy() + { +#ifdef G2O_DEBUG_FACTORY + std::cout << __FUNCTION__ << ": Unregistering " << _name << " of type " << typeid(T).name() << std::endl; +#endif + Factory::instance()->unregisterType(_name); + } + + private: + std::string _name; + }; + +#if defined _MSC_VER && defined G2O_SHARED_LIBS +# define G2O_FACTORY_EXPORT __declspec(dllexport) +# define G2O_FACTORY_IMPORT __declspec(dllimport) +#else +# define G2O_FACTORY_EXPORT +# define G2O_FACTORY_IMPORT +#endif + + // These macros are used to automate registering types and forcing linkage +#define G2O_REGISTER_TYPE(name, classname) \ + extern "C" void G2O_FACTORY_EXPORT g2o_type_##classname(void) {} \ + static g2o::RegisterTypeProxy g_type_proxy_##classname(#name); + +#define G2O_USE_TYPE_BY_CLASS_NAME(classname) \ + extern "C" void G2O_FACTORY_IMPORT g2o_type_##classname(void); \ + static g2o::ForceLinker proxy_##classname(g2o_type_##classname); + +#define G2O_REGISTER_TYPE_GROUP(typeGroupName) \ + extern "C" void G2O_FACTORY_EXPORT g2o_type_group_##typeGroupName(void) {} + +#define G2O_USE_TYPE_GROUP(typeGroupName) \ + extern "C" void G2O_FACTORY_IMPORT g2o_type_group_##typeGroupName(void); \ + static g2o::ForceLinker g2o_force_type_link_##typeGroupName(g2o_type_group_##typeGroupName); +} + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/hyper_dijkstra.cpp b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/hyper_dijkstra.cpp new file mode 100644 index 0000000..a54eca5 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/hyper_dijkstra.cpp @@ -0,0 +1,261 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#include +#include +#include +#include +#include +#include "hyper_dijkstra.h" +#include "../stuff/macros.h" + +namespace g2o{ + + using namespace std; + + double HyperDijkstra::TreeAction::perform(HyperGraph::Vertex* v, HyperGraph::Vertex* vParent, HyperGraph::Edge* e){ + (void) v; + (void) vParent; + (void) e; + return std::numeric_limits::max(); + } + + double HyperDijkstra::TreeAction::perform(HyperGraph::Vertex* v, HyperGraph::Vertex* vParent, HyperGraph::Edge* e, double distance){ + if (distance==-1) + return perform (v,vParent,e); + return std::numeric_limits::max(); + } + + HyperDijkstra::AdjacencyMapEntry::AdjacencyMapEntry(HyperGraph::Vertex* child_, HyperGraph::Vertex* parent_, + HyperGraph::Edge* edge_, double distance_) + { + _child=child_; + _parent=parent_; + _edge=edge_; + _distance=distance_; + } + + HyperDijkstra::HyperDijkstra(HyperGraph* g): _graph(g) + { + for (HyperGraph::VertexIDMap::const_iterator it=_graph->vertices().begin(); it!=_graph->vertices().end(); it++){ + AdjacencyMapEntry entry(it->second, 0,0,std::numeric_limits< double >::max()); + _adjacencyMap.insert(make_pair(entry.child(), entry)); + } + } + + void HyperDijkstra::reset() + { + for (HyperGraph::VertexSet::iterator it=_visited.begin(); it!=_visited.end(); it++){ + AdjacencyMap::iterator at=_adjacencyMap.find(*it); + assert(at!=_adjacencyMap.end()); + at->second=AdjacencyMapEntry(at->first,0,0,std::numeric_limits< double >::max()); + } + _visited.clear(); + } + + + bool operator<(const HyperDijkstra::AdjacencyMapEntry& a, const HyperDijkstra::AdjacencyMapEntry& b) + { + return a.distance()>b.distance(); + } + + + void HyperDijkstra::shortestPaths(HyperGraph::VertexSet& vset, HyperDijkstra::CostFunction* cost, + double maxDistance, double comparisonConditioner, bool directed, double maxEdgeCost) + { + reset(); + std::priority_queue< AdjacencyMapEntry > frontier; + for (HyperGraph::VertexSet::iterator vit=vset.begin(); vit!=vset.end(); ++vit){ + HyperGraph::Vertex* v=*vit; + assert(v!=0); + AdjacencyMap::iterator it=_adjacencyMap.find(v); + if (it == _adjacencyMap.end()) { + cerr << __PRETTY_FUNCTION__ << "Vertex " << v->id() << " is not in the adjacency map" << endl; + } + assert(it!=_adjacencyMap.end()); + it->second._distance=0.; + it->second._parent=0; + frontier.push(it->second); + } + + while(! frontier.empty()){ + AdjacencyMapEntry entry=frontier.top(); + frontier.pop(); + HyperGraph::Vertex* u=entry.child(); + AdjacencyMap::iterator ut=_adjacencyMap.find(u); + if (ut == _adjacencyMap.end()) { + cerr << __PRETTY_FUNCTION__ << "Vertex " << u->id() << " is not in the adjacency map" << endl; + } + assert(ut!=_adjacencyMap.end()); + double uDistance=ut->second.distance(); + + std::pair< HyperGraph::VertexSet::iterator, bool> insertResult=_visited.insert(u); (void) insertResult; + HyperGraph::EdgeSet::iterator et=u->edges().begin(); + while (et != u->edges().end()){ + HyperGraph::Edge* edge=*et; + ++et; + + if (directed && edge->vertex(0) != u) + continue; + + for (size_t i = 0; i < edge->vertices().size(); ++i) { + HyperGraph::Vertex* z = edge->vertex(i); + if (z == u) + continue; + + double edgeDistance=(*cost)(edge, u, z); + if (edgeDistance==std::numeric_limits< double >::max() || edgeDistance > maxEdgeCost) + continue; + double zDistance=uDistance+edgeDistance; + //cerr << z->id() << " " << zDistance << endl; + + AdjacencyMap::iterator ot=_adjacencyMap.find(z); + assert(ot!=_adjacencyMap.end()); + + if (zDistance+comparisonConditionersecond.distance() && zDistancesecond._distance=zDistance; + ot->second._parent=u; + ot->second._edge=edge; + frontier.push(ot->second); + } + } + } + } + } + + void HyperDijkstra::shortestPaths(HyperGraph::Vertex* v, HyperDijkstra::CostFunction* cost, double maxDistance, + double comparisonConditioner, bool directed, double maxEdgeCost) + { + HyperGraph::VertexSet vset; + vset.insert(v); + shortestPaths(vset, cost, maxDistance, comparisonConditioner, directed, maxEdgeCost); + } + + void HyperDijkstra::computeTree(AdjacencyMap& amap) + { + for (AdjacencyMap::iterator it=amap.begin(); it!=amap.end(); ++it){ + AdjacencyMapEntry& entry(it->second); + entry._children.clear(); + } + for (AdjacencyMap::iterator it=amap.begin(); it!=amap.end(); ++it){ + AdjacencyMapEntry& entry(it->second); + HyperGraph::Vertex* parent=entry.parent(); + if (!parent){ + continue; + } + HyperGraph::Vertex* v=entry.child(); + assert (v==it->first); + + AdjacencyMap::iterator pt=amap.find(parent); + assert(pt!=amap.end()); + pt->second._children.insert(v); + } + } + + + void HyperDijkstra::visitAdjacencyMap(AdjacencyMap& amap, TreeAction* action, bool useDistance) + { + + typedef std::deque Deque; + Deque q; + // scans for the vertices without the parent (whcih are the roots of the trees) and applies the action to them. + for (AdjacencyMap::iterator it=amap.begin(); it!=amap.end(); ++it){ + AdjacencyMapEntry& entry(it->second); + if (! entry.parent()) { + action->perform(it->first,0,0); + q.push_back(it->first); + } + } + + //std::cerr << "q.size()" << q.size() << endl; + int count=0; + while (! q.empty()){ + HyperGraph::Vertex* parent=q.front(); + q.pop_front(); + ++count; + AdjacencyMap::iterator parentIt=amap.find(parent); + if (parentIt==amap.end()) { + continue; + } + //cerr << "parent= " << parent << " parent id= " << parent->id() << "\t children id ="; + HyperGraph::VertexSet& childs(parentIt->second.children()); + for (HyperGraph::VertexSet::iterator childsIt=childs.begin(); childsIt!=childs.end(); ++childsIt){ + HyperGraph::Vertex* child=*childsIt; + //cerr << child->id(); + AdjacencyMap::iterator adjacencyIt=amap.find(child); + assert (adjacencyIt!=amap.end()); + HyperGraph::Edge* edge=adjacencyIt->second.edge(); + + assert(adjacencyIt->first==child); + assert(adjacencyIt->second.child()==child); + assert(adjacencyIt->second.parent()==parent); + if (! useDistance) { + action->perform(child, parent, edge); + } else { + action->perform(child, parent, edge, adjacencyIt->second.distance()); + } + q.push_back(child); + } + //cerr << endl; + } + + } + + void HyperDijkstra::connectedSubset(HyperGraph::VertexSet& connected, HyperGraph::VertexSet& visited, + HyperGraph::VertexSet& startingSet, + HyperGraph* g, HyperGraph::Vertex* v, + HyperDijkstra::CostFunction* cost, double distance, + double comparisonConditioner, double maxEdgeCost) + { + typedef std::queue VertexDeque; + visited.clear(); + connected.clear(); + VertexDeque frontier; + HyperDijkstra dv(g); + connected.insert(v); + frontier.push(v); + while (! frontier.empty()){ + HyperGraph::Vertex* v0=frontier.front(); + frontier.pop(); + dv.shortestPaths(v0, cost, distance, comparisonConditioner, false, maxEdgeCost); + for (HyperGraph::VertexSet::iterator it=dv.visited().begin(); it!=dv.visited().end(); ++it){ + visited.insert(*it); + if (startingSet.find(*it)==startingSet.end()) + continue; + std::pair insertOutcome=connected.insert(*it); + if (insertOutcome.second){ // the node was not in the connectedSet; + frontier.push(dynamic_cast(*it)); + } + } + } + } + + double UniformCostFunction::operator () (HyperGraph::Edge* /*edge*/, HyperGraph::Vertex* /*from*/, HyperGraph::Vertex* /*to*/) + { + return 1.; + } + +}; diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/hyper_dijkstra.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/hyper_dijkstra.h new file mode 100644 index 0000000..fe2c2f4 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/hyper_dijkstra.h @@ -0,0 +1,112 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_AIS_GENERAL_DIJKSTRA_HH +#define G2O_AIS_GENERAL_DIJKSTRA_HH + +#include +#include +#include + +#include "hyper_graph.h" + +namespace g2o{ + + struct HyperDijkstra{ + struct CostFunction { + virtual double operator() (HyperGraph::Edge* e, HyperGraph::Vertex* from, HyperGraph::Vertex* to)=0; + virtual ~CostFunction() { } + }; + + struct TreeAction { + virtual double perform(HyperGraph::Vertex* v, HyperGraph::Vertex* vParent, HyperGraph::Edge* e); + virtual double perform(HyperGraph::Vertex* v, HyperGraph::Vertex* vParent, HyperGraph::Edge* e, double distance); + }; + + + struct AdjacencyMapEntry{ + friend struct HyperDijkstra; + AdjacencyMapEntry(HyperGraph::Vertex* _child=0, + HyperGraph::Vertex* _parent=0, + HyperGraph::Edge* _edge=0, + double _distance=std::numeric_limits::max()); + HyperGraph::Vertex* child() const {return _child;} + HyperGraph::Vertex* parent() const {return _parent;} + HyperGraph::Edge* edge() const {return _edge;} + double distance() const {return _distance;} + HyperGraph::VertexSet& children() {return _children;} + const HyperGraph::VertexSet& children() const {return _children;} + protected: + HyperGraph::Vertex* _child; + HyperGraph::Vertex* _parent; + HyperGraph::Edge* _edge; + double _distance; + HyperGraph::VertexSet _children; + }; + + typedef std::map AdjacencyMap; + HyperDijkstra(HyperGraph* g); + HyperGraph::VertexSet& visited() {return _visited; } + AdjacencyMap& adjacencyMap() {return _adjacencyMap; } + HyperGraph* graph() {return _graph;} + + void shortestPaths(HyperGraph::Vertex* v, + HyperDijkstra::CostFunction* cost, + double maxDistance=std::numeric_limits< double >::max(), + double comparisonConditioner=1e-3, + bool directed=false, + double maxEdgeCost=std::numeric_limits< double >::max()); + + void shortestPaths(HyperGraph::VertexSet& vset, + HyperDijkstra::CostFunction* cost, + double maxDistance=std::numeric_limits< double >::max(), + double comparisonConditioner=1e-3, + bool directed=false, + double maxEdgeCost=std::numeric_limits< double >::max()); + + + static void computeTree(AdjacencyMap& amap); + static void visitAdjacencyMap(AdjacencyMap& amap, TreeAction* action, bool useDistance=false); + static void connectedSubset(HyperGraph::VertexSet& connected, HyperGraph::VertexSet& visited, + HyperGraph::VertexSet& startingSet, + HyperGraph* g, HyperGraph::Vertex* v, + HyperDijkstra::CostFunction* cost, double distance, double comparisonConditioner, + double maxEdgeCost=std::numeric_limits< double >::max() ); + + protected: + void reset(); + + AdjacencyMap _adjacencyMap; + HyperGraph::VertexSet _visited; + HyperGraph* _graph; + }; + + struct UniformCostFunction: public HyperDijkstra::CostFunction { + virtual double operator ()(HyperGraph::Edge* edge, HyperGraph::Vertex* from, HyperGraph::Vertex* to); + }; + +} +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/hyper_graph.cpp b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/hyper_graph.cpp new file mode 100644 index 0000000..1e1ea76 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/hyper_graph.cpp @@ -0,0 +1,166 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#include "hyper_graph.h" + +#include +#include + +namespace g2o { + + HyperGraph::Vertex::Vertex(int id) : _id(id) + { + } + + HyperGraph::Vertex::~Vertex() + { + } + + HyperGraph::Edge::Edge(int id) : _id(id) + { + } + + HyperGraph::Edge::~Edge() + { + } + + void HyperGraph::Edge::resize(size_t size) + { + _vertices.resize(size, 0); + } + + void HyperGraph::Edge::setId(int id) + { + _id = id; + } + + HyperGraph::Vertex* HyperGraph::vertex(int id) + { + VertexIDMap::iterator it=_vertices.find(id); + if (it==_vertices.end()) + return 0; + return it->second; + } + + const HyperGraph::Vertex* HyperGraph::vertex(int id) const + { + VertexIDMap::const_iterator it=_vertices.find(id); + if (it==_vertices.end()) + return 0; + return it->second; + } + + bool HyperGraph::addVertex(Vertex* v) + { + Vertex* vn=vertex(v->id()); + if (vn) + return false; + _vertices.insert( std::make_pair(v->id(),v) ); + return true; + } + + /** + * changes the id of a vertex already in the graph, and updates the bookkeeping + @ returns false if the vertex is not in the graph; + */ + bool HyperGraph::changeId(Vertex* v, int newId){ + Vertex* v2 = vertex(v->id()); + if (v != v2) + return false; + _vertices.erase(v->id()); + v->setId(newId); + _vertices.insert(std::make_pair(v->id(), v)); + return true; + } + + bool HyperGraph::addEdge(Edge* e) + { + std::pair result = _edges.insert(e); + if (! result.second) + return false; + for (std::vector::iterator it = e->vertices().begin(); it != e->vertices().end(); ++it) { + Vertex* v = *it; + v->edges().insert(e); + } + return true; + } + + bool HyperGraph::removeVertex(Vertex* v) + { + VertexIDMap::iterator it=_vertices.find(v->id()); + if (it==_vertices.end()) + return false; + assert(it->second==v); + //remove all edges which are entering or leaving v; + EdgeSet tmp(v->edges()); + for (EdgeSet::iterator it=tmp.begin(); it!=tmp.end(); ++it){ + if (!removeEdge(*it)){ + assert(0); + } + } + _vertices.erase(it); + delete v; + return true; + } + + bool HyperGraph::removeEdge(Edge* e) + { + EdgeSet::iterator it = _edges.find(e); + if (it == _edges.end()) + return false; + _edges.erase(it); + + for (std::vector::iterator vit = e->vertices().begin(); vit != e->vertices().end(); ++vit) { + Vertex* v = *vit; + it = v->edges().find(e); + assert(it!=v->edges().end()); + v->edges().erase(it); + } + + delete e; + return true; + } + + HyperGraph::HyperGraph() + { + } + + void HyperGraph::clear() + { + for (VertexIDMap::iterator it=_vertices.begin(); it!=_vertices.end(); ++it) + delete (it->second); + for (EdgeSet::iterator it=_edges.begin(); it!=_edges.end(); ++it) + delete (*it); + _vertices.clear(); + _edges.clear(); + } + + HyperGraph::~HyperGraph() + { + clear(); + } + +} // end namespace diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/hyper_graph.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/hyper_graph.h new file mode 100644 index 0000000..da6bb3d --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/hyper_graph.h @@ -0,0 +1,220 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_AIS_HYPER_GRAPH_HH +#define G2O_AIS_HYPER_GRAPH_HH + +#include +#include +#include +#include +#include +#include +#include + +#ifdef _MSC_VER +#include +#else +#include +#endif + + +/** @addtogroup graph */ +//@{ +namespace g2o { + + /** + Class that models a directed Hyper-Graph. An hyper graph is a graph where an edge + can connect one or more nodes. Both Vertices and Edges of an hyoper graph + derive from the same class HyperGraphElement, thus one can implement generic algorithms + that operate transparently on edges or vertices (see HyperGraphAction). + + The vertices are uniquely identified by an int id, while the edges are + identfied by their pointers. + */ + class HyperGraph + { + public: + + /** + * \brief enum of all the types we have in our graphs + */ + enum HyperGraphElementType { + HGET_VERTEX, + HGET_EDGE, + HGET_PARAMETER, + HGET_CACHE, + HGET_DATA, + HGET_NUM_ELEMS // keep as last elem + }; + + typedef std::bitset GraphElemBitset; + + class Vertex; + class Edge; + + /** + * base hyper graph element, specialized in vertex and edge + */ + struct HyperGraphElement { + virtual ~HyperGraphElement() {} + /** + * returns the type of the graph element, see HyperGraphElementType + */ + virtual HyperGraphElementType elementType() const = 0; + }; + + typedef std::set EdgeSet; + typedef std::set VertexSet; + + typedef std::tr1::unordered_map VertexIDMap; + typedef std::vector VertexContainer; + + //! abstract Vertex, your types must derive from that one + class Vertex : public HyperGraphElement { + public: + //! creates a vertex having an ID specified by the argument + explicit Vertex(int id=-1); + virtual ~Vertex(); + //! returns the id + int id() const {return _id;} + virtual void setId( int newId) { _id=newId; } + //! returns the set of hyper-edges that are leaving/entering in this vertex + const EdgeSet& edges() const {return _edges;} + //! returns the set of hyper-edges that are leaving/entering in this vertex + EdgeSet& edges() {return _edges;} + virtual HyperGraphElementType elementType() const { return HGET_VERTEX;} + protected: + int _id; + EdgeSet _edges; + }; + + /** + * Abstract Edge class. Your nice edge classes should inherit from that one. + * An hyper-edge has pointers to the vertices it connects and stores them in a vector. + */ + class Edge : public HyperGraphElement { + public: + //! creates and empty edge with no vertices + explicit Edge(int id = -1); + virtual ~Edge(); + + /** + * resizes the number of vertices connected by this edge + */ + virtual void resize(size_t size); + /** + returns the vector of pointers to the vertices connected by the hyper-edge. + */ + const VertexContainer& vertices() const { return _vertices;} + /** + returns the vector of pointers to the vertices connected by the hyper-edge. + */ + VertexContainer& vertices() { return _vertices;} + /** + returns the pointer to the ith vertex connected to the hyper-edge. + */ + const Vertex* vertex(size_t i) const { assert(i < _vertices.size() && "index out of bounds"); return _vertices[i];} + /** + returns the pointer to the ith vertex connected to the hyper-edge. + */ + Vertex* vertex(size_t i) { assert(i < _vertices.size() && "index out of bounds"); return _vertices[i];} + /** + set the ith vertex on the hyper-edge to the pointer supplied + */ + void setVertex(size_t i, Vertex* v) { assert(i < _vertices.size() && "index out of bounds"); _vertices[i]=v;} + + int id() const {return _id;} + void setId(int id); + virtual HyperGraphElementType elementType() const { return HGET_EDGE;} + protected: + VertexContainer _vertices; + int _id; ///< unique id + }; + + public: + //! constructs an empty hyper graph + HyperGraph(); + //! destroys the hyper-graph and all the vertices of the graph + virtual ~HyperGraph(); + + //! returns a vertex id in the hyper-graph, or 0 if the vertex id is not present + Vertex* vertex(int id); + //! returns a vertex id in the hyper-graph, or 0 if the vertex id is not present + const Vertex* vertex(int id) const; + + //! removes a vertex from the graph. Returns true on success (vertex was present) + virtual bool removeVertex(Vertex* v); + //! removes a vertex from the graph. Returns true on success (edge was present) + virtual bool removeEdge(Edge* e); + //! clears the graph and empties all structures. + virtual void clear(); + + //! @returns the map id -> vertex where the vertices are stored + const VertexIDMap& vertices() const {return _vertices;} + //! @returns the map id -> vertex where the vertices are stored + VertexIDMap& vertices() {return _vertices;} + + //! @returns the set of edges of the hyper graph + const EdgeSet& edges() const {return _edges;} + //! @returns the set of edges of the hyper graph + EdgeSet& edges() {return _edges;} + + /** + * adds a vertex to the graph. The id of the vertex should be set before + * invoking this function. the function fails if another vertex + * with the same id is already in the graph. + * returns true, on success, or false on failure. + */ + virtual bool addVertex(Vertex* v); + + /** + * Adds an edge to the graph. If the edge is already in the graph, it + * does nothing and returns false. Otherwise it returns true. + */ + virtual bool addEdge(Edge* e); + + /** + * changes the id of a vertex already in the graph, and updates the bookkeeping + @ returns false if the vertex is not in the graph; + */ + virtual bool changeId(Vertex* v, int newId); + + protected: + VertexIDMap _vertices; + EdgeSet _edges; + + private: + // Disable the copy constructor and assignment operator + HyperGraph(const HyperGraph&) { } + HyperGraph& operator= (const HyperGraph&) { return *this; } + }; + +} // end namespace + +//@} + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/hyper_graph_action.cpp b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/hyper_graph_action.cpp new file mode 100644 index 0000000..1fe2439 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/hyper_graph_action.cpp @@ -0,0 +1,268 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#include "hyper_graph_action.h" +#include "optimizable_graph.h" +#include "../stuff/macros.h" + + +#include + +namespace g2o { + using namespace std; + + HyperGraphActionLibrary* HyperGraphActionLibrary::actionLibInstance = 0; + + HyperGraphAction::Parameters::~Parameters() + { + } + + HyperGraphAction::ParametersIteration::ParametersIteration(int iter) : + HyperGraphAction::Parameters(), + iteration(iter) + { + } + + HyperGraphAction::~HyperGraphAction() + { + } + + HyperGraphAction* HyperGraphAction::operator()(const HyperGraph*, Parameters*) + { + return 0; + } + + HyperGraphElementAction::Parameters::~Parameters() + { + } + + HyperGraphElementAction::HyperGraphElementAction(const std::string& typeName_) + { + _typeName = typeName_; + } + + void HyperGraphElementAction::setTypeName(const std::string& typeName_) + { + _typeName = typeName_; + } + + + HyperGraphElementAction* HyperGraphElementAction::operator()(HyperGraph::HyperGraphElement* , HyperGraphElementAction::Parameters* ) + { + return 0; + } + + HyperGraphElementAction* HyperGraphElementAction::operator()(const HyperGraph::HyperGraphElement* , HyperGraphElementAction::Parameters* ) + { + return 0; + } + + HyperGraphElementAction::~HyperGraphElementAction() + { + } + + HyperGraphElementActionCollection::HyperGraphElementActionCollection(const std::string& name_) + { + _name = name_; + } + + HyperGraphElementActionCollection::~HyperGraphElementActionCollection() + { + for (ActionMap::iterator it = _actionMap.begin(); it != _actionMap.end(); ++it) { + delete it->second; + } + } + + HyperGraphElementAction* HyperGraphElementActionCollection::operator()(HyperGraph::HyperGraphElement* element, HyperGraphElementAction::Parameters* params) + { + ActionMap::iterator it=_actionMap.find(typeid(*element).name()); + //cerr << typeid(*element).name() << endl; + if (it==_actionMap.end()) + return 0; + HyperGraphElementAction* action=it->second; + return (*action)(element, params); + } + + HyperGraphElementAction* HyperGraphElementActionCollection::operator()(const HyperGraph::HyperGraphElement* element, HyperGraphElementAction::Parameters* params) + { + ActionMap::iterator it=_actionMap.find(typeid(*element).name()); + if (it==_actionMap.end()) + return 0; + HyperGraphElementAction* action=it->second; + return (*action)(element, params); + } + + bool HyperGraphElementActionCollection::registerAction(HyperGraphElementAction* action) + { +# ifdef G2O_DEBUG_ACTIONLIB + cerr << __PRETTY_FUNCTION__ << " " << action->name() << " " << action->typeName() << endl; +# endif + if (action->name()!=name()){ + cerr << __PRETTY_FUNCTION__ << ": invalid attempt to register an action in a collection with a different name " << name() << " " << action->name() << endl; + } + _actionMap.insert(make_pair ( action->typeName(), action) ); + return true; + } + + bool HyperGraphElementActionCollection::unregisterAction(HyperGraphElementAction* action) + { + for (HyperGraphElementAction::ActionMap::iterator it=_actionMap.begin(); it != _actionMap.end(); ++it) { + if (it->second == action){ + _actionMap.erase(it); + return true; + } + } + return false; + } + + HyperGraphActionLibrary::HyperGraphActionLibrary() + { + } + + HyperGraphActionLibrary* HyperGraphActionLibrary::instance() + { + if (actionLibInstance == 0) { + actionLibInstance = new HyperGraphActionLibrary; + } + return actionLibInstance; + } + + void HyperGraphActionLibrary::destroy() + { + delete actionLibInstance; + actionLibInstance = 0; + } + + HyperGraphActionLibrary::~HyperGraphActionLibrary() + { + for (HyperGraphElementAction::ActionMap::iterator it = _actionMap.begin(); it != _actionMap.end(); ++it) { + delete it->second; + } + } + + HyperGraphElementAction* HyperGraphActionLibrary::actionByName(const std::string& name) + { + HyperGraphElementAction::ActionMap::iterator it=_actionMap.find(name); + if (it!=_actionMap.end()) + return it->second; + return 0; + } + + bool HyperGraphActionLibrary::registerAction(HyperGraphElementAction* action) + { + HyperGraphElementAction* oldAction = actionByName(action->name()); + HyperGraphElementActionCollection* collection = 0; + if (oldAction) { + collection = dynamic_cast(oldAction); + if (! collection) { + cerr << __PRETTY_FUNCTION__ << ": fatal error, a collection is not at the first level in the library" << endl; + return 0; + } + } + if (! collection) { +#ifdef G2O_DEBUG_ACTIONLIB + cerr << __PRETTY_FUNCTION__ << ": creating collection for \"" << action->name() << "\"" << endl; +#endif + collection = new HyperGraphElementActionCollection(action->name()); + _actionMap.insert(make_pair(action->name(), collection)); + } + return collection->registerAction(action); + } + + bool HyperGraphActionLibrary::unregisterAction(HyperGraphElementAction* action) + { + list collectionDeleteList; + + // Search all the collections and delete the registered actions; if a collection becomes empty, schedule it for deletion; note that we can't delete the collections as we go because this will screw up the state of the iterators + for (HyperGraphElementAction::ActionMap::iterator it=_actionMap.begin(); it != _actionMap.end(); ++it) { + HyperGraphElementActionCollection* collection = dynamic_cast (it->second); + if (collection != 0) { + collection->unregisterAction(action); + if (collection->actionMap().size() == 0) { + collectionDeleteList.push_back(collection); + } + } + } + + // Delete any empty action collections + for (list::iterator itc = collectionDeleteList.begin(); itc != collectionDeleteList.end(); ++itc) { + //cout << "Deleting collection " << (*itc)->name() << endl; + _actionMap.erase((*itc)->name()); + } + + return true; + } + + + WriteGnuplotAction::WriteGnuplotAction(const std::string& typeName_) + : HyperGraphElementAction(typeName_) + { + _name="writeGnuplot"; + } + + DrawAction::Parameters::Parameters(){ + } + + DrawAction::DrawAction(const std::string& typeName_) + : HyperGraphElementAction(typeName_) + { + _name="draw"; + _previousParams = (Parameters*)0x42; + refreshPropertyPtrs(0); + } + + bool DrawAction::refreshPropertyPtrs(HyperGraphElementAction::Parameters* params_){ + if (_previousParams == params_) + return false; + DrawAction::Parameters* p=dynamic_cast(params_); + if (! p){ + _previousParams = 0; + _show = 0; + _showId = 0; + } else { + _previousParams = p; + _show = p->makeProperty(_typeName+"::SHOW", true); + _showId = p->makeProperty(_typeName+"::SHOW_ID", false); + } + return true; + } + + void applyAction(HyperGraph* graph, HyperGraphElementAction* action, HyperGraphElementAction::Parameters* params, const std::string& typeName) + { + for (HyperGraph::VertexIDMap::iterator it=graph->vertices().begin(); + it!=graph->vertices().end(); ++it){ + if ( typeName.empty() || typeid(*it->second).name()==typeName){ + (*action)(it->second, params); + } + } + for (HyperGraph::EdgeSet::iterator it=graph->edges().begin(); + it!=graph->edges().end(); ++it){ + if ( typeName.empty() || typeid(**it).name()==typeName) + (*action)(*it, params); + } + } + +} // end namespace diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/hyper_graph_action.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/hyper_graph_action.h new file mode 100644 index 0000000..21417c9 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/hyper_graph_action.h @@ -0,0 +1,222 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_HYPER_GRAPH_ACTION_H +#define G2O_HYPER_GRAPH_ACTION_H + +#include "hyper_graph.h" +#include "../stuff/property.h" + +#include +#include +#include +#include +#include + + +// define to get verbose output +//#define G2O_DEBUG_ACTIONLIB + +namespace g2o { + + /** + * \brief Abstract action that operates on an entire graph + */ + class HyperGraphAction { + public: + class Parameters { + public: + virtual ~Parameters(); + }; + + class ParametersIteration : public Parameters { + public: + explicit ParametersIteration(int iter); + int iteration; + }; + + virtual ~HyperGraphAction(); + + /** + * re-implement to carry out an action given the graph + */ + virtual HyperGraphAction* operator()(const HyperGraph* graph, Parameters* parameters = 0); + }; + + /** + * \brief Abstract action that operates on a graph entity + */ + class HyperGraphElementAction{ + public: + struct Parameters{ + virtual ~Parameters(); + }; + typedef std::map ActionMap; + //! an action should be instantiated with the typeid.name of the graph element + //! on which it operates + HyperGraphElementAction(const std::string& typeName_=""); + + //! redefine this to do the action stuff. If successful, the action returns a pointer to itself + virtual HyperGraphElementAction* operator()(HyperGraph::HyperGraphElement* element, Parameters* parameters); + + //! redefine this to do the action stuff. If successful, the action returns a pointer to itself + virtual HyperGraphElementAction* operator()(const HyperGraph::HyperGraphElement* element, Parameters* parameters); + + //! destroyed actions release the memory + virtual ~HyperGraphElementAction(); + + //! returns the typeid name of the action + const std::string& typeName() const { return _typeName;} + + //! returns the name of an action, e.g "draw" + const std::string& name() const{ return _name;} + + //! sets the type on which an action has to operate + void setTypeName(const std::string& typeName_); + + protected: + std::string _typeName; + std::string _name; + }; + + /** + * \brief collection of actions + * + * collection of actions calls contains homogeneous actions operating on different types + * all collected actions have the same name and should have the same functionality + */ + class HyperGraphElementActionCollection: public HyperGraphElementAction{ + public: + //! constructor. name_ is the name of the action e.g.draw). + HyperGraphElementActionCollection(const std::string& name_); + //! destructor: it deletes all actions in the pool. + virtual ~HyperGraphElementActionCollection(); + //! calling functions, they return a pointer to the instance of action in actionMap + //! that was active on element + virtual HyperGraphElementAction* operator()(HyperGraph::HyperGraphElement* element, Parameters* parameters); + virtual HyperGraphElementAction* operator()(const HyperGraph::HyperGraphElement* element, Parameters* parameters); + ActionMap& actionMap() {return _actionMap;} + //! inserts an action in the pool. The action should have the same name of the container. + //! returns false on failure (the container has a different name than the action); + bool registerAction(HyperGraphElementAction* action); + bool unregisterAction(HyperGraphElementAction* action); + protected: + ActionMap _actionMap; + }; + + /** + * \brief library of actions, indexed by the action name; + * + * library of actions, indexed by the action name; + * one can use ti to register a collection of actions + */ + class HyperGraphActionLibrary{ + public: + //! return the single instance of the HyperGraphActionLibrary + static HyperGraphActionLibrary* instance(); + //! free the instance + static void destroy(); + + // returns a pointer to a collection indexed by name + HyperGraphElementAction* actionByName(const std::string& name); + // registers a basic action in the pool. If necessary a container is created + bool registerAction(HyperGraphElementAction* action); + bool unregisterAction(HyperGraphElementAction* action); + + inline HyperGraphElementAction::ActionMap& actionMap() {return _actionMap;} + protected: + HyperGraphActionLibrary(); + ~HyperGraphActionLibrary(); + HyperGraphElementAction::ActionMap _actionMap; + private: + static HyperGraphActionLibrary* actionLibInstance; + }; + + /** + * apply an action to all the elements of the graph. + */ + void applyAction(HyperGraph* graph, HyperGraphElementAction* action, HyperGraphElementAction::Parameters* parameters=0, const std::string& typeName=""); + + /** + * brief write into gnuplot + */ + class WriteGnuplotAction: public HyperGraphElementAction{ + public: + struct Parameters: public HyperGraphElementAction::Parameters{ + std::ostream* os; + }; + WriteGnuplotAction(const std::string& typeName_); + }; + + /** + * \brief draw actions + */ + + class DrawAction : public HyperGraphElementAction{ + public: + class Parameters: public HyperGraphElementAction::Parameters, public PropertyMap{ + public: + Parameters(); + }; + DrawAction(const std::string& typeName_); + protected: + virtual bool refreshPropertyPtrs(HyperGraphElementAction::Parameters* params_); + Parameters* _previousParams; + BoolProperty* _show; + BoolProperty* _showId; + }; + + template class RegisterActionProxy + { + public: + RegisterActionProxy() + { +#ifdef G2O_DEBUG_ACTIONLIB + std::cout << __FUNCTION__ << ": Registering action of type " << typeid(T).name() << std::endl; +#endif + _action = new T(); + HyperGraphActionLibrary::instance()->registerAction(_action); + } + + ~RegisterActionProxy() + { +#ifdef G2O_DEBUG_ACTIONLIB + std::cout << __FUNCTION__ << ": Unregistering action of type " << typeid(T).name() << std::endl; +#endif + HyperGraphActionLibrary::instance()->unregisterAction(_action); + delete _action; + } + + private: + HyperGraphElementAction* _action; + }; + +#define G2O_REGISTER_ACTION(classname) \ + extern "C" void g2o_action_##classname(void) {} \ + static g2o::RegisterActionProxy g_action_proxy_##classname; +}; + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/jacobian_workspace.cpp b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/jacobian_workspace.cpp new file mode 100644 index 0000000..9890a18 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/jacobian_workspace.cpp @@ -0,0 +1,89 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#include "jacobian_workspace.h" + +#include + +#include "optimizable_graph.h" + +using namespace std; + +namespace g2o { + +JacobianWorkspace::JacobianWorkspace() : + _maxNumVertices(-1), _maxDimension(-1) +{ +} + +JacobianWorkspace::~JacobianWorkspace() +{ +} + +bool JacobianWorkspace::allocate() +{ + //cerr << __PRETTY_FUNCTION__ << " " << PVAR(this) << " " << PVAR(_maxNumVertices) << " " << PVAR(_maxDimension) << endl; + if (_maxNumVertices <=0 || _maxDimension <= 0) + return false; + _workspace.resize(_maxNumVertices); + for (WorkspaceVector::iterator it = _workspace.begin(); it != _workspace.end(); ++it) { + it->resize(_maxDimension); + it->setZero(); + } + return true; +} + +void JacobianWorkspace::updateSize(const HyperGraph::Edge* e_) +{ + const OptimizableGraph::Edge* e = static_cast(e_); + int errorDimension = e->dimension(); + int numVertices = e->vertices().size(); + int maxDimensionForEdge = -1; + for (int i = 0; i < numVertices; ++i) { + const OptimizableGraph::Vertex* v = static_cast(e->vertex(i)); + assert(v && "Edge has no vertex assigned"); + maxDimensionForEdge = max(v->dimension() * errorDimension, maxDimensionForEdge); + } + _maxNumVertices = max(numVertices, _maxNumVertices); + _maxDimension = max(maxDimensionForEdge, _maxDimension); + //cerr << __PRETTY_FUNCTION__ << " " << PVAR(this) << " " << PVAR(_maxNumVertices) << " " << PVAR(_maxDimension) << endl; +} + +void JacobianWorkspace::updateSize(const OptimizableGraph& graph) +{ + for (OptimizableGraph::EdgeSet::const_iterator it = graph.edges().begin(); it != graph.edges().end(); ++it) { + const OptimizableGraph::Edge* e = static_cast(*it); + updateSize(e); + } +} + +void JacobianWorkspace::updateSize(int numVertices, int dimension) +{ + _maxNumVertices = max(numVertices, _maxNumVertices); + _maxDimension = max(dimension, _maxDimension); +} + +} // end namespace diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/jacobian_workspace.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/jacobian_workspace.h new file mode 100644 index 0000000..e1f1602 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/jacobian_workspace.h @@ -0,0 +1,96 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef JACOBIAN_WORKSPACE_H +#define JACOBIAN_WORKSPACE_H + +#include +#include + +#include +#include + +#include "hyper_graph.h" + +namespace g2o { + + struct OptimizableGraph; + + /** + * \brief provide memory workspace for computing the Jacobians + * + * The workspace is used by an OptimizableGraph to provide temporary memory + * for computing the Jacobian of the error functions. + * Before calling linearizeOplus on an edge, the workspace needs to be allocated + * by calling allocate(). + */ + class JacobianWorkspace + { + public: + typedef std::vector > WorkspaceVector; + + public: + JacobianWorkspace(); + ~JacobianWorkspace(); + + /** + * allocate the workspace + */ + bool allocate(); + + /** + * update the maximum required workspace needed by taking into account this edge + */ + void updateSize(const HyperGraph::Edge* e); + + /** + * update the required workspace by looking at a full graph + */ + void updateSize(const OptimizableGraph& graph); + + /** + * manually update with the given parameters + */ + void updateSize(int numVertices, int dimension); + + /** + * return the workspace for a vertex in an edge + */ + double* workspaceForVertex(int vertexIndex) + { + assert(vertexIndex >= 0 && (size_t)vertexIndex < _workspace.size() && "Index out of bounds"); + return _workspace[vertexIndex].data(); + } + + protected: + WorkspaceVector _workspace; ///< the memory pre-allocated for computing the Jacobians + int _maxNumVertices; ///< the maximum number of vertices connected by a hyper-edge + int _maxDimension; ///< the maximum dimension (number of elements) for a Jacobian + }; + +} // end namespace + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/linear_solver.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/linear_solver.h new file mode 100644 index 0000000..20213d4 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/linear_solver.h @@ -0,0 +1,109 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_LINEAR_SOLVER_H +#define G2O_LINEAR_SOLVER_H +#include "sparse_block_matrix.h" +#include "sparse_block_matrix_ccs.h" + +namespace g2o { + +/** + * \brief basic solver for Ax = b + * + * basic solver for Ax = b which has to reimplemented for different linear algebra libraries. + * A is assumed to be symmetric (only upper triangular block is stored) and positive-semi-definit. + */ +template +class LinearSolver +{ + public: + LinearSolver() {}; + virtual ~LinearSolver() {} + + /** + * init for operating on matrices with a different non-zero pattern like before + */ + virtual bool init() = 0; + + /** + * Assumes that A is the same matrix for several calls. + * Among other assumptions, the non-zero pattern does not change! + * If the matrix changes call init() before. + * solve system Ax = b, x and b have to allocated beforehand!! + */ + virtual bool solve(const SparseBlockMatrix& A, double* x, double* b) = 0; + + /** + * Inverts the diagonal blocks of A + * @returns false if not defined. + */ + virtual bool solveBlocks(double**&blocks, const SparseBlockMatrix& A) { (void)blocks; (void) A; return false; } + + + /** + * Inverts the a block pattern of A in spinv + * @returns false if not defined. + */ + virtual bool solvePattern(SparseBlockMatrix& spinv, const std::vector >& blockIndices, const SparseBlockMatrix& A){ + (void) spinv; + (void) blockIndices; + (void) A; + return false; + } + + //! write a debug dump of the system matrix if it is not PSD in solve + virtual bool writeDebug() const { return false;} + virtual void setWriteDebug(bool) {} +}; + +/** + * \brief Solver with faster iterating structure for the linear matrix + */ +template +class LinearSolverCCS : public LinearSolver +{ + public: + LinearSolverCCS() : LinearSolver(), _ccsMatrix(0) {} + ~LinearSolverCCS() + { + delete _ccsMatrix; + } + + protected: + SparseBlockMatrixCCS* _ccsMatrix; + + void initMatrixStructure(const SparseBlockMatrix& A) + { + delete _ccsMatrix; + _ccsMatrix = new SparseBlockMatrixCCS(A.rowBlockIndices(), A.colBlockIndices()); + A.fillSparseBlockMatrixCCS(*_ccsMatrix); + } +}; + +} // end namespace + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/marginal_covariance_cholesky.cpp b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/marginal_covariance_cholesky.cpp new file mode 100644 index 0000000..bc11f5c --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/marginal_covariance_cholesky.cpp @@ -0,0 +1,222 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#include "marginal_covariance_cholesky.h" + +#include +#include +using namespace std; + +namespace g2o { + +struct MatrixElem +{ + int r, c; + MatrixElem(int r_, int c_) : r(r_), c(c_) {} + bool operator<(const MatrixElem& other) const + { + return c > other.c || (c == other.c && r > other.r); + } +}; + +MarginalCovarianceCholesky::MarginalCovarianceCholesky() : + _n(0), _Ap(0), _Ai(0), _Ax(0), _perm(0) +{ +} + +MarginalCovarianceCholesky::~MarginalCovarianceCholesky() +{ +} + +void MarginalCovarianceCholesky::setCholeskyFactor(int n, int* Lp, int* Li, double* Lx, int* permInv) +{ + _n = n; + _Ap = Lp; + _Ai = Li; + _Ax = Lx; + _perm = permInv; + + // pre-compute reciprocal values of the diagonal of L + _diag.resize(n); + for (int r = 0; r < n; ++r) { + const int& sc = _Ap[r]; // L is lower triangular, thus the first elem in the column is the diagonal entry + assert(r == _Ai[sc] && "Error in CCS storage of L"); + _diag[r] = 1.0 / _Ax[sc]; + } +} + +double MarginalCovarianceCholesky::computeEntry(int r, int c) +{ + assert(r <= c); + int idx = computeIndex(r, c); + + LookupMap::const_iterator foundIt = _map.find(idx); + if (foundIt != _map.end()) { + return foundIt->second; + } + + // compute the summation over column r + double s = 0.; + const int& sc = _Ap[r]; + const int& ec = _Ap[r+1]; + for (int j = sc+1; j < ec; ++j) { // sum over row r while skipping the element on the diagonal + const int& rr = _Ai[j]; + double val = rr < c ? computeEntry(rr, c) : computeEntry(c, rr); + s += val * _Ax[j]; + } + + double result; + if (r == c) { + const double& diagElem = _diag[r]; + result = diagElem * (diagElem - s); + } else { + result = -s * _diag[r]; + } + _map[idx] = result; + return result; +} + +void MarginalCovarianceCholesky::computeCovariance(double** covBlocks, const std::vector& blockIndices) +{ + _map.clear(); + int base = 0; + vector elemsToCompute; + for (size_t i = 0; i < blockIndices.size(); ++i) { + int nbase = blockIndices[i]; + int vdim = nbase - base; + for (int rr = 0; rr < vdim; ++rr) + for (int cc = rr; cc < vdim; ++cc) { + int r = _perm ? _perm[rr + base] : rr + base; // apply permutation + int c = _perm ? _perm[cc + base] : cc + base; + if (r > c) // make sure it's still upper triangular after applying the permutation + swap(r, c); + elemsToCompute.push_back(MatrixElem(r, c)); + } + base = nbase; + } + + // sort the elems to reduce the recursive calls + sort(elemsToCompute.begin(), elemsToCompute.end()); + + // compute the inverse elements we need + for (size_t i = 0; i < elemsToCompute.size(); ++i) { + const MatrixElem& me = elemsToCompute[i]; + computeEntry(me.r, me.c); + } + + // set the marginal covariance for the vertices, by writing to the blocks memory + base = 0; + for (size_t i = 0; i < blockIndices.size(); ++i) { + int nbase = blockIndices[i]; + int vdim = nbase - base; + double* cov = covBlocks[i]; + for (int rr = 0; rr < vdim; ++rr) + for (int cc = rr; cc < vdim; ++cc) { + int r = _perm ? _perm[rr + base] : rr + base; // apply permutation + int c = _perm ? _perm[cc + base] : cc + base; + if (r > c) // upper triangle + swap(r, c); + int idx = computeIndex(r, c); + LookupMap::const_iterator foundIt = _map.find(idx); + assert(foundIt != _map.end()); + cov[rr*vdim + cc] = foundIt->second; + if (rr != cc) + cov[cc*vdim + rr] = foundIt->second; + } + base = nbase; + } +} + + +void MarginalCovarianceCholesky::computeCovariance(SparseBlockMatrix& spinv, const std::vector& rowBlockIndices, const std::vector< std::pair >& blockIndices) +{ + // allocate the sparse + spinv = SparseBlockMatrix(&rowBlockIndices[0], + &rowBlockIndices[0], + rowBlockIndices.size(), + rowBlockIndices.size(), true); + _map.clear(); + vector elemsToCompute; + for (size_t i = 0; i < blockIndices.size(); ++i) { + int blockRow=blockIndices[i].first; + int blockCol=blockIndices[i].second; + assert(blockRow>=0); + assert(blockRow < (int)rowBlockIndices.size()); + assert(blockCol>=0); + assert(blockCol < (int)rowBlockIndices.size()); + + int rowBase=spinv.rowBaseOfBlock(blockRow); + int colBase=spinv.colBaseOfBlock(blockCol); + + MatrixXd *block=spinv.block(blockRow, blockCol, true); + assert(block); + for (int iRow=0; iRowrows(); ++iRow) + for (int iCol=0; iColcols(); ++iCol){ + int rr=rowBase+iRow; + int cc=colBase+iCol; + int r = _perm ? _perm[rr] : rr; // apply permutation + int c = _perm ? _perm[cc] : cc; + if (r > c) + swap(r, c); + elemsToCompute.push_back(MatrixElem(r, c)); + } + } + + // sort the elems to reduce the number of recursive calls + sort(elemsToCompute.begin(), elemsToCompute.end()); + + // compute the inverse elements we need + for (size_t i = 0; i < elemsToCompute.size(); ++i) { + const MatrixElem& me = elemsToCompute[i]; + computeEntry(me.r, me.c); + } + + // set the marginal covariance + for (size_t i = 0; i < blockIndices.size(); ++i) { + int blockRow=blockIndices[i].first; + int blockCol=blockIndices[i].second; + int rowBase=spinv.rowBaseOfBlock(blockRow); + int colBase=spinv.colBaseOfBlock(blockCol); + + MatrixXd *block=spinv.block(blockRow, blockCol); + assert(block); + for (int iRow=0; iRowrows(); ++iRow) + for (int iCol=0; iColcols(); ++iCol){ + int rr=rowBase+iRow; + int cc=colBase+iCol; + int r = _perm ? _perm[rr] : rr; // apply permutation + int c = _perm ? _perm[cc] : cc; + if (r > c) + swap(r, c); + int idx = computeIndex(r, c); + LookupMap::const_iterator foundIt = _map.find(idx); + assert(foundIt != _map.end()); + (*block)(iRow, iCol) = foundIt->second; + } + } +} + +} // end namespace diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/marginal_covariance_cholesky.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/marginal_covariance_cholesky.h new file mode 100644 index 0000000..e7dfce8 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/marginal_covariance_cholesky.h @@ -0,0 +1,103 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_MARGINAL_COVARIANCE_CHOLESKY_H +#define G2O_MARGINAL_COVARIANCE_CHOLESKY_H + +#include "optimizable_graph.h" +#include "sparse_block_matrix.h" + +#include +#include + +#ifdef _MSC_VER +#include +#else +#include +#endif + + +namespace g2o { + + /** + * \brief computing the marginal covariance given a cholesky factor (lower triangle of the factor) + */ + class MarginalCovarianceCholesky { + protected: + /** + * hash struct for storing the matrix elements needed to compute the covariance + */ + typedef std::tr1::unordered_map LookupMap; + + public: + MarginalCovarianceCholesky(); + ~MarginalCovarianceCholesky(); + + /** + * compute the marginal cov for the given block indices, write the result to the covBlocks memory (which has to + * be provided by the caller). + */ + void computeCovariance(double** covBlocks, const std::vector& blockIndices); + + + /** + * compute the marginal cov for the given block indices, write the result in spinv). + */ + void computeCovariance(SparseBlockMatrix& spinv, const std::vector& rowBlockIndices, const std::vector< std::pair >& blockIndices); + + + /** + * set the CCS representation of the cholesky factor along with the inverse permutation used to reduce the fill-in. + * permInv might be 0, will then not permute the entries. + * + * The pointers provided by the user need to be still valid when calling computeCovariance(). The pointers + * are owned by the caller, MarginalCovarianceCholesky does not free the pointers. + */ + void setCholeskyFactor(int n, int* Lp, int* Li, double* Lx, int* permInv); + + protected: + // information about the cholesky factor (lower triangle) + int _n; ///< L is an n X n matrix + int* _Ap; ///< column pointer of the CCS storage + int* _Ai; ///< row indices of the CCS storage + double* _Ax; ///< values of the cholesky factor + int* _perm; ///< permutation of the cholesky factor. Variable re-ordering for better fill-in + + LookupMap _map; ///< hash look up table for the already computed entries + std::vector _diag; ///< cache 1 / H_ii to avoid recalculations + + //! compute the index used for hashing + int computeIndex(int r, int c) const { /*assert(r <= c);*/ return r*_n + c;} + /** + * compute one entry in the covariance, r and c are values after applying the permutation, and upper triangular. + * May issue recursive calls to itself to compute the missing values. + */ + double computeEntry(int r, int c); + }; + +} + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/matrix_operations.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/matrix_operations.h new file mode 100644 index 0000000..28e6fbe --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/matrix_operations.h @@ -0,0 +1,74 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_CORE_MATRIX_OPERATIONS_H +#define G2O_CORE_MATRIX_OPERATIONS_H + +#include + +namespace g2o { + namespace internal { + + template + inline void axpy(const MatrixType& A, const Eigen::Map& x, int xoff, Eigen::Map& y, int yoff) + { + y.segment(yoff) += A * x.segment(xoff); + } + + template + inline void axpy(const Eigen::Matrix& A, const Eigen::Map& x, int xoff, Eigen::Map& y, int yoff) + { + y.segment(yoff, A.rows()) += A * x.segment::ColsAtCompileTime>(xoff); + } + + template<> + inline void axpy(const Eigen::MatrixXd& A, const Eigen::Map& x, int xoff, Eigen::Map& y, int yoff) + { + y.segment(yoff, A.rows()) += A * x.segment(xoff, A.cols()); + } + + template + inline void atxpy(const MatrixType& A, const Eigen::Map& x, int xoff, Eigen::Map& y, int yoff) + { + y.segment(yoff) += A.transpose() * x.segment(xoff); + } + + template + inline void atxpy(const Eigen::Matrix& A, const Eigen::Map& x, int xoff, Eigen::Map& y, int yoff) + { + y.segment::ColsAtCompileTime>(yoff) += A.transpose() * x.segment(xoff, A.rows()); + } + + template<> + inline void atxpy(const Eigen::MatrixXd& A, const Eigen::Map& x, int xoff, Eigen::Map& y, int yoff) + { + y.segment(yoff, A.cols()) += A.transpose() * x.segment(xoff, A.rows()); + } + + } // end namespace internal +} // end namespace g2o + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/matrix_structure.cpp b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/matrix_structure.cpp new file mode 100644 index 0000000..3152195 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/matrix_structure.cpp @@ -0,0 +1,125 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#include "matrix_structure.h" + +#include +#include +#include +#include +using namespace std; + +namespace g2o { + +struct ColSort +{ + bool operator()(const pair& e1, const pair& e2) const + { + return e1.second < e2.second || (e1.second == e2.second && e1.first < e2.first); + } +}; + +MatrixStructure::MatrixStructure() : + n(0), m(0), Ap(0), Aii(0), maxN(0), maxNz(0) +{ +} + +MatrixStructure::~MatrixStructure() +{ + free(); +} + +void MatrixStructure::alloc(int n_, int nz) +{ + if (n == 0) { + maxN = n = n_; + maxNz = nz; + Ap = new int[maxN + 1]; + Aii = new int[maxNz]; + } + else { + n = n_; + if (maxNz < nz) { + maxNz = 2 * nz; + delete[] Aii; + Aii = new int[maxNz]; + } + if (maxN < n) { + maxN = 2 * n; + delete[] Ap; + Ap = new int[maxN + 1]; + } + } +} + +void MatrixStructure::free() +{ + n = 0; + m = 0; + maxN = 0; + maxNz = 0; + delete[] Aii; Aii = 0; + delete[] Ap; Ap = 0; +} + +bool MatrixStructure::write(const char* filename) const +{ + const int& cols = n; + const int& rows = m; + + string name = filename; + std::string::size_type lastDot = name.find_last_of('.'); + if (lastDot != std::string::npos) + name = name.substr(0, lastDot); + + vector > entries; + for (int i=0; i < cols; ++i) { + const int& rbeg = Ap[i]; + const int& rend = Ap[i+1]; + for (int j = rbeg; j < rend; ++j) { + entries.push_back(make_pair(Aii[j], i)); + if (Aii[j] != i) + entries.push_back(make_pair(i, Aii[j])); + } + } + + sort(entries.begin(), entries.end(), ColSort()); + + std::ofstream fout(filename); + fout << "# name: " << name << std::endl; + fout << "# type: sparse matrix" << std::endl; + fout << "# nnz: " << entries.size() << std::endl; + fout << "# rows: " << rows << std::endl; + fout << "# columns: " << cols << std::endl; + for (vector >::const_iterator it = entries.begin(); it != entries.end(); ++it) { + const pair& entry = *it; + fout << entry.first << " " << entry.second << " 0" << std::endl; // write a constant value of 0 + } + + return fout.good(); +} + +} // end namespace diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/matrix_structure.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/matrix_structure.h new file mode 100644 index 0000000..fd70e53 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/matrix_structure.h @@ -0,0 +1,69 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_MATRIX_STRUCTURE_H +#define G2O_MATRIX_STRUCTURE_H + + +namespace g2o { + +/** + * \brief representing the structure of a matrix in column compressed structure (only the upper triangular part of the matrix) + */ +class MatrixStructure +{ + public: + MatrixStructure(); + ~MatrixStructure(); + /** + * allocate space for the Matrix Structure. You may call this on an already allocated struct, it will + * then reallocate the memory + additional space (double the required space). + */ + void alloc(int n_, int nz); + + void free(); + + /** + * Write the matrix pattern to a file. File is also loadable by octave, e.g., then use spy(matrix) + */ + bool write(const char* filename) const; + + int n; ///< A is m-by-n. n must be >= 0. + int m; ///< A is m-by-n. m must be >= 0. + int* Ap; ///< column pointers for A, of size n+1 + int* Aii; ///< row indices of A, of size nz = Ap [n] + + //! max number of non-zeros blocks + int nzMax() const { return maxNz;} + + protected: + int maxN; ///< size of the allocated memory + int maxNz; ///< size of the allocated memory +}; + +} // end namespace + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/openmp_mutex.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/openmp_mutex.h new file mode 100644 index 0000000..6a9b8f4 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/openmp_mutex.h @@ -0,0 +1,97 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_OPENMP_MUTEX +#define G2O_OPENMP_MUTEX + +#include "../../config.h" + +#ifdef G2O_OPENMP +#include +#else +#include +#endif + +namespace g2o { + +#ifdef G2O_OPENMP + + /** + * \brief Mutex realized via OpenMP + */ + class OpenMPMutex + { + public: + OpenMPMutex() { omp_init_lock(&_lock); } + ~OpenMPMutex() { omp_destroy_lock(&_lock); } + void lock() { omp_set_lock(&_lock); } + void unlock() { omp_unset_lock(&_lock); } + protected: + omp_lock_t _lock; + }; + +#else + + /* + * dummy which does nothing in case we don't have OpenMP support. + * In debug mode, the mutex allows to verify the correct lock and unlock behavior + */ + class OpenMPMutex + { + public: +#ifdef NDEBUG + OpenMPMutex() {} +#else + OpenMPMutex() : _cnt(0) {} +#endif + ~OpenMPMutex() { assert(_cnt == 0 && "Freeing locked mutex");} + void lock() { assert(++_cnt == 1 && "Locking already locked mutex");} + void unlock() { assert(--_cnt == 0 && "Trying to unlock a mutex which is not locked");} + protected: +#ifndef NDEBUG + char _cnt; +#endif + }; + +#endif + + /** + * \brief lock a mutex within a scope + */ + class ScopedOpenMPMutex + { + public: + explicit ScopedOpenMPMutex(OpenMPMutex* mutex) : _mutex(mutex) { _mutex->lock(); } + ~ScopedOpenMPMutex() { _mutex->unlock(); } + private: + OpenMPMutex* const _mutex; + ScopedOpenMPMutex(const ScopedOpenMPMutex&); + void operator=(const ScopedOpenMPMutex&); + }; + +} + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/optimizable_graph.cpp b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/optimizable_graph.cpp new file mode 100644 index 0000000..bb6b54b --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/optimizable_graph.cpp @@ -0,0 +1,910 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, H. Strasdat, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#include "optimizable_graph.h" + +#include +#include +#include +#include +#include + +#include + +#include "estimate_propagator.h" +#include "factory.h" +#include "optimization_algorithm_property.h" +#include "hyper_graph_action.h" +#include "cache.h" +#include "robust_kernel.h" + +#include "../stuff/macros.h" +#include "../stuff/color_macros.h" +#include "../stuff/string_tools.h" +#include "../stuff/misc.h" + +namespace g2o { + + using namespace std; + + OptimizableGraph::Data::Data(){ + _next = 0; + } + + OptimizableGraph::Data::~Data(){ + if (_next) + delete _next; + } + + + OptimizableGraph::Vertex::Vertex() : + HyperGraph::Vertex(), + _graph(0), _userData(0), _hessianIndex(-1), _fixed(false), _marginalized(false), + _colInHessian(-1), _cacheContainer(0) + { + } + + CacheContainer* OptimizableGraph::Vertex::cacheContainer(){ + if (! _cacheContainer) + _cacheContainer = new CacheContainer(this); + return _cacheContainer; + } + + + void OptimizableGraph::Vertex::updateCache(){ + if (_cacheContainer){ + _cacheContainer->setUpdateNeeded(); + _cacheContainer->update(); + } + } + + OptimizableGraph::Vertex::~Vertex() + { + if (_cacheContainer) + delete (_cacheContainer); + if (_userData) + delete _userData; + } + + OptimizableGraph::Vertex* OptimizableGraph::Vertex::clone() const + { + return 0; + } + + bool OptimizableGraph::Vertex::setEstimateData(const double* v) + { + bool ret = setEstimateDataImpl(v); + updateCache(); + return ret; + } + + bool OptimizableGraph::Vertex::getEstimateData(double *) const + { + return false; + } + + int OptimizableGraph::Vertex::estimateDimension() const + { + return -1; + } + + bool OptimizableGraph::Vertex::setMinimalEstimateData(const double* v) + { + bool ret = setMinimalEstimateDataImpl(v); + updateCache(); + return ret; + } + + bool OptimizableGraph::Vertex::getMinimalEstimateData(double *) const + { + return false; + } + + int OptimizableGraph::Vertex::minimalEstimateDimension() const + { + return -1; + } + + + OptimizableGraph::Edge::Edge() : + HyperGraph::Edge(), + _dimension(-1), _level(0), _robustKernel(0) + { + } + + OptimizableGraph::Edge::~Edge() + { + delete _robustKernel; + } + + OptimizableGraph* OptimizableGraph::Edge::graph(){ + if (! _vertices.size()) + return 0; + OptimizableGraph::Vertex* v=(OptimizableGraph::Vertex*)_vertices[0]; + if (!v) + return 0; + return v->graph(); + } + + const OptimizableGraph* OptimizableGraph::Edge::graph() const{ + if (! _vertices.size()) + return 0; + const OptimizableGraph::Vertex* v=(const OptimizableGraph::Vertex*) _vertices[0]; + if (!v) + return 0; + return v->graph(); + } + + bool OptimizableGraph::Edge::setParameterId(int argNum, int paramId){ + if ((int)_parameters.size()<=argNum) + return false; + if (argNum<0) + return false; + *_parameters[argNum] = 0; + _parameterIds[argNum] = paramId; + return true; + } + + bool OptimizableGraph::Edge::resolveParameters() { + if (!graph()) { + cerr << __PRETTY_FUNCTION__ << ": edge not registered with a graph" << endl; + return false; + } + + assert (_parameters.size() == _parameterIds.size()); + //cerr << __PRETTY_FUNCTION__ << ": encountered " << _parameters.size() << " parameters" << endl; + for (size_t i=0; i<_parameters.size(); i++){ + int index = _parameterIds[i]; + *_parameters[i] = graph()->parameter(index); + if (typeid(**_parameters[i]).name()!=_parameterTypes[i]){ + cerr << __PRETTY_FUNCTION__ << ": FATAL, parameter type mismatch - encountered " << typeid(**_parameters[i]).name() << "; should be " << _parameterTypes[i] << endl; + } + if (!*_parameters[i]) { + cerr << __PRETTY_FUNCTION__ << ": FATAL, *_parameters[i] == 0" << endl; + return false; + } + } + return true; + } + + void OptimizableGraph::Edge::setRobustKernel(RobustKernel* ptr) + { + if (_robustKernel) + delete _robustKernel; + _robustKernel = ptr; + } + + bool OptimizableGraph::Edge::resolveCaches() { + return true; + } + + bool OptimizableGraph::Edge::setMeasurementData(const double *) + { + return false; + } + + bool OptimizableGraph::Edge::getMeasurementData(double *) const + { + return false; + } + + int OptimizableGraph::Edge::measurementDimension() const + { + return -1; + } + + bool OptimizableGraph::Edge::setMeasurementFromState(){ + return false; + } + + + OptimizableGraph::Edge* OptimizableGraph::Edge::clone() const + { + // TODO + return 0; + } + + + OptimizableGraph::OptimizableGraph() + { + _nextEdgeId = 0; _edge_has_id = false; + _graphActions.resize(AT_NUM_ELEMENTS); + } + + OptimizableGraph::~OptimizableGraph() + { + clear(); + clearParameters(); + } + + bool OptimizableGraph::addVertex(HyperGraph::Vertex* v, Data* userData) + { + Vertex* inserted = vertex(v->id()); + if (inserted) { + cerr << __FUNCTION__ << ": FATAL, a vertex with ID " << v->id() << " has already been registered with this graph" << endl; + assert(0 && "Vertex with this ID already contained in the graph"); + return false; + } + OptimizableGraph::Vertex* ov=dynamic_cast(v); + assert(ov && "Vertex does not inherit from OptimizableGraph::Vertex"); + if (ov->_graph != 0 && ov->_graph != this) { + cerr << __FUNCTION__ << ": FATAL, vertex with ID " << v->id() << " has already registered with another graph " << ov->_graph << endl; + assert(0 && "Vertex already registered with another graph"); + return false; + } + if (userData) + ov->setUserData(userData); + ov->_graph=this; + return HyperGraph::addVertex(v); + } + + bool OptimizableGraph::addEdge(HyperGraph::Edge* e_) + { + OptimizableGraph::Edge* e = dynamic_cast(e_); + assert(e && "Edge does not inherit from OptimizableGraph::Edge"); + if (! e) + return false; + bool eresult = HyperGraph::addEdge(e); + if (! eresult) + return false; + e->_internalId = _nextEdgeId++; + if (! e->resolveParameters()){ + cerr << __FUNCTION__ << ": FATAL, cannot resolve parameters for edge " << e << endl; + return false; + } + if (! e->resolveCaches()){ + cerr << __FUNCTION__ << ": FATAL, cannot resolve caches for edge " << e << endl; + return false; + } + _jacobianWorkspace.updateSize(e); + + return true; + } + + int OptimizableGraph::optimize(int /*iterations*/, bool /*online*/) {return 0;} + +double OptimizableGraph::chi2() const +{ + double chi = 0.0; + for (OptimizableGraph::EdgeSet::const_iterator it = this->edges().begin(); it != this->edges().end(); ++it) { + const OptimizableGraph::Edge* e = static_cast(*it); + chi += e->chi2(); + } + return chi; +} + +void OptimizableGraph::push() +{ + for (OptimizableGraph::VertexIDMap::iterator it=_vertices.begin(); it!=_vertices.end(); ++it) { + OptimizableGraph::Vertex* v = static_cast(it->second); + v->push(); + } +} + +void OptimizableGraph::pop() +{ + for (OptimizableGraph::VertexIDMap::iterator it=_vertices.begin(); it!=_vertices.end(); ++it) { + OptimizableGraph::Vertex* v= static_cast(it->second); + v->pop(); + } +} + +void OptimizableGraph::discardTop() +{ + for (OptimizableGraph::VertexIDMap::iterator it=_vertices.begin(); it!=_vertices.end(); ++it) { + OptimizableGraph::Vertex* v= static_cast(it->second); + v->discardTop(); + } +} + +void OptimizableGraph::push(HyperGraph::VertexSet& vset) +{ + for (HyperGraph::VertexSet::iterator it=vset.begin(); it!=vset.end(); ++it) { + OptimizableGraph::Vertex* v = static_cast(*it); + v->push(); + } +} + +void OptimizableGraph::pop(HyperGraph::VertexSet& vset) +{ + for (HyperGraph::VertexSet::iterator it=vset.begin(); it!=vset.end(); ++it) { + OptimizableGraph::Vertex* v = static_cast(*it); + v->pop(); + } +} + +void OptimizableGraph::discardTop(HyperGraph::VertexSet& vset) +{ + for (HyperGraph::VertexSet::iterator it=vset.begin(); it!=vset.end(); ++it) { + OptimizableGraph::Vertex* v = static_cast(*it); + v->discardTop(); + } +} + + void OptimizableGraph::setFixed(HyperGraph::VertexSet& vset, bool fixed) +{ + for (HyperGraph::VertexSet::iterator it=vset.begin(); it!=vset.end(); ++it) { + OptimizableGraph::Vertex* v = static_cast(*it); + v->setFixed(fixed); + } +} + + +bool OptimizableGraph::load(istream& is, bool createEdges) +{ + // scna for the paramers in the whole file + if (!_parameters.read(is,&_renamedTypesLookup)) + return false; +#ifndef NDEBUG + cerr << "Loaded " << _parameters.size() << " parameters" << endl; +#endif + is.clear(); + is.seekg(ios_base::beg); + set warnedUnknownTypes; + stringstream currentLine; + string token; + + Factory* factory = Factory::instance(); + HyperGraph::GraphElemBitset elemBitset; + elemBitset[HyperGraph::HGET_PARAMETER] = 1; + elemBitset.flip(); + + Vertex* previousVertex = 0; + Data* previousData = 0; + + while (1) { + int bytesRead = readLine(is, currentLine); + if (bytesRead == -1) + break; + currentLine >> token; + //cerr << "Token=" << token << endl; + if (bytesRead == 0 || token.size() == 0 || token[0] == '#') + continue; + + // handle commands encoded in the file + bool handledCommand = false; + + if (token == "FIX") { + handledCommand = true; + int id; + while (currentLine >> id) { + OptimizableGraph::Vertex* v = static_cast(vertex(id)); + if (v) { +# ifndef NDEBUG + cerr << "Fixing vertex " << v->id() << endl; +# endif + v->setFixed(true); + } else { + cerr << "Warning: Unable to fix vertex with id " << id << ". Not found in the graph." << endl; + } + } + } + + if (handledCommand) + continue; + + // do the mapping to an internal type if it matches + if (_renamedTypesLookup.size() > 0) { + map::const_iterator foundIt = _renamedTypesLookup.find(token); + if (foundIt != _renamedTypesLookup.end()) { + token = foundIt->second; + } + } + + if (! factory->knowsTag(token)) { + if (warnedUnknownTypes.count(token) != 1) { + warnedUnknownTypes.insert(token); + cerr << CL_RED(__PRETTY_FUNCTION__ << " unknown type: " << token) << endl; + } + continue; + } + + HyperGraph::HyperGraphElement* element = factory->construct(token, elemBitset); + if (dynamic_cast(element)) { // it's a vertex type + //cerr << "it is a vertex" << endl; + previousData = 0; + Vertex* v = static_cast(element); + int id; + currentLine >> id; + bool r = v->read(currentLine); + if (! r) + cerr << __PRETTY_FUNCTION__ << ": Error reading vertex " << token << " " << id << endl; + v->setId(id); + if (!addVertex(v)) { + cerr << __PRETTY_FUNCTION__ << ": Failure adding Vertex, " << token << " " << id << endl; + delete v; + } else { + previousVertex = v; + } + } + else if (dynamic_cast(element)) { + //cerr << "it is an edge" << endl; + previousData = 0; + Edge* e = static_cast(element); + int numV = e->vertices().size(); + if (_edge_has_id){ + int id; + currentLine >> id; + e->setId(id); + } + //cerr << PVAR(token) << " " << PVAR(numV) << endl; + if (numV == 2) { // it's a pairwise / binary edge type which we handle in a special way + int id1, id2; + currentLine >> id1 >> id2; + Vertex* from = vertex(id1); + Vertex* to = vertex(id2); + int doInit=0; + if ((!from || !to) ) { + if (! createEdges) { + cerr << __PRETTY_FUNCTION__ << ": Unable to find vertices for edge " << token << " " << id1 << " <-> " << id2 << endl; + delete e; + } else { + if (! from) { + from=e->createFrom(); + from->setId(id1); + addVertex(from); + doInit=2; + } + if (! to) { + to=e->createTo(); + to->setId(id2); + addVertex(to); + doInit=1; + } + } + } + if (from && to) { + e->setVertex(0, from); + e->setVertex(1, to); + e->read(currentLine); + if (!addEdge(e)) { + cerr << __PRETTY_FUNCTION__ << ": Unable to add edge " << token << " " << id1 << " <-> " << id2 << endl; + delete e; + } else { + switch (doInit){ + case 1: + { + HyperGraph::VertexSet fromSet; + fromSet.insert(from); + e->initialEstimate(fromSet, to); + break; + } + case 2: + { + HyperGraph::VertexSet toSet; + toSet.insert(to); + e->initialEstimate(toSet, from); + break; + } + default:; + } + } + } + } + else { + vector ids; + ids.resize(numV); + for (int l = 0; l < numV; ++l) + currentLine >> ids[l]; + bool vertsOkay = true; + for (int l = 0; l < numV; ++l) { + e->setVertex(l, vertex(ids[l])); + if (e->vertex(l) == 0) { + vertsOkay = false; + break; + } + } + if (! vertsOkay) { + cerr << __PRETTY_FUNCTION__ << ": Unable to find vertices for edge " << token; + for (int l = 0; l < numV; ++l) { + if (l > 0) + cerr << " <->"; + cerr << " " << ids[l]; + } + delete e; + } else { + bool r = e->read(currentLine); + if (!r || !addEdge(e)) { + cerr << __PRETTY_FUNCTION__ << ": Unable to add edge " << token; + for (int l = 0; l < numV; ++l) { + if (l > 0) + cerr << " <->"; + cerr << " " << ids[l]; + } + delete e; + } + } + } + } else if (dynamic_cast(element)) { // reading in the data packet for the vertex + //cerr << "read data packet " << token << " vertex " << previousVertex->id() << endl; + Data* d = static_cast(element); + bool r = d->read(currentLine); + if (! r) { + cerr << __PRETTY_FUNCTION__ << ": Error reading data " << token << " for vertex " << previousVertex->id() << endl; + delete d; + previousData = 0; + } else if (previousData){ + //cerr << "chaining" << endl; + previousData->setNext(d); + previousData = d; + //cerr << "done" << endl; + } else if (previousVertex){ + //cerr << "embedding in vertex" << endl; + previousVertex->setUserData(d); + previousData = d; + previousVertex = 0; + //cerr << "done" << endl; + } else { + cerr << __PRETTY_FUNCTION__ << ": got data element, but no vertex available" << endl; + delete d; + previousData = 0; + } + } + } // while read line + + return true; +} + +bool OptimizableGraph::load(const char* filename, bool createEdges) +{ + ifstream ifs(filename); + if (!ifs) { + cerr << __PRETTY_FUNCTION__ << " unable to open file " << filename << endl; + return false; + } + return load(ifs, createEdges); +} + +bool OptimizableGraph::save(const char* filename, int level) const +{ + ofstream ofs(filename); + if (!ofs) + return false; + return save(ofs, level); +} + +bool OptimizableGraph::save(ostream& os, int level) const +{ + if (! _parameters.write(os)) + return false; + set verticesToSave; + for (HyperGraph::EdgeSet::const_iterator it = edges().begin(); it != edges().end(); ++it) { + OptimizableGraph::Edge* e = static_cast(*it); + if (e->level() == level) { + for (vector::const_iterator it = e->vertices().begin(); it != e->vertices().end(); ++it) { + verticesToSave.insert(static_cast(*it)); + } + } + } + + for (set::const_iterator it = verticesToSave.begin(); it != verticesToSave.end(); ++it){ + OptimizableGraph::Vertex* v = *it; + saveVertex(os, v); + } + + EdgeContainer edgesToSave; + for (HyperGraph::EdgeSet::const_iterator it = edges().begin(); it != edges().end(); ++it) { + const OptimizableGraph::Edge* e = dynamic_cast(*it); + if (e->level() == level) + edgesToSave.push_back(const_cast(e)); + } + sort(edgesToSave.begin(), edgesToSave.end(), EdgeIDCompare()); + + for (EdgeContainer::const_iterator it = edgesToSave.begin(); it != edgesToSave.end(); ++it) { + OptimizableGraph::Edge* e = *it; + saveEdge(os, e); + } + + return os.good(); +} + + +bool OptimizableGraph::saveSubset(ostream& os, HyperGraph::VertexSet& vset, int level) +{ + if (! _parameters.write(os)) + return false; + + for (HyperGraph::VertexSet::const_iterator it=vset.begin(); it!=vset.end(); it++){ + OptimizableGraph::Vertex* v = dynamic_cast(*it); + saveVertex(os, v); + } + for (HyperGraph::EdgeSet::const_iterator it = edges().begin(); it != edges().end(); ++it) { + OptimizableGraph::Edge* e = dynamic_cast< OptimizableGraph::Edge*>(*it); + if (e->level() != level) + continue; + + bool verticesInEdge = true; + for (vector::const_iterator it = e->vertices().begin(); it != e->vertices().end(); ++it) { + if (vset.find(*it) == vset.end()) { + verticesInEdge = false; + break; + } + } + if (! verticesInEdge) + continue; + + saveEdge(os, e); + } + + return os.good(); +} + +bool OptimizableGraph::saveSubset(ostream& os, HyperGraph::EdgeSet& eset) +{ + if (!_parameters.write(os)) + return false; + std::set vset; + for (HyperGraph::EdgeSet::const_iterator it = eset.begin(); it != eset.end(); ++it) { + HyperGraph::Edge* e = *it; + for (vector::const_iterator it = e->vertices().begin(); it != e->vertices().end(); ++it) { + OptimizableGraph::Vertex* v = static_cast(*it); + vset.insert(v); + } + } + + for (std::set::const_iterator it=vset.begin(); it!=vset.end(); ++it){ + OptimizableGraph::Vertex* v = dynamic_cast(*it); + saveVertex(os, v); + } + + for (HyperGraph::EdgeSet::const_iterator it = eset.begin(); it != eset.end(); ++it) { + OptimizableGraph::Edge* e = dynamic_cast< OptimizableGraph::Edge*>(*it); + saveEdge(os, e); + } + + return os.good(); +} + +void OptimizableGraph::addGraph(OptimizableGraph* g){ + for (HyperGraph::VertexIDMap::iterator it=g->vertices().begin(); it!=g->vertices().end(); ++it){ + OptimizableGraph::Vertex* v= (OptimizableGraph::Vertex*)(it->second); + if (vertex(v->id())) + continue; + OptimizableGraph::Vertex* v2=v->clone(); + v2->edges().clear(); + v2->setHessianIndex(-1); + addVertex(v2); + } + for (HyperGraph::EdgeSet::iterator it=g->edges().begin(); it!=g->edges().end(); ++it){ + OptimizableGraph::Edge* e = (OptimizableGraph::Edge*)(*it); + OptimizableGraph::Edge* en = e->clone(); + en->resize(e->vertices().size()); + int cnt = 0; + for (vector::const_iterator it = e->vertices().begin(); it != e->vertices().end(); ++it) { + OptimizableGraph::Vertex* v = (OptimizableGraph::Vertex*) vertex((*it)->id()); + assert(v); + en->setVertex(cnt++, v); + } + addEdge(en); + } +} + +int OptimizableGraph::maxDimension() const{ + int maxDim=0; + for (HyperGraph::VertexIDMap::const_iterator it=vertices().begin(); it!=vertices().end(); ++it){ + const OptimizableGraph::Vertex* v= static_cast< const OptimizableGraph::Vertex*>(it->second); + maxDim = (std::max)(maxDim, v->dimension()); + } + return maxDim; +} + +void OptimizableGraph::setRenamedTypesFromString(const std::string& types) +{ + Factory* factory = Factory::instance(); + vector typesMap = strSplit(types, ","); + for (size_t i = 0; i < typesMap.size(); ++i) { + vector m = strSplit(typesMap[i], "="); + if (m.size() != 2) { + cerr << __PRETTY_FUNCTION__ << ": unable to extract type map from " << typesMap[i] << endl; + continue; + } + string typeInFile = trim(m[0]); + string loadedType = trim(m[1]); + if (! factory->knowsTag(loadedType)) { + cerr << __PRETTY_FUNCTION__ << ": unknown type " << loadedType << endl; + continue; + } + + _renamedTypesLookup[typeInFile] = loadedType; + } + + cerr << "# load look up table" << endl; + for (std::map::const_iterator it = _renamedTypesLookup.begin(); it != _renamedTypesLookup.end(); ++it) { + cerr << "#\t" << it->first << " -> " << it->second << endl; + } +} + +bool OptimizableGraph::isSolverSuitable(const OptimizationAlgorithmProperty& solverProperty, const std::set& vertDims_) const +{ + std::set auxDims; + if (vertDims_.size() == 0) { + auxDims = dimensions(); + } + const set& vertDims = vertDims_.size() == 0 ? auxDims : vertDims_; + bool suitableSolver = true; + if (vertDims.size() == 2) { + if (solverProperty.requiresMarginalize) { + suitableSolver = vertDims.count(solverProperty.poseDim) == 1 && vertDims.count(solverProperty.landmarkDim) == 1; + } + else { + suitableSolver = solverProperty.poseDim == -1; + } + } else if (vertDims.size() == 1) { + suitableSolver = vertDims.count(solverProperty.poseDim) == 1 || solverProperty.poseDim == -1; + } else { + suitableSolver = solverProperty.poseDim == -1 && !solverProperty.requiresMarginalize; + } + return suitableSolver; +} + +std::set OptimizableGraph::dimensions() const +{ + std::set auxDims; + for (VertexIDMap::const_iterator it = vertices().begin(); it != vertices().end(); ++it) { + OptimizableGraph::Vertex* v = static_cast(it->second); + auxDims.insert(v->dimension()); + } + return auxDims; +} + +void OptimizableGraph::preIteration(int iter) +{ + HyperGraphActionSet& actions = _graphActions[AT_PREITERATION]; + if (actions.size() > 0) { + HyperGraphAction::ParametersIteration params(iter); + for (HyperGraphActionSet::iterator it = actions.begin(); it != actions.end(); ++it) { + (*(*it))(this, ¶ms); + } + } +} + +void OptimizableGraph::postIteration(int iter) +{ + HyperGraphActionSet& actions = _graphActions[AT_POSTITERATION]; + if (actions.size() > 0) { + HyperGraphAction::ParametersIteration params(iter); + for (HyperGraphActionSet::iterator it = actions.begin(); it != actions.end(); ++it) { + (*(*it))(this, ¶ms); + } + } +} + +bool OptimizableGraph::addPostIterationAction(HyperGraphAction* action) +{ + std::pair insertResult = _graphActions[AT_POSTITERATION].insert(action); + return insertResult.second; +} + +bool OptimizableGraph::addPreIterationAction(HyperGraphAction* action) +{ + std::pair insertResult = _graphActions[AT_PREITERATION].insert(action); + return insertResult.second; +} + +bool OptimizableGraph::removePreIterationAction(HyperGraphAction* action) +{ + return _graphActions[AT_PREITERATION].erase(action) > 0; +} + +bool OptimizableGraph::removePostIterationAction(HyperGraphAction* action) +{ + return _graphActions[AT_POSTITERATION].erase(action) > 0; +} + +bool OptimizableGraph::saveVertex(std::ostream& os, OptimizableGraph::Vertex* v) const +{ + Factory* factory = Factory::instance(); + string tag = factory->tag(v); + if (tag.size() > 0) { + os << tag << " " << v->id() << " "; + v->write(os); + os << endl; + Data* d=v->userData(); + while (d) { // write the data packet for the vertex + tag = factory->tag(d); + if (tag.size() > 0) { + os << tag << " "; + d->write(os); + os << endl; + } + d=d->next(); + } + if (v->fixed()) { + os << "FIX " << v->id() << endl; + } + return os.good(); + } + return false; +} + +bool OptimizableGraph::saveEdge(std::ostream& os, OptimizableGraph::Edge* e) const +{ + Factory* factory = Factory::instance(); + string tag = factory->tag(e); + if (tag.size() > 0) { + os << tag << " "; + if (_edge_has_id) + os << e->id() << " "; + for (vector::const_iterator it = e->vertices().begin(); it != e->vertices().end(); ++it) { + OptimizableGraph::Vertex* v = static_cast(*it); + os << v->id() << " "; + } + e->write(os); + os << endl; + return os.good(); + } + return false; +} + +void OptimizableGraph::clearParameters() +{ + _parameters.clear(); +} + +bool OptimizableGraph::verifyInformationMatrices(bool verbose) const +{ + bool allEdgeOk = true; + SelfAdjointEigenSolver eigenSolver; + for (OptimizableGraph::EdgeSet::const_iterator it = edges().begin(); it != edges().end(); ++it) { + OptimizableGraph::Edge* e = static_cast(*it); + Eigen::MatrixXd::MapType information(e->informationData(), e->dimension(), e->dimension()); + // test on symmetry + bool isSymmetric = information.transpose() == information; + bool okay = isSymmetric; + if (isSymmetric) { + // compute the eigenvalues + eigenSolver.compute(information, Eigen::EigenvaluesOnly); + bool isSPD = eigenSolver.eigenvalues()(0) >= 0.; + okay = okay && isSPD; + } + allEdgeOk = allEdgeOk && okay; + if (! okay) { + if (verbose) { + if (! isSymmetric) + cerr << "Information Matrix for an edge is not symmetric:"; + else + cerr << "Information Matrix for an edge is not SPD:"; + for (size_t i = 0; i < e->vertices().size(); ++i) + cerr << " " << e->vertex(i)->id(); + if (isSymmetric) + cerr << "\teigenvalues: " << eigenSolver.eigenvalues().transpose(); + cerr << endl; + } + } + } + return allEdgeOk; +} + +bool OptimizableGraph::initMultiThreading() +{ +# if (defined G2O_OPENMP) && EIGEN_VERSION_AT_LEAST(3,1,0) + Eigen::initParallel(); +# endif + return true; +} + +} // end namespace + diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/optimizable_graph.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/optimizable_graph.h new file mode 100644 index 0000000..9d9b561 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/optimizable_graph.h @@ -0,0 +1,688 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, H. Strasdat, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_AIS_OPTIMIZABLE_GRAPH_HH_ +#define G2O_AIS_OPTIMIZABLE_GRAPH_HH_ + +#include +#include +#include +#include +#include +#include + +#include "openmp_mutex.h" +#include "hyper_graph.h" +#include "parameter.h" +#include "parameter_container.h" +#include "jacobian_workspace.h" + +#include "../stuff/macros.h" + +namespace g2o { + + class HyperGraphAction; + struct OptimizationAlgorithmProperty; + class Cache; + class CacheContainer; + class RobustKernel; + + /** + @addtogroup g2o + */ + /** + This is an abstract class that represents one optimization + problem. It specializes the general graph to contain special + vertices and edges. The vertices represent parameters that can + be optimized, while the edges represent constraints. This class + also provides basic functionalities to handle the backup/restore + of portions of the vertices. + */ + struct OptimizableGraph : public HyperGraph { + + enum ActionType { + AT_PREITERATION, AT_POSTITERATION, + AT_NUM_ELEMENTS, // keep as last element + }; + + typedef std::set HyperGraphActionSet; + + // forward declarations + class Vertex; + class Edge; + + /** + * \brief data packet for a vertex. Extend this class to store in the vertices + * the potential additional information you need (e.g. images, laser scans, ...). + */ + class Data : public HyperGraph::HyperGraphElement + { + friend struct OptimizableGraph; + public: + virtual ~Data(); + Data(); + //! read the data from a stream + virtual bool read(std::istream& is) = 0; + //! write the data to a stream + virtual bool write(std::ostream& os) const = 0; + virtual HyperGraph::HyperGraphElementType elementType() const { return HyperGraph::HGET_DATA;} + const Data* next() const {return _next;} + Data* next() {return _next;} + void setNext(Data* next_) { _next = next_; } + protected: + Data* _next; // linked list of multiple data; + }; + + /** + * \brief order vertices based on their ID + */ + struct VertexIDCompare { + bool operator() (const Vertex* v1, const Vertex* v2) const + { + return v1->id() < v2->id(); + } + }; + + /** + * \brief order edges based on the internal ID, which is assigned to the edge in addEdge() + */ + struct EdgeIDCompare { + bool operator() (const Edge* e1, const Edge* e2) const + { + return e1->internalId() < e2->internalId(); + } + }; + + //! vector container for vertices + typedef std::vector VertexContainer; + //! vector container for edges + typedef std::vector EdgeContainer; + + /** + * \brief A general case Vertex for optimization + */ + class Vertex : public HyperGraph::Vertex { + private: + friend struct OptimizableGraph; + public: + Vertex(); + + //! returns a deep copy of the current vertex + virtual Vertex* clone() const ; + + //! the user data associated with this vertex + const Data* userData() const { return _userData; } + Data* userData() { return _userData; } + + void setUserData(Data* obs) { _userData = obs;} + void addUserData(Data* obs) { + if (obs) { + obs->setNext(_userData); + _userData=obs; + } + } + + virtual ~Vertex(); + + //! sets the node to the origin (used in the multilevel stuff) + void setToOrigin() { setToOriginImpl(); updateCache();} + + //! get the element from the hessian matrix + virtual const double& hessian(int i, int j) const = 0; + virtual double& hessian(int i, int j) = 0; + virtual double hessianDeterminant() const = 0; + virtual double* hessianData() = 0; + + /** maps the internal matrix to some external memory location */ + virtual void mapHessianMemory(double* d) = 0; + + /** + * copies the b vector in the array b_ + * @return the number of elements copied + */ + virtual int copyB(double* b_) const = 0; + + //! get the b vector element + virtual const double& b(int i) const = 0; + virtual double& b(int i) = 0; + //! return a pointer to the b vector associated with this vertex + virtual double* bData() = 0; + + /** + * set the b vector part of this vertex to zero + */ + virtual void clearQuadraticForm() = 0; + + /** + * updates the current vertex with the direct solution x += H_ii\b_ii + * @return the determinant of the inverted hessian + */ + virtual double solveDirect(double lambda=0) = 0; + + /** + * sets the initial estimate from an array of double + * Implement setEstimateDataImpl() + * @return true on success + */ + bool setEstimateData(const double* estimate); + + /** + * sets the initial estimate from an array of double + * Implement setEstimateDataImpl() + * @return true on success + */ + bool setEstimateData(const std::vector& estimate) { +#ifndef NDEBUG + int dim = estimateDimension(); + assert((dim == -1) || (estimate.size() == std::size_t(dim))); +#endif + return setEstimateData(&estimate[0]); + }; + + /** + * writes the estimater to an array of double + * @returns true on success + */ + virtual bool getEstimateData(double* estimate) const; + + /** + * writes the estimater to an array of double + * @returns true on success + */ + virtual bool getEstimateData(std::vector& estimate) const { + int dim = estimateDimension(); + if (dim < 0) + return false; + estimate.resize(dim); + return getEstimateData(&estimate[0]); + }; + + /** + * returns the dimension of the extended representation used by get/setEstimate(double*) + * -1 if it is not supported + */ + virtual int estimateDimension() const; + + /** + * sets the initial estimate from an array of double. + * Implement setMinimalEstimateDataImpl() + * @return true on success + */ + bool setMinimalEstimateData(const double* estimate); + + /** + * sets the initial estimate from an array of double. + * Implement setMinimalEstimateDataImpl() + * @return true on success + */ + bool setMinimalEstimateData(const std::vector& estimate) { +#ifndef NDEBUG + int dim = minimalEstimateDimension(); + assert((dim == -1) || (estimate.size() == std::size_t(dim))); +#endif + return setMinimalEstimateData(&estimate[0]); + }; + + /** + * writes the estimate to an array of double + * @returns true on success + */ + virtual bool getMinimalEstimateData(double* estimate) const ; + + /** + * writes the estimate to an array of double + * @returns true on success + */ + virtual bool getMinimalEstimateData(std::vector& estimate) const { + int dim = minimalEstimateDimension(); + if (dim < 0) + return false; + estimate.resize(dim); + return getMinimalEstimateData(&estimate[0]); + }; + + /** + * returns the dimension of the extended representation used by get/setEstimate(double*) + * -1 if it is not supported + */ + virtual int minimalEstimateDimension() const; + + //! backup the position of the vertex to a stack + virtual void push() = 0; + + //! restore the position of the vertex by retrieving the position from the stack + virtual void pop() = 0; + + //! pop the last element from the stack, without restoring the current estimate + virtual void discardTop() = 0; + + //! return the stack size + virtual int stackSize() const = 0; + + /** + * Update the position of the node from the parameters in v. + * Depends on the implementation of oplusImpl in derived classes to actually carry + * out the update. + * Will also call updateCache() to update the caches of depending on the vertex. + */ + void oplus(const double* v) + { + oplusImpl(v); + updateCache(); + } + + //! temporary index of this node in the parameter vector obtained from linearization + int hessianIndex() const { return _hessianIndex;} + int G2O_ATTRIBUTE_DEPRECATED(tempIndex() const) { return hessianIndex();} + //! set the temporary index of the vertex in the parameter blocks + void setHessianIndex(int ti) { _hessianIndex = ti;} + void G2O_ATTRIBUTE_DEPRECATED(setTempIndex(int ti)) { setHessianIndex(ti);} + + //! true => this node is fixed during the optimization + bool fixed() const {return _fixed;} + //! true => this node should be considered fixed during the optimization + void setFixed(bool fixed) { _fixed = fixed;} + + //! true => this node is marginalized out during the optimization + bool marginalized() const {return _marginalized;} + //! true => this node should be marginalized out during the optimization + void setMarginalized(bool marginalized) { _marginalized = marginalized;} + + //! dimension of the estimated state belonging to this node + int dimension() const { return _dimension;} + + //! sets the id of the node in the graph be sure that the graph keeps consistent after changing the id + virtual void setId(int id) {_id = id;} + + //! set the row of this vertex in the Hessian + void setColInHessian(int c) { _colInHessian = c;} + //! get the row of this vertex in the Hessian + int colInHessian() const {return _colInHessian;} + + const OptimizableGraph* graph() const {return _graph;} + + OptimizableGraph* graph() {return _graph;} + + /** + * lock for the block of the hessian and the b vector associated with this vertex, to avoid + * race-conditions if multi-threaded. + */ + void lockQuadraticForm() { _quadraticFormMutex.lock();} + /** + * unlock the block of the hessian and the b vector associated with this vertex + */ + void unlockQuadraticForm() { _quadraticFormMutex.unlock();} + + //! read the vertex from a stream, i.e., the internal state of the vertex + virtual bool read(std::istream& is) = 0; + //! write the vertex to a stream + virtual bool write(std::ostream& os) const = 0; + + virtual void updateCache(); + + CacheContainer* cacheContainer(); + protected: + OptimizableGraph* _graph; + Data* _userData; + int _hessianIndex; + bool _fixed; + bool _marginalized; + int _dimension; + int _colInHessian; + OpenMPMutex _quadraticFormMutex; + + CacheContainer* _cacheContainer; + + /** + * update the position of the node from the parameters in v. + * Implement in your class! + */ + virtual void oplusImpl(const double* v) = 0; + + //! sets the node to the origin (used in the multilevel stuff) + virtual void setToOriginImpl() = 0; + + /** + * writes the estimater to an array of double + * @returns true on success + */ + virtual bool setEstimateDataImpl(const double* ) { return false;} + + /** + * sets the initial estimate from an array of double + * @return true on success + */ + virtual bool setMinimalEstimateDataImpl(const double* ) { return false;} + + }; + + class Edge: public HyperGraph::Edge { + private: + friend struct OptimizableGraph; + public: + Edge(); + virtual ~Edge(); + virtual Edge* clone() const; + + // indicates if all vertices are fixed + virtual bool allVerticesFixed() const = 0; + + // computes the error of the edge and stores it in an internal structure + virtual void computeError() = 0; + + //! sets the measurement from an array of double + //! @returns true on success + virtual bool setMeasurementData(const double* m); + + //! writes the measurement to an array of double + //! @returns true on success + virtual bool getMeasurementData(double* m) const; + + //! returns the dimension of the measurement in the extended representation which is used + //! by get/setMeasurement; + virtual int measurementDimension() const; + + /** + * sets the estimate to have a zero error, based on the current value of the state variables + * returns false if not supported. + */ + virtual bool setMeasurementFromState(); + + //! if NOT NULL, error of this edge will be robustifed with the kernel + RobustKernel* robustKernel() const { return _robustKernel;} + /** + * specify the robust kernel to be used in this edge + */ + void setRobustKernel(RobustKernel* ptr); + + //! returns the error vector cached after calling the computeError; + virtual const double* errorData() const = 0; + virtual double* errorData() = 0; + + //! returns the memory of the information matrix, usable for example with a Eigen::Map + virtual const double* informationData() const = 0; + virtual double* informationData() = 0; + + //! computes the chi2 based on the cached error value, only valid after computeError has been called. + virtual double chi2() const = 0; + + /** + * Linearizes the constraint in the edge. + * Makes side effect on the vertices of the graph by changing + * the parameter vector b and the hessian blocks ii and jj. + * The off diagoinal block is accesed via _hessian. + */ + virtual void constructQuadraticForm() = 0; + + /** + * maps the internal matrix to some external memory location, + * you need to provide the memory before calling constructQuadraticForm + * @param d the memory location to which we map + * @param i index of the vertex i + * @param j index of the vertex j (j > i, upper triangular fashion) + * @param rowMajor if true, will write in rowMajor order to the block. Since EIGEN is columnMajor by default, this results in writing the transposed + */ + virtual void mapHessianMemory(double* d, int i, int j, bool rowMajor) = 0; + + /** + * Linearizes the constraint in the edge in the manifold space, and store + * the result in the given workspace + */ + virtual void linearizeOplus(JacobianWorkspace& jacobianWorkspace) = 0; + + /** set the estimate of the to vertex, based on the estimate of the from vertices in the edge. */ + virtual void initialEstimate(const OptimizableGraph::VertexSet& from, OptimizableGraph::Vertex* to) = 0; + + /** + * override in your class if it's possible to initialize the vertices in certain combinations. + * The return value may correspond to the cost for initiliaizng the vertex but should be positive if + * the initialization is possible and negative if not possible. + */ + virtual double initialEstimatePossible(const OptimizableGraph::VertexSet& from, OptimizableGraph::Vertex* to) { (void) from; (void) to; return -1.;} + + //! returns the level of the edge + int level() const { return _level;} + //! sets the level of the edge + void setLevel(int l) { _level=l;} + + //! returns the dimensions of the error function + int dimension() const { return _dimension;} + + virtual Vertex* createFrom() {return 0;} + virtual Vertex* createTo() {return 0;} + + //! read the vertex from a stream, i.e., the internal state of the vertex + virtual bool read(std::istream& is) = 0; + //! write the vertex to a stream + virtual bool write(std::ostream& os) const = 0; + + //! the internal ID of the edge + long long internalId() const { return _internalId;} + + OptimizableGraph* graph(); + const OptimizableGraph* graph() const; + + bool setParameterId(int argNum, int paramId); + inline const Parameter* parameter(int argNo) const {return *_parameters.at(argNo);} + inline size_t numParameters() const {return _parameters.size();} + inline void resizeParameters(size_t newSize) { + _parameters.resize(newSize, 0); + _parameterIds.resize(newSize, -1); + _parameterTypes.resize(newSize, typeid(void*).name()); + } + protected: + int _dimension; + int _level; + RobustKernel* _robustKernel; + long long _internalId; + + std::vector _cacheIds; + + template + bool installParameter(ParameterType*& p, size_t argNo, int paramId=-1){ + if (argNo>=_parameters.size()) + return false; + _parameterIds[argNo] = paramId; + _parameters[argNo] = (Parameter**)&p; + _parameterTypes[argNo] = typeid(ParameterType).name(); + return true; + } + + template + void resolveCache(CacheType*& cache, OptimizableGraph::Vertex*, + const std::string& _type, + const ParameterVector& parameters); + + bool resolveParameters(); + virtual bool resolveCaches(); + + std::vector _parameterTypes; + std::vector _parameters; + std::vector _parameterIds; + }; + + //! returns the vertex number id appropriately casted + inline Vertex* vertex(int id) { return reinterpret_cast(HyperGraph::vertex(id));} + + //! returns the vertex number id appropriately casted + inline const Vertex* vertex (int id) const{ return reinterpret_cast(HyperGraph::vertex(id));} + + //! empty constructor + OptimizableGraph(); + virtual ~OptimizableGraph(); + + //! adds all edges and vertices of the graph g to this graph. + void addGraph(OptimizableGraph* g); + + /** + * adds a new vertex. The new vertex is then "taken". + * @return false if a vertex with the same id as v is already in the graph, true otherwise. + */ + virtual bool addVertex(HyperGraph::Vertex* v, Data* userData); + virtual bool addVertex(HyperGraph::Vertex* v) { return addVertex(v, 0);} + + /** + * adds a new edge. + * The edge should point to the vertices that it is connecting (setFrom/setTo). + * @return false if the insertion does not work (incompatible types of the vertices/missing vertex). true otherwise. + */ + virtual bool addEdge(HyperGraph::Edge* e); + + //! returns the chi2 of the current configuration + double chi2() const; + + //! return the maximum dimension of all vertices in the graph + int maxDimension() const; + + /** + * iterates over all vertices and returns a set of all the vertex dimensions in the graph + */ + std::set dimensions() const; + + /** + * carry out n iterations + * @return the number of performed iterations + */ + virtual int optimize(int iterations, bool online=false); + + //! called at the beginning of an iteration (argument is the number of the iteration) + virtual void preIteration(int); + //! called at the end of an iteration (argument is the number of the iteration) + virtual void postIteration(int); + + //! add an action to be executed before each iteration + bool addPreIterationAction(HyperGraphAction* action); + //! add an action to be executed after each iteration + bool addPostIterationAction(HyperGraphAction* action); + + //! remove an action that should no longer be execured before each iteration + bool removePreIterationAction(HyperGraphAction* action); + //! remove an action that should no longer be execured after each iteration + bool removePostIterationAction(HyperGraphAction* action); + + //! push the estimate of all variables onto a stack + virtual void push(); + //! pop (restore) the estimate of all variables from the stack + virtual void pop(); + //! discard the last backup of the estimate for all variables by removing it from the stack + virtual void discardTop(); + + //! load the graph from a stream. Uses the Factory singleton for creating the vertices and edges. + virtual bool load(std::istream& is, bool createEdges=true); + bool load(const char* filename, bool createEdges=true); + //! save the graph to a stream. Again uses the Factory system. + virtual bool save(std::ostream& os, int level = 0) const; + //! function provided for convenience, see save() above + bool save(const char* filename, int level = 0) const; + + + //! save a subgraph to a stream. Again uses the Factory system. + bool saveSubset(std::ostream& os, HyperGraph::VertexSet& vset, int level = 0); + + //! save a subgraph to a stream. Again uses the Factory system. + bool saveSubset(std::ostream& os, HyperGraph::EdgeSet& eset); + + //! push the estimate of a subset of the variables onto a stack + virtual void push(HyperGraph::VertexSet& vset); + //! pop (restore) the estimate a subset of the variables from the stack + virtual void pop(HyperGraph::VertexSet& vset); + //! ignore the latest stored element on the stack, remove it from the stack but do not restore the estimate + virtual void discardTop(HyperGraph::VertexSet& vset); + + //! fixes/releases a set of vertices + virtual void setFixed(HyperGraph::VertexSet& vset, bool fixed); + + /** + * set the renamed types lookup from a string, format is for example: + * VERTEX_CAM=VERTEX_SE3:EXPMAP,EDGE_PROJECT_P2MC=EDGE_PROJECT_XYZ:EXPMAP + * This will change the occurance of VERTEX_CAM in the file to VERTEX_SE3:EXPMAP + */ + void setRenamedTypesFromString(const std::string& types); + + /** + * test whether a solver is suitable for optimizing this graph. + * @param solverProperty the solver property to evaluate. + * @param vertDims should equal to the set returned by dimensions() to avoid re-evaluating. + */ + bool isSolverSuitable(const OptimizationAlgorithmProperty& solverProperty, const std::set& vertDims = std::set()) const; + + /** + * remove the parameters of the graph + */ + virtual void clearParameters(); + + bool addParameter(Parameter* p) { + return _parameters.addParameter(p); + } + + Parameter* parameter(int id) { + return _parameters.getParameter(id); + } + + /** + * verify that all the information of the edges are semi positive definite, i.e., + * all Eigenvalues are >= 0. + * @param verbose output edges with not PSD information matrix on cerr + * @return true if all edges have PSD information matrix + */ + bool verifyInformationMatrices(bool verbose = false) const; + + // helper functions to save an individual vertex + bool saveVertex(std::ostream& os, Vertex* v) const; + + // helper functions to save an individual edge + bool saveEdge(std::ostream& os, Edge* e) const; + //! the workspace for storing the Jacobians of the graph + JacobianWorkspace& jacobianWorkspace() { return _jacobianWorkspace;} + const JacobianWorkspace& jacobianWorkspace() const { return _jacobianWorkspace;} + + /** + * Eigen starting from version 3.1 requires that we call an initialize + * function, if we perform calls to Eigen from several threads. + * Currently, this function calls Eigen::initParallel if g2o is compiled + * with OpenMP support and Eigen's version is at least 3.1 + */ + static bool initMultiThreading(); + + protected: + std::map _renamedTypesLookup; + long long _nextEdgeId; + std::vector _graphActions; + + // do not watch this. To be removed soon, or integrated in a nice way + bool _edge_has_id; + + ParameterContainer _parameters; + JacobianWorkspace _jacobianWorkspace; + }; + + /** + @} + */ + +} // end namespace + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/optimization_algorithm.cpp b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/optimization_algorithm.cpp new file mode 100644 index 0000000..0888176 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/optimization_algorithm.cpp @@ -0,0 +1,62 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#include "optimization_algorithm.h" + +using namespace std; + +namespace g2o { + +OptimizationAlgorithm::OptimizationAlgorithm() : + _optimizer(0) +{ +} + +OptimizationAlgorithm::~OptimizationAlgorithm() +{ +} + +void OptimizationAlgorithm::printProperties(std::ostream& os) const +{ + os << "------------- Algorithm Properties -------------" << endl; + for (PropertyMap::const_iterator it = _properties.begin(); it != _properties.end(); ++it) { + BaseProperty* p = it->second; + os << it->first << "\t" << p->toString() << endl; + } + os << "------------------------------------------------" << endl; +} + +bool OptimizationAlgorithm::updatePropertiesFromString(const std::string& propString) +{ + return _properties.updateMapFromString(propString); +} + +void OptimizationAlgorithm::setOptimizer(SparseOptimizer* optimizer) +{ + _optimizer = optimizer; +} + +} // end namespace diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/optimization_algorithm.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/optimization_algorithm.h new file mode 100644 index 0000000..470a450 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/optimization_algorithm.h @@ -0,0 +1,117 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_OPTIMIZATION_ALGORITHM_H +#define G2O_OPTIMIZATION_ALGORITHM_H + +#include +#include +#include + +#include "../stuff/property.h" + +#include "hyper_graph.h" +#include "sparse_block_matrix.h" + +namespace g2o { + + class SparseOptimizer; + + /** + * \brief Generic interface for a non-linear solver operating on a graph + */ + class OptimizationAlgorithm + { + public: + enum SolverResult {Terminate=2, OK=1, Fail=-1}; + OptimizationAlgorithm(); + virtual ~OptimizationAlgorithm(); + + /** + * initialize the solver, called once before the first call to solve() + */ + virtual bool init(bool online = false) = 0; + + /** + * Solve one iteration. The SparseOptimizer running on-top will call this + * for the given number of iterations. + * @param iteration indicates the current iteration + */ + virtual SolverResult solve(int iteration, bool online = false) = 0; + + /** + * computes the block diagonal elements of the pattern specified in the input + * and stores them in given SparseBlockMatrix. + * If your solver does not support computing the marginals, return false. + */ + virtual bool computeMarginals(SparseBlockMatrix& spinv, const std::vector >& blockIndices) = 0; + + /** + * update the structures for online processing + */ + virtual bool updateStructure(const std::vector& vset, const HyperGraph::EdgeSet& edges) = 0; + + /** + * called by the optimizer if verbose. re-implement, if you want to print something + */ + virtual void printVerbose(std::ostream& os) const {(void) os;}; + + public: + //! return the optimizer operating on + const SparseOptimizer* optimizer() const { return _optimizer;} + SparseOptimizer* optimizer() { return _optimizer;} + + /** + * specify on which optimizer the solver should work on + */ + void setOptimizer(SparseOptimizer* optimizer); + + //! return the properties of the solver + const PropertyMap& properties() const { return _properties;} + + /** + * update the properties from a string, see PropertyMap::updateMapFromString() + */ + bool updatePropertiesFromString(const std::string& propString); + + /** + * print the properties to a stream in a human readable fashion + */ + void printProperties(std::ostream& os) const; + + protected: + SparseOptimizer* _optimizer; ///< the optimizer the solver is working on + PropertyMap _properties; ///< the properties of your solver, use this to store the parameters of your solver + + private: + // Disable the copy constructor and assignment operator + OptimizationAlgorithm(const OptimizationAlgorithm&) { } + OptimizationAlgorithm& operator= (const OptimizationAlgorithm&) { return *this; } + }; + +} // end namespace + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/optimization_algorithm_dogleg.cpp b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/optimization_algorithm_dogleg.cpp new file mode 100644 index 0000000..f63e071 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/optimization_algorithm_dogleg.cpp @@ -0,0 +1,229 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#include "optimization_algorithm_dogleg.h" + +#include + +#include "../stuff/timeutil.h" + +#include "block_solver.h" +#include "sparse_optimizer.h" +#include "solver.h" +#include "batch_stats.h" +using namespace std; + +namespace g2o { + + OptimizationAlgorithmDogleg::OptimizationAlgorithmDogleg(BlockSolverBase* solver) : + OptimizationAlgorithmWithHessian(solver) + { + _userDeltaInit = _properties.makeProperty >("initialDelta", 1e4); + _maxTrialsAfterFailure = _properties.makeProperty >("maxTrialsAfterFailure", 100); + _initialLambda = _properties.makeProperty >("initialLambda", 1e-7); + _lamdbaFactor = _properties.makeProperty >("lambdaFactor", 10.); + _delta = _userDeltaInit->value(); + _lastStep = STEP_UNDEFINED; + _wasPDInAllIterations = true; + } + + OptimizationAlgorithmDogleg::~OptimizationAlgorithmDogleg() + { + } + + OptimizationAlgorithm::SolverResult OptimizationAlgorithmDogleg::solve(int iteration, bool online) + { + assert(_optimizer && "_optimizer not set"); + assert(_solver->optimizer() == _optimizer && "underlying linear solver operates on different graph"); + assert(dynamic_cast(_solver) && "underlying linear solver is not a block solver"); + + BlockSolverBase* blockSolver = static_cast(_solver); + + if (iteration == 0 && !online) { // built up the CCS structure, here due to easy time measure + bool ok = _solver->buildStructure(); + if (! ok) { + cerr << __PRETTY_FUNCTION__ << ": Failure while building CCS structure" << endl; + return OptimizationAlgorithm::Fail; + } + + // init some members to the current size of the problem + _hsd.resize(_solver->vectorSize()); + _hdl.resize(_solver->vectorSize()); + _auxVector.resize(_solver->vectorSize()); + _delta = _userDeltaInit->value(); + _currentLambda = _initialLambda->value(); + _wasPDInAllIterations = true; + } + + double t=get_monotonic_time(); + _optimizer->computeActiveErrors(); + G2OBatchStatistics* globalStats = G2OBatchStatistics::globalStats(); + if (globalStats) { + globalStats->timeResiduals = get_monotonic_time()-t; + t=get_monotonic_time(); + } + + double currentChi = _optimizer->activeRobustChi2(); + + _solver->buildSystem(); + if (globalStats) { + globalStats->timeQuadraticForm = get_monotonic_time()-t; + } + + Eigen::VectorXd::ConstMapType b(_solver->b(), _solver->vectorSize()); + + // compute alpha + _auxVector.setZero(); + blockSolver->multiplyHessian(_auxVector.data(), _solver->b()); + double bNormSquared = b.squaredNorm(); + double alpha = bNormSquared / _auxVector.dot(b); + + _hsd = alpha * b; + double hsdNorm = _hsd.norm(); + double hgnNorm = -1.; + + bool solvedGaussNewton = false; + bool goodStep = false; + int& numTries = _lastNumTries; + numTries = 0; + do { + ++numTries; + + if (! solvedGaussNewton) { + const double minLambda = 1e-12; + const double maxLambda = 1e3; + solvedGaussNewton = true; + // apply a damping factor to enforce positive definite Hessian, if the matrix appeared + // to be not positive definite in at least one iteration before. + // We apply a damping factor to obtain a PD matrix. + bool solverOk = false; + while(!solverOk) { + if (! _wasPDInAllIterations) + _solver->setLambda(_currentLambda, true); // add _currentLambda to the diagonal + solverOk = _solver->solve(); + if (! _wasPDInAllIterations) + _solver->restoreDiagonal(); + _wasPDInAllIterations = _wasPDInAllIterations && solverOk; + if (! _wasPDInAllIterations) { + // simple strategy to control the damping factor + if (solverOk) { + _currentLambda = std::max(minLambda, _currentLambda / (0.5 * _lamdbaFactor->value())); + } else { + _currentLambda *= _lamdbaFactor->value(); + if (_currentLambda > maxLambda) { + _currentLambda = maxLambda; + return Fail; + } + } + } + } + if (!solverOk) { + return Fail; + } + hgnNorm = Eigen::VectorXd::ConstMapType(_solver->x(), _solver->vectorSize()).norm(); + } + + Eigen::VectorXd::ConstMapType hgn(_solver->x(), _solver->vectorSize()); + assert(hgnNorm >= 0. && "Norm of the GN step is not computed"); + + if (hgnNorm < _delta) { + _hdl = hgn; + _lastStep = STEP_GN; + } + else if (hsdNorm > _delta) { + _hdl = _delta / hsdNorm * _hsd; + _lastStep = STEP_SD; + } else { + _auxVector = hgn - _hsd; // b - a + double c = _hsd.dot(_auxVector); + double bmaSquaredNorm = _auxVector.squaredNorm(); + double beta; + if (c <= 0.) + beta = (-c + sqrt(c*c + bmaSquaredNorm * (_delta*_delta - _hsd.squaredNorm()))) / bmaSquaredNorm; + else { + double hsdSqrNorm = _hsd.squaredNorm(); + beta = (_delta*_delta - hsdSqrNorm) / (c + sqrt(c*c + bmaSquaredNorm * (_delta*_delta - hsdSqrNorm))); + } + assert(beta > 0. && beta < 1 && "Error while computing beta"); + _hdl = _hsd + beta * (hgn - _hsd); + _lastStep = STEP_DL; + assert(_hdl.norm() < _delta + 1e-5 && "Computed step does not correspond to the trust region"); + } + + // compute the linear gain + _auxVector.setZero(); + blockSolver->multiplyHessian(_auxVector.data(), _hdl.data()); + double linearGain = -1 * (_auxVector.dot(_hdl)) + 2 * (b.dot(_hdl)); + + // apply the update and see what happens + _optimizer->push(); + _optimizer->update(_hdl.data()); + _optimizer->computeActiveErrors(); + double newChi = _optimizer-> activeRobustChi2(); + double nonLinearGain = currentChi - newChi; + if (fabs(linearGain) < 1e-12) + linearGain = 1e-12; + double rho = nonLinearGain / linearGain; + //cerr << PVAR(nonLinearGain) << " " << PVAR(linearGain) << " " << PVAR(rho) << endl; + if (rho > 0) { // step is good and will be accepted + _optimizer->discardTop(); + goodStep = true; + } else { // recover previous state + _optimizer->pop(); + } + + // update trust region based on the step quality + if (rho > 0.75) + _delta = std::max(_delta, 3. * _hdl.norm()); + else if (rho < 0.25) + _delta *= 0.5; + } while (!goodStep && numTries < _maxTrialsAfterFailure->value()); + if (numTries == _maxTrialsAfterFailure->value() || !goodStep) + return Terminate; + return OK; + } + + void OptimizationAlgorithmDogleg::printVerbose(std::ostream& os) const + { + os + << "\t Delta= " << _delta + << "\t step= " << stepType2Str(_lastStep) + << "\t tries= " << _lastNumTries; + if (! _wasPDInAllIterations) + os << "\t lambda= " << _currentLambda; + } + + const char* OptimizationAlgorithmDogleg::stepType2Str(int stepType) + { + switch (stepType) { + case STEP_SD: return "Descent"; + case STEP_GN: return "GN"; + case STEP_DL: return "Dogleg"; + default: return "Undefined"; + } + } + +} // end namespace diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/optimization_algorithm_dogleg.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/optimization_algorithm_dogleg.h new file mode 100644 index 0000000..e49761c --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/optimization_algorithm_dogleg.h @@ -0,0 +1,89 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_OPTIMIZATION_ALGORITHM_DOGLEG_H +#define G2O_OPTIMIZATION_ALGORITHM_DOGLEG_H + +#include "optimization_algorithm_with_hessian.h" + +namespace g2o { + + class BlockSolverBase; + + /** + * \brief Implementation of Powell's Dogleg Algorithm + */ + class OptimizationAlgorithmDogleg : public OptimizationAlgorithmWithHessian + { + public: + /** \brief type of the step to take */ + enum { + STEP_UNDEFINED, + STEP_SD, STEP_GN, STEP_DL + }; + + public: + /** + * construct the Dogleg algorithm, which will use the given Solver for solving the + * linearized system. + */ + explicit OptimizationAlgorithmDogleg(BlockSolverBase* solver); + virtual ~OptimizationAlgorithmDogleg(); + + virtual SolverResult solve(int iteration, bool online = false); + + virtual void printVerbose(std::ostream& os) const; + + //! return the type of the last step taken by the algorithm + int lastStep() const { return _lastStep;} + //! return the diameter of the trust region + double trustRegion() const { return _delta;} + + //! convert the type into an integer + static const char* stepType2Str(int stepType); + + protected: + // parameters + Property* _maxTrialsAfterFailure; + Property* _userDeltaInit; + // damping to enforce positive definite matrix + Property* _initialLambda; + Property* _lamdbaFactor; + + Eigen::VectorXd _hsd; ///< steepest decent step + Eigen::VectorXd _hdl; ///< final dogleg step + Eigen::VectorXd _auxVector; ///< auxilary vector used to perform multiplications or other stuff + + double _currentLambda; ///< the damping factor to force positive definite matrix + double _delta; ///< trust region + int _lastStep; ///< type of the step taken by the algorithm + bool _wasPDInAllIterations; ///< the matrix we solve was positive definite in all iterations -> if not apply damping + int _lastNumTries; + }; + +} // end namespace + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/optimization_algorithm_factory.cpp b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/optimization_algorithm_factory.cpp new file mode 100644 index 0000000..a9be96e --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/optimization_algorithm_factory.cpp @@ -0,0 +1,137 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#include "optimization_algorithm_factory.h" + +#include +#include +#include + +using namespace std; + +namespace g2o { + + AbstractOptimizationAlgorithmCreator::AbstractOptimizationAlgorithmCreator(const OptimizationAlgorithmProperty& p) : + _property(p) + { + } + + OptimizationAlgorithmFactory* OptimizationAlgorithmFactory::factoryInstance = 0; + + OptimizationAlgorithmFactory::OptimizationAlgorithmFactory() + { + } + + OptimizationAlgorithmFactory::~OptimizationAlgorithmFactory() + { + for (CreatorList::iterator it = _creator.begin(); it != _creator.end(); ++it) + delete *it; + } + + OptimizationAlgorithmFactory* OptimizationAlgorithmFactory::instance() + { + if (factoryInstance == 0) { + factoryInstance = new OptimizationAlgorithmFactory; + } + return factoryInstance; + } + + void OptimizationAlgorithmFactory::registerSolver(AbstractOptimizationAlgorithmCreator* c) + { + const string& name = c->property().name; + CreatorList::iterator foundIt = findSolver(name); + if (foundIt != _creator.end()) { + _creator.erase(foundIt); + cerr << "SOLVER FACTORY WARNING: Overwriting Solver creator " << name << endl; + assert(0); + } + _creator.push_back(c); + } + + void OptimizationAlgorithmFactory::unregisterSolver(AbstractOptimizationAlgorithmCreator* c) + { + const string& name = c->property().name; + CreatorList::iterator foundIt = findSolver(name); + if (foundIt != _creator.end()) { + delete *foundIt; + _creator.erase(foundIt); + } + } + + OptimizationAlgorithm* OptimizationAlgorithmFactory::construct(const std::string& name, OptimizationAlgorithmProperty& solverProperty) const + { + CreatorList::const_iterator foundIt = findSolver(name); + if (foundIt != _creator.end()) { + solverProperty = (*foundIt)->property(); + return (*foundIt)->construct(); + } + cerr << "SOLVER FACTORY WARNING: Unable to create solver " << name << endl; + return 0; + } + + void OptimizationAlgorithmFactory::destroy() + { + delete factoryInstance; + factoryInstance = 0; + } + + void OptimizationAlgorithmFactory::listSolvers(std::ostream& os) const + { + size_t solverNameColumnLength = 0; + for (CreatorList::const_iterator it = _creator.begin(); it != _creator.end(); ++it) + solverNameColumnLength = std::max(solverNameColumnLength, (*it)->property().name.size()); + solverNameColumnLength += 4; + + for (CreatorList::const_iterator it = _creator.begin(); it != _creator.end(); ++it) { + const OptimizationAlgorithmProperty& sp = (*it)->property(); + os << sp.name; + for (size_t i = sp.name.size(); i < solverNameColumnLength; ++i) + os << ' '; + os << sp.desc << endl; + } + } + + OptimizationAlgorithmFactory::CreatorList::const_iterator OptimizationAlgorithmFactory::findSolver(const std::string& name) const + { + for (CreatorList::const_iterator it = _creator.begin(); it != _creator.end(); ++it) { + const OptimizationAlgorithmProperty& sp = (*it)->property(); + if (sp.name == name) + return it; + } + return _creator.end(); + } + + OptimizationAlgorithmFactory::CreatorList::iterator OptimizationAlgorithmFactory::findSolver(const std::string& name) + { + for (CreatorList::iterator it = _creator.begin(); it != _creator.end(); ++it) { + const OptimizationAlgorithmProperty& sp = (*it)->property(); + if (sp.name == name) + return it; + } + return _creator.end(); + } + +} // end namespace diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/optimization_algorithm_factory.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/optimization_algorithm_factory.h new file mode 100644 index 0000000..b8bf26e --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/optimization_algorithm_factory.h @@ -0,0 +1,167 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_OPTMIZATION_ALGORITHM_PROPERTY_H +#define G2O_OPTMIZATION_ALGORITHM_PROPERTY_H + +#include "../../config.h" +#include "../stuff/misc.h" +#include "optimization_algorithm_property.h" + +#include +#include +#include + + +// define to get some verbose output +//#define G2O_DEBUG_OPTIMIZATION_ALGORITHM_FACTORY + +namespace g2o { + + // forward decl + class OptimizationAlgorithm; + class SparseOptimizer; + + /** + * \brief base for allocating an optimization algorithm + * + * Allocating a solver for a given optimizer. The method construct() has to be + * implemented in your derived class to allocate the desired solver. + */ + class AbstractOptimizationAlgorithmCreator + { + public: + AbstractOptimizationAlgorithmCreator(const OptimizationAlgorithmProperty& p); + virtual ~AbstractOptimizationAlgorithmCreator() { } + //! allocate a solver operating on optimizer, re-implement for your creator + virtual OptimizationAlgorithm* construct() = 0; + //! return the properties of the solver + const OptimizationAlgorithmProperty& property() const { return _property;} + protected: + OptimizationAlgorithmProperty _property; + }; + + /** + * \brief create solvers based on their short name + * + * Factory to allocate solvers based on their short name. + * The Factory is implemented as a sigleton and the single + * instance can be accessed via the instance() function. + */ + class OptimizationAlgorithmFactory + { + public: + typedef std::list CreatorList; + + //! return the instance + static OptimizationAlgorithmFactory* instance(); + + //! free the instance + static void destroy(); + + /** + * register a specific creator for allocating a solver + */ + void registerSolver(AbstractOptimizationAlgorithmCreator* c); + + /** + * unregister a specific creator for allocating a solver + */ + void unregisterSolver(AbstractOptimizationAlgorithmCreator* c); + + /** + * construct a solver based on its name, e.g., var, fix3_2_cholmod + */ + OptimizationAlgorithm* construct(const std::string& tag, OptimizationAlgorithmProperty& solverProperty) const; + + //! list the known solvers into a stream + void listSolvers(std::ostream& os) const; + + //! return the underlying list of creators + const CreatorList& creatorList() const { return _creator;} + + protected: + OptimizationAlgorithmFactory(); + ~OptimizationAlgorithmFactory(); + + CreatorList _creator; + + CreatorList::const_iterator findSolver(const std::string& name) const; + CreatorList::iterator findSolver(const std::string& name); + + private: + static OptimizationAlgorithmFactory* factoryInstance; + }; + + class RegisterOptimizationAlgorithmProxy + { + public: + RegisterOptimizationAlgorithmProxy(AbstractOptimizationAlgorithmCreator* c) + { + _creator = c; +#ifdef G2O_DEBUG_OPTIMIZATION_ALGORITHM_FACTORY + std::cout << __FUNCTION__ << ": Registering " << _creator->property().name << " of type " << typeid(*_creator).name() << std::endl; +#endif + OptimizationAlgorithmFactory::instance()->registerSolver(c); + } + + ~RegisterOptimizationAlgorithmProxy() + { +#ifdef G2O_DEBUG_OPTIMIZATION_ALGORITHM_FACTORY + std::cout << __FUNCTION__ << ": Unregistering " << _creator->property().name << std::endl; +#endif + OptimizationAlgorithmFactory::instance()->unregisterSolver(_creator); + } + private: + AbstractOptimizationAlgorithmCreator* _creator; + }; + +} + +#if defined _MSC_VER && defined G2O_SHARED_LIBS +# define G2O_OAF_EXPORT __declspec(dllexport) +# define G2O_OAF_IMPORT __declspec(dllimport) +#else +# define G2O_OAF_EXPORT +# define G2O_OAF_IMPORT +#endif + +#define G2O_REGISTER_OPTIMIZATION_LIBRARY(libraryname) \ + extern "C" void G2O_OAF_EXPORT g2o_optimization_library_##libraryname(void) {} + +#define G2O_USE_OPTIMIZATION_LIBRARY(libraryname) \ + extern "C" void G2O_OAF_IMPORT g2o_optimization_library_##libraryname(void); \ + static g2o::ForceLinker g2o_force_optimization_algorithm_library_##libraryname(g2o_optimization_library_##libraryname); + +#define G2O_REGISTER_OPTIMIZATION_ALGORITHM(optimizername, instance) \ + extern "C" void G2O_OAF_EXPORT g2o_optimization_algorithm_##optimizername(void) {} \ + static g2o::RegisterOptimizationAlgorithmProxy g_optimization_algorithm_proxy_##optimizername(instance); + +#define G2O_USE_OPTIMIZATION_ALGORITHM(optimizername) \ + extern "C" void G2O_OAF_IMPORT g2o_optimization_algorithm_##optimizername(void); \ + static g2o::ForceLinker g2o_force_optimization_algorithm_link_##optimizername(g2o_optimization_algorithm_##optimizername); + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/optimization_algorithm_gauss_newton.cpp b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/optimization_algorithm_gauss_newton.cpp new file mode 100644 index 0000000..04ca445 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/optimization_algorithm_gauss_newton.cpp @@ -0,0 +1,101 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#include "optimization_algorithm_gauss_newton.h" + +#include + +#include "../stuff/timeutil.h" +#include "../stuff/macros.h" + +#include "solver.h" +#include "batch_stats.h" +#include "sparse_optimizer.h" +using namespace std; + +namespace g2o { + + OptimizationAlgorithmGaussNewton::OptimizationAlgorithmGaussNewton(Solver* solver) : + OptimizationAlgorithmWithHessian(solver) + { + } + + OptimizationAlgorithmGaussNewton::~OptimizationAlgorithmGaussNewton() + { + } + + OptimizationAlgorithm::SolverResult OptimizationAlgorithmGaussNewton::solve(int iteration, bool online) + { + assert(_optimizer && "_optimizer not set"); + assert(_solver->optimizer() == _optimizer && "underlying linear solver operates on different graph"); + bool ok = true; + + //here so that correct component for max-mixtures can be computed before the build structure + double t=get_monotonic_time(); + _optimizer->computeActiveErrors(); + G2OBatchStatistics* globalStats = G2OBatchStatistics::globalStats(); + if (globalStats) { + globalStats->timeResiduals = get_monotonic_time()-t; + } + + if (iteration == 0 && !online) { // built up the CCS structure, here due to easy time measure + ok = _solver->buildStructure(); + if (! ok) { + cerr << __PRETTY_FUNCTION__ << ": Failure while building CCS structure" << endl; + return OptimizationAlgorithm::Fail; + } + } + + t=get_monotonic_time(); + _solver->buildSystem(); + if (globalStats) { + globalStats->timeQuadraticForm = get_monotonic_time()-t; + t=get_monotonic_time(); + } + + ok = _solver->solve(); + if (globalStats) { + globalStats->timeLinearSolution = get_monotonic_time()-t; + t=get_monotonic_time(); + } + + _optimizer->update(_solver->x()); + if (globalStats) { + globalStats->timeUpdate = get_monotonic_time()-t; + } + if (ok) + return OK; + else + return Fail; + } + + void OptimizationAlgorithmGaussNewton::printVerbose(std::ostream& os) const + { + os + << "\t schur= " << _solver->schur(); + } + +} // end namespace diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/optimization_algorithm_gauss_newton.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/optimization_algorithm_gauss_newton.h new file mode 100644 index 0000000..409aa27 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/optimization_algorithm_gauss_newton.h @@ -0,0 +1,54 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_OPTIMIZATION_ALGORITHM_GAUSS_NEWTON_H +#define G2O_OPTIMIZATION_ALGORITHM_GAUSS_NEWTON_H + +#include "optimization_algorithm_with_hessian.h" + +namespace g2o { + + /** + * \brief Implementation of the Gauss Newton Algorithm + */ + class OptimizationAlgorithmGaussNewton : public OptimizationAlgorithmWithHessian + { + public: + /** + * construct the Gauss Newton algorithm, which use the given Solver for solving the + * linearized system. + */ + explicit OptimizationAlgorithmGaussNewton(Solver* solver); + virtual ~OptimizationAlgorithmGaussNewton(); + + virtual SolverResult solve(int iteration, bool online = false); + + virtual void printVerbose(std::ostream& os) const; + }; + +} // end namespace + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/optimization_algorithm_levenberg.cpp b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/optimization_algorithm_levenberg.cpp new file mode 100644 index 0000000..067678f --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/optimization_algorithm_levenberg.cpp @@ -0,0 +1,214 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +// Modified Raul Mur Artal (2014) +// - Stop criterium (solve function) + +#include "optimization_algorithm_levenberg.h" + +#include + +#include "../stuff/timeutil.h" + +#include "sparse_optimizer.h" +#include "solver.h" +#include "batch_stats.h" +using namespace std; + +namespace g2o { + + OptimizationAlgorithmLevenberg::OptimizationAlgorithmLevenberg(Solver* solver) : + OptimizationAlgorithmWithHessian(solver) + { + _currentLambda = -1.; + _tau = 1e-5; // Carlos: originally 1e-5 + _goodStepUpperScale = 2./3.; + _goodStepLowerScale = 1./3.; + _userLambdaInit = _properties.makeProperty >("initialLambda", 0.); + _maxTrialsAfterFailure = _properties.makeProperty >("maxTrialsAfterFailure", 10); // Carlos: Originally 10 iterations + _ni=2.; + _levenbergIterations = 0; + _nBad = 0; + } + + OptimizationAlgorithmLevenberg::~OptimizationAlgorithmLevenberg() + { + } + + OptimizationAlgorithm::SolverResult OptimizationAlgorithmLevenberg::solve(int iteration, bool online) + { + assert(_optimizer && "_optimizer not set"); + assert(_solver->optimizer() == _optimizer && "underlying linear solver operates on different graph"); + + if (iteration == 0 && !online) { // built up the CCS structure, here due to easy time measure + bool ok = _solver->buildStructure(); + if (! ok) { + cerr << __PRETTY_FUNCTION__ << ": Failure while building CCS structure" << endl; + return OptimizationAlgorithm::Fail; + } + } + + double t=get_monotonic_time(); + _optimizer->computeActiveErrors(); + G2OBatchStatistics* globalStats = G2OBatchStatistics::globalStats(); + if (globalStats) { + globalStats->timeResiduals = get_monotonic_time()-t; + t=get_monotonic_time(); + } + + double currentChi = _optimizer->activeRobustChi2(); + double tempChi=currentChi; + + double iniChi = currentChi; + + _solver->buildSystem(); + if (globalStats) { + globalStats->timeQuadraticForm = get_monotonic_time()-t; + } + + // core part of the Levenbarg algorithm + if (iteration == 0) { + _currentLambda = computeLambdaInit(); + _ni = 2; + _nBad = 0; + } + + double rho=0; + int& qmax = _levenbergIterations; + qmax = 0; + do { + _optimizer->push(); + if (globalStats) { + globalStats->levenbergIterations++; + t=get_monotonic_time(); + } + // update the diagonal of the system matrix + _solver->setLambda(_currentLambda, true); + bool ok2 = _solver->solve(); + if (globalStats) { + globalStats->timeLinearSolution+=get_monotonic_time()-t; + t=get_monotonic_time(); + } + _optimizer->update(_solver->x()); + if (globalStats) { + globalStats->timeUpdate = get_monotonic_time()-t; + } + + // restore the diagonal + _solver->restoreDiagonal(); + + _optimizer->computeActiveErrors(); + tempChi = _optimizer->activeRobustChi2(); + // cout << "tempChi: " << tempChi << endl; + if (! ok2) + tempChi=std::numeric_limits::max(); + + rho = (currentChi-tempChi); + double scale = computeScale(); + scale += 1e-3; // make sure it's non-zero :) + rho /= scale; + + if (rho>0 && g2o_isfinite(tempChi)){ // last step was good + double alpha = 1.-pow((2*rho-1),3); + // crop lambda between minimum and maximum factors + alpha = (std::min)(alpha, _goodStepUpperScale); + double scaleFactor = (std::max)(_goodStepLowerScale, alpha); + _currentLambda *= scaleFactor; + _ni = 2; + currentChi=tempChi; + _optimizer->discardTop(); + } else { + _currentLambda*=_ni; + _ni*=2; + _optimizer->pop(); // restore the last state before trying to optimize + } + qmax++; + } while (rho<0 && qmax < _maxTrialsAfterFailure->value() && ! _optimizer->terminate()); + + if (qmax == _maxTrialsAfterFailure->value() || rho==0) + { + // cout << "qmax = " << qmax << " rho = " << rho << endl; + return Terminate; + } + + //Stop criterium (Raul) + if((iniChi-currentChi)*1e3=3) + { + return Terminate; + } + + return OK; + } + + double OptimizationAlgorithmLevenberg::computeLambdaInit() const + { + if (_userLambdaInit->value() > 0) + return _userLambdaInit->value(); + double maxDiagonal=0.; + for (size_t k = 0; k < _optimizer->indexMapping().size(); k++) { + OptimizableGraph::Vertex* v = _optimizer->indexMapping()[k]; + assert(v); + int dim = v->dimension(); + for (int j = 0; j < dim; ++j){ + maxDiagonal = std::max(fabs(v->hessian(j,j)),maxDiagonal); + } + } + return _tau*maxDiagonal; + } + + double OptimizationAlgorithmLevenberg::computeScale() const + { + double scale = 0.; + for (size_t j=0; j < _solver->vectorSize(); j++){ + scale += _solver->x()[j] * (_currentLambda * _solver->x()[j] + _solver->b()[j]); + } + return scale; + } + + void OptimizationAlgorithmLevenberg::setMaxTrialsAfterFailure(int max_trials) + { + _maxTrialsAfterFailure->setValue(max_trials); + } + + void OptimizationAlgorithmLevenberg::setUserLambdaInit(double lambda) + { + _userLambdaInit->setValue(lambda); + } + + void OptimizationAlgorithmLevenberg::printVerbose(std::ostream& os) const + { + os + << "\t schur= " << _solver->schur() + << "\t lambda= " << FIXED(_currentLambda) + << "\t levenbergIter= " << _levenbergIterations; + } + +} // end namespace diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/optimization_algorithm_levenberg.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/optimization_algorithm_levenberg.h new file mode 100644 index 0000000..bc4a4a0 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/optimization_algorithm_levenberg.h @@ -0,0 +1,92 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_SOLVER_LEVENBERG_H +#define G2O_SOLVER_LEVENBERG_H + +#include "optimization_algorithm_with_hessian.h" + +namespace g2o { + + /** + * \brief Implementation of the Levenberg Algorithm + */ + class OptimizationAlgorithmLevenberg : public OptimizationAlgorithmWithHessian + { + public: + /** + * construct the Levenberg algorithm, which will use the given Solver for solving the + * linearized system. + */ + explicit OptimizationAlgorithmLevenberg(Solver* solver); + virtual ~OptimizationAlgorithmLevenberg(); + + virtual SolverResult solve(int iteration, bool online = false); + + virtual void printVerbose(std::ostream& os) const; + + //! return the currently used damping factor + double currentLambda() const { return _currentLambda;} + + //! the number of internal iteration if an update step increases chi^2 within Levenberg-Marquardt + void setMaxTrialsAfterFailure(int max_trials); + + //! get the number of inner iterations for Levenberg-Marquardt + int maxTrialsAfterFailure() const { return _maxTrialsAfterFailure->value();} + + //! return the lambda set by the user, if < 0 the SparseOptimizer will compute the initial lambda + double userLambdaInit() {return _userLambdaInit->value();} + //! specify the initial lambda used for the first iteraion, if not given the SparseOptimizer tries to compute a suitable value + void setUserLambdaInit(double lambda); + + //! return the number of levenberg iterations performed in the last round + int levenbergIteration() { return _levenbergIterations;} + + protected: + // Levenberg parameters + Property* _maxTrialsAfterFailure; + Property* _userLambdaInit; + double _currentLambda; + double _tau; + double _goodStepLowerScale; ///< lower bound for lambda decrease if a good LM step + double _goodStepUpperScale; ///< upper bound for lambda decrease if a good LM step + double _ni; + int _levenbergIterations; ///< the numer of levenberg iterations performed to accept the last step + //RAUL + int _nBad; + + /** + * helper for Levenberg, this function computes the initial damping factor, if the user did not + * specify an own value, see setUserLambdaInit() + */ + double computeLambdaInit() const; + double computeScale() const; + + }; + +} // end namespace + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/optimization_algorithm_property.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/optimization_algorithm_property.h new file mode 100644 index 0000000..62abb0e --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/optimization_algorithm_property.h @@ -0,0 +1,57 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_OPTIMIZATION_ALGORITHM_PROPERTY_H +#define G2O_OPTIMIZATION_ALGORITHM_PROPERTY_H + +#include + +namespace g2o { + +/** + * \brief describe the properties of a solver + */ +struct OptimizationAlgorithmProperty +{ + std::string name; ///< name of the solver, e.g., var + std::string desc; ///< short description of the solver + std::string type; ///< type of solver, e.g., "CSparse Cholesky", "PCG" + bool requiresMarginalize; ///< whether the solver requires marginalization of landmarks + int poseDim; ///< dimension of the pose vertices (-1 if variable) + int landmarkDim; ///< dimension of the landmar vertices (-1 if variable) + OptimizationAlgorithmProperty() : + name(), desc(), type(), requiresMarginalize(false), poseDim(-1), landmarkDim(-1) + { + } + OptimizationAlgorithmProperty(const std::string& name_, const std::string& desc_, const std::string& type_, bool requiresMarginalize_, int poseDim_, int landmarkDim_) : + name(name_), desc(desc_), type(type_), requiresMarginalize(requiresMarginalize_), poseDim(poseDim_), landmarkDim(landmarkDim_) + { + } +}; + +} // end namespace + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/optimization_algorithm_with_hessian.cpp b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/optimization_algorithm_with_hessian.cpp new file mode 100644 index 0000000..5c23a78 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/optimization_algorithm_with_hessian.cpp @@ -0,0 +1,101 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#include "optimization_algorithm_with_hessian.h" + +#include "solver.h" +#include "optimizable_graph.h" +#include "sparse_optimizer.h" + +#include +using namespace std; + +namespace g2o { + + OptimizationAlgorithmWithHessian::OptimizationAlgorithmWithHessian(Solver* solver) : + OptimizationAlgorithm(), + _solver(solver) + { + _writeDebug = _properties.makeProperty >("writeDebug", true); + } + + OptimizationAlgorithmWithHessian::~OptimizationAlgorithmWithHessian() + { + delete _solver; + } + + bool OptimizationAlgorithmWithHessian::init(bool online) + { + assert(_optimizer && "_optimizer not set"); + assert(_solver && "Solver not set"); + _solver->setWriteDebug(_writeDebug->value()); + bool useSchur=false; + for (OptimizableGraph::VertexContainer::const_iterator it=_optimizer->activeVertices().begin(); it!=_optimizer->activeVertices().end(); ++it) { + OptimizableGraph::Vertex* v= *it; + if (v->marginalized()){ + useSchur=true; + break; + } + } + if (useSchur){ + if (_solver->supportsSchur()) + _solver->setSchur(true); + } else { + if (_solver->supportsSchur()) + _solver->setSchur(false); + } + + bool initState = _solver->init(_optimizer, online); + return initState; + } + + bool OptimizationAlgorithmWithHessian::computeMarginals(SparseBlockMatrix& spinv, const std::vector >& blockIndices) + { + return _solver ? _solver->computeMarginals(spinv, blockIndices) : false; + } + + bool OptimizationAlgorithmWithHessian::buildLinearStructure() + { + return _solver ? _solver->buildStructure() : false; + } + + void OptimizationAlgorithmWithHessian::updateLinearSystem() + { + if (_solver) + _solver->buildSystem(); + } + + bool OptimizationAlgorithmWithHessian::updateStructure(const std::vector& vset, const HyperGraph::EdgeSet& edges) + { + return _solver ? _solver->updateStructure(vset, edges) : false; + } + + void OptimizationAlgorithmWithHessian::setWriteDebug(bool writeDebug) + { + _writeDebug->setValue(writeDebug); + } + +} // end namespace diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/optimization_algorithm_with_hessian.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/optimization_algorithm_with_hessian.h new file mode 100644 index 0000000..cf5da58 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/optimization_algorithm_with_hessian.h @@ -0,0 +1,72 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_OPTIMIZATION_ALGORITHM_WITH_HESSIAN_H +#define G2O_OPTIMIZATION_ALGORITHM_WITH_HESSIAN_H + +#include "optimization_algorithm.h" + +namespace g2o { + + class Solver; + + /** + * \brief Base for solvers operating on the approximated Hessian, e.g., Gauss-Newton, Levenberg + */ + class OptimizationAlgorithmWithHessian : public OptimizationAlgorithm + { + public: + explicit OptimizationAlgorithmWithHessian(Solver* solver); + virtual ~OptimizationAlgorithmWithHessian(); + + virtual bool init(bool online = false); + + virtual bool computeMarginals(SparseBlockMatrix& spinv, const std::vector >& blockIndices); + + virtual bool buildLinearStructure(); + + virtual void updateLinearSystem(); + + virtual bool updateStructure(const std::vector& vset, const HyperGraph::EdgeSet& edges); + + //! return the underlying solver used to solve the linear system + Solver* solver() { return _solver;} + + /** + * write debug output of the Hessian if system is not positive definite + */ + virtual void setWriteDebug(bool writeDebug); + virtual bool writeDebug() const { return _writeDebug->value();} + + protected: + Solver* _solver; + Property* _writeDebug; + + }; + +}// end namespace + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/parameter.cpp b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/parameter.cpp new file mode 100644 index 0000000..345f9c0 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/parameter.cpp @@ -0,0 +1,40 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#include "parameter.h" + +namespace g2o { + + Parameter::Parameter() : _id(-1) + { + } + + void Parameter::setId(int id_) + { + _id = id_; + } + +} // end namespace diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/parameter.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/parameter.h new file mode 100644 index 0000000..6def664 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/parameter.h @@ -0,0 +1,56 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_GRAPH_PARAMETER_HH_ +#define G2O_GRAPH_PARAMETER_HH_ + +#include + +#include "hyper_graph.h" + +namespace g2o { + + class Parameter : public HyperGraph::HyperGraphElement + { + public: + Parameter(); + virtual ~Parameter() {}; + //! read the data from a stream + virtual bool read(std::istream& is) = 0; + //! write the data to a stream + virtual bool write(std::ostream& os) const = 0; + int id() const {return _id;} + void setId(int id_); + virtual HyperGraph::HyperGraphElementType elementType() const { return HyperGraph::HGET_PARAMETER;} + protected: + int _id; + }; + + typedef std::vector ParameterVector; + +} // end namespace + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/parameter_container.cpp b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/parameter_container.cpp new file mode 100644 index 0000000..d012331 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/parameter_container.cpp @@ -0,0 +1,142 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#include "parameter_container.h" + +#include + +#include "factory.h" +#include "parameter.h" + +#include "../stuff/macros.h" +#include "../stuff/color_macros.h" +#include "../stuff/string_tools.h" + +namespace g2o { + + using namespace std; + + ParameterContainer::ParameterContainer(bool isMainStorage_) : + _isMainStorage(isMainStorage_) + { + } + + void ParameterContainer::clear() { + if (!_isMainStorage) + return; + for (iterator it = begin(); it!=end(); it++){ + delete it->second; + } + BaseClass::clear(); + } + + ParameterContainer::~ParameterContainer(){ + clear(); + } + + bool ParameterContainer::addParameter(Parameter* p){ + if (p->id()<0) + return false; + iterator it=find(p->id()); + if (it!=end()) + return false; + insert(make_pair(p->id(), p)); + return true; + } + + Parameter* ParameterContainer::getParameter(int id) { + iterator it=find(id); + if (it==end()) + return 0; + return it->second; + } + + Parameter* ParameterContainer::detachParameter(int id){ + iterator it=find(id); + if (it==end()) + return 0; + Parameter* p=it->second; + erase(it); + return p; + } + + bool ParameterContainer::write(std::ostream& os) const{ + Factory* factory = Factory::instance(); + for (const_iterator it=begin(); it!=end(); it++){ + os << factory->tag(it->second) << " "; + os << it->second->id() << " "; + it->second->write(os); + os << endl; + } + return true; + } + + bool ParameterContainer::read(std::istream& is, const std::map* _renamedTypesLookup){ + stringstream currentLine; + string token; + + Factory* factory = Factory::instance(); + HyperGraph::GraphElemBitset elemBitset; + elemBitset[HyperGraph::HGET_PARAMETER] = 1; + + while (1) { + int bytesRead = readLine(is, currentLine); + if (bytesRead == -1) + break; + currentLine >> token; + if (bytesRead == 0 || token.size() == 0 || token[0] == '#') + continue; + if (_renamedTypesLookup && _renamedTypesLookup->size()>0){ + map::const_iterator foundIt = _renamedTypesLookup->find(token); + if (foundIt != _renamedTypesLookup->end()) { + token = foundIt->second; + } + } + + HyperGraph::HyperGraphElement* element = factory->construct(token, elemBitset); + if (! element) // not a parameter or otherwise unknown tag + continue; + assert(element->elementType() == HyperGraph::HGET_PARAMETER && "Should be a param"); + + Parameter* p = static_cast(element); + int pid; + currentLine >> pid; + p->setId(pid); + bool r = p->read(currentLine); + if (! r) { + cerr << __PRETTY_FUNCTION__ << ": Error reading data " << token << " for parameter " << pid << endl; + delete p; + } else { + if (! addParameter(p) ){ + cerr << __PRETTY_FUNCTION__ << ": Parameter of type:" << token << " id:" << pid << " already defined" << endl; + } + } + } // while read line + + return true; + } + +} // end namespace diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/parameter_container.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/parameter_container.h new file mode 100644 index 0000000..eef6c2f --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/parameter_container.h @@ -0,0 +1,74 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_GRAPH_PARAMETER_CONTAINER_HH_ +#define G2O_GRAPH_PARAMETER_CONTAINER_HH_ + +#include +#include +#include + +namespace g2o { + + class Parameter; + + /** + * \brief map id to parameters + */ + class ParameterContainer : protected std::map + { + public: + typedef std::map BaseClass; + + /** + * create a container for the parameters. + * @param isMainStorage_ pointers to the parameters are owned by this container, i.e., freed in its constructor + */ + ParameterContainer(bool isMainStorage_=true); + virtual ~ParameterContainer(); + //! add parameter to the container + bool addParameter(Parameter* p); + //! return a parameter based on its ID + Parameter* getParameter(int id); + //! remove a parameter from the container, i.e., the user now owns the pointer + Parameter* detachParameter(int id); + //! read parameters from a stream + virtual bool read(std::istream& is, const std::map* renamedMap =0); + //! write the data to a stream + virtual bool write(std::ostream& os) const; + bool isMainStorage() const {return _isMainStorage;} + void clear(); + + // stuff of the base class that should re-appear + using BaseClass::size; + + protected: + bool _isMainStorage; + }; + +} // end namespace + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/robust_kernel.cpp b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/robust_kernel.cpp new file mode 100644 index 0000000..ac6776d --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/robust_kernel.cpp @@ -0,0 +1,46 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#include "robust_kernel.h" + +namespace g2o { + +RobustKernel::RobustKernel() : + _delta(1.) +{ +} + +RobustKernel::RobustKernel(double delta) : + _delta(delta) +{ +} + +void RobustKernel::setDelta(double delta) +{ + _delta = delta; +} + +} // end namespace g2o diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/robust_kernel.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/robust_kernel.h new file mode 100644 index 0000000..29e1394 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/robust_kernel.h @@ -0,0 +1,81 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_ROBUST_KERNEL_H +#define G2O_ROBUST_KERNEL_H + +#ifdef _MSC_VER +#include +#else +#include +#endif +#include + + +namespace g2o { + + /** + * \brief base for all robust cost functions + * + * Note in all the implementations for the other cost functions the e in the + * funtions corresponds to the sqaured errors, i.e., the robustification + * functions gets passed the squared error. + * + * e.g. the robustified least squares function is + * + * chi^2 = sum_{e} rho( e^T Omega e ) + */ + class RobustKernel + { + public: + RobustKernel(); + explicit RobustKernel(double delta); + virtual ~RobustKernel() {} + /** + * compute the scaling factor for a error: + * The error is e^T Omega e + * The output rho is + * rho[0]: The actual scaled error value + * rho[1]: First derivative of the scaling function + * rho[2]: Second derivative of the scaling function + */ + virtual void robustify(double squaredError, Eigen::Vector3d& rho) const = 0; + + /** + * set the window size of the error. A squared error above delta^2 is considered + * as outlier in the data. + */ + virtual void setDelta(double delta); + double delta() const { return _delta;} + + protected: + double _delta; + }; + typedef std::tr1::shared_ptr RobustKernelPtr; + +} // end namespace g2o + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/robust_kernel_factory.cpp b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/robust_kernel_factory.cpp new file mode 100644 index 0000000..1d028cf --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/robust_kernel_factory.cpp @@ -0,0 +1,111 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#include "robust_kernel_factory.h" +#include "robust_kernel.h" + +#include + +using namespace std; + +namespace g2o { + +RobustKernelFactory* RobustKernelFactory::factoryInstance = 0; + +RobustKernelFactory::RobustKernelFactory() +{ +} + +RobustKernelFactory::~RobustKernelFactory() +{ + for (CreatorMap::iterator it = _creator.begin(); it != _creator.end(); ++it) { + delete it->second; + } + _creator.clear(); +} + +RobustKernelFactory* RobustKernelFactory::instance() +{ + if (factoryInstance == 0) { + factoryInstance = new RobustKernelFactory; + } + + return factoryInstance; +} + +void RobustKernelFactory::registerRobustKernel(const std::string& tag, AbstractRobustKernelCreator* c) +{ + CreatorMap::const_iterator foundIt = _creator.find(tag); + if (foundIt != _creator.end()) { + cerr << "RobustKernelFactory WARNING: Overwriting robust kernel tag " << tag << endl; + assert(0); + } + + _creator[tag] = c; +} + +void RobustKernelFactory::unregisterType(const std::string& tag) +{ + CreatorMap::iterator tagPosition = _creator.find(tag); + if (tagPosition != _creator.end()) { + AbstractRobustKernelCreator* c = tagPosition->second; + delete c; + _creator.erase(tagPosition); + } +} + +RobustKernel* RobustKernelFactory::construct(const std::string& tag) const +{ + CreatorMap::const_iterator foundIt = _creator.find(tag); + if (foundIt != _creator.end()) { + return foundIt->second->construct(); + } + return 0; +} + +AbstractRobustKernelCreator* RobustKernelFactory::creator(const std::string& tag) const +{ + CreatorMap::const_iterator foundIt = _creator.find(tag); + if (foundIt != _creator.end()) { + return foundIt->second; + } + return 0; +} + +void RobustKernelFactory::fillKnownKernels(std::vector& types) const +{ + types.clear(); + for (CreatorMap::const_iterator it = _creator.begin(); it != _creator.end(); ++it) + types.push_back(it->first); +} + +void RobustKernelFactory::destroy() +{ + delete factoryInstance; + factoryInstance = 0; +} + +} // end namespace diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/robust_kernel_factory.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/robust_kernel_factory.h new file mode 100644 index 0000000..bcdec07 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/robust_kernel_factory.h @@ -0,0 +1,151 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_ROBUST_KERNEL_FACTORY_H +#define G2O_ROBUST_KERNEL_FACTORY_H + +#include "../stuff/misc.h" + +#include +#include +#include +#include + +namespace g2o { + + class RobustKernel; + + /** + * \brief Abstract interface for allocating a robust kernel + */ + class AbstractRobustKernelCreator + { + public: + /** + * create a hyper graph element. Has to implemented in derived class. + */ + virtual RobustKernel* construct() = 0; + virtual ~AbstractRobustKernelCreator() { } + }; + + /** + * \brief templatized creator class which creates graph elements + */ + template + class RobustKernelCreator : public AbstractRobustKernelCreator + { + public: + RobustKernel* construct() { return new T;} + }; + + /** + * \brief create robust kernels based on their human readable name + */ + class RobustKernelFactory + { + public: + + //! return the instance + static RobustKernelFactory* instance(); + + //! free the instance + static void destroy(); + + /** + * register a tag for a specific creator + */ + void registerRobustKernel(const std::string& tag, AbstractRobustKernelCreator* c); + + /** + * unregister a tag for a specific creator + */ + void unregisterType(const std::string& tag); + + /** + * construct a robust kernel based on its tag + */ + RobustKernel* construct(const std::string& tag) const; + + /** + * return the creator for a specific tag + */ + AbstractRobustKernelCreator* creator(const std::string& tag) const; + + /** + * get a list of all known robust kernels + */ + void fillKnownKernels(std::vector& types) const; + + protected: + + typedef std::map CreatorMap; + RobustKernelFactory(); + ~RobustKernelFactory(); + + CreatorMap _creator; ///< look-up map for the existing creators + + private: + static RobustKernelFactory* factoryInstance; + }; + + template + class RegisterRobustKernelProxy + { + public: + RegisterRobustKernelProxy(const std::string& name) : _name(name) + { + RobustKernelFactory::instance()->registerRobustKernel(_name, new RobustKernelCreator()); + } + + ~RegisterRobustKernelProxy() + { + RobustKernelFactory::instance()->unregisterType(_name); + } + + private: + std::string _name; + }; + +#if defined _MSC_VER && defined G2O_SHARED_LIBS +# define G2O_ROBUST_KERNEL_FACTORY_EXPORT __declspec(dllexport) +# define G2O_ROBUST_KERNEL_FACTORY_IMPORT __declspec(dllimport) +#else +# define G2O_ROBUST_KERNEL_FACTORY_EXPORT +# define G2O_ROBUST_KERNEL_FACTORY_IMPORT +#endif + + // These macros are used to automate registering of robust kernels and forcing linkage +#define G2O_REGISTER_ROBUST_KERNEL(name, classname) \ + extern "C" void G2O_ROBUST_KERNEL_FACTORY_EXPORT g2o_robust_kernel_##classname(void) {} \ + static g2o::RegisterRobustKernelProxy g_robust_kernel_proxy_##classname(#name); + +#define G2O_USE_ROBUST_KERNEL(classname) \ + extern "C" void G2O_ROBUST_KERNEL_FACTORY_IMPORT g2o_robust_kernel_##classname(void); \ + static g2o::TypeFunctionProxy proxy_##classname(g2o_robust_kernel_##classname); + +} // end namespace g2o + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/robust_kernel_impl.cpp b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/robust_kernel_impl.cpp new file mode 100644 index 0000000..e446efc --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/robust_kernel_impl.cpp @@ -0,0 +1,173 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#include "robust_kernel_impl.h" +#include "robust_kernel_factory.h" + +#include + +namespace g2o { + +RobustKernelScaleDelta::RobustKernelScaleDelta(const RobustKernelPtr& kernel, double delta) : + RobustKernel(delta), + _kernel(kernel) +{ +} + +RobustKernelScaleDelta::RobustKernelScaleDelta(double delta) : + RobustKernel(delta) +{ +} + +void RobustKernelScaleDelta::setKernel(const RobustKernelPtr& ptr) +{ + _kernel = ptr; +} + +void RobustKernelScaleDelta::robustify(double error, Eigen::Vector3d& rho) const +{ + if (_kernel.get()) { + double dsqr = _delta * _delta; + double dsqrReci = 1. / dsqr; + _kernel->robustify(dsqrReci * error, rho); + rho[0] *= dsqr; + rho[2] *= dsqrReci; + } else { // no robustification + rho[0] = error; + rho[1] = 1.; + rho[2] = 0.; + } +} + +void RobustKernelHuber::setDelta(double delta) +{ + dsqr = delta*delta; + _delta = delta; +} + + +void RobustKernelHuber::setDeltaSqr(const double &delta, const double &deltaSqr) +{ + dsqr = deltaSqr; + _delta = delta; +} + +void RobustKernelHuber::robustify(double e, Eigen::Vector3d& rho) const +{ + //dsqr = _delta * _delta; + if (e <= dsqr) { // inlier + rho[0] = e; + rho[1] = 1.; + rho[2] = 0.; + } else { // outlier + double sqrte = sqrt(e); // absolut value of the error + rho[0] = 2*sqrte*_delta - dsqr; // rho(e) = 2 * delta * e^(1/2) - delta^2 + rho[1] = _delta / sqrte; // rho'(e) = delta / sqrt(e) + rho[2] = - 0.5 * rho[1] / e; // rho''(e) = -1 / (2*e^(3/2)) = -1/2 * (delta/e) / e + } +} + +void RobustKernelTukey::setDeltaSqr(const double &deltaSqr, const double &inv) +{ + _deltaSqr = deltaSqr; + _invDeltaSqr = inv; + +} + +void RobustKernelTukey::robustify(double e, Eigen::Vector3d& rho) const +{ + if (e <= _deltaSqr) { // inlier + double factor = e*_invDeltaSqr; + double d = 1-factor; + double dd = d*d; + rho[0] = _deltaSqr*(1-dd*d); + rho[1] = 3*dd; + rho[2] = -6*_invDeltaSqr*d; + } else { // outlier + rho[0] = _deltaSqr; // rho(e) = delta^2 + rho[1] = 0.; + rho[2] = 0.; + } +} + +void RobustKernelPseudoHuber::robustify(double e2, Eigen::Vector3d& rho) const +{ + double dsqr = _delta * _delta; + double dsqrReci = 1. / dsqr; + double aux1 = dsqrReci * e2 + 1.0; + double aux2 = sqrt(aux1); + rho[0] = 2 * dsqr * (aux2 - 1); + rho[1] = 1. / aux2; + rho[2] = -0.5 * dsqrReci * rho[1] / aux1; +} + +void RobustKernelCauchy::robustify(double e2, Eigen::Vector3d& rho) const +{ + double dsqr = _delta * _delta; + double dsqrReci = 1. / dsqr; + double aux = dsqrReci * e2 + 1.0; + rho[0] = dsqr * log(aux); + rho[1] = 1. / aux; + rho[2] = -dsqrReci * std::pow(rho[1], 2); +} + +void RobustKernelSaturated::robustify(double e2, Eigen::Vector3d& rho) const +{ + double dsqr = _delta * _delta; + if (e2 <= dsqr) { // inlier + rho[0] = e2; + rho[1] = 1.; + rho[2] = 0.; + } else { // outlier + rho[0] = dsqr; + rho[1] = 0.; + rho[2] = 0.; + } +} + +//delta is used as $phi$ +void RobustKernelDCS::robustify(double e2, Eigen::Vector3d& rho) const +{ + const double& phi = _delta; + double scale = (2.0*phi)/(phi+e2); + if(scale>=1.0) + scale = 1.0; + + rho[0] = scale*e2*scale; + rho[1] = (scale*scale); + rho[2] = 0; +} + + +// register the kernel to their factory +G2O_REGISTER_ROBUST_KERNEL(Huber, RobustKernelHuber) +G2O_REGISTER_ROBUST_KERNEL(Tukey, RobustKernelTukey) +G2O_REGISTER_ROBUST_KERNEL(PseudoHuber, RobustKernelPseudoHuber) +G2O_REGISTER_ROBUST_KERNEL(Cauchy, RobustKernelCauchy) +G2O_REGISTER_ROBUST_KERNEL(Saturated, RobustKernelSaturated) +G2O_REGISTER_ROBUST_KERNEL(DCS, RobustKernelDCS) + +} // end namespace g2o diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/robust_kernel_impl.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/robust_kernel_impl.h new file mode 100644 index 0000000..066cc37 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/robust_kernel_impl.h @@ -0,0 +1,167 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_ROBUST_KERNEL_IMPL_H +#define G2O_ROBUST_KERNEL_IMPL_H + +#include "robust_kernel.h" + +namespace g2o { + + /** + * \brief scale a robust kernel to another delta (window size) + * + * Scales a robust kernel to another window size. Useful, in case if + * one implements a kernel which only is designed for a fixed window + * size. + */ + class RobustKernelScaleDelta : public RobustKernel + { + public: + /** + * construct the scaled kernel ontop of another kernel which might be shared accross + * several scaled kernels + */ + explicit RobustKernelScaleDelta(const RobustKernelPtr& kernel, double delta = 1.); + explicit RobustKernelScaleDelta(double delta = 1.); + + //! return the underlying kernel + const RobustKernelPtr kernel() const { return _kernel;} + //! use another kernel for the underlying operation + void setKernel(const RobustKernelPtr& ptr); + + void robustify(double error, Eigen::Vector3d& rho) const; + + protected: + RobustKernelPtr _kernel; + }; + + /** + * \brief Huber Cost Function + * + * Loss function as described by Huber + * See http://en.wikipedia.org/wiki/Huber_loss_function + * + * If e^(1/2) < d + * rho(e) = e + * + * else + * + * 1/2 2 + * rho(e) = 2 d e - d + */ + class RobustKernelHuber : public RobustKernel + { + public: + virtual void setDelta(double delta); + virtual void setDeltaSqr(const double &delta, const double &deltaSqr); + virtual void robustify(double e2, Eigen::Vector3d& rho) const; + + private: + float dsqr; + }; + + /** + * \brief Tukey Cost Function + * + * + * If e^(1/2) < d + * rho(e) = delta2(1-(1-e/delta2)^3) + * + * else + * + * rho(e) = delta2 + */ + class RobustKernelTukey : public RobustKernel + { + public: + + virtual void setDeltaSqr(const double &deltaSqr, const double &inv); + virtual void robustify(double e2, Eigen::Vector3d& rho) const; + private: + float _deltaSqr; + float _invDeltaSqr; + }; + + + /** + * \brief Pseudo Huber Cost Function + * + * The smooth pseudo huber cost function: + * See http://en.wikipedia.org/wiki/Huber_loss_function + * + * 2 e + * 2 d (sqrt(-- + 1) - 1) + * 2 + * d + */ + class RobustKernelPseudoHuber : public RobustKernel + { + public: + virtual void robustify(double e2, Eigen::Vector3d& rho) const; + }; + + /** + * \brief Cauchy cost function + * + * 2 e + * d log(-- + 1) + * 2 + * d + */ + class RobustKernelCauchy : public RobustKernel + { + public: + virtual void robustify(double e2, Eigen::Vector3d& rho) const; + }; + + /** + * \brief Saturated cost function. + * + * The error is at most delta^2 + */ + class RobustKernelSaturated : public RobustKernel + { + public: + virtual void robustify(double e2, Eigen::Vector3d& rho) const; + }; + + /** + * \brief Dynamic covariance scaling - DCS + * + * See paper Robust Map Optimization from Agarwal et al. ICRA 2013 + * + * delta is used as $phi$ + */ + class RobustKernelDCS : public RobustKernel + { + public: + virtual void robustify(double e2, Eigen::Vector3d& rho) const; + }; + +} // end namespace g2o + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/solver.cpp b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/solver.cpp new file mode 100644 index 0000000..cdddfac --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/solver.cpp @@ -0,0 +1,87 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#include "solver.h" + +#include +#include + +namespace g2o { + +Solver::Solver() : + _optimizer(0), _x(0), _b(0), _xSize(0), _maxXSize(0), + _isLevenberg(false), _additionalVectorSpace(0) +{ +} + +Solver::~Solver() +{ + delete[] _x; + delete[] _b; +} + +void Solver::resizeVector(size_t sx) +{ + size_t oldSize = _xSize; + _xSize = sx; + sx += _additionalVectorSpace; // allocate some additional space if requested + if (_maxXSize < sx) { + _maxXSize = 2*sx; + delete[] _x; + _x = new double[_maxXSize]; +#ifndef NDEBUG + memset(_x, 0, _maxXSize * sizeof(double)); +#endif + if (_b) { // backup the former b, might still be needed for online processing + memcpy(_x, _b, oldSize * sizeof(double)); + delete[] _b; + _b = new double[_maxXSize]; + std::swap(_b, _x); + } else { + _b = new double[_maxXSize]; +#ifndef NDEBUG + memset(_b, 0, _maxXSize * sizeof(double)); +#endif + } + } +} + +void Solver::setOptimizer(SparseOptimizer* optimizer) +{ + _optimizer = optimizer; +} + +void Solver::setLevenberg(bool levenberg) +{ + _isLevenberg = levenberg; +} + +void Solver::setAdditionalVectorSpace(size_t s) +{ + _additionalVectorSpace = s; +} + +} // end namespace diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/solver.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/solver.h new file mode 100644 index 0000000..a801d31 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/solver.h @@ -0,0 +1,151 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_SOLVER_H +#define G2O_SOLVER_H + +#include "hyper_graph.h" +#include "batch_stats.h" +#include "sparse_block_matrix.h" +#include + +namespace g2o { + + + class SparseOptimizer; + + /** + * \brief Generic interface for a sparse solver operating on a graph which solves one iteration of the linearized objective function + */ + class Solver + { + public: + Solver(); + virtual ~Solver(); + + public: + /** + * initialize the solver, called once before the first iteration + */ + virtual bool init(SparseOptimizer* optimizer, bool online = false) = 0; + + /** + * build the structure of the system + */ + virtual bool buildStructure(bool zeroBlocks = false) = 0; + /** + * update the structures for online processing + */ + virtual bool updateStructure(const std::vector& vset, const HyperGraph::EdgeSet& edges) = 0; + /** + * build the current system + */ + virtual bool buildSystem() = 0; + + /** + * solve Ax = b + */ + virtual bool solve() = 0; + + /** + * computes the block diagonal elements of the pattern specified in the input + * and stores them in given SparseBlockMatrix + */ + virtual bool computeMarginals(SparseBlockMatrix& spinv, const std::vector >& blockIndices) = 0; + + /** + * update the system while performing Levenberg, i.e., modifying the diagonal + * components of A by doing += lambda along the main diagonal of the Matrix. + * Note that this function may be called with a positive and a negative lambda. + * The latter is used to undo a former modification. + * If backup is true, then the solver should store a backup of the diagonal, which + * can be restored by restoreDiagonal() + */ + virtual bool setLambda(double lambda, bool backup = false) = 0; + + /** + * restore a previosly made backup of the diagonal + */ + virtual void restoreDiagonal() = 0; + + //! return x, the solution vector + double* x() { return _x;} + const double* x() const { return _x;} + //! return b, the right hand side of the system + double* b() { return _b;} + const double* b() const { return _b;} + + //! return the size of the solution vector (x) and b + size_t vectorSize() const { return _xSize;} + + //! the optimizer (graph) on which the solver works + SparseOptimizer* optimizer() const { return _optimizer;} + void setOptimizer(SparseOptimizer* optimizer); + + //! the system is Levenberg-Marquardt + bool levenberg() const { return _isLevenberg;} + void setLevenberg(bool levenberg); + + /** + * does this solver support the Schur complement for solving a system consisting of poses and + * landmarks. Re-implemement in a derived solver, if your solver supports it. + */ + virtual bool supportsSchur() {return false;} + + //! should the solver perform the schur complement or not + virtual bool schur()=0; + virtual void setSchur(bool s)=0; + + size_t additionalVectorSpace() const { return _additionalVectorSpace;} + void setAdditionalVectorSpace(size_t s); + + /** + * write debug output of the Hessian if system is not positive definite + */ + virtual void setWriteDebug(bool) = 0; + virtual bool writeDebug() const = 0; + + //! write the hessian to disk using the specified file name + virtual bool saveHessian(const std::string& /*fileName*/) const = 0; + + protected: + SparseOptimizer* _optimizer; + double* _x; + double* _b; + size_t _xSize, _maxXSize; + bool _isLevenberg; ///< the system we gonna solve is a Levenberg-Marquardt system + size_t _additionalVectorSpace; + + void resizeVector(size_t sx); + + private: + // Disable the copy constructor and assignment operator + Solver(const Solver&) { } + Solver& operator= (const Solver&) { return *this; } + }; +} // end namespace + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/sparse_block_matrix.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/sparse_block_matrix.h new file mode 100644 index 0000000..8e9b5ef --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/sparse_block_matrix.h @@ -0,0 +1,231 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_SPARSE_BLOCK_MATRIX_ +#define G2O_SPARSE_BLOCK_MATRIX_ + +#include +#include +#include +#include +#include +#include +#include + +#include "sparse_block_matrix_ccs.h" +#include "matrix_structure.h" +#include "matrix_operations.h" +#include "../../config.h" + +namespace g2o { + using namespace Eigen; +/** + * \brief Sparse matrix which uses blocks + * + * Template class that specifies a sparse block matrix. A block + * matrix is a sparse matrix made of dense blocks. These blocks + * cannot have a random pattern, but follow a (variable) grid + * structure. This structure is specified by a partition of the rows + * and the columns of the matrix. The blocks are represented by the + * Eigen::Matrix structure, thus they can be statically or dynamically + * allocated. For efficiency reasons it is convenient to allocate them + * statically, when possible. A static block matrix has all blocks of + * the same size, and the size of the block is specified by the + * template argument. If this is not the case, and you have different + * block sizes than you have to use a dynamic-block matrix (default + * template argument). + */ +template +class SparseBlockMatrix { + + public: + //! this is the type of the elementary block, it is an Eigen::Matrix. + typedef MatrixType SparseMatrixBlock; + + //! columns of the matrix + inline int cols() const {return _colBlockIndices.size() ? _colBlockIndices.back() : 0;} + //! rows of the matrix + inline int rows() const {return _rowBlockIndices.size() ? _rowBlockIndices.back() : 0;} + + typedef std::map IntBlockMap; + + /** + * constructs a sparse block matrix having a specific layout + * @param rbi: array of int containing the row layout of the blocks. + * the component i of the array should contain the index of the first row of the block i+1. + * @param rbi: array of int containing the column layout of the blocks. + * the component i of the array should contain the index of the first col of the block i+1. + * @param rb: number of row blocks + * @param cb: number of col blocks + * @param hasStorage: set it to true if the matrix "owns" the blocks, thus it deletes it on destruction. + * if false the matrix is only a "view" over an existing structure. + */ + SparseBlockMatrix( const int * rbi, const int* cbi, int rb, int cb, bool hasStorage=true); + + SparseBlockMatrix(); + + ~SparseBlockMatrix(); + + + //! this zeroes all the blocks. If dealloc=true the blocks are removed from memory + void clear(bool dealloc=false) ; + + //! returns the block at location r,c. if alloc=true he block is created if it does not exist + SparseMatrixBlock* block(int r, int c, bool alloc=false); + //! returns the block at location r,c + const SparseMatrixBlock* block(int r, int c) const; + + //! how many rows does the block at block-row r has? + inline int rowsOfBlock(int r) const { return r ? _rowBlockIndices[r] - _rowBlockIndices[r-1] : _rowBlockIndices[0] ; } + + //! how many cols does the block at block-col c has? + inline int colsOfBlock(int c) const { return c ? _colBlockIndices[c] - _colBlockIndices[c-1] : _colBlockIndices[0]; } + + //! where does the row at block-row r starts? + inline int rowBaseOfBlock(int r) const { return r ? _rowBlockIndices[r-1] : 0 ; } + + //! where does the col at block-col r starts? + inline int colBaseOfBlock(int c) const { return c ? _colBlockIndices[c-1] : 0 ; } + + //! number of non-zero elements + size_t nonZeros() const; + //! number of allocated blocks + size_t nonZeroBlocks() const; + + //! deep copy of a sparse-block-matrix; + SparseBlockMatrix* clone() const ; + + /** + * returns a view or a copy of the block matrix + * @param rmin: starting block row + * @param rmax: ending block row + * @param cmin: starting block col + * @param cmax: ending block col + * @param alloc: if true it makes a deep copy, if false it creates a view. + */ + SparseBlockMatrix* slice(int rmin, int rmax, int cmin, int cmax, bool alloc=true) const; + + //! transposes a block matrix, The transposed type should match the argument false on failure + template + bool transpose(SparseBlockMatrix*& dest) const; + + //! adds the current matrix to the destination + bool add(SparseBlockMatrix*& dest) const ; + + //! dest = (*this) * M + template + bool multiply(SparseBlockMatrix *& dest, const SparseBlockMatrix* M) const; + + //! dest = (*this) * src + void multiply(double*& dest, const double* src) const; + + /** + * compute dest = (*this) * src + * However, assuming that this is a symmetric matrix where only the upper triangle is stored + */ + void multiplySymmetricUpperTriangle(double*& dest, const double* src) const; + + //! dest = M * (*this) + void rightMultiply(double*& dest, const double* src) const; + + //! *this *= a + void scale( double a); + + /** + * writes in dest a block permutaton specified by pinv. + * @param pinv: array such that new_block[i] = old_block[pinv[i]] + */ + bool symmPermutation(SparseBlockMatrix*& dest, const int* pinv, bool onlyUpper=false) const; + + /** + * fill the CCS arrays of a matrix, arrays have to be allocated beforehand + */ + int fillCCS(int* Cp, int* Ci, double* Cx, bool upperTriangle = false) const; + + /** + * fill the CCS arrays of a matrix, arrays have to be allocated beforehand. This function only writes + * the values and assumes that column and row structures have already been written. + */ + int fillCCS(double* Cx, bool upperTriangle = false) const; + + //! exports the non zero blocks in the structure matrix ms + void fillBlockStructure(MatrixStructure& ms) const; + + //! the block matrices per block-column + const std::vector& blockCols() const { return _blockCols;} + std::vector& blockCols() { return _blockCols;} + + //! indices of the row blocks + const std::vector& rowBlockIndices() const { return _rowBlockIndices;} + std::vector& rowBlockIndices() { return _rowBlockIndices;} + + //! indices of the column blocks + const std::vector& colBlockIndices() const { return _colBlockIndices;} + std::vector& colBlockIndices() { return _colBlockIndices;} + + /** + * write the content of this matrix to a stream loadable by Octave + * @param upperTriangle does this matrix store only the upper triangular blocks + */ + bool writeOctave(const char* filename, bool upperTriangle = true) const; + + /** + * copy into CCS structure + * @return number of processed blocks, -1 on error + */ + int fillSparseBlockMatrixCCS(SparseBlockMatrixCCS& blockCCS) const; + + /** + * copy as transposed into a CCS structure + * @return number of processed blocks, -1 on error + */ + int fillSparseBlockMatrixCCSTransposed(SparseBlockMatrixCCS& blockCCS) const; + + /** + * take over the memory and matrix pattern from a hash matrix. + * The structure of the hash matrix will be cleared. + */ + void takePatternFromHash(SparseBlockMatrixHashMap& hashMatrix); + + protected: + std::vector _rowBlockIndices; ///< vector of the indices of the blocks along the rows. + std::vector _colBlockIndices; ///< vector of the indices of the blocks along the cols + //! array of maps of blocks. The index of the array represent a block column of the matrix + //! and the block column is stored as a map row_block -> matrix_block_ptr. + std::vector _blockCols; + bool _hasStorage; +}; + +template < class MatrixType > +std::ostream& operator << (std::ostream&, const SparseBlockMatrix& m); + + typedef SparseBlockMatrix SparseBlockMatrixXd; + +} //end namespace + +#include "sparse_block_matrix.hpp" + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/sparse_block_matrix.hpp b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/sparse_block_matrix.hpp new file mode 100644 index 0000000..8dfa99c --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/sparse_block_matrix.hpp @@ -0,0 +1,657 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +namespace g2o { + using namespace Eigen; + + namespace { + struct TripletEntry + { + int r, c; + double x; + TripletEntry(int r_, int c_, double x_) : r(r_), c(c_), x(x_) {} + }; + struct TripletColSort + { + bool operator()(const TripletEntry& e1, const TripletEntry& e2) const + { + return e1.c < e2.c || (e1.c == e2.c && e1.r < e2.r); + } + }; + /** Helper class to sort pair based on first elem */ + template > + struct CmpPairFirst { + bool operator()(const std::pair& left, const std::pair& right) { + return Pred()(left.first, right.first); + } + }; + } + + template + SparseBlockMatrix::SparseBlockMatrix( const int * rbi, const int* cbi, int rb, int cb, bool hasStorage): + _rowBlockIndices(rbi,rbi+rb), + _colBlockIndices(cbi,cbi+cb), + _blockCols(cb), _hasStorage(hasStorage) + { + } + + template + SparseBlockMatrix::SparseBlockMatrix( ): + _blockCols(0), _hasStorage(true) + { + } + + template + void SparseBlockMatrix::clear(bool dealloc) { +# ifdef G2O_OPENMP +# pragma omp parallel for default (shared) if (_blockCols.size() > 100) +# endif + for (int i=0; i < static_cast(_blockCols.size()); ++i) { + for (typename SparseBlockMatrix::IntBlockMap::const_iterator it=_blockCols[i].begin(); it!=_blockCols[i].end(); ++it){ + typename SparseBlockMatrix::SparseMatrixBlock* b=it->second; + if (_hasStorage && dealloc) + delete b; + else + b->setZero(); + } + if (_hasStorage && dealloc) + _blockCols[i].clear(); + } + } + + template + SparseBlockMatrix::~SparseBlockMatrix(){ + if (_hasStorage) + clear(true); + } + + template + typename SparseBlockMatrix::SparseMatrixBlock* SparseBlockMatrix::block(int r, int c, bool alloc) { + typename SparseBlockMatrix::IntBlockMap::iterator it =_blockCols[c].find(r); + typename SparseBlockMatrix::SparseMatrixBlock* _block=0; + if (it==_blockCols[c].end()){ + if (!_hasStorage && ! alloc ) + return 0; + else { + int rb=rowsOfBlock(r); + int cb=colsOfBlock(c); + _block=new typename SparseBlockMatrix::SparseMatrixBlock(rb,cb); + _block->setZero(); + std::pair < typename SparseBlockMatrix::IntBlockMap::iterator, bool> result + =_blockCols[c].insert(std::make_pair(r,_block)); (void) result; + assert (result.second); + } + } else { + _block=it->second; + } + return _block; + } + + template + const typename SparseBlockMatrix::SparseMatrixBlock* SparseBlockMatrix::block(int r, int c) const { + typename SparseBlockMatrix::IntBlockMap::const_iterator it =_blockCols[c].find(r); + if (it==_blockCols[c].end()) + return 0; + return it->second; + } + + + template + SparseBlockMatrix* SparseBlockMatrix::clone() const { + SparseBlockMatrix* ret= new SparseBlockMatrix(&_rowBlockIndices[0], &_colBlockIndices[0], _rowBlockIndices.size(), _colBlockIndices.size()); + for (size_t i=0; i<_blockCols.size(); ++i){ + for (typename SparseBlockMatrix::IntBlockMap::const_iterator it=_blockCols[i].begin(); it!=_blockCols[i].end(); ++it){ + typename SparseBlockMatrix::SparseMatrixBlock* b=new typename SparseBlockMatrix::SparseMatrixBlock(*it->second); + ret->_blockCols[i].insert(std::make_pair(it->first, b)); + } + } + ret->_hasStorage=true; + return ret; + } + + + template + template + bool SparseBlockMatrix::transpose(SparseBlockMatrix*& dest) const { + if (! dest){ + dest=new SparseBlockMatrix(&_colBlockIndices[0], &_rowBlockIndices[0], _colBlockIndices.size(), _rowBlockIndices.size()); + } else { + if (! dest->_hasStorage) + return false; + if(_rowBlockIndices.size()!=dest->_colBlockIndices.size()) + return false; + if (_colBlockIndices.size()!=dest->_rowBlockIndices.size()) + return false; + for (size_t i=0; i<_rowBlockIndices.size(); ++i){ + if(_rowBlockIndices[i]!=dest->_colBlockIndices[i]) + return false; + } + for (size_t i=0; i<_colBlockIndices.size(); ++i){ + if(_colBlockIndices[i]!=dest->_rowBlockIndices[i]) + return false; + } + } + + for (size_t i=0; i<_blockCols.size(); ++i){ + for (typename SparseBlockMatrix::IntBlockMap::const_iterator it=_blockCols[i].begin(); it!=_blockCols[i].end(); ++it){ + typename SparseBlockMatrix::SparseMatrixBlock* s=it->second; + typename SparseBlockMatrix::SparseMatrixBlock* d=dest->block(i,it->first,true); + *d = s->transpose(); + } + } + return true; + } + + template + bool SparseBlockMatrix::add(SparseBlockMatrix*& dest) const { + if (! dest){ + dest=new SparseBlockMatrix(&_rowBlockIndices[0], &_colBlockIndices[0], _rowBlockIndices.size(), _colBlockIndices.size()); + } else { + if (! dest->_hasStorage) + return false; + if(_rowBlockIndices.size()!=dest->_rowBlockIndices.size()) + return false; + if (_colBlockIndices.size()!=dest->_colBlockIndices.size()) + return false; + for (size_t i=0; i<_rowBlockIndices.size(); ++i){ + if(_rowBlockIndices[i]!=dest->_rowBlockIndices[i]) + return false; + } + for (size_t i=0; i<_colBlockIndices.size(); ++i){ + if(_colBlockIndices[i]!=dest->_colBlockIndices[i]) + return false; + } + } + for (size_t i=0; i<_blockCols.size(); ++i){ + for (typename SparseBlockMatrix::IntBlockMap::const_iterator it=_blockCols[i].begin(); it!=_blockCols[i].end(); ++it){ + typename SparseBlockMatrix::SparseMatrixBlock* s=it->second; + typename SparseBlockMatrix::SparseMatrixBlock* d=dest->block(it->first,i,true); + (*d)+=*s; + } + } + return true; + } + + template + template < class MatrixResultType, class MatrixFactorType > + bool SparseBlockMatrix::multiply(SparseBlockMatrix*& dest, const SparseBlockMatrix * M) const { + // sanity check + if (_colBlockIndices.size()!=M->_rowBlockIndices.size()) + return false; + for (size_t i=0; i<_colBlockIndices.size(); ++i){ + if (_colBlockIndices[i]!=M->_rowBlockIndices[i]) + return false; + } + if (! dest) { + dest=new SparseBlockMatrix(&_rowBlockIndices[0],&(M->_colBlockIndices[0]), _rowBlockIndices.size(), M->_colBlockIndices.size() ); + } + if (! dest->_hasStorage) + return false; + for (size_t i=0; i_blockCols.size(); ++i){ + for (typename SparseBlockMatrix::IntBlockMap::const_iterator it=M->_blockCols[i].begin(); it!=M->_blockCols[i].end(); ++it){ + // look for a non-zero block in a row of column it + int colM=i; + const typename SparseBlockMatrix::SparseMatrixBlock *b=it->second; + typename SparseBlockMatrix::IntBlockMap::const_iterator rbt=_blockCols[it->first].begin(); + while(rbt!=_blockCols[it->first].end()){ + //int colA=it->first; + int rowA=rbt->first; + typename SparseBlockMatrix::SparseMatrixBlock *a=rbt->second; + typename SparseBlockMatrix::SparseMatrixBlock *c=dest->block(rowA,colM,true); + assert (c->rows()==a->rows()); + assert (c->cols()==b->cols()); + ++rbt; + (*c)+=(*a)*(*b); + } + } + } + return false; + } + + template + void SparseBlockMatrix::multiply(double*& dest, const double* src) const { + if (! dest){ + dest=new double [_rowBlockIndices[_rowBlockIndices.size()-1] ]; + memset(dest,0, _rowBlockIndices[_rowBlockIndices.size()-1]*sizeof(double)); + } + + // map the memory by Eigen + Eigen::Map destVec(dest, rows()); + const Eigen::Map srcVec(src, cols()); + + for (size_t i=0; i<_blockCols.size(); ++i){ + int srcOffset = i ? _colBlockIndices[i-1] : 0; + + for (typename SparseBlockMatrix::IntBlockMap::const_iterator it=_blockCols[i].begin(); it!=_blockCols[i].end(); ++it){ + const typename SparseBlockMatrix::SparseMatrixBlock* a=it->second; + int destOffset = it->first ? _rowBlockIndices[it->first - 1] : 0; + // destVec += *a * srcVec (according to the sub-vector parts) + internal::axpy(*a, srcVec, srcOffset, destVec, destOffset); + } + } + } + + template + void SparseBlockMatrix::multiplySymmetricUpperTriangle(double*& dest, const double* src) const + { + if (! dest){ + dest=new double [_rowBlockIndices[_rowBlockIndices.size()-1] ]; + memset(dest,0, _rowBlockIndices[_rowBlockIndices.size()-1]*sizeof(double)); + } + + // map the memory by Eigen + Eigen::Map destVec(dest, rows()); + const Eigen::Map srcVec(src, cols()); + + for (size_t i=0; i<_blockCols.size(); ++i){ + int srcOffset = colBaseOfBlock(i); + for (typename SparseBlockMatrix::IntBlockMap::const_iterator it=_blockCols[i].begin(); it!=_blockCols[i].end(); ++it){ + const typename SparseBlockMatrix::SparseMatrixBlock* a=it->second; + int destOffset = rowBaseOfBlock(it->first); + if (destOffset > srcOffset) // only upper triangle + break; + // destVec += *a * srcVec (according to the sub-vector parts) + internal::axpy(*a, srcVec, srcOffset, destVec, destOffset); + if (destOffset < srcOffset) + internal::atxpy(*a, srcVec, destOffset, destVec, srcOffset); + } + } + } + + template + void SparseBlockMatrix::rightMultiply(double*& dest, const double* src) const { + int destSize=cols(); + + if (! dest){ + dest=new double [ destSize ]; + memset(dest,0, destSize*sizeof(double)); + } + + // map the memory by Eigen + Eigen::Map destVec(dest, destSize); + Eigen::Map srcVec(src, rows()); + +# ifdef G2O_OPENMP +# pragma omp parallel for default (shared) schedule(dynamic, 10) +# endif + for (int i=0; i < static_cast(_blockCols.size()); ++i){ + int destOffset = colBaseOfBlock(i); + for (typename SparseBlockMatrix::IntBlockMap::const_iterator it=_blockCols[i].begin(); + it!=_blockCols[i].end(); + ++it){ + const typename SparseBlockMatrix::SparseMatrixBlock* a=it->second; + int srcOffset = rowBaseOfBlock(it->first); + // destVec += *a.transpose() * srcVec (according to the sub-vector parts) + internal::atxpy(*a, srcVec, srcOffset, destVec, destOffset); + } + } + + } + + template + void SparseBlockMatrix::scale(double a_) { + for (size_t i=0; i<_blockCols.size(); ++i){ + for (typename SparseBlockMatrix::IntBlockMap::const_iterator it=_blockCols[i].begin(); it!=_blockCols[i].end(); ++it){ + typename SparseBlockMatrix::SparseMatrixBlock* a=it->second; + *a *= a_; + } + } + } + + template + SparseBlockMatrix* SparseBlockMatrix::slice(int rmin, int rmax, int cmin, int cmax, bool alloc) const { + int m=rmax-rmin; + int n=cmax-cmin; + int rowIdx [m]; + rowIdx[0] = rowsOfBlock(rmin); + for (int i=1; i::SparseBlockMatrix* s=new SparseBlockMatrix(rowIdx, colIdx, m, n, true); + for (int i=0; i::IntBlockMap::const_iterator it=_blockCols[mc].begin(); it!=_blockCols[mc].end(); ++it){ + if (it->first >= rmin && it->first < rmax){ + typename SparseBlockMatrix::SparseMatrixBlock* b = alloc ? new typename SparseBlockMatrix::SparseMatrixBlock (* (it->second) ) : it->second; + s->_blockCols[i].insert(std::make_pair(it->first-rmin, b)); + } + } + } + s->_hasStorage=alloc; + return s; + } + + template + size_t SparseBlockMatrix::nonZeroBlocks() const { + size_t count=0; + for (size_t i=0; i<_blockCols.size(); ++i) + count+=_blockCols[i].size(); + return count; + } + + template + size_t SparseBlockMatrix::nonZeros() const{ + if (MatrixType::SizeAtCompileTime != Eigen::Dynamic) { + size_t nnz = nonZeroBlocks() * MatrixType::SizeAtCompileTime; + return nnz; + } else { + size_t count=0; + for (size_t i=0; i<_blockCols.size(); ++i){ + for (typename SparseBlockMatrix::IntBlockMap::const_iterator it=_blockCols[i].begin(); it!=_blockCols[i].end(); ++it){ + const typename SparseBlockMatrix::SparseMatrixBlock* a=it->second; + count += a->cols()*a->rows(); + } + } + return count; + } + } + + template + std::ostream& operator << (std::ostream& os, const SparseBlockMatrix& m){ + os << "RBI: " << m.rowBlockIndices().size(); + for (size_t i=0; i::IntBlockMap::const_iterator it=m.blockCols()[i].begin(); it!=m.blockCols()[i].end(); ++it){ + const typename SparseBlockMatrix::SparseMatrixBlock* b=it->second; + os << "BLOCK: " << it->first << " " << i << std::endl; + os << *b << std::endl; + } + } + return os; + } + + template + bool SparseBlockMatrix::symmPermutation(SparseBlockMatrix*& dest, const int* pinv, bool upperTriangle) const{ + // compute the permuted version of the new row/column layout + size_t n=_rowBlockIndices.size(); + // computed the block sizes + int blockSizes[_rowBlockIndices.size()]; + blockSizes[0]=_rowBlockIndices[0]; + for (size_t i=1; i_rowBlockIndices.size()!=n) + return false; + if (dest->_colBlockIndices.size()!=n) + return false; + for (size_t i=0; i_rowBlockIndices[i]!=pBlockIndices[i]) + return false; + if (dest->_colBlockIndices[i]!=pBlockIndices[i]) + return false; + } + dest->clear(); + } + // now ready to permute the columns + for (size_t i=0; i::IntBlockMap::const_iterator it=_blockCols[i].begin(); + it!=_blockCols[i].end(); ++it){ + int pj=pinv[it->first]; + + const typename SparseBlockMatrix::SparseMatrixBlock* s=it->second; + + typename SparseBlockMatrix::SparseMatrixBlock* b=0; + if (! upperTriangle || pj<=pi) { + b=dest->block(pj,pi,true); + assert(b->cols()==s->cols()); + assert(b->rows()==s->rows()); + *b=*s; + } else { + b=dest->block(pi,pj,true); + assert(b); + assert(b->rows()==s->cols()); + assert(b->cols()==s->rows()); + *b=s->transpose(); + } + } + //cerr << endl; + // within each row, + } + return true; + + } + + template + int SparseBlockMatrix::fillCCS(double* Cx, bool upperTriangle) const + { + assert(Cx && "Target destination is NULL"); + double* CxStart = Cx; + for (size_t i=0; i<_blockCols.size(); ++i){ + int cstart=i ? _colBlockIndices[i-1] : 0; + int csize=colsOfBlock(i); + for (int c=0; c::IntBlockMap::const_iterator it=_blockCols[i].begin(); it!=_blockCols[i].end(); ++it){ + const typename SparseBlockMatrix::SparseMatrixBlock* b=it->second; + int rstart=it->first ? _rowBlockIndices[it->first-1] : 0; + + int elemsToCopy = b->rows(); + if (upperTriangle && rstart == cstart) + elemsToCopy = c + 1; + memcpy(Cx, b->data() + c*b->rows(), elemsToCopy * sizeof(double)); + Cx += elemsToCopy; + + } + } + } + return Cx - CxStart; + } + + template + int SparseBlockMatrix::fillCCS(int* Cp, int* Ci, double* Cx, bool upperTriangle) const + { + assert(Cp && Ci && Cx && "Target destination is NULL"); + int nz=0; + for (size_t i=0; i<_blockCols.size(); ++i){ + int cstart=i ? _colBlockIndices[i-1] : 0; + int csize=colsOfBlock(i); + for (int c=0; c::IntBlockMap::const_iterator it=_blockCols[i].begin(); it!=_blockCols[i].end(); ++it){ + const typename SparseBlockMatrix::SparseMatrixBlock* b=it->second; + int rstart=it->first ? _rowBlockIndices[it->first-1] : 0; + + int elemsToCopy = b->rows(); + if (upperTriangle && rstart == cstart) + elemsToCopy = c + 1; + for (int r=0; r + void SparseBlockMatrix::fillBlockStructure(MatrixStructure& ms) const + { + int n = _colBlockIndices.size(); + int nzMax = (int)nonZeroBlocks(); + + ms.alloc(n, nzMax); + ms.m = _rowBlockIndices.size(); + + int nz = 0; + int* Cp = ms.Ap; + int* Ci = ms.Aii; + for (int i = 0; i < static_cast(_blockCols.size()); ++i){ + *Cp = nz; + const int& c = i; + for (typename SparseBlockMatrix::IntBlockMap::const_iterator it=_blockCols[i].begin(); it!=_blockCols[i].end(); ++it) { + const int& r = it->first; + if (r <= c) { + *Ci++ = r; + ++nz; + } + } + Cp++; + } + *Cp=nz; + assert(nz <= nzMax); + } + + template + bool SparseBlockMatrix::writeOctave(const char* filename, bool upperTriangle) const + { + std::string name = filename; + std::string::size_type lastDot = name.find_last_of('.'); + if (lastDot != std::string::npos) + name = name.substr(0, lastDot); + + std::vector entries; + for (size_t i = 0; i<_blockCols.size(); ++i){ + const int& c = i; + for (typename SparseBlockMatrix::IntBlockMap::const_iterator it=_blockCols[i].begin(); it!=_blockCols[i].end(); ++it) { + const int& r = it->first; + const MatrixType& m = *(it->second); + for (int cc = 0; cc < m.cols(); ++cc) + for (int rr = 0; rr < m.rows(); ++rr) { + int aux_r = rowBaseOfBlock(r) + rr; + int aux_c = colBaseOfBlock(c) + cc; + entries.push_back(TripletEntry(aux_r, aux_c, m(rr, cc))); + if (upperTriangle && r != c) { + entries.push_back(TripletEntry(aux_c, aux_r, m(rr, cc))); + } + } + } + } + + int nz = entries.size(); + std::sort(entries.begin(), entries.end(), TripletColSort()); + + std::ofstream fout(filename); + fout << "# name: " << name << std::endl; + fout << "# type: sparse matrix" << std::endl; + fout << "# nnz: " << nz << std::endl; + fout << "# rows: " << rows() << std::endl; + fout << "# columns: " << cols() << std::endl; + fout << std::setprecision(9) << std::fixed << std::endl; + + for (std::vector::const_iterator it = entries.begin(); it != entries.end(); ++it) { + const TripletEntry& entry = *it; + fout << entry.r+1 << " " << entry.c+1 << " " << entry.x << std::endl; + } + return fout.good(); + } + + template + int SparseBlockMatrix::fillSparseBlockMatrixCCS(SparseBlockMatrixCCS& blockCCS) const + { + blockCCS.blockCols().resize(blockCols().size()); + int numblocks = 0; + for (size_t i = 0; i < blockCols().size(); ++i) { + const IntBlockMap& row = blockCols()[i]; + typename SparseBlockMatrixCCS::SparseColumn& dest = blockCCS.blockCols()[i]; + dest.clear(); + dest.reserve(row.size()); + for (typename IntBlockMap::const_iterator it = row.begin(); it != row.end(); ++it) { + dest.push_back(typename SparseBlockMatrixCCS::RowBlock(it->first, it->second)); + ++numblocks; + } + } + return numblocks; + } + + template + int SparseBlockMatrix::fillSparseBlockMatrixCCSTransposed(SparseBlockMatrixCCS& blockCCS) const + { + blockCCS.blockCols().clear(); + blockCCS.blockCols().resize(_rowBlockIndices.size()); + int numblocks = 0; + for (size_t i = 0; i < blockCols().size(); ++i) { + const IntBlockMap& row = blockCols()[i]; + for (typename IntBlockMap::const_iterator it = row.begin(); it != row.end(); ++it) { + typename SparseBlockMatrixCCS::SparseColumn& dest = blockCCS.blockCols()[it->first]; + dest.push_back(typename SparseBlockMatrixCCS::RowBlock(i, it->second)); + ++numblocks; + } + } + return numblocks; + } + + template + void SparseBlockMatrix::takePatternFromHash(SparseBlockMatrixHashMap& hashMatrix) + { + // sort the sparse columns and add them to the map structures by + // exploiting that we are inserting a sorted structure + typedef std::pair SparseColumnPair; + typedef typename SparseBlockMatrixHashMap::SparseColumn HashSparseColumn; + for (size_t i = 0; i < hashMatrix.blockCols().size(); ++i) { + // prepare a temporary vector for sorting + HashSparseColumn& column = hashMatrix.blockCols()[i]; + if (column.size() == 0) + continue; + std::vector sparseRowSorted; // temporary structure + sparseRowSorted.reserve(column.size()); + for (typename HashSparseColumn::const_iterator it = column.begin(); it != column.end(); ++it) + sparseRowSorted.push_back(*it); + std::sort(sparseRowSorted.begin(), sparseRowSorted.end(), CmpPairFirst()); + // try to free some memory early + HashSparseColumn aux; + swap(aux, column); + // now insert sorted vector to the std::map structure + IntBlockMap& destColumnMap = blockCols()[i]; + destColumnMap.insert(sparseRowSorted[0]); + for (size_t j = 1; j < sparseRowSorted.size(); ++j) { + typename SparseBlockMatrix::IntBlockMap::iterator hint = destColumnMap.end(); + --hint; // cppreference says the element goes after the hint (until C++11) + destColumnMap.insert(hint, sparseRowSorted[j]); + } + } + } + +}// end namespace diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/sparse_block_matrix_ccs.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/sparse_block_matrix_ccs.h new file mode 100644 index 0000000..eb9042c --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/sparse_block_matrix_ccs.h @@ -0,0 +1,282 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_SPARSE_BLOCK_MATRIX_CCS_H +#define G2O_SPARSE_BLOCK_MATRIX_CCS_H + +#include +#include +#include + +#include "../../config.h" +#include "matrix_operations.h" + +#ifdef _MSC_VER +#include +#else +#include +#endif + +namespace g2o { + + /** + * \brief Sparse matrix which uses blocks + * + * This class is used as a const view on a SparseBlockMatrix + * which allows a faster iteration over the elements of the + * matrix. + */ + template + class SparseBlockMatrixCCS + { + public: + //! this is the type of the elementary block, it is an Eigen::Matrix. + typedef MatrixType SparseMatrixBlock; + + //! columns of the matrix + int cols() const {return _colBlockIndices.size() ? _colBlockIndices.back() : 0;} + //! rows of the matrix + int rows() const {return _rowBlockIndices.size() ? _rowBlockIndices.back() : 0;} + + /** + * \brief A block within a column + */ + struct RowBlock + { + int row; ///< row of the block + MatrixType* block; ///< matrix pointer for the block + RowBlock() : row(-1), block(0) {} + RowBlock(int r, MatrixType* b) : row(r), block(b) {} + bool operator<(const RowBlock& other) const { return row < other.row;} + }; + typedef std::vector SparseColumn; + + SparseBlockMatrixCCS(const std::vector& rowIndices, const std::vector& colIndices) : + _rowBlockIndices(rowIndices), _colBlockIndices(colIndices) + {} + + //! how many rows does the block at block-row r has? + int rowsOfBlock(int r) const { return r ? _rowBlockIndices[r] - _rowBlockIndices[r-1] : _rowBlockIndices[0] ; } + + //! how many cols does the block at block-col c has? + int colsOfBlock(int c) const { return c ? _colBlockIndices[c] - _colBlockIndices[c-1] : _colBlockIndices[0]; } + + //! where does the row at block-row r start? + int rowBaseOfBlock(int r) const { return r ? _rowBlockIndices[r-1] : 0 ; } + + //! where does the col at block-col r start? + int colBaseOfBlock(int c) const { return c ? _colBlockIndices[c-1] : 0 ; } + + //! the block matrices per block-column + const std::vector& blockCols() const { return _blockCols;} + std::vector& blockCols() { return _blockCols;} + + //! indices of the row blocks + const std::vector& rowBlockIndices() const { return _rowBlockIndices;} + + //! indices of the column blocks + const std::vector& colBlockIndices() const { return _colBlockIndices;} + + void rightMultiply(double*& dest, const double* src) const + { + int destSize=cols(); + + if (! dest){ + dest=new double [ destSize ]; + memset(dest,0, destSize*sizeof(double)); + } + + // map the memory by Eigen + Eigen::Map destVec(dest, destSize); + Eigen::Map srcVec(src, rows()); + +# ifdef G2O_OPENMP +# pragma omp parallel for default (shared) schedule(dynamic, 10) +# endif + for (int i=0; i < static_cast(_blockCols.size()); ++i){ + int destOffset = colBaseOfBlock(i); + for (typename SparseColumn::const_iterator it = _blockCols[i].begin(); it!=_blockCols[i].end(); ++it) { + const SparseMatrixBlock* a = it->block; + int srcOffset = rowBaseOfBlock(it->row); + // destVec += *a.transpose() * srcVec (according to the sub-vector parts) + internal::atxpy(*a, srcVec, srcOffset, destVec, destOffset); + } + } + } + + /** + * sort the blocks in each column + */ + void sortColumns() + { + for (int i=0; i < static_cast(_blockCols.size()); ++i){ + std::sort(_blockCols[i].begin(), _blockCols[i].end()); + } + } + + /** + * fill the CCS arrays of a matrix, arrays have to be allocated beforehand + */ + int fillCCS(int* Cp, int* Ci, double* Cx, bool upperTriangle = false) const + { + assert(Cp && Ci && Cx && "Target destination is NULL"); + int nz=0; + for (size_t i=0; i<_blockCols.size(); ++i){ + int cstart=i ? _colBlockIndices[i-1] : 0; + int csize=colsOfBlock(i); + for (int c=0; cblock; + int rstart=it->row ? _rowBlockIndices[it->row-1] : 0; + + int elemsToCopy = b->rows(); + if (upperTriangle && rstart == cstart) + elemsToCopy = c + 1; + for (int r=0; rblock; + int rstart = it->row ? _rowBlockIndices[it->row-1] : 0; + + int elemsToCopy = b->rows(); + if (upperTriangle && rstart == cstart) + elemsToCopy = c + 1; + memcpy(Cx, b->data() + c*b->rows(), elemsToCopy * sizeof(double)); + Cx += elemsToCopy; + + } + } + cstart = _colBlockIndices[i]; + } + return Cx - CxStart; + } + + protected: + const std::vector& _rowBlockIndices; ///< vector of the indices of the blocks along the rows. + const std::vector& _colBlockIndices; ///< vector of the indices of the blocks along the cols + std::vector _blockCols; ///< the matrices stored in CCS order + }; + + + + /** + * \brief Sparse matrix which uses blocks based on hash structures + * + * This class is used to construct the pattern of a sparse block matrix + */ + template + class SparseBlockMatrixHashMap + { + public: + //! this is the type of the elementary block, it is an Eigen::Matrix. + typedef MatrixType SparseMatrixBlock; + + //! columns of the matrix + int cols() const {return _colBlockIndices.size() ? _colBlockIndices.back() : 0;} + //! rows of the matrix + int rows() const {return _rowBlockIndices.size() ? _rowBlockIndices.back() : 0;} + + typedef std::tr1::unordered_map SparseColumn; + + SparseBlockMatrixHashMap(const std::vector& rowIndices, const std::vector& colIndices) : + _rowBlockIndices(rowIndices), _colBlockIndices(colIndices) + {} + + //! how many rows does the block at block-row r has? + int rowsOfBlock(int r) const { return r ? _rowBlockIndices[r] - _rowBlockIndices[r-1] : _rowBlockIndices[0] ; } + + //! how many cols does the block at block-col c has? + int colsOfBlock(int c) const { return c ? _colBlockIndices[c] - _colBlockIndices[c-1] : _colBlockIndices[0]; } + + //! where does the row at block-row r start? + int rowBaseOfBlock(int r) const { return r ? _rowBlockIndices[r-1] : 0 ; } + + //! where does the col at block-col r start? + int colBaseOfBlock(int c) const { return c ? _colBlockIndices[c-1] : 0 ; } + + //! the block matrices per block-column + const std::vector& blockCols() const { return _blockCols;} + std::vector& blockCols() { return _blockCols;} + + //! indices of the row blocks + const std::vector& rowBlockIndices() const { return _rowBlockIndices;} + + //! indices of the column blocks + const std::vector& colBlockIndices() const { return _colBlockIndices;} + + /** + * add a block to the pattern, return a pointer to the added block + */ + MatrixType* addBlock(int r, int c, bool zeroBlock = false) + { + assert(c <(int)_blockCols.size() && "accessing column which is not available"); + SparseColumn& sparseColumn = _blockCols[c]; + typename SparseColumn::iterator foundIt = sparseColumn.find(r); + if (foundIt == sparseColumn.end()) { + int rb = rowsOfBlock(r); + int cb = colsOfBlock(c); + MatrixType* m = new MatrixType(rb, cb); + if (zeroBlock) + m->setZero(); + sparseColumn[r] = m; + return m; + } + return foundIt->second; + } + + protected: + const std::vector& _rowBlockIndices; ///< vector of the indices of the blocks along the rows. + const std::vector& _colBlockIndices; ///< vector of the indices of the blocks along the cols + std::vector _blockCols; ///< the matrices stored in CCS order + }; + +} //end namespace + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/sparse_block_matrix_diagonal.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/sparse_block_matrix_diagonal.h new file mode 100644 index 0000000..7b13b9f --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/sparse_block_matrix_diagonal.h @@ -0,0 +1,108 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_SPARSE_BLOCK_MATRIX_DIAGONAL_H +#define G2O_SPARSE_BLOCK_MATRIX_DIAGONAL_H + +#include +#include +#include + +#include "../../config.h" +#include "matrix_operations.h" + +namespace g2o { + + /** + * \brief Sparse matrix which uses blocks on the diagonal + * + * This class is used as a const view on a SparseBlockMatrix + * which allows a faster iteration over the elements of the + * matrix. + */ + template + class SparseBlockMatrixDiagonal + { + public: + //! this is the type of the elementary block, it is an Eigen::Matrix. + typedef MatrixType SparseMatrixBlock; + + //! columns of the matrix + int cols() const {return _blockIndices.size() ? _blockIndices.back() : 0;} + //! rows of the matrix + int rows() const {return _blockIndices.size() ? _blockIndices.back() : 0;} + + typedef std::vector > DiagonalVector; + + SparseBlockMatrixDiagonal(const std::vector& blockIndices) : + _blockIndices(blockIndices) + {} + + //! how many rows/cols does the block at block-row / block-column r has? + inline int dimOfBlock(int r) const { return r ? _blockIndices[r] - _blockIndices[r-1] : _blockIndices[0] ; } + + //! where does the row /col at block-row / block-column r starts? + inline int baseOfBlock(int r) const { return r ? _blockIndices[r-1] : 0 ; } + + //! the block matrices per block-column + const DiagonalVector& diagonal() const { return _diagonal;} + DiagonalVector& diagonal() { return _diagonal;} + + //! indices of the row blocks + const std::vector& blockIndices() const { return _blockIndices;} + + void multiply(double*& dest, const double* src) const + { + int destSize=cols(); + if (! dest) { + dest=new double[destSize]; + memset(dest,0, destSize*sizeof(double)); + } + + // map the memory by Eigen + Eigen::Map destVec(dest, destSize); + Eigen::Map srcVec(src, rows()); + +# ifdef G2O_OPENMP +# pragma omp parallel for default (shared) schedule(dynamic, 10) +# endif + for (int i=0; i < static_cast(_diagonal.size()); ++i){ + int destOffset = baseOfBlock(i); + int srcOffset = destOffset; + const SparseMatrixBlock& A = _diagonal[i]; + // destVec += *A.transpose() * srcVec (according to the sub-vector parts) + internal::axpy(A, srcVec, srcOffset, destVec, destOffset); + } + } + + protected: + const std::vector& _blockIndices; ///< vector of the indices of the blocks along the diagonal + DiagonalVector _diagonal; + }; + +} //end namespace + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/sparse_block_matrix_test.cpp b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/sparse_block_matrix_test.cpp new file mode 100644 index 0000000..42a4560 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/sparse_block_matrix_test.cpp @@ -0,0 +1,107 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#include "sparse_block_matrix.h" +#include + +using namespace std; +using namespace g2o; +using namespace Eigen; + +typedef SparseBlockMatrix< MatrixXd > +SparseBlockMatrixX; + +std::ostream& operator << (std::ostream& os, const SparseBlockMatrixX::SparseMatrixBlock& m) { + for (int i=0; iblock(0,0, true); + cerr << b->rows() << " " << b->cols() << endl; + for (int i=0; irows(); ++i) + for (int j=0; jcols(); ++j){ + (*b)(i,j)=i*b->cols()+j; + } + + + cerr << "block access 2" << endl; + b=M->block(0,2, true); + cerr << b->rows() << " " << b->cols() << endl; + for (int i=0; irows(); ++i) + for (int j=0; jcols(); ++j){ + (*b)(i,j)=i*b->cols()+j; + } + + b=M->block(3,2, true); + cerr << b->rows() << " " << b->cols() << endl; + for (int i=0; irows(); ++i) + for (int j=0; jcols(); ++j){ + (*b)(i,j)=i*b->cols()+j; + } + + cerr << *M << endl; + + cerr << "SUM" << endl; + + SparseBlockMatrixX* Ms=0; + M->add(Ms); + M->add(Ms); + cerr << *Ms; + + SparseBlockMatrixX* Mt=0; + M->transpose(Mt); + cerr << *Mt << endl; + + SparseBlockMatrixX* Mp=0; + M->multiply(Mp, Mt); + cerr << *Mp << endl; + + int iperm[]={3,2,1,0}; + SparseBlockMatrixX* PMp=0; + + Mp->symmPermutation(PMp,iperm, false); + cerr << *PMp << endl; + + PMp->clear(true); + Mp->block(3,0)->fill(0.); + Mp->symmPermutation(PMp,iperm, true); + cerr << *PMp << endl; + + + +} diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/sparse_optimizer.cpp b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/sparse_optimizer.cpp new file mode 100644 index 0000000..7c316e6 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/sparse_optimizer.cpp @@ -0,0 +1,615 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#include "sparse_optimizer.h" + +#include +#include +#include +#include +#include +#include + +#include "estimate_propagator.h" +#include "optimization_algorithm.h" +#include "batch_stats.h" +#include "hyper_graph_action.h" +#include "robust_kernel.h" +#include "../stuff/timeutil.h" +#include "../stuff/macros.h" +#include "../stuff/misc.h" +#include "../../config.h" + +namespace g2o{ + using namespace std; + + + SparseOptimizer::SparseOptimizer() : + _forceStopFlag(0), _verbose(false), _algorithm(0), _computeBatchStatistics(false) + { + _graphActions.resize(AT_NUM_ELEMENTS); + } + + SparseOptimizer::~SparseOptimizer(){ + delete _algorithm; + G2OBatchStatistics::setGlobalStats(0); + } + + void SparseOptimizer::computeActiveErrors() + { + // call the callbacks in case there is something registered + HyperGraphActionSet& actions = _graphActions[AT_COMPUTEACTIVERROR]; + if (actions.size() > 0) { + for (HyperGraphActionSet::iterator it = actions.begin(); it != actions.end(); ++it) + (*(*it))(this); + } + +# ifdef G2O_OPENMP +# pragma omp parallel for default (shared) if (_activeEdges.size() > 50) +# endif + for (int k = 0; k < static_cast(_activeEdges.size()); ++k) { + OptimizableGraph::Edge* e = _activeEdges[k]; + e->computeError(); + } + +# ifndef NDEBUG + for (int k = 0; k < static_cast(_activeEdges.size()); ++k) { + OptimizableGraph::Edge* e = _activeEdges[k]; + bool hasNan = arrayHasNaN(e->errorData(), e->dimension()); + if (hasNan) { + cerr << "computeActiveErrors(): found NaN in error for edge " << e << endl; + } + } +# endif + + } + + double SparseOptimizer::activeChi2( ) const + { + double chi = 0.0; + for (EdgeContainer::const_iterator it = _activeEdges.begin(); it != _activeEdges.end(); ++it) { + const OptimizableGraph::Edge* e = *it; + chi += e->chi2(); + } + return chi; + } + + double SparseOptimizer::activeRobustChi2() const + { + Eigen::Vector3d rho; + double chi = 0.0; + for (EdgeContainer::const_iterator it = _activeEdges.begin(); it != _activeEdges.end(); ++it) { + const OptimizableGraph::Edge* e = *it; + if (e->robustKernel()) { + e->robustKernel()->robustify(e->chi2(), rho); + chi += rho[0]; + } + else + chi += e->chi2(); + } + return chi; + } + + OptimizableGraph::Vertex* SparseOptimizer::findGauge(){ + if (vertices().empty()) + return 0; + + int maxDim=0; + for (HyperGraph::VertexIDMap::iterator it=vertices().begin(); it!=vertices().end(); ++it){ + OptimizableGraph::Vertex* v=static_cast(it->second); + maxDim=std::max(maxDim,v->dimension()); + } + + OptimizableGraph::Vertex* rut=0; + for (HyperGraph::VertexIDMap::iterator it=vertices().begin(); it!=vertices().end(); ++it){ + OptimizableGraph::Vertex* v=static_cast(it->second); + if (v->dimension()==maxDim){ + rut=v; + break; + } + } + return rut; + } + + bool SparseOptimizer::gaugeFreedom() + { + if (vertices().empty()) + return false; + + int maxDim=0; + for (HyperGraph::VertexIDMap::iterator it=vertices().begin(); it!=vertices().end(); ++it){ + OptimizableGraph::Vertex* v=static_cast(it->second); + maxDim = std::max(maxDim,v->dimension()); + } + + for (HyperGraph::VertexIDMap::iterator it=vertices().begin(); it!=vertices().end(); ++it){ + OptimizableGraph::Vertex* v=static_cast(it->second); + if (v->dimension() == maxDim) { + // test for fixed vertex + if (v->fixed()) { + return false; + } + // test for full dimension prior + for (HyperGraph::EdgeSet::const_iterator eit = v->edges().begin(); eit != v->edges().end(); ++eit) { + OptimizableGraph::Edge* e = static_cast(*eit); + if (e->vertices().size() == 1 && e->dimension() == maxDim) + return false; + } + } + } + return true; + } + + bool SparseOptimizer::buildIndexMapping(SparseOptimizer::VertexContainer& vlist){ + if (! vlist.size()){ + _ivMap.clear(); + return false; + } + + _ivMap.resize(vlist.size()); + size_t i = 0; + for (int k=0; k<2; k++) + for (VertexContainer::iterator it=vlist.begin(); it!=vlist.end(); ++it){ + OptimizableGraph::Vertex* v = *it; + if (! v->fixed()){ + if (static_cast(v->marginalized()) == k){ + v->setHessianIndex(i); + _ivMap[i]=v; + i++; + } + } + else { + v->setHessianIndex(-1); + } + } + _ivMap.resize(i); + return true; + } + + void SparseOptimizer::clearIndexMapping(){ + for (size_t i=0; i<_ivMap.size(); ++i){ + _ivMap[i]->setHessianIndex(-1); + _ivMap[i]=0; + } + } + + bool SparseOptimizer::initializeOptimization(int level){ + HyperGraph::VertexSet vset; + for (VertexIDMap::iterator it=vertices().begin(); it!=vertices().end(); ++it) + vset.insert(it->second); + return initializeOptimization(vset,level); + } + + bool SparseOptimizer::initializeOptimization(HyperGraph::VertexSet& vset, int level){ + if (edges().size() == 0) { + cerr << __PRETTY_FUNCTION__ << ": Attempt to initialize an empty graph" << endl; + return false; + } + bool workspaceAllocated = _jacobianWorkspace.allocate(); (void) workspaceAllocated; + assert(workspaceAllocated && "Error while allocating memory for the Jacobians"); + clearIndexMapping(); + _activeVertices.clear(); + _activeVertices.reserve(vset.size()); + _activeEdges.clear(); + set auxEdgeSet; // temporary structure to avoid duplicates + for (HyperGraph::VertexSet::iterator it=vset.begin(); it!=vset.end(); ++it){ + OptimizableGraph::Vertex* v= (OptimizableGraph::Vertex*) *it; + const OptimizableGraph::EdgeSet& vEdges=v->edges(); + // count if there are edges in that level. If not remove from the pool + int levelEdges=0; + for (OptimizableGraph::EdgeSet::const_iterator it=vEdges.begin(); it!=vEdges.end(); ++it){ + OptimizableGraph::Edge* e=reinterpret_cast(*it); + if (level < 0 || e->level() == level) { + + bool allVerticesOK = true; + for (vector::const_iterator vit = e->vertices().begin(); vit != e->vertices().end(); ++vit) { + if (vset.find(*vit) == vset.end()) { + allVerticesOK = false; + break; + } + } + if (allVerticesOK && !e->allVerticesFixed()) { + auxEdgeSet.insert(e); + levelEdges++; + } + + } + } + if (levelEdges){ + _activeVertices.push_back(v); + + // test for NANs in the current estimate if we are debugging +# ifndef NDEBUG + int estimateDim = v->estimateDimension(); + if (estimateDim > 0) { + Eigen::VectorXd estimateData(estimateDim); + if (v->getEstimateData(estimateData.data()) == true) { + int k; + bool hasNan = arrayHasNaN(estimateData.data(), estimateDim, &k); + if (hasNan) + cerr << __PRETTY_FUNCTION__ << ": Vertex " << v->id() << " contains a nan entry at index " << k << endl; + } + } +# endif + + } + } + + _activeEdges.reserve(auxEdgeSet.size()); + for (set::iterator it = auxEdgeSet.begin(); it != auxEdgeSet.end(); ++it) + _activeEdges.push_back(*it); + + sortVectorContainers(); + return buildIndexMapping(_activeVertices); + } + + bool SparseOptimizer::initializeOptimization(HyperGraph::EdgeSet& eset){ + bool workspaceAllocated = _jacobianWorkspace.allocate(); (void) workspaceAllocated; + assert(workspaceAllocated && "Error while allocating memory for the Jacobians"); + clearIndexMapping(); + _activeVertices.clear(); + _activeEdges.clear(); + _activeEdges.reserve(eset.size()); + set auxVertexSet; // temporary structure to avoid duplicates + for (HyperGraph::EdgeSet::iterator it=eset.begin(); it!=eset.end(); ++it){ + OptimizableGraph::Edge* e=(OptimizableGraph::Edge*)(*it); + for (vector::const_iterator vit = e->vertices().begin(); vit != e->vertices().end(); ++vit) { + auxVertexSet.insert(static_cast(*vit)); + } + _activeEdges.push_back(reinterpret_cast(*it)); + } + + _activeVertices.reserve(auxVertexSet.size()); + for (set::iterator it = auxVertexSet.begin(); it != auxVertexSet.end(); ++it) + _activeVertices.push_back(*it); + + sortVectorContainers(); + return buildIndexMapping(_activeVertices); + } + + void SparseOptimizer::setToOrigin(){ + for (VertexIDMap::iterator it=vertices().begin(); it!=vertices().end(); ++it) { + OptimizableGraph::Vertex* v = static_cast(it->second); + v->setToOrigin(); + } + } + + void SparseOptimizer::computeInitialGuess() + { + EstimatePropagator::PropagateCost costFunction(this); + computeInitialGuess(costFunction); + } + + void SparseOptimizer::computeInitialGuess(EstimatePropagatorCost& costFunction) + { + OptimizableGraph::VertexSet emptySet; + std::set backupVertices; + HyperGraph::VertexSet fixedVertices; // these are the root nodes where to start the initialization + for (EdgeContainer::iterator it = _activeEdges.begin(); it != _activeEdges.end(); ++it) { + OptimizableGraph::Edge* e = *it; + for (size_t i = 0; i < e->vertices().size(); ++i) { + OptimizableGraph::Vertex* v = static_cast(e->vertex(i)); + if (v->fixed()) + fixedVertices.insert(v); + else { // check for having a prior which is able to fully initialize a vertex + for (EdgeSet::const_iterator vedgeIt = v->edges().begin(); vedgeIt != v->edges().end(); ++vedgeIt) { + OptimizableGraph::Edge* vedge = static_cast(*vedgeIt); + if (vedge->vertices().size() == 1 && vedge->initialEstimatePossible(emptySet, v) > 0.) { + //cerr << "Initialize with prior for " << v->id() << endl; + vedge->initialEstimate(emptySet, v); + fixedVertices.insert(v); + } + } + } + if (v->hessianIndex() == -1) { + std::set::const_iterator foundIt = backupVertices.find(v); + if (foundIt == backupVertices.end()) { + v->push(); + backupVertices.insert(v); + } + } + } + } + + EstimatePropagator estimatePropagator(this); + estimatePropagator.propagate(fixedVertices, costFunction); + + // restoring the vertices that should not be initialized + for (std::set::iterator it = backupVertices.begin(); it != backupVertices.end(); ++it) { + Vertex* v = *it; + v->pop(); + } + if (verbose()) { + computeActiveErrors(); + cerr << "iteration= -1\t chi2= " << activeChi2() + << "\t time= 0.0" + << "\t cumTime= 0.0" + << "\t (using initial guess from " << costFunction.name() << ")" << endl; + } + } + + int SparseOptimizer::optimize(int iterations, bool online) + { + if (_ivMap.size() == 0) { + cerr << __PRETTY_FUNCTION__ << ": 0 vertices to optimize, maybe forgot to call initializeOptimization()" << endl; + return -1; + } + + int cjIterations=0; + double cumTime=0; + bool ok=true; + + ok = _algorithm->init(online); + if (! ok) { + cerr << __PRETTY_FUNCTION__ << " Error while initializing" << endl; + return -1; + } + + _batchStatistics.clear(); + if (_computeBatchStatistics) + _batchStatistics.resize(iterations); + + OptimizationAlgorithm::SolverResult result = OptimizationAlgorithm::OK; + for (int i=0; isolve(i, online); + ok = ( result == OptimizationAlgorithm::OK ); + + bool errorComputed = false; + if (_computeBatchStatistics) { + computeActiveErrors(); + errorComputed = true; + _batchStatistics[i].chi2 = activeRobustChi2(); + _batchStatistics[i].timeIteration = get_monotonic_time()-ts; + } + + if (verbose()){ + double dts = get_monotonic_time()-ts; + cumTime += dts; + if (! errorComputed) + computeActiveErrors(); + cerr << "iteration= " << i + << "\t chi2= " << FIXED(activeRobustChi2()) + << "\t time= " << dts + << "\t cumTime= " << cumTime + << "\t edges= " << _activeEdges.size(); + _algorithm->printVerbose(cerr); + cerr << endl; + } + ++cjIterations; + postIteration(i); + } + if (result == OptimizationAlgorithm::Fail) { + return 0; + } + return cjIterations; + } + + + void SparseOptimizer::update(const double* update) + { + // update the graph by calling oplus on the vertices + for (size_t i=0; i < _ivMap.size(); ++i) { + OptimizableGraph::Vertex* v= _ivMap[i]; +#ifndef NDEBUG + bool hasNan = arrayHasNaN(update, v->dimension()); + if (hasNan) + cerr << __PRETTY_FUNCTION__ << ": Update contains a nan for vertex " << v->id() << endl; +#endif + v->oplus(update); + update += v->dimension(); + } + } + + void SparseOptimizer::setComputeBatchStatistics(bool computeBatchStatistics) + { + if ((_computeBatchStatistics == true) && (computeBatchStatistics == false)) { + G2OBatchStatistics::setGlobalStats(0); + _batchStatistics.clear(); + } + _computeBatchStatistics = computeBatchStatistics; + } + + bool SparseOptimizer::updateInitialization(HyperGraph::VertexSet& vset, HyperGraph::EdgeSet& eset) + { + std::vector newVertices; + newVertices.reserve(vset.size()); + _activeVertices.reserve(_activeVertices.size() + vset.size()); + _activeEdges.reserve(_activeEdges.size() + eset.size()); + for (HyperGraph::EdgeSet::iterator it = eset.begin(); it != eset.end(); ++it) { + OptimizableGraph::Edge* e = static_cast(*it); + if (!e->allVerticesFixed()) _activeEdges.push_back(e); + } + + // update the index mapping + size_t next = _ivMap.size(); + for (HyperGraph::VertexSet::iterator it = vset.begin(); it != vset.end(); ++it) { + OptimizableGraph::Vertex* v=static_cast(*it); + if (! v->fixed()){ + if (! v->marginalized()){ + v->setHessianIndex(next); + _ivMap.push_back(v); + newVertices.push_back(v); + _activeVertices.push_back(v); + next++; + } + else // not supported right now + abort(); + } + else { + v->setHessianIndex(-1); + } + } + + //if (newVertices.size() != vset.size()) + //cerr << __PRETTY_FUNCTION__ << ": something went wrong " << PVAR(vset.size()) << " " << PVAR(newVertices.size()) << endl; + return _algorithm->updateStructure(newVertices, eset); + } + + void SparseOptimizer::sortVectorContainers() + { + // sort vector structures to get deterministic ordering based on IDs + sort(_activeVertices.begin(), _activeVertices.end(), VertexIDCompare()); + sort(_activeEdges.begin(), _activeEdges.end(), EdgeIDCompare()); + } + + void SparseOptimizer::clear() { + _ivMap.clear(); + _activeVertices.clear(); + _activeEdges.clear(); + OptimizableGraph::clear(); + } + + SparseOptimizer::VertexContainer::const_iterator SparseOptimizer::findActiveVertex(const OptimizableGraph::Vertex* v) const + { + VertexContainer::const_iterator lower = lower_bound(_activeVertices.begin(), _activeVertices.end(), v, VertexIDCompare()); + if (lower == _activeVertices.end()) + return _activeVertices.end(); + if ((*lower) == v) + return lower; + return _activeVertices.end(); + } + + SparseOptimizer::EdgeContainer::const_iterator SparseOptimizer::findActiveEdge(const OptimizableGraph::Edge* e) const + { + EdgeContainer::const_iterator lower = lower_bound(_activeEdges.begin(), _activeEdges.end(), e, EdgeIDCompare()); + if (lower == _activeEdges.end()) + return _activeEdges.end(); + if ((*lower) == e) + return lower; + return _activeEdges.end(); + } + + void SparseOptimizer::push(SparseOptimizer::VertexContainer& vlist) + { + for (VertexContainer::iterator it = vlist.begin(); it != vlist.end(); ++it) + (*it)->push(); + } + + void SparseOptimizer::pop(SparseOptimizer::VertexContainer& vlist) + { + for (VertexContainer::iterator it = vlist.begin(); it != vlist.end(); ++it) + (*it)->pop(); + } + + void SparseOptimizer::push(HyperGraph::VertexSet& vlist) + { + for (HyperGraph::VertexSet::iterator it = vlist.begin(); it != vlist.end(); ++it) { + OptimizableGraph::Vertex* v = dynamic_cast(*it); + if (v) + v->push(); + else + cerr << __FUNCTION__ << ": FATAL PUSH SET" << endl; + } + } + + void SparseOptimizer::pop(HyperGraph::VertexSet& vlist) + { + for (HyperGraph::VertexSet::iterator it = vlist.begin(); it != vlist.end(); ++it){ + OptimizableGraph::Vertex* v = dynamic_cast (*it); + if (v) + v->pop(); + else + cerr << __FUNCTION__ << ": FATAL POP SET" << endl; + } + } + + void SparseOptimizer::discardTop(SparseOptimizer::VertexContainer& vlist) + { + for (VertexContainer::iterator it = vlist.begin(); it != vlist.end(); ++it) + (*it)->discardTop(); + } + + void SparseOptimizer::setVerbose(bool verbose) + { + _verbose = verbose; + } + + void SparseOptimizer::setAlgorithm(OptimizationAlgorithm* algorithm) + { + if (_algorithm) // reset the optimizer for the formerly used solver + _algorithm->setOptimizer(0); + _algorithm = algorithm; + if (_algorithm) + _algorithm->setOptimizer(this); + } + + bool SparseOptimizer::computeMarginals(SparseBlockMatrix& spinv, const std::vector >& blockIndices){ + return _algorithm->computeMarginals(spinv, blockIndices); + } + + void SparseOptimizer::setForceStopFlag(bool* flag) + { + _forceStopFlag=flag; + } + + bool SparseOptimizer::removeVertex(HyperGraph::Vertex* v) + { + OptimizableGraph::Vertex* vv = static_cast(v); + if (vv->hessianIndex() >= 0) { + clearIndexMapping(); + _ivMap.clear(); + } + return HyperGraph::removeVertex(v); + } + + bool SparseOptimizer::addComputeErrorAction(HyperGraphAction* action) + { + std::pair insertResult = _graphActions[AT_COMPUTEACTIVERROR].insert(action); + return insertResult.second; + } + + bool SparseOptimizer::removeComputeErrorAction(HyperGraphAction* action) + { + return _graphActions[AT_COMPUTEACTIVERROR].erase(action) > 0; + } + + void SparseOptimizer::push() + { + push(_activeVertices); + } + + void SparseOptimizer::pop() + { + pop(_activeVertices); + } + + void SparseOptimizer::discardTop() + { + discardTop(_activeVertices); + } + +} // end namespace diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/sparse_optimizer.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/sparse_optimizer.h new file mode 100644 index 0000000..3b09f5a --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/core/sparse_optimizer.h @@ -0,0 +1,312 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_GRAPH_OPTIMIZER_CHOL_H_ +#define G2O_GRAPH_OPTIMIZER_CHOL_H_ + +#include "../stuff/macros.h" + +#include "optimizable_graph.h" +#include "sparse_block_matrix.h" +#include "batch_stats.h" + +#include + +namespace g2o { + + // forward declaration + class ActivePathCostFunction; + class OptimizationAlgorithm; + class EstimatePropagatorCost; + + class SparseOptimizer : public OptimizableGraph { + + public: + enum { + AT_COMPUTEACTIVERROR = OptimizableGraph::AT_NUM_ELEMENTS, + AT_NUM_ELEMENTS, // keep as last element + }; + + friend class ActivePathCostFunction; + + // Attention: _solver & _statistics is own by SparseOptimizer and will be + // deleted in its destructor. + SparseOptimizer(); + virtual ~SparseOptimizer(); + + // new interface for the optimizer + // the old functions will be dropped + /** + * Initializes the structures for optimizing a portion of the graph specified by a subset of edges. + * Before calling it be sure to invoke marginalized() and fixed() to the vertices you want to include in the + * schur complement or to set as fixed during the optimization. + * @param eset: the subgraph to be optimized. + * @returns false if somethings goes wrong + */ + virtual bool initializeOptimization(HyperGraph::EdgeSet& eset); + + /** + * Initializes the structures for optimizing a portion of the graph specified by a subset of vertices. + * Before calling it be sure to invoke marginalized() and fixed() to the vertices you want to include in the + * schur complement or to set as fixed during the optimization. + * @param vset: the subgraph to be optimized. + * @param level: is the level (in multilevel optimization) + * @returns false if somethings goes wrong + */ + virtual bool initializeOptimization(HyperGraph::VertexSet& vset, int level=0); + + /** + * Initializes the structures for optimizing the whole graph. + * Before calling it be sure to invoke marginalized() and fixed() to the vertices you want to include in the + * schur complement or to set as fixed during the optimization. + * @param level: is the level (in multilevel optimization) + * @returns false if somethings goes wrong + */ + virtual bool initializeOptimization(int level=0); + + /** + * HACK updating the internal structures for online processing + */ + virtual bool updateInitialization(HyperGraph::VertexSet& vset, HyperGraph::EdgeSet& eset); + + /** + * Propagates an initial guess from the vertex specified as origin. + * It should be called after initializeOptimization(...), as it relies on the _activeVertices/_edges structures. + * It constructs a set of trees starting from the nodes in the graph which are fixed and eligible for preforming optimization. + * The trees are constructed by utlizing a cost-function specified. + * @param costFunction: the cost function used + * @patam maxDistance: the distance where to stop the search + */ + virtual void computeInitialGuess(); + + /** + * Same as above but using a specific propagator + */ + virtual void computeInitialGuess(EstimatePropagatorCost& propagator); + + /** + * sets all vertices to their origin. + */ + virtual void setToOrigin(); + + + /** + * starts one optimization run given the current configuration of the graph, + * and the current settings stored in the class instance. + * It can be called only after initializeOptimization + */ + int optimize(int iterations, bool online = false); + + /** + * computes the blocks of the inverse of the specified pattern. + * the pattern is given via pairs of the blocks in the hessian + * @param blockIndices: the pattern + * @param spinv: the sparse block matrix with the result + * @returns false if the operation is not supported by the solver + */ + bool computeMarginals(SparseBlockMatrix& spinv, const std::vector >& blockIndices); + + /** + * computes the inverse of the specified vertex. + * @param vertex: the vertex whose state is to be marginalised + * @param spinv: the sparse block matrix with the result + * @returns false if the operation is not supported by the solver + */ + bool computeMarginals(SparseBlockMatrix& spinv, const Vertex* vertex) { + if (vertex->hessianIndex() < 0) { + return false; + } + std::vector > index; + index.push_back(std::pair(vertex->hessianIndex(), vertex->hessianIndex())); + return computeMarginals(spinv, index); + } + + /** + * computes the inverse of the set specified vertices, assembled into a single covariance matrix. + * @param vertex: the pattern + * @param spinv: the sparse block matrix with the result + * @returns false if the operation is not supported by the solver + */ + bool computeMarginals(SparseBlockMatrix& spinv, const VertexContainer& vertices) { + std::vector > indices; + for (VertexContainer::const_iterator it = vertices.begin(); it != vertices.end(); ++it) { + indices.push_back(std::pair((*it)->hessianIndex(),(*it)->hessianIndex())); + } + return computeMarginals(spinv, indices); + } + + //! finds a gauge in the graph to remove the undefined dof. + // The gauge should be fixed() and then the optimization can work (if no additional dof are in + // the system. The default implementation returns a node with maximum dimension. + virtual Vertex* findGauge(); + + bool gaugeFreedom(); + + /**returns the cached chi2 of the active portion of the graph*/ + double activeChi2() const; + /** + * returns the cached chi2 of the active portion of the graph. + * In contrast to activeChi2() this functions considers the weighting + * of the error according to the robustification of the error functions. + */ + double activeRobustChi2() const; + + //! verbose information during optimization + bool verbose() const {return _verbose;} + void setVerbose(bool verbose); + + /** + * sets a variable checked at every iteration to force a user stop. The iteration exits when the variable is true; + */ + void setForceStopFlag(bool* flag); + bool* forceStopFlag() const { return _forceStopFlag;}; + + //! if external stop flag is given, return its state. False otherwise + bool terminate() {return _forceStopFlag ? (*_forceStopFlag) : false; } + + //! the index mapping of the vertices + const VertexContainer& indexMapping() const {return _ivMap;} + //! the vertices active in the current optimization + const VertexContainer& activeVertices() const { return _activeVertices;} + //! the edges active in the current optimization + const EdgeContainer& activeEdges() const { return _activeEdges;} + + /** + * Remove a vertex. If the vertex is contained in the currently active set + * of vertices, then the internal temporary structures are cleaned, e.g., the index + * mapping is erased. In case you need the index mapping for manipulating the + * graph, you have to store it in your own copy. + */ + virtual bool removeVertex(HyperGraph::Vertex* v); + + /** + * search for an edge in _activeVertices and return the iterator pointing to it + * getActiveVertices().end() if not found + */ + VertexContainer::const_iterator findActiveVertex(const OptimizableGraph::Vertex* v) const; + /** + * search for an edge in _activeEdges and return the iterator pointing to it + * getActiveEdges().end() if not found + */ + EdgeContainer::const_iterator findActiveEdge(const OptimizableGraph::Edge* e) const; + + //! the solver used by the optimizer + const OptimizationAlgorithm* algorithm() const { return _algorithm;} + OptimizationAlgorithm* solver() { return _algorithm;} + void setAlgorithm(OptimizationAlgorithm* algorithm); + + //! push the estimate of a subset of the variables onto a stack + void push(SparseOptimizer::VertexContainer& vlist); + //! push the estimate of a subset of the variables onto a stack + void push(HyperGraph::VertexSet& vlist); + //! push all the active vertices onto a stack + void push(); + //! pop (restore) the estimate a subset of the variables from the stack + void pop(SparseOptimizer::VertexContainer& vlist); + //! pop (restore) the estimate a subset of the variables from the stack + void pop(HyperGraph::VertexSet& vlist); + //! pop (restore) the estimate of the active vertices from the stack + void pop(); + + //! ignore the latest stored element on the stack, remove it from the stack but do not restore the estimate + void discardTop(SparseOptimizer::VertexContainer& vlist); + //! same as above, but for the active vertices + void discardTop(); + using OptimizableGraph::discardTop; + + /** + * clears the graph, and polishes some intermediate structures + * Note that this only removes nodes / edges. Parameters can be removed + * with clearParameters(). + */ + virtual void clear(); + + /** + * computes the error vectors of all edges in the activeSet, and caches them + */ + void computeActiveErrors(); + + /** + * Linearizes the system by computing the Jacobians for the nodes + * and edges in the graph + */ + G2O_ATTRIBUTE_DEPRECATED(void linearizeSystem()) + { + // nothing needed, linearization is now done inside the solver + } + + /** + * update the estimate of the active vertices + * @param update: the double vector containing the stacked + * elements of the increments on the vertices. + */ + void update(const double* update); + + /** + returns the set of batch statistics about the optimisation + */ + const BatchStatisticsContainer& batchStatistics() const { return _batchStatistics;} + /** + returns the set of batch statistics about the optimisation + */ + BatchStatisticsContainer& batchStatistics() { return _batchStatistics;} + + void setComputeBatchStatistics(bool computeBatchStatistics); + + bool computeBatchStatistics() const { return _computeBatchStatistics;} + + /**** callbacks ****/ + //! add an action to be executed before the error vectors are computed + bool addComputeErrorAction(HyperGraphAction* action); + //! remove an action that should no longer be execured before computing the error vectors + bool removeComputeErrorAction(HyperGraphAction* action); + + + + protected: + bool* _forceStopFlag; + bool _verbose; + + VertexContainer _ivMap; + VertexContainer _activeVertices; ///< sorted according to VertexIDCompare + EdgeContainer _activeEdges; ///< sorted according to EdgeIDCompare + + void sortVectorContainers(); + + OptimizationAlgorithm* _algorithm; + + /** + * builds the mapping of the active vertices to the (block) row / column in the Hessian + */ + bool buildIndexMapping(SparseOptimizer::VertexContainer& vlist); + void clearIndexMapping(); + + BatchStatisticsContainer _batchStatistics; ///< global statistics of the optimizer, e.g., timing, num-non-zeros + bool _computeBatchStatistics; + }; +} // end namespace + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/solvers/linear_solver_dense.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/solvers/linear_solver_dense.h new file mode 100644 index 0000000..b34674c --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/solvers/linear_solver_dense.h @@ -0,0 +1,125 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 H. Strasdat +// Copyright (C) 2012 R. Kümmerle +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_LINEAR_SOLVER_DENSE_H +#define G2O_LINEAR_SOLVER_DENSE_H + +#include "../core/linear_solver.h" +#include "../core/batch_stats.h" + +#include +#include +#include +#include + + +namespace g2o { + + /** + * \brief linear solver using dense cholesky decomposition + */ + template + class LinearSolverDense : public LinearSolver + { + public: + LinearSolverDense() : + LinearSolver(), + _reset(true) + { + } + + virtual ~LinearSolverDense() + { + } + + virtual bool init() + { + _reset = true; + return true; + } + + bool solve(const SparseBlockMatrix& A, double* x, double* b) + { + int n = A.cols(); + int m = A.cols(); + + Eigen::MatrixXd& H = _H; + if (H.cols() != n) { + H.resize(n, m); + _reset = true; + } + if (_reset) { + _reset = false; + H.setZero(); + } + + // copy the sparse block matrix into a dense matrix + int c_idx = 0; + for (size_t i = 0; i < A.blockCols().size(); ++i) { + int c_size = A.colsOfBlock(i); + assert(c_idx == A.colBaseOfBlock(i) && "mismatch in block indices"); + + const typename SparseBlockMatrix::IntBlockMap& col = A.blockCols()[i]; + if (col.size() > 0) { + typename SparseBlockMatrix::IntBlockMap::const_iterator it; + for (it = col.begin(); it != col.end(); ++it) { + int r_idx = A.rowBaseOfBlock(it->first); + // only the upper triangular block is processed + if (it->first <= (int)i) { + int r_size = A.rowsOfBlock(it->first); + H.block(r_idx, c_idx, r_size, c_size) = *(it->second); + if (r_idx != c_idx) // write the lower triangular block + H.block(c_idx, r_idx, c_size, r_size) = it->second->transpose(); + } + } + } + + c_idx += c_size; + } + + // solving via Cholesky decomposition + Eigen::VectorXd::MapType xvec(x, m); + Eigen::VectorXd::ConstMapType bvec(b, n); + _cholesky.compute(H); + if (_cholesky.isPositive()) { + xvec = _cholesky.solve(bvec); + return true; + } + return false; + } + + protected: + bool _reset; + Eigen::MatrixXd _H; + Eigen::LDLT _cholesky; + + }; + + +}// end namespace + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/solvers/linear_solver_eigen.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/solvers/linear_solver_eigen.h new file mode 100644 index 0000000..492aea9 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/solvers/linear_solver_eigen.h @@ -0,0 +1,237 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_LINEAR_SOLVER_EIGEN_H +#define G2O_LINEAR_SOLVER_EIGEN_H + +#include +#include + +#include "../core/linear_solver.h" +#include "../core/batch_stats.h" +#include "../stuff/timeutil.h" + +#include "../core/eigen_types.h" + +#include +#include + +namespace g2o { + +/** + * \brief linear solver which uses the sparse Cholesky solver from Eigen + * + * Has no dependencies except Eigen. Hence, should compile almost everywhere + * without to much issues. Performance should be similar to CSparse, I guess. + */ +template +class LinearSolverEigen: public LinearSolver +{ + public: + typedef Eigen::SparseMatrix SparseMatrix; + typedef Eigen::Triplet Triplet; + typedef Eigen::PermutationMatrix PermutationMatrix; + /** + * \brief Sub-classing Eigen's SimplicialLDLT to perform ordering with a given ordering + */ + class CholeskyDecomposition : public Eigen::SimplicialLDLT + { + public: + CholeskyDecomposition() : Eigen::SimplicialLDLT() {} + using Eigen::SimplicialLDLT< SparseMatrix, Eigen::Upper>::analyzePattern_preordered; + + void analyzePatternWithPermutation(SparseMatrix& a, const PermutationMatrix& permutation) + { + m_Pinv = permutation; + m_P = permutation.inverse(); + int size = a.cols(); + SparseMatrix ap(size, size); + ap.selfadjointView() = a.selfadjointView().twistedBy(m_P); + analyzePattern_preordered(ap, true); + } + }; + + public: + LinearSolverEigen() : + LinearSolver(), + _init(true), _blockOrdering(false), _writeDebug(false) + { + } + + virtual ~LinearSolverEigen() + { + } + + virtual bool init() + { + _init = true; + return true; + } + + bool solve(const SparseBlockMatrix& A, double* x, double* b) + { + if (_init) + _sparseMatrix.resize(A.rows(), A.cols()); + fillSparseMatrix(A, !_init); + if (_init) // compute the symbolic composition once + computeSymbolicDecomposition(A); + _init = false; + + double t=get_monotonic_time(); + _cholesky.factorize(_sparseMatrix); + if (_cholesky.info() != Eigen::Success) { // the matrix is not positive definite + if (_writeDebug) { + std::cerr << "Cholesky failure, writing debug.txt (Hessian loadable by Octave)" << std::endl; + A.writeOctave("debug.txt"); + } + return false; + } + + // Solving the system + VectorXD::MapType xx(x, _sparseMatrix.cols()); + VectorXD::ConstMapType bb(b, _sparseMatrix.cols()); + xx = _cholesky.solve(bb); + G2OBatchStatistics* globalStats = G2OBatchStatistics::globalStats(); + if (globalStats) { + globalStats->timeNumericDecomposition = get_monotonic_time() - t; + globalStats->choleskyNNZ = _cholesky.matrixL().nestedExpression().nonZeros() + _sparseMatrix.cols(); // the elements of D + } + + return true; + } + + //! do the AMD ordering on the blocks or on the scalar matrix + bool blockOrdering() const { return _blockOrdering;} + void setBlockOrdering(bool blockOrdering) { _blockOrdering = blockOrdering;} + + //! write a debug dump of the system matrix if it is not SPD in solve + virtual bool writeDebug() const { return _writeDebug;} + virtual void setWriteDebug(bool b) { _writeDebug = b;} + + protected: + bool _init; + bool _blockOrdering; + bool _writeDebug; + SparseMatrix _sparseMatrix; + CholeskyDecomposition _cholesky; + + /** + * compute the symbolic decompostion of the matrix only once. + * Since A has the same pattern in all the iterations, we only + * compute the fill-in reducing ordering once and re-use for all + * the following iterations. + */ + void computeSymbolicDecomposition(const SparseBlockMatrix& A) + { + double t=get_monotonic_time(); + if (! _blockOrdering) { + _cholesky.analyzePattern(_sparseMatrix); + } else { + // block ordering with the Eigen Interface + // This is really ugly currently, as it calls internal functions from Eigen + // and modifies the SparseMatrix class + Eigen::PermutationMatrix blockP; + { + // prepare a block structure matrix for calling AMD + std::vector triplets; + for (size_t c = 0; c < A.blockCols().size(); ++c){ + const typename SparseBlockMatrix::IntBlockMap& column = A.blockCols()[c]; + for (typename SparseBlockMatrix::IntBlockMap::const_iterator it = column.begin(); it != column.end(); ++it) { + const int& r = it->first; + if (r > static_cast(c)) // only upper triangle + break; + triplets.push_back(Triplet(r, c, 0.)); + } + } + + // call the AMD ordering on the block matrix. + // Relies on Eigen's internal stuff, probably bad idea + SparseMatrix auxBlockMatrix(A.blockCols().size(), A.blockCols().size()); + auxBlockMatrix.setFromTriplets(triplets.begin(), triplets.end()); + typename CholeskyDecomposition::CholMatrixType C; + C = auxBlockMatrix.selfadjointView(); + Eigen::internal::minimum_degree_ordering(C, blockP); + } + + int rows = A.rows(); + assert(rows == A.cols() && "Matrix A is not square"); + + // Adapt the block permutation to the scalar matrix + PermutationMatrix scalarP; + scalarP.resize(rows); + int scalarIdx = 0; + for (int i = 0; i < blockP.size(); ++i) { + const int& p = blockP.indices()(i); + int base = A.colBaseOfBlock(p); + int nCols = A.colsOfBlock(p); + for (int j = 0; j < nCols; ++j) + scalarP.indices()(scalarIdx++) = base++; + } + assert(scalarIdx == rows && "did not completely fill the permutation matrix"); + // analyze with the scalar permutation + _cholesky.analyzePatternWithPermutation(_sparseMatrix, scalarP); + + } + G2OBatchStatistics* globalStats = G2OBatchStatistics::globalStats(); + if (globalStats) + globalStats->timeSymbolicDecomposition = get_monotonic_time() - t; + } + + void fillSparseMatrix(const SparseBlockMatrix& A, bool onlyValues) + { + if (onlyValues) { + A.fillCCS(_sparseMatrix.valuePtr(), true); + } else { + + // create from triplet structure + std::vector triplets; + triplets.reserve(A.nonZeros()); + for (size_t c = 0; c < A.blockCols().size(); ++c) { + int colBaseOfBlock = A.colBaseOfBlock(c); + const typename SparseBlockMatrix::IntBlockMap& column = A.blockCols()[c]; + for (typename SparseBlockMatrix::IntBlockMap::const_iterator it = column.begin(); it != column.end(); ++it) { + int rowBaseOfBlock = A.rowBaseOfBlock(it->first); + const MatrixType& m = *(it->second); + for (int cc = 0; cc < m.cols(); ++cc) { + int aux_c = colBaseOfBlock + cc; + for (int rr = 0; rr < m.rows(); ++rr) { + int aux_r = rowBaseOfBlock + rr; + if (aux_r > aux_c) + break; + triplets.push_back(Triplet(aux_r, aux_c, m(rr, cc))); + } + } + } + } + _sparseMatrix.setFromTriplets(triplets.begin(), triplets.end()); + + } + } +}; + +} // end namespace + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/stuff/color_macros.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/stuff/color_macros.h new file mode 100644 index 0000000..7115bbe --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/stuff/color_macros.h @@ -0,0 +1,65 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_COLOR_MACROS_H +#define G2O_COLOR_MACROS_H + +// font attributes +#define FT_BOLD "\033[1m" +#define FT_UNDERLINE "\033[4m" + +//background color +#define BG_BLACK "\033[40m" +#define BG_RED "\033[41m" +#define BG_GREEN "\033[42m" +#define BG_YELLOW "\033[43m" +#define BG_LIGHTBLUE "\033[44m" +#define BG_MAGENTA "\033[45m" +#define BG_BLUE "\033[46m" +#define BG_WHITE "\033[47m" + +// font color +#define CL_BLACK(s) "\033[30m" << s << "\033[0m" +#define CL_RED(s) "\033[31m" << s << "\033[0m" +#define CL_GREEN(s) "\033[32m" << s << "\033[0m" +#define CL_YELLOW(s) "\033[33m" << s << "\033[0m" +#define CL_LIGHTBLUE(s) "\033[34m" << s << "\033[0m" +#define CL_MAGENTA(s) "\033[35m" << s << "\033[0m" +#define CL_BLUE(s) "\033[36m" << s << "\033[0m" +#define CL_WHITE(s) "\033[37m" << s << "\033[0m" + +#define FG_BLACK "\033[30m" +#define FG_RED "\033[31m" +#define FG_GREEN "\033[32m" +#define FG_YELLOW "\033[33m" +#define FG_LIGHTBLUE "\033[34m" +#define FG_MAGENTA "\033[35m" +#define FG_BLUE "\033[36m" +#define FG_WHITE "\033[37m" + +#define FG_NORM "\033[0m" + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/stuff/macros.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/stuff/macros.h new file mode 100644 index 0000000..be4a245 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/stuff/macros.h @@ -0,0 +1,134 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_MACROS_H +#define G2O_MACROS_H + +#ifndef DEG2RAD +#define DEG2RAD(x) ((x) * 0.01745329251994329575) +#endif + +#ifndef RAD2DEG +#define RAD2DEG(x) ((x) * 57.29577951308232087721) +#endif + +// GCC the one and only +#if defined(__GNUC__) +# define G2O_ATTRIBUTE_CONSTRUCTOR(func) \ + static void func(void)__attribute__ ((constructor)); \ + static void func(void) + +# define G2O_ATTRIBUTE_UNUSED __attribute__((unused)) +# define G2O_ATTRIBUTE_FORMAT12 __attribute__ ((format (printf, 1, 2))) +# define G2O_ATTRIBUTE_FORMAT23 __attribute__ ((format (printf, 2, 3))) +# define G2O_ATTRIBUTE_WARNING(func) func __attribute__((warning)) +# define G2O_ATTRIBUTE_DEPRECATED(func) func __attribute__((deprecated)) + +#ifdef ANDROID +# define g2o_isnan(x) isnan(x) +# define g2o_isinf(x) isinf(x) +# define g2o_isfinite(x) isfinite(x) +#else +# define g2o_isnan(x) std::isnan(x) +# define g2o_isinf(x) std::isinf(x) +# define g2o_isfinite(x) std::isfinite(x) +#endif + +// MSVC on Windows +#elif defined _MSC_VER +# define __PRETTY_FUNCTION__ __FUNCTION__ + +/** +Modified by Mark Pupilli from: + + "Initializer/finalizer sample for MSVC and GCC. + 2010 Joe Lowe. Released into the public domain." + + "For MSVC, places a ptr to the function in the user initializer section (.CRT$XCU), basically the same thing the compiler does for the constructor calls for static C++ objects. For GCC, uses a constructor attribute." + + (As posted on Stack OVerflow) +*/ +# define G2O_ATTRIBUTE_CONSTRUCTOR(f) \ + __pragma(section(".CRT$XCU",read)) \ + static void __cdecl f(void); \ + __declspec(allocate(".CRT$XCU")) void (__cdecl*f##_)(void) = f; \ + static void __cdecl f(void) + +# define G2O_ATTRIBUTE_UNUSED +# define G2O_ATTRIBUTE_FORMAT12 +# define G2O_ATTRIBUTE_FORMAT23 +# define G2O_ATTRIBUTE_WARNING(func) func +# define G2O_ATTRIBUTE_DEPRECATED(func) func + +#include + +# define g2o_isnan(x) _isnan(x) +# define g2o_isinf(x) (_finite(x) == 0) +# define g2o_isfinite(x) (_finite(x) != 0) + +// unknown compiler +#else +# ifndef __PRETTY_FUNCTION__ +# define __PRETTY_FUNCTION__ "" +# endif +# define G2O_ATTRIBUTE_CONSTRUCTOR(func) func +# define G2O_ATTRIBUTE_UNUSED +# define G2O_ATTRIBUTE_FORMAT12 +# define G2O_ATTRIBUTE_FORMAT23 +# define G2O_ATTRIBUTE_WARNING(func) func +# define G2O_ATTRIBUTE_DEPRECATED(func) func + +#include +#define g2o_isnan(x) isnan(x) +#define g2o_isinf(x) isinf(x) +#define g2o_isfinite(x) isfinite(x) + +#endif + +// some macros that are only useful for c++ +#ifdef __cplusplus + +#define G2O_FSKIP_LINE(f) \ + {char c=' ';while(c != '\n' && f.good() && !(f).eof()) (f).get(c);} + +#ifndef PVAR + #define PVAR(s) \ + #s << " = " << (s) << std::flush +#endif + +#ifndef PVARA +#define PVARA(s) \ + #s << " = " << RAD2DEG(s) << "deg" << std::flush +#endif + +#ifndef FIXED +#define FIXED(s) \ + std::fixed << s << std::resetiosflags(std::ios_base::fixed) +#endif + +#endif // __cplusplus + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/stuff/misc.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/stuff/misc.h new file mode 100644 index 0000000..4fa4ff3 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/stuff/misc.h @@ -0,0 +1,206 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_STUFF_MISC_H +#define G2O_STUFF_MISC_H + +#include "macros.h" +#include + +#ifndef M_PI +#define M_PI 3.14159265358979323846 +#endif + +/** @addtogroup utils **/ +// @{ + +/** \file misc.h + * \brief some general case utility functions + * + * This file specifies some general case utility functions + **/ + +namespace g2o { + +/** + * return the square value + */ +template +inline T square(T x) +{ + return x*x; +} + +/** + * return the hypot of x and y + */ +template +inline T hypot(T x, T y) +{ + return (T) (sqrt(x*x + y*y)); +} + +/** + * return the squared hypot of x and y + */ +template +inline T hypot_sqr(T x, T y) +{ + return x*x + y*y; +} + +/** + * convert from degree to radian + */ +inline double deg2rad(double degree) +{ + return degree * 0.01745329251994329576; +} + +/** + * convert from radian to degree + */ +inline double rad2deg(double rad) +{ + return rad * 57.29577951308232087721; +} + +/** + * normalize the angle + */ +inline double normalize_theta(double theta) +{ + if (theta >= -M_PI && theta < M_PI) + return theta; + + double multiplier = floor(theta / (2*M_PI)); + theta = theta - multiplier*2*M_PI; + if (theta >= M_PI) + theta -= 2*M_PI; + if (theta < -M_PI) + theta += 2*M_PI; + + return theta; +} + +/** + * inverse of an angle, i.e., +180 degree + */ +inline double inverse_theta(double th) +{ + return normalize_theta(th + M_PI); +} + +/** + * average two angles + */ +inline double average_angle(double theta1, double theta2) +{ + double x, y; + + x = cos(theta1) + cos(theta2); + y = sin(theta1) + sin(theta2); + if(x == 0 && y == 0) + return 0; + else + return std::atan2(y, x); +} + +/** + * sign function. + * @return the sign of x. +1 for x > 0, -1 for x < 0, 0 for x == 0 + */ +template +inline int sign(T x) +{ + if (x > 0) + return 1; + else if (x < 0) + return -1; + else + return 0; +} + +/** + * clamp x to the interval [l, u] + */ +template +inline T clamp(T l, T x, T u) +{ + if (x < l) + return l; + if (x > u) + return u; + return x; +} + +/** + * wrap x to be in the interval [l, u] + */ +template +inline T wrap(T l, T x, T u) +{ + T intervalWidth = u - l; + while (x < l) + x += intervalWidth; + while (x > u) + x -= intervalWidth; + return x; +} + +/** + * tests whether there is a NaN in the array + */ +inline bool arrayHasNaN(const double* array, int size, int* nanIndex = 0) +{ + for (int i = 0; i < size; ++i) + if (g2o_isnan(array[i])) { + if (nanIndex) + *nanIndex = i; + return true; + } + return false; +} + +/** + * The following two functions are used to force linkage with static libraries. + */ +extern "C" +{ + typedef void (* ForceLinkFunction) (void); +} + +struct ForceLinker +{ + ForceLinker(ForceLinkFunction function) { (function)(); } +}; + + +} // end namespace + +// @} + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/stuff/os_specific.c b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/stuff/os_specific.c new file mode 100644 index 0000000..85f9368 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/stuff/os_specific.c @@ -0,0 +1,64 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#include "os_specific.h" + +#ifdef WINDOWS + +int vasprintf(char** strp, const char* fmt, va_list ap) +{ + int n; + int size = 100; + char* p; + char* np; + + if ((p = (char*)malloc(size * sizeof(char))) == NULL) + return -1; + + while (1) { +#ifdef _MSC_VER + n = vsnprintf_s(p, size, size - 1, fmt, ap); +#else + n = vsnprintf(p, size, fmt, ap); +#endif + if (n > -1 && n < size) { + *strp = p; + return n; + } + if (n > -1) + size = n+1; + else + size *= 2; + if ((np = (char*)realloc (p, size * sizeof(char))) == NULL) { + free(p); + return -1; + } else + p = np; + } +} + + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/stuff/os_specific.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/stuff/os_specific.h new file mode 100644 index 0000000..89dd0cc --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/stuff/os_specific.h @@ -0,0 +1,56 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_OS_SPECIFIC_HH_ +#define G2O_OS_SPECIFIC_HH_ + +#ifdef WINDOWS +#include +#include +#include +#ifndef _WINDOWS +#include +#endif +#define drand48() ((double) rand()/(double)RAND_MAX) + +#ifdef __cplusplus +extern "C" { +#endif + +int vasprintf(char** strp, const char* fmt, va_list ap); + +#ifdef __cplusplus +} +#endif + +#endif + +#ifdef UNIX +#include +// nothing to do on real operating systems +#endif + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/stuff/property.cpp b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/stuff/property.cpp new file mode 100644 index 0000000..f13016e --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/stuff/property.cpp @@ -0,0 +1,105 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#include "property.h" + +#include +#include + +#include "macros.h" + +#include "string_tools.h" +using namespace std; + +namespace g2o { + + BaseProperty::BaseProperty(const std::string name_) :_name(name_){ + } + + BaseProperty::~BaseProperty(){} + + bool PropertyMap::addProperty(BaseProperty* p) { + std::pair result = insert(make_pair(p->name(), p)); + return result.second; + } + + bool PropertyMap::eraseProperty(const std::string& name) { + PropertyMapIterator it=find(name); + if (it==end()) + return false; + delete it->second; + erase(it); + return true; + } + + PropertyMap::~PropertyMap() { + for (PropertyMapIterator it=begin(); it!=end(); it++){ + if (it->second) + delete it->second; + } + } + + bool PropertyMap::updatePropertyFromString(const std::string& name, const std::string& value) + { + PropertyMapIterator it = find(name); + if (it == end()) + return false; + it->second->fromString(value); + return true; + } + + void PropertyMap::writeToCSV(std::ostream& os) const + { + for (PropertyMapConstIterator it=begin(); it!=end(); it++){ + BaseProperty* p =it->second; + os << p->name() << ", "; + } + os << std::endl; + for (PropertyMapConstIterator it=begin(); it!=end(); it++){ + BaseProperty* p =it->second; + os << p->toString() << ", "; + } + os << std::endl; + } + + bool PropertyMap::updateMapFromString(const std::string& values) + { + bool status = true; + vector valuesMap = strSplit(values, ","); + for (size_t i = 0; i < valuesMap.size(); ++i) { + vector m = strSplit(valuesMap[i], "="); + if (m.size() != 2) { + cerr << __PRETTY_FUNCTION__ << ": unable to extract name=value pair from " << valuesMap[i] << endl; + continue; + } + string name = trim(m[0]); + string value = trim(m[1]); + status = status && updatePropertyFromString(name, value); + } + return status; + } + +} // end namespace diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/stuff/property.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/stuff/property.h new file mode 100644 index 0000000..7b63878 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/stuff/property.h @@ -0,0 +1,158 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_PROPERTY_H_ +#define G2O_PROPERTY_H_ + +#include +#include +#include + +#include "string_tools.h" + +namespace g2o { + + class BaseProperty { + public: + BaseProperty(const std::string name_); + virtual ~BaseProperty(); + const std::string& name() {return _name;} + virtual std::string toString() const = 0; + virtual bool fromString(const std::string& s) = 0; + protected: + std::string _name; + }; + + template + class Property: public BaseProperty { + public: + typedef T ValueType; + Property(const std::string& name_): BaseProperty(name_){} + Property(const std::string& name_, const T& v): BaseProperty(name_), _value(v){} + void setValue(const T& v) {_value = v; } + const T& value() const {return _value;} + virtual std::string toString() const + { + std::stringstream sstr; + sstr << _value; + return sstr.str(); + } + virtual bool fromString(const std::string& s) + { + bool status = convertString(s, _value); + return status; + } + protected: + T _value; + }; + + /** + * \brief a collection of properties mapping from name to the property itself + */ + class PropertyMap : protected std::map + { + public: + typedef std::map BaseClass; + typedef BaseClass::iterator PropertyMapIterator; + typedef BaseClass::const_iterator PropertyMapConstIterator; + + ~PropertyMap(); + + /** + * add a property to the map + */ + bool addProperty(BaseProperty* p); + + /** + * remove a property from the map + */ + bool eraseProperty(const std::string& name_); + + /** + * return a property by its name + */ + template + P* getProperty(const std::string& name_) + { + PropertyMapIterator it=find(name_); + if (it==end()) + return 0; + return dynamic_cast(it->second); + } + template + const P* getProperty(const std::string& name_) const + { + PropertyMapConstIterator it=find(name_); + if (it==end()) + return 0; + return dynamic_cast(it->second); + } + + /** + * create a property and insert it + */ + template + P* makeProperty(const std::string& name_, const typename P::ValueType& v) + { + PropertyMapIterator it=find(name_); + if (it==end()){ + P* p=new P(name_, v); + addProperty(p); + return p; + } else + return dynamic_cast(it->second); + } + + /** + * update a specfic property with a new value + * @return true if the params is stored and update was carried out + */ + bool updatePropertyFromString(const std::string& name, const std::string& value); + + /** + * update the map based on a name=value string, e.g., name1=val1,name2=val2 + * @return true, if it was possible to update all parameters + */ + bool updateMapFromString(const std::string& values); + + void writeToCSV(std::ostream& os) const; + + using BaseClass::size; + using BaseClass::begin; + using BaseClass::end; + using BaseClass::iterator; + using BaseClass::const_iterator; + + }; + + typedef Property IntProperty; + typedef Property BoolProperty; + typedef Property FloatProperty; + typedef Property DoubleProperty; + typedef Property StringProperty; + +} // end namespace +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/stuff/string_tools.cpp b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/stuff/string_tools.cpp new file mode 100644 index 0000000..0a4f60a --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/stuff/string_tools.cpp @@ -0,0 +1,185 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#include "string_tools.h" +#include "os_specific.h" +#include "macros.h" + +#include +#include +#include +#include +#include +#include +#include +#include + +#if (defined (UNIX) || defined(CYGWIN)) && !defined(ANDROID) +#include +#endif + +namespace g2o { + +using namespace std; + +std::string trim(const std::string& s) +{ + if(s.length() == 0) + return s; + string::size_type b = s.find_first_not_of(" \t\n"); + string::size_type e = s.find_last_not_of(" \t\n"); + if(b == string::npos) + return ""; + return std::string(s, b, e - b + 1); +} + +std::string trimLeft(const std::string& s) +{ + if(s.length() == 0) + return s; + string::size_type b = s.find_first_not_of(" \t\n"); + string::size_type e = s.length() - 1; + if(b == string::npos) + return ""; + return std::string(s, b, e - b + 1); +} + +std::string trimRight(const std::string& s) +{ + if(s.length() == 0) + return s; + string::size_type b = 0; + string::size_type e = s.find_last_not_of(" \t\n"); + if(b == string::npos) + return ""; + return std::string(s, b, e - b + 1); +} + +std::string strToLower(const std::string& s) +{ + string ret; + std::transform(s.begin(), s.end(), back_inserter(ret), (int(*)(int)) std::tolower); + return ret; +} + +std::string strToUpper(const std::string& s) +{ + string ret; + std::transform(s.begin(), s.end(), back_inserter(ret), (int(*)(int)) std::toupper); + return ret; +} + +std::string formatString(const char* fmt, ...) +{ + char* auxPtr = NULL; + va_list arg_list; + va_start(arg_list, fmt); + int numChar = vasprintf(&auxPtr, fmt, arg_list); + va_end(arg_list); + string retString; + if (numChar != -1) + retString = auxPtr; + else { + cerr << __PRETTY_FUNCTION__ << ": Error while allocating memory" << endl; + } + free(auxPtr); + return retString; +} + +int strPrintf(std::string& str, const char* fmt, ...) +{ + char* auxPtr = NULL; + va_list arg_list; + va_start(arg_list, fmt); + int numChars = vasprintf(&auxPtr, fmt, arg_list); + va_end(arg_list); + str = auxPtr; + free(auxPtr); + return numChars; +} + +std::string strExpandFilename(const std::string& filename) +{ +#if (defined (UNIX) || defined(CYGWIN)) && !defined(ANDROID) + string result = filename; + wordexp_t p; + + wordexp(filename.c_str(), &p, 0); + if(p.we_wordc > 0) { + result = p.we_wordv[0]; + } + wordfree(&p); + return result; +#else + (void) filename; + std::cerr << "WARNING: " << __PRETTY_FUNCTION__ << " not implemented" << std::endl; + return std::string(); +#endif +} + +std::vector strSplit(const std::string& str, const std::string& delimiters) +{ + std::vector tokens; + string::size_type lastPos = 0; + string::size_type pos = 0; + + do { + pos = str.find_first_of(delimiters, lastPos); + tokens.push_back(str.substr(lastPos, pos - lastPos)); + lastPos = pos + 1; + } while (string::npos != pos); + + return tokens; +} + +bool strStartsWith(const std::string& s, const std::string& start) +{ + if (s.size() < start.size()) + return false; + return equal(start.begin(), start.end(), s.begin()); +} + +bool strEndsWith(const std::string& s, const std::string& end) +{ + if (s.size() < end.size()) + return false; + return equal(end.rbegin(), end.rend(), s.rbegin()); +} + +int readLine(std::istream& is, std::stringstream& currentLine) +{ + if (is.eof()) + return -1; + currentLine.str(""); + currentLine.clear(); + is.get(*currentLine.rdbuf()); + if (is.fail()) // fail is set on empty lines + is.clear(); + G2O_FSKIP_LINE(is); // read \n not read by get() + return static_cast(currentLine.str().size()); +} + +} // end namespace diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/stuff/string_tools.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/stuff/string_tools.h new file mode 100644 index 0000000..226208f --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/stuff/string_tools.h @@ -0,0 +1,176 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_STRING_TOOLS_H +#define G2O_STRING_TOOLS_H + +#include +#include +#include +#include + +#include "macros.h" + +namespace g2o { + +/** @addtogroup utils **/ +// @{ + +/** \file stringTools.h + * \brief utility functions for handling strings + */ + +/** + * remove whitespaces from the start/end of a string + */ + std::string trim(const std::string& s); + +/** + * remove whitespaces from the left side of the string + */ + std::string trimLeft(const std::string& s); + +/** + * remove whitespaced from the right side of the string + */ + std::string trimRight(const std::string& s); + +/** + * convert the string to lower case + */ + std::string strToLower(const std::string& s); + +/** + * convert a string to upper case + */ + std::string strToUpper(const std::string& s); + +/** + * read integer values (seperated by spaces) from a string and store + * them in the given OutputIterator. + */ +template +OutputIterator readInts(const char* str, OutputIterator out) +{ + char* cl = (char*)str; + char* cle = cl; + while (1) { + int id = strtol(cl, &cle, 10); + if (cl == cle) + break; + *out++ = id; + cl = cle; + } + return out; +} + +/** + * read float values (seperated by spaces) from a string and store + * them in the given OutputIterator. + */ +template +OutputIterator readFloats(const char* str, OutputIterator out) +{ + char* cl = (char*)str; + char* cle = cl; + while (1) { + double val = strtod(cl, &cle); + if (cl == cle) + break; + *out++ = val; + cl = cle; + } + return out; +} + +/** + * format a string and return a std::string. + * Format is just like printf, see man 3 printf + */ + std::string formatString(const char* fmt, ...) G2O_ATTRIBUTE_FORMAT12; + +/** + * replacement function for sprintf which fills a std::string instead of a char* + */ + int strPrintf(std::string& str, const char* fmt, ...) G2O_ATTRIBUTE_FORMAT23; + +/** + * convert a string into an other type. + */ +template +bool convertString(const std::string& s, T& x, bool failIfLeftoverChars = true) +{ + std::istringstream i(s); + char c; + if (!(i >> x) || (failIfLeftoverChars && i.get(c))) + return false; + return true; +} + +/** + * convert a string into an other type. + * Return the converted value. Throw error if parsing is wrong. + */ +template +T stringToType(const std::string& s, bool failIfLeftoverChars = true) +{ + T x; + convertString(s, x, failIfLeftoverChars); + return x; +} + +/** + * return true, if str starts with substr + */ + bool strStartsWith(const std::string & str, const std::string& substr); + +/** + * return true, if str ends with substr + */ + bool strEndsWith(const std::string & str, const std::string& substr); + +/** + * expand the given filename like a posix shell, e.g., ~ $CARMEN_HOME and other will get expanded. + * Also command substitution, e.g. `pwd` will give the current directory. + */ + std::string strExpandFilename(const std::string& filename); + +/** + * split a string into token based on the characters given in delim + */ + std::vector strSplit(const std::string& s, const std::string& delim); + +/** + * read a line from is into currentLine. + * @return the number of characters read into currentLine (excluding newline), -1 on eof() + */ + int readLine(std::istream& is, std::stringstream& currentLine); + +// @} + +} // end namespace + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/stuff/timeutil.cpp b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/stuff/timeutil.cpp new file mode 100644 index 0000000..ec19051 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/stuff/timeutil.cpp @@ -0,0 +1,124 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#include "timeutil.h" +#include + +#ifdef _WINDOWS +#include +#include +#endif + +#ifdef UNIX +#include +#endif + +namespace g2o { + +#ifdef _WINDOWS +#if defined(_MSC_VER) || defined(_MSC_EXTENSIONS) + #define DELTA_EPOCH_IN_MICROSECS 11644473600000000Ui64 +#else + #define DELTA_EPOCH_IN_MICROSECS 11644473600000000ULL +#endif + +struct timezone +{ + int tz_minuteswest; /* minutes W of Greenwich */ + int tz_dsttime; /* type of dst correction */ +}; + +int gettimeofday(struct timeval *tv, struct timezone *tz) +{ +// Define a structure to receive the current Windows filetime + FILETIME ft; + +// Initialize the present time to 0 and the timezone to UTC + unsigned __int64 tmpres = 0; + static int tzflag = 0; + + if (NULL != tv) + { + GetSystemTimeAsFileTime(&ft); + +// The GetSystemTimeAsFileTime returns the number of 100 nanosecond +// intervals since Jan 1, 1601 in a structure. Copy the high bits to +// the 64 bit tmpres, shift it left by 32 then or in the low 32 bits. + tmpres |= ft.dwHighDateTime; + tmpres <<= 32; + tmpres |= ft.dwLowDateTime; + +// Convert to microseconds by dividing by 10 + tmpres /= 10; + +// The Unix epoch starts on Jan 1 1970. Need to subtract the difference +// in seconds from Jan 1 1601. + tmpres -= DELTA_EPOCH_IN_MICROSECS; + +// Finally change microseconds to seconds and place in the seconds value. +// The modulus picks up the microseconds. + tv->tv_sec = (long)(tmpres / 1000000UL); + tv->tv_usec = (long)(tmpres % 1000000UL); + } + + if (NULL != tz) { + if (!tzflag) { + _tzset(); + tzflag++; + } + + long sec; + int hours; + _get_timezone(&sec); + _get_daylight(&hours); + +// Adjust for the timezone west of Greenwich + tz->tz_minuteswest = sec / 60; + tz->tz_dsttime = hours; + } + + return 0; +} +#endif + +ScopeTime::ScopeTime(const char* title) : _title(title), _startTime(get_monotonic_time()) {} + +ScopeTime::~ScopeTime() { + std::cerr << _title<<" took "<<1000*(get_monotonic_time()-_startTime)<<"ms.\n"; +} + +double get_monotonic_time() +{ +#if (defined(_POSIX_TIMERS) && (_POSIX_TIMERS+0 >= 0) && defined(_POSIX_MONOTONIC_CLOCK)) + struct timespec ts; + clock_gettime(CLOCK_MONOTONIC, &ts); + return ts.tv_sec + ts.tv_nsec*1e-9; +#else + return get_time(); +#endif +} + +} // end namespace diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/stuff/timeutil.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/stuff/timeutil.h new file mode 100644 index 0000000..bde8e31 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/stuff/timeutil.h @@ -0,0 +1,132 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_TIMEUTIL_H +#define G2O_TIMEUTIL_H + +#ifdef _WINDOWS +#include +#else +#include +#endif + +#include + + +/** @addtogroup utils **/ +// @{ + +/** \file timeutil.h + * \brief utility functions for handling time related stuff + */ + +/// Executes code, only if secs are gone since last exec. +/// extended version, in which the current time is given, e.g., timestamp of IPC message +#ifndef DO_EVERY_TS +#define DO_EVERY_TS(secs, currentTime, code) \ +if (1) {\ + static double s_lastDone_ = (currentTime); \ + double s_now_ = (currentTime); \ + if (s_lastDone_ > s_now_) \ + s_lastDone_ = s_now_; \ + if (s_now_ - s_lastDone_ > (secs)) { \ + code; \ + s_lastDone_ = s_now_; \ + }\ +} else \ + (void)0 +#endif + +/// Executes code, only if secs are gone since last exec. +#ifndef DO_EVERY +#define DO_EVERY(secs, code) DO_EVERY_TS(secs, g2o::get_time(), code) +#endif + +#ifndef MEASURE_TIME +#define MEASURE_TIME(text, code) \ + if(1) { \ + double _start_time_ = g2o::get_time(); \ + code; \ + fprintf(stderr, "%s took %f sec\n", text, g2o::get_time() - _start_time_); \ + } else \ + (void) 0 +#endif + +namespace g2o { + +#ifdef _WINDOWS +typedef struct timeval { + long tv_sec; + long tv_usec; +} timeval; + int gettimeofday(struct timeval *tv, struct timezone *tz); +#endif + +/** + * return the current time in seconds since 1. Jan 1970 + */ +inline double get_time() +{ + struct timeval ts; + gettimeofday(&ts,0); + return ts.tv_sec + ts.tv_usec*1e-6; +} + +/** + * return a monotonic increasing time which basically does not need to + * have a reference point. Consider this for measuring how long some + * code fragments required to execute. + * + * On Linux we call clock_gettime() on other systems we currently + * call get_time(). + */ + double get_monotonic_time(); + +/** + * \brief Class to measure the time spent in a scope + * + * To use this class, e.g. to measure the time spent in a function, + * just create and instance at the beginning of the function. + */ +class ScopeTime { + public: + ScopeTime(const char* title); + ~ScopeTime(); + private: + std::string _title; + double _startTime; +}; + +} // end namespace + +#ifndef MEASURE_FUNCTION_TIME +#define MEASURE_FUNCTION_TIME \ + g2o::ScopeTime scopeTime(__PRETTY_FUNCTION__) +#endif + + +// @} +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/types/se3_ops.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/types/se3_ops.h new file mode 100644 index 0000000..b5c59d3 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/types/se3_ops.h @@ -0,0 +1,47 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 H. Strasdat +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_MATH_STUFF +#define G2O_MATH_STUFF + +#include +#include + +namespace g2o { + using namespace Eigen; + + inline Matrix3d skew(const Vector3d&v); + inline Vector3d deltaR(const Matrix3d& R); + inline Vector2d project(const Vector3d&); + inline Vector3d project(const Vector4d&); + inline Vector3d unproject(const Vector2d&); + inline Vector4d unproject(const Vector3d&); + +#include "se3_ops.hpp" + +} + +#endif //MATH_STUFF diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/types/se3_ops.hpp b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/types/se3_ops.hpp new file mode 100644 index 0000000..c28860d --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/types/se3_ops.hpp @@ -0,0 +1,85 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 H. Strasdat +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + + Matrix3d skew(const Vector3d&v) + { + Matrix3d m; + m.fill(0.); + m(0,1) = -v(2); + m(0,2) = v(1); + m(1,2) = -v(0); + m(1,0) = v(2); + m(2,0) = -v(1); + m(2,1) = v(0); + return m; + } + + Vector3d deltaR(const Matrix3d& R) + { + Vector3d v; + v(0)=R(2,1)-R(1,2); + v(1)=R(0,2)-R(2,0); + v(2)=R(1,0)-R(0,1); + return v; + } + + Vector2d project(const Vector3d& v) + { + Vector2d res; + res(0) = v(0)/v(2); + res(1) = v(1)/v(2); + return res; + } + + Vector3d project(const Vector4d& v) + { + Vector3d res; + res(0) = v(0)/v(3); + res(1) = v(1)/v(3); + res(2) = v(2)/v(3); + return res; + } + + Vector3d unproject(const Vector2d& v) + { + Vector3d res; + res(0) = v(0); + res(1) = v(1); + res(2) = 1; + return res; + } + + Vector4d unproject(const Vector3d& v) + { + Vector4d res; + res(0) = v(0); + res(1) = v(1); + res(2) = v(2); + res(3) = 1; + return res; + } + + diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/types/se3mat.cpp b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/types/se3mat.cpp new file mode 100644 index 0000000..d9d2c69 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/types/se3mat.cpp @@ -0,0 +1,39 @@ +#include "se3mat.h" + +namespace g2o { + + +void SE3mat::Retract(const Eigen::Vector3d dr, const Eigen::Vector3d &dt) +{ + t += R*dt; + R = R*ExpSO3(dr); +} + +Eigen::Matrix3d SE3mat::ExpSO3(const Eigen::Vector3d r) +{ + Eigen::Matrix3d W; + W << 0, -r[2], r[1], + r[2], 0, -r[0], + -r[1], r[0], 0; + + const double theta = r.norm(); + + if(theta<1e-6) + return Eigen::Matrix3d::Identity() + W + 0.5l*W*W; + else + return Eigen::Matrix3d::Identity() + W*sin(theta)/theta + W*W*(1-cos(theta))/(theta*theta); +} + +Eigen::Vector3d SE3mat::LogSO3(const Eigen::Matrix3d R) +{ + const double tr = R(0,0)+R(1,1)+R(2,2); + const double theta = acos((tr-1.0l)*0.5l); + Eigen::Vector3d w; + w << R(2,1), R(0,2), R(1,0); + if(theta<1e-6) + return w; + else + return theta*w/sin(theta); +} + +} //namespace g2o diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/types/se3mat.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/types/se3mat.h new file mode 100644 index 0000000..e78673c --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/types/se3mat.h @@ -0,0 +1,47 @@ +#ifndef SE3mat_H +#define SE3mat_H + +#include +#include + +namespace g2o { + +class SE3mat +{ +public: + SE3mat(){ + R = Eigen::Matrix3d::Identity(); + t.setZero(); + } + + SE3mat(const Eigen::Matrix3d &R_, const Eigen::Vector3d &t_):R(R_),t(t_){} + + void Retract(const Eigen::Vector3d dr, const Eigen::Vector3d &dt); + + inline Eigen::Vector3d operator* (const Eigen::Vector3d& v) const { + return R*v + t; + } + + inline SE3mat& operator*= (const SE3mat& T2){ + t+=R*T2.t; + R*=T2.R; + return *this; + } + + inline SE3mat inverse() const{ + Eigen::Matrix3d Rt = R.transpose(); + return SE3mat(Rt,-Rt*t); + } + +protected: + Eigen::Vector3d t; + Eigen::Matrix3d R; + +public: + static Eigen::Matrix3d ExpSO3(const Eigen::Vector3d r); + static Eigen::Vector3d LogSO3(const Eigen::Matrix3d R); +}; + +}//namespace g2o + +#endif // SE3mat_H diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/types/se3quat.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/types/se3quat.h new file mode 100644 index 0000000..ac5ec57 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/types/se3quat.h @@ -0,0 +1,306 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 H. Strasdat +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_SE3QUAT_H_ +#define G2O_SE3QUAT_H_ + +#include "se3_ops.h" + +#include +#include + +namespace g2o { + using namespace Eigen; + + typedef Matrix Vector6d; + typedef Matrix Vector7d; + + class SE3Quat { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW; + + + protected: + + Quaterniond _r; + Vector3d _t; + + + public: + SE3Quat(){ + _r.setIdentity(); + _t.setZero(); + } + + SE3Quat(const Matrix3d& R, const Vector3d& t):_r(Quaterniond(R)),_t(t){ + normalizeRotation(); + } + + SE3Quat(const Quaterniond& q, const Vector3d& t):_r(q),_t(t){ + normalizeRotation(); + } + + /** + * templaized constructor which allows v to be an arbitrary Eigen Vector type, e.g., Vector6d or Map + */ + template + explicit SE3Quat(const MatrixBase& v) + { + assert((v.size() == 6 || v.size() == 7) && "Vector dimension does not match"); + if (v.size() == 6) { + for (int i=0; i<3; i++){ + _t[i]=v[i]; + _r.coeffs()(i)=v[i+3]; + } + _r.w() = 0.; // recover the positive w + if (_r.norm()>1.){ + _r.normalize(); + } else { + double w2=1.-_r.squaredNorm(); + _r.w()= (w2<0.) ? 0. : sqrt(w2); + } + } + else if (v.size() == 7) { + int idx = 0; + for (int i=0; i<3; ++i, ++idx) + _t(i) = v(idx); + for (int i=0; i<4; ++i, ++idx) + _r.coeffs()(i) = v(idx); + normalizeRotation(); + } + } + + inline const Vector3d& translation() const {return _t;} + + inline void setTranslation(const Vector3d& t_) {_t = t_;} + + inline const Quaterniond& rotation() const {return _r;} + + void setRotation(const Quaterniond& r_) {_r=r_;} + + inline SE3Quat operator* (const SE3Quat& tr2) const{ + SE3Quat result(*this); + result._t += _r*tr2._t; + result._r*=tr2._r; + result.normalizeRotation(); + return result; + } + + inline SE3Quat& operator*= (const SE3Quat& tr2){ + _t+=_r*tr2._t; + _r*=tr2._r; + normalizeRotation(); + return *this; + } + + inline Vector3d operator* (const Vector3d& v) const { + return _t+_r*v; + } + + inline SE3Quat inverse() const{ + SE3Quat ret; + ret._r=_r.conjugate(); + ret._t=ret._r*(_t*-1.); + return ret; + } + + inline double operator [](int i) const { + assert(i<7); + if (i<3) + return _t[i]; + return _r.coeffs()[i-3]; + } + + + inline Vector7d toVector() const{ + Vector7d v; + v[0]=_t(0); + v[1]=_t(1); + v[2]=_t(2); + v[3]=_r.x(); + v[4]=_r.y(); + v[5]=_r.z(); + v[6]=_r.w(); + return v; + } + + inline void fromVector(const Vector7d& v){ + _r=Quaterniond(v[6], v[3], v[4], v[5]); + _t=Vector3d(v[0], v[1], v[2]); + } + + inline Vector6d toMinimalVector() const{ + Vector6d v; + v[0]=_t(0); + v[1]=_t(1); + v[2]=_t(2); + v[3]=_r.x(); + v[4]=_r.y(); + v[5]=_r.z(); + return v; + } + + inline void fromMinimalVector(const Vector6d& v){ + double w = 1.-v[3]*v[3]-v[4]*v[4]-v[5]*v[5]; + if (w>0){ + _r=Quaterniond(sqrt(w), v[3], v[4], v[5]); + } else { + _r=Quaterniond(0, -v[3], -v[4], -v[5]); + } + _t=Vector3d(v[0], v[1], v[2]); + } + + + + Vector6d log() const { + Vector6d res; + Matrix3d _R = _r.toRotationMatrix(); + double d = 0.5*(_R(0,0)+_R(1,1)+_R(2,2)-1); + Vector3d omega; + Vector3d upsilon; + + + Vector3d dR = deltaR(_R); + Matrix3d V_inv; + + if (d>0.99999) + { + + omega=0.5*dR; + Matrix3d Omega = skew(omega); + V_inv = Matrix3d::Identity()- 0.5*Omega + (1./12.)*(Omega*Omega); + } + else + { + double theta = acos(d); + omega = theta/(2*sqrt(1-d*d))*dR; + Matrix3d Omega = skew(omega); + V_inv = ( Matrix3d::Identity() - 0.5*Omega + + ( 1-theta/(2*tan(theta/2)))/(theta*theta)*(Omega*Omega) ); + } + + upsilon = V_inv*_t; + for (int i=0; i<3;i++){ + res[i]=omega[i]; + } + for (int i=0; i<3;i++){ + res[i+3]=upsilon[i]; + } + + return res; + + } + + Vector3d map(const Vector3d & xyz) const + { + return _r*xyz + _t; + } + + + static SE3Quat exp(const Vector6d & update) + { + Vector3d omega; + for (int i=0; i<3; i++) + omega[i]=update[i]; + Vector3d upsilon; + for (int i=0; i<3; i++) + upsilon[i]=update[i+3]; + + double theta = omega.norm(); + Matrix3d Omega = skew(omega); + + Matrix3d R; + Matrix3d V; + if (theta<0.00001) + { + //TODO: CHECK WHETHER THIS IS CORRECT!!! + R = (Matrix3d::Identity() + Omega + Omega*Omega); + + V = R; + } + else + { + Matrix3d Omega2 = Omega*Omega; + + R = (Matrix3d::Identity() + + sin(theta)/theta *Omega + + (1-cos(theta))/(theta*theta)*Omega2); + + V = (Matrix3d::Identity() + + (1-cos(theta))/(theta*theta)*Omega + + (theta-sin(theta))/(pow(theta,3))*Omega2); + } + return SE3Quat(Quaterniond(R),V*upsilon); + } + + Matrix adj() const + { + Matrix3d R = _r.toRotationMatrix(); + Matrix res; + res.block(0,0,3,3) = R; + res.block(3,3,3,3) = R; + res.block(3,0,3,3) = skew(_t)*R; + res.block(0,3,3,3) = Matrix3d::Zero(3,3); + return res; + } + + Matrix to_homogeneous_matrix() const + { + Matrix homogeneous_matrix; + homogeneous_matrix.setIdentity(); + homogeneous_matrix.block(0,0,3,3) = _r.toRotationMatrix(); + homogeneous_matrix.col(3).head(3) = translation(); + + return homogeneous_matrix; + } + + void normalizeRotation(){ + if (_r.w()<0){ + _r.coeffs() *= -1; + } + _r.normalize(); + } + + /** + * cast SE3Quat into an Eigen::Isometry3d + */ + operator Eigen::Isometry3d() const + { + Eigen::Isometry3d result = (Eigen::Isometry3d) rotation(); + result.translation() = translation(); + return result; + } + }; + + inline std::ostream& operator <<(std::ostream& out_str, const SE3Quat& se3) + { + out_str << se3.to_homogeneous_matrix() << std::endl; + return out_str; + } + +} // end namespace + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/types/sim3.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/types/sim3.h new file mode 100644 index 0000000..cfd6d5e --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/types/sim3.h @@ -0,0 +1,307 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 H. Strasdat +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_SIM_3 +#define G2O_SIM_3 + +#include "se3_ops.h" +#include + +namespace g2o +{ + using namespace Eigen; + + typedef Matrix Vector7d; + typedef Matrix Matrix7d; + + + struct Sim3 + { + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + protected: + Quaterniond r; + Vector3d t; + double s; + + +public: + Sim3() + { + r.setIdentity(); + t.fill(0.); + s=1.; + } + + Sim3(const Quaterniond & r, const Vector3d & t, double s) + : r(r),t(t),s(s) + { + } + + Sim3(const Matrix3d & R, const Vector3d & t, double s) + : r(Quaterniond(R)),t(t),s(s) + { + } + + + Sim3(const Vector7d & update) + { + + Vector3d omega; + for (int i=0; i<3; i++) + omega[i]=update[i]; + + Vector3d upsilon; + for (int i=0; i<3; i++) + upsilon[i]=update[i+3]; + + double sigma = update[6]; + double theta = omega.norm(); + Matrix3d Omega = skew(omega); + s = std::exp(sigma); + Matrix3d Omega2 = Omega*Omega; + Matrix3d I; + I.setIdentity(); + Matrix3d R; + + double eps = 0.00001; + double A,B,C; + if (fabs(sigma)1-eps) + { + omega=0.5*deltaR(R); + Omega = skew(omega); + A = 1./2.; + B = 1./6.; + } + else + { + double theta = acos(d); + double theta2 = theta*theta; + omega = theta/(2*sqrt(1-d*d))*deltaR(R); + Omega = skew(omega); + A = (1-cos(theta))/(theta2); + B = (theta-sin(theta))/(theta2*theta); + } + } + else + { + C=(s-1)/sigma; + if (d>1-eps) + { + + double sigma2 = sigma*sigma; + omega=0.5*deltaR(R); + Omega = skew(omega); + A = ((sigma-1)*s+1)/(sigma2); + B = ((0.5*sigma2-sigma+1)*s)/(sigma2*sigma); + } + else + { + double theta = acos(d); + omega = theta/(2*sqrt(1-d*d))*deltaR(R); + Omega = skew(omega); + double theta2 = theta*theta; + double a=s*sin(theta); + double b=s*cos(theta); + double c=theta2 + sigma*sigma; + A = (a*sigma+ (1-b)*theta)/(theta*c); + B = (C-((b-1)*sigma+a*theta)/(c))*1./(theta2); + } + } + + Matrix3d W = A*Omega + B*Omega*Omega + C*I; + + upsilon = W.lu().solve(t); + + + for (int i=0; i<3; i++) + res[i] = omega[i]; + + for (int i=0; i<3; i++) + res[i+3] = upsilon[i]; + + res[6] = sigma; + + return res; + + } + + + Sim3 inverse() const + { + return Sim3(r.conjugate(), r.conjugate()*((-1./s)*t), 1./s); + } + + + double operator[](int i) const + { + assert(i<8); + if (i<4){ + + return r.coeffs()[i]; + } + if (i<7){ + return t[i-4]; + } + return s; + } + + double& operator[](int i) + { + assert(i<8); + if (i<4){ + + return r.coeffs()[i]; + } + if (i<7) + { + return t[i-4]; + } + return s; + } + + Sim3 operator *(const Sim3& other) const { + Sim3 ret; + ret.r = r*other.r; + ret.t=s*(r*other.t)+t; + ret.s=s*other.s; + return ret; + } + + Sim3& operator *=(const Sim3& other){ + Sim3 ret=(*this)*other; + *this=ret; + return *this; + } + + inline const Vector3d& translation() const {return t;} + + inline Vector3d& translation() {return t;} + + inline const Quaterniond& rotation() const {return r;} + + inline Quaterniond& rotation() {return r;} + + inline const double& scale() const {return s;} + + inline double& scale() {return s;} + + }; + + inline std::ostream& operator <<(std::ostream& out_str, + const Sim3& sim3) + { + out_str << sim3.rotation().coeffs() << std::endl; + out_str << sim3.translation() << std::endl; + out_str << sim3.scale() << std::endl; + + return out_str; + } + +} // end namespace + + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/types/types_sba.cpp b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/types/types_sba.cpp new file mode 100644 index 0000000..d91b498 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/types/types_sba.cpp @@ -0,0 +1,56 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 Kurt Konolige +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#include "types_sba.h" +#include + +namespace g2o { + + using namespace std; + + + VertexSBAPointXYZ::VertexSBAPointXYZ() : BaseVertex<3, Vector3d>() + { + } + + bool VertexSBAPointXYZ::read(std::istream& is) + { + Vector3d lv; + for (int i=0; i<3; i++) + is >> _estimate[i]; + return true; + } + + bool VertexSBAPointXYZ::write(std::ostream& os) const + { + Vector3d lv=estimate(); + for (int i=0; i<3; i++){ + os << lv[i] << " "; + } + return os.good(); + } + +} // end namespace diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/types/types_sba.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/types/types_sba.h new file mode 100644 index 0000000..bb419df --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/types/types_sba.h @@ -0,0 +1,61 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 Kurt Konolige +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#ifndef G2O_SBA_TYPES +#define G2O_SBA_TYPES + +#include "../core/base_vertex.h" + +#include +#include + +namespace g2o { + +/** + * \brief Point vertex, XYZ + */ + class VertexSBAPointXYZ : public BaseVertex<3, Vector3d> +{ + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + VertexSBAPointXYZ(); + virtual bool read(std::istream& is); + virtual bool write(std::ostream& os) const; + + virtual void setToOriginImpl() { + _estimate.fill(0.); + } + + virtual void oplusImpl(const double* update) + { + Eigen::Map v(update); + _estimate += v; + } +}; + +} // end namespace + +#endif // SBA_TYPES diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/types/types_seven_dof_expmap.cpp b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/types/types_seven_dof_expmap.cpp new file mode 100644 index 0000000..abf1b1d --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/types/types_seven_dof_expmap.cpp @@ -0,0 +1,239 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 H. Strasdat +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#include "types_seven_dof_expmap.h" + +namespace g2o { + + VertexSim3Expmap::VertexSim3Expmap() : BaseVertex<7, Sim3>() + { + _marginalized=false; + _fix_scale = false; + } + + + EdgeSim3::EdgeSim3() : + BaseBinaryEdge<7, Sim3, VertexSim3Expmap, VertexSim3Expmap>() + { + } + + + bool VertexSim3Expmap::read(std::istream& is) + { + Vector7d cam2world; + for (int i=0; i<6; i++){ + is >> cam2world[i]; + } + is >> cam2world[6]; +// if (! is) { +// // if the scale is not specified we set it to 1; +// std::cerr << "!s"; +// cam2world[6]=0.; +// } + + for (int i=0; i<2; i++) + { + is >> _focal_length1[i]; + } + for (int i=0; i<2; i++) + { + is >> _principle_point1[i]; + } + + setEstimate(Sim3(cam2world).inverse()); + return true; + } + + bool VertexSim3Expmap::write(std::ostream& os) const + { + Sim3 cam2world(estimate().inverse()); + Vector7d lv=cam2world.log(); + for (int i=0; i<7; i++){ + os << lv[i] << " "; + } + for (int i=0; i<2; i++) + { + os << _focal_length1[i] << " "; + } + for (int i=0; i<2; i++) + { + os << _principle_point1[i] << " "; + } + return os.good(); + } + + bool EdgeSim3::read(std::istream& is) + { + Vector7d v7; + for (int i=0; i<7; i++){ + is >> v7[i]; + } + + Sim3 cam2world(v7); + setMeasurement(cam2world.inverse()); + + for (int i=0; i<7; i++) + for (int j=i; j<7; j++) + { + is >> information()(i,j); + if (i!=j) + information()(j,i)=information()(i,j); + } + return true; + } + + bool EdgeSim3::write(std::ostream& os) const + { + Sim3 cam2world(measurement().inverse()); + Vector7d v7 = cam2world.log(); + for (int i=0; i<7; i++) + { + os << v7[i] << " "; + } + for (int i=0; i<7; i++) + for (int j=i; j<7; j++){ + os << " " << information()(i,j); + } + return os.good(); + } + + /**Sim3ProjectXYZ*/ + + EdgeSim3ProjectXYZ::EdgeSim3ProjectXYZ() : + BaseBinaryEdge<2, Vector2d, VertexSBAPointXYZ, VertexSim3Expmap>() + { + } + + bool EdgeSim3ProjectXYZ::read(std::istream& is) + { + for (int i=0; i<2; i++) + { + is >> _measurement[i]; + } + + for (int i=0; i<2; i++) + for (int j=i; j<2; j++) { + is >> information()(i,j); + if (i!=j) + information()(j,i)=information()(i,j); + } + return true; + } + + bool EdgeSim3ProjectXYZ::write(std::ostream& os) const + { + for (int i=0; i<2; i++){ + os << _measurement[i] << " "; + } + + for (int i=0; i<2; i++) + for (int j=i; j<2; j++){ + os << " " << information()(i,j); + } + return os.good(); + } + +/**InverseSim3ProjectXYZ*/ + + EdgeInverseSim3ProjectXYZ::EdgeInverseSim3ProjectXYZ() : + BaseBinaryEdge<2, Vector2d, VertexSBAPointXYZ, VertexSim3Expmap>() + { + } + + bool EdgeInverseSim3ProjectXYZ::read(std::istream& is) + { + for (int i=0; i<2; i++) + { + is >> _measurement[i]; + } + + for (int i=0; i<2; i++) + for (int j=i; j<2; j++) { + is >> information()(i,j); + if (i!=j) + information()(j,i)=information()(i,j); + } + return true; + } + + bool EdgeInverseSim3ProjectXYZ::write(std::ostream& os) const + { + for (int i=0; i<2; i++){ + os << _measurement[i] << " "; + } + + for (int i=0; i<2; i++) + for (int j=i; j<2; j++){ + os << " " << information()(i,j); + } + return os.good(); + } + + +// void EdgeSim3ProjectXYZ::linearizeOplus() +// { +// VertexSim3Expmap * vj = static_cast(_vertices[1]); +// Sim3 T = vj->estimate(); + +// VertexPointXYZ* vi = static_cast(_vertices[0]); +// Vector3d xyz = vi->estimate(); +// Vector3d xyz_trans = T.map(xyz); + +// double x = xyz_trans[0]; +// double y = xyz_trans[1]; +// double z = xyz_trans[2]; +// double z_2 = z*z; + +// Matrix tmp; +// tmp(0,0) = _focal_length(0); +// tmp(0,1) = 0; +// tmp(0,2) = -x/z*_focal_length(0); + +// tmp(1,0) = 0; +// tmp(1,1) = _focal_length(1); +// tmp(1,2) = -y/z*_focal_length(1); + +// _jacobianOplusXi = -1./z * tmp * T.rotation().toRotationMatrix(); + +// _jacobianOplusXj(0,0) = x*y/z_2 * _focal_length(0); +// _jacobianOplusXj(0,1) = -(1+(x*x/z_2)) *_focal_length(0); +// _jacobianOplusXj(0,2) = y/z *_focal_length(0); +// _jacobianOplusXj(0,3) = -1./z *_focal_length(0); +// _jacobianOplusXj(0,4) = 0; +// _jacobianOplusXj(0,5) = x/z_2 *_focal_length(0); +// _jacobianOplusXj(0,6) = 0; // scale is ignored + + +// _jacobianOplusXj(1,0) = (1+y*y/z_2) *_focal_length(1); +// _jacobianOplusXj(1,1) = -x*y/z_2 *_focal_length(1); +// _jacobianOplusXj(1,2) = -x/z *_focal_length(1); +// _jacobianOplusXj(1,3) = 0; +// _jacobianOplusXj(1,4) = -1./z *_focal_length(1); +// _jacobianOplusXj(1,5) = y/z_2 *_focal_length(1); +// _jacobianOplusXj(1,6) = 0; // scale is ignored +// } + +} // end namespace diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/types/types_seven_dof_expmap.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/types/types_seven_dof_expmap.h new file mode 100644 index 0000000..b63a585 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/types/types_seven_dof_expmap.h @@ -0,0 +1,176 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 H. Strasdat +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +// Modified by Raúl Mur Artal (2014) +// - Added EdgeInverseSim3ProjectXYZ +// - Modified VertexSim3Expmap to represent relative transformation between two cameras. Includes calibration of both cameras. + +#ifndef G2O_SEVEN_DOF_EXPMAP_TYPES +#define G2O_SEVEN_DOF_EXPMAP_TYPES + +#include "../core/base_vertex.h" +#include "../core/base_binary_edge.h" +#include "types_six_dof_expmap.h" +#include "sim3.h" + +namespace g2o { + + using namespace Eigen; + + /** + * \brief Sim3 Vertex, (x,y,z,qw,qx,qy,qz) + * the parameterization for the increments constructed is a 7d vector + * (x,y,z,qx,qy,qz) (note that we leave out the w part of the quaternion. + */ + class VertexSim3Expmap : public BaseVertex<7, Sim3> + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + VertexSim3Expmap(); + virtual bool read(std::istream& is); + virtual bool write(std::ostream& os) const; + + virtual void setToOriginImpl() { + _estimate = Sim3(); + } + + virtual void oplusImpl(const double* update_) + { + Eigen::Map update(const_cast(update_)); + + if (_fix_scale) + update[6] = 0; + + Sim3 s(update); + setEstimate(s*estimate()); + } + + Vector2d _principle_point1, _principle_point2; + Vector2d _focal_length1, _focal_length2; + + Vector2d cam_map1(const Vector2d & v) const + { + Vector2d res; + res[0] = v[0]*_focal_length1[0] + _principle_point1[0]; + res[1] = v[1]*_focal_length1[1] + _principle_point1[1]; + return res; + } + + Vector2d cam_map2(const Vector2d & v) const + { + Vector2d res; + res[0] = v[0]*_focal_length2[0] + _principle_point2[0]; + res[1] = v[1]*_focal_length2[1] + _principle_point2[1]; + return res; + } + + bool _fix_scale; + + + protected: + }; + + /** + * \brief 7D edge between two Vertex7 + */ + class EdgeSim3 : public BaseBinaryEdge<7, Sim3, VertexSim3Expmap, VertexSim3Expmap> + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + EdgeSim3(); + virtual bool read(std::istream& is); + virtual bool write(std::ostream& os) const; + void computeError() + { + const VertexSim3Expmap* v1 = static_cast(_vertices[0]); + const VertexSim3Expmap* v2 = static_cast(_vertices[1]); + + Sim3 C(_measurement); + Sim3 error_=C*v1->estimate()*v2->estimate().inverse(); + _error = error_.log(); + } + + virtual double initialEstimatePossible(const OptimizableGraph::VertexSet& , OptimizableGraph::Vertex* ) { return 1.;} + virtual void initialEstimate(const OptimizableGraph::VertexSet& from, OptimizableGraph::Vertex* /*to*/) + { + VertexSim3Expmap* v1 = static_cast(_vertices[0]); + VertexSim3Expmap* v2 = static_cast(_vertices[1]); + if (from.count(v1) > 0) + v2->setEstimate(measurement()*v1->estimate()); + else + v1->setEstimate(measurement().inverse()*v2->estimate()); + } + }; + + +/**/ +class EdgeSim3ProjectXYZ : public BaseBinaryEdge<2, Vector2d, VertexSBAPointXYZ, VertexSim3Expmap> +{ + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + EdgeSim3ProjectXYZ(); + virtual bool read(std::istream& is); + virtual bool write(std::ostream& os) const; + + void computeError() + { + const VertexSim3Expmap* v1 = static_cast(_vertices[1]); + const VertexSBAPointXYZ* v2 = static_cast(_vertices[0]); + + Vector2d obs(_measurement); + _error = obs-v1->cam_map1(project(v1->estimate().map(v2->estimate()))); + } + + // virtual void linearizeOplus(); + +}; + +/**/ +class EdgeInverseSim3ProjectXYZ : public BaseBinaryEdge<2, Vector2d, VertexSBAPointXYZ, VertexSim3Expmap> +{ + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + EdgeInverseSim3ProjectXYZ(); + virtual bool read(std::istream& is); + virtual bool write(std::ostream& os) const; + + void computeError() + { + const VertexSim3Expmap* v1 = static_cast(_vertices[1]); + const VertexSBAPointXYZ* v2 = static_cast(_vertices[0]); + + Vector2d obs(_measurement); + _error = obs-v1->cam_map2(project(v1->estimate().inverse().map(v2->estimate()))); + } + + // virtual void linearizeOplus(); + +}; + +} // end namespace + +#endif + diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/types/types_six_dof_expmap.cpp b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/types/types_six_dof_expmap.cpp new file mode 100644 index 0000000..b74a1d1 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/types/types_six_dof_expmap.cpp @@ -0,0 +1,407 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 H. Strasdat +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#include "types_six_dof_expmap.h" + +#include "../core/factory.h" +#include "../stuff/macros.h" + +namespace g2o { + +using namespace std; + + +Vector2d project2d(const Vector3d& v) { + Vector2d res; + res(0) = v(0)/v(2); + res(1) = v(1)/v(2); + return res; +} + +Vector3d unproject2d(const Vector2d& v) { + Vector3d res; + res(0) = v(0); + res(1) = v(1); + res(2) = 1; + return res; +} + +VertexSE3Expmap::VertexSE3Expmap() : BaseVertex<6, SE3Quat>() { +} + +bool VertexSE3Expmap::read(std::istream& is) { + Vector7d est; + for (int i=0; i<7; i++) + is >> est[i]; + SE3Quat cam2world; + cam2world.fromVector(est); + setEstimate(cam2world.inverse()); + return true; +} + +bool VertexSE3Expmap::write(std::ostream& os) const { + SE3Quat cam2world(estimate().inverse()); + for (int i=0; i<7; i++) + os << cam2world[i] << " "; + return os.good(); +} + + EdgeSE3::EdgeSE3() : + BaseBinaryEdge<6, SE3Quat, VertexSE3Expmap, VertexSE3Expmap>() + { + } + + bool EdgeSE3::read(std::istream& is) + { + Vector6d v6; + for (int i=0; i<6; i++){ + is >> v6[i]; + } + + SE3Quat cam2world(v6); + setMeasurement(cam2world.inverse()); + + for (int i=0; i<6; i++) + for (int j=i; j<6; j++) + { + is >> information()(i,j); + if (i!=j) + information()(j,i)=information()(i,j); + } + return true; + } + + bool EdgeSE3::write(std::ostream& os) const + { + SE3Quat cam2world(measurement().inverse()); + Vector6d v6 = cam2world.log(); + for (int i=0; i<6; i++) + { + os << v6[i] << " "; + } + for (int i=0; i<6; i++) + for (int j=i; j<6; j++){ + os << " " << information()(i,j); + } + return os.good(); + } + + +EdgeSE3ProjectXYZ::EdgeSE3ProjectXYZ() : BaseBinaryEdge<2, Vector2d, VertexSBAPointXYZ, VertexSE3Expmap>() { +} + +bool EdgeSE3ProjectXYZ::read(std::istream& is){ + for (int i=0; i<2; i++){ + is >> _measurement[i]; + } + for (int i=0; i<2; i++) + for (int j=i; j<2; j++) { + is >> information()(i,j); + if (i!=j) + information()(j,i)=information()(i,j); + } + return true; +} + +bool EdgeSE3ProjectXYZ::write(std::ostream& os) const { + + for (int i=0; i<2; i++){ + os << measurement()[i] << " "; + } + + for (int i=0; i<2; i++) + for (int j=i; j<2; j++){ + os << " " << information()(i,j); + } + return os.good(); +} + + +void EdgeSE3ProjectXYZ::linearizeOplus() { + VertexSE3Expmap * vj = static_cast(_vertices[1]); + SE3Quat T(vj->estimate()); + VertexSBAPointXYZ* vi = static_cast(_vertices[0]); + Vector3d xyz = vi->estimate(); + Vector3d xyz_trans = T.map(xyz); + + double x = xyz_trans[0]; + double y = xyz_trans[1]; + double z = xyz_trans[2]; + double z_2 = z*z; + + Matrix tmp; + tmp(0,0) = fx; + tmp(0,1) = 0; + tmp(0,2) = -x/z*fx; + + tmp(1,0) = 0; + tmp(1,1) = fy; + tmp(1,2) = -y/z*fy; + + _jacobianOplusXi = -1./z * tmp * T.rotation().toRotationMatrix(); + + _jacobianOplusXj(0,0) = x*y/z_2 *fx; + _jacobianOplusXj(0,1) = -(1+(x*x/z_2)) *fx; + _jacobianOplusXj(0,2) = y/z *fx; + _jacobianOplusXj(0,3) = -1./z *fx; + _jacobianOplusXj(0,4) = 0; + _jacobianOplusXj(0,5) = x/z_2 *fx; + + _jacobianOplusXj(1,0) = (1+y*y/z_2) *fy; + _jacobianOplusXj(1,1) = -x*y/z_2 *fy; + _jacobianOplusXj(1,2) = -x/z *fy; + _jacobianOplusXj(1,3) = 0; + _jacobianOplusXj(1,4) = -1./z *fy; + _jacobianOplusXj(1,5) = y/z_2 *fy; +} + +Vector2d EdgeSE3ProjectXYZ::cam_project(const Vector3d & trans_xyz) const{ + Vector2d proj = project2d(trans_xyz); + Vector2d res; + res[0] = proj[0]*fx + cx; + res[1] = proj[1]*fy + cy; + return res; +} + + +Vector3d EdgeStereoSE3ProjectXYZ::cam_project(const Vector3d & trans_xyz, const float &bf) const{ + const float invz = 1.0f/trans_xyz[2]; + Vector3d res; + res[0] = trans_xyz[0]*invz*fx + cx; + res[1] = trans_xyz[1]*invz*fy + cy; + res[2] = res[0] - bf*invz; + return res; +} + +EdgeStereoSE3ProjectXYZ::EdgeStereoSE3ProjectXYZ() : BaseBinaryEdge<3, Vector3d, VertexSBAPointXYZ, VertexSE3Expmap>() { +} + +bool EdgeStereoSE3ProjectXYZ::read(std::istream& is){ + for (int i=0; i<=3; i++){ + is >> _measurement[i]; + } + for (int i=0; i<=2; i++) + for (int j=i; j<=2; j++) { + is >> information()(i,j); + if (i!=j) + information()(j,i)=information()(i,j); + } + return true; +} + +bool EdgeStereoSE3ProjectXYZ::write(std::ostream& os) const { + + for (int i=0; i<=3; i++){ + os << measurement()[i] << " "; + } + + for (int i=0; i<=2; i++) + for (int j=i; j<=2; j++){ + os << " " << information()(i,j); + } + return os.good(); +} + +void EdgeStereoSE3ProjectXYZ::linearizeOplus() { + VertexSE3Expmap * vj = static_cast(_vertices[1]); + SE3Quat T(vj->estimate()); + VertexSBAPointXYZ* vi = static_cast(_vertices[0]); + Vector3d xyz = vi->estimate(); + Vector3d xyz_trans = T.map(xyz); + + const Matrix3d R = T.rotation().toRotationMatrix(); + + double x = xyz_trans[0]; + double y = xyz_trans[1]; + double z = xyz_trans[2]; + double z_2 = z*z; + + _jacobianOplusXi(0,0) = -fx*R(0,0)/z+fx*x*R(2,0)/z_2; + _jacobianOplusXi(0,1) = -fx*R(0,1)/z+fx*x*R(2,1)/z_2; + _jacobianOplusXi(0,2) = -fx*R(0,2)/z+fx*x*R(2,2)/z_2; + + _jacobianOplusXi(1,0) = -fy*R(1,0)/z+fy*y*R(2,0)/z_2; + _jacobianOplusXi(1,1) = -fy*R(1,1)/z+fy*y*R(2,1)/z_2; + _jacobianOplusXi(1,2) = -fy*R(1,2)/z+fy*y*R(2,2)/z_2; + + _jacobianOplusXi(2,0) = _jacobianOplusXi(0,0)-bf*R(2,0)/z_2; + _jacobianOplusXi(2,1) = _jacobianOplusXi(0,1)-bf*R(2,1)/z_2; + _jacobianOplusXi(2,2) = _jacobianOplusXi(0,2)-bf*R(2,2)/z_2; + + _jacobianOplusXj(0,0) = x*y/z_2 *fx; + _jacobianOplusXj(0,1) = -(1+(x*x/z_2)) *fx; + _jacobianOplusXj(0,2) = y/z *fx; + _jacobianOplusXj(0,3) = -1./z *fx; + _jacobianOplusXj(0,4) = 0; + _jacobianOplusXj(0,5) = x/z_2 *fx; + + _jacobianOplusXj(1,0) = (1+y*y/z_2) *fy; + _jacobianOplusXj(1,1) = -x*y/z_2 *fy; + _jacobianOplusXj(1,2) = -x/z *fy; + _jacobianOplusXj(1,3) = 0; + _jacobianOplusXj(1,4) = -1./z *fy; + _jacobianOplusXj(1,5) = y/z_2 *fy; + + _jacobianOplusXj(2,0) = _jacobianOplusXj(0,0)-bf*y/z_2; + _jacobianOplusXj(2,1) = _jacobianOplusXj(0,1)+bf*x/z_2; + _jacobianOplusXj(2,2) = _jacobianOplusXj(0,2); + _jacobianOplusXj(2,3) = _jacobianOplusXj(0,3); + _jacobianOplusXj(2,4) = 0; + _jacobianOplusXj(2,5) = _jacobianOplusXj(0,5)-bf/z_2; +} + + +//Only Pose + +bool EdgeSE3ProjectXYZOnlyPose::read(std::istream& is){ + for (int i=0; i<2; i++){ + is >> _measurement[i]; + } + for (int i=0; i<2; i++) + for (int j=i; j<2; j++) { + is >> information()(i,j); + if (i!=j) + information()(j,i)=information()(i,j); + } + return true; +} + +bool EdgeSE3ProjectXYZOnlyPose::write(std::ostream& os) const { + + for (int i=0; i<2; i++){ + os << measurement()[i] << " "; + } + + for (int i=0; i<2; i++) + for (int j=i; j<2; j++){ + os << " " << information()(i,j); + } + return os.good(); +} + + +void EdgeSE3ProjectXYZOnlyPose::linearizeOplus() { + VertexSE3Expmap * vi = static_cast(_vertices[0]); + Vector3d xyz_trans = vi->estimate().map(Xw); + + double x = xyz_trans[0]; + double y = xyz_trans[1]; + double invz = 1.0/xyz_trans[2]; + double invz_2 = invz*invz; + + _jacobianOplusXi(0,0) = x*y*invz_2 *fx; + _jacobianOplusXi(0,1) = -(1+(x*x*invz_2)) *fx; + _jacobianOplusXi(0,2) = y*invz *fx; + _jacobianOplusXi(0,3) = -invz *fx; + _jacobianOplusXi(0,4) = 0; + _jacobianOplusXi(0,5) = x*invz_2 *fx; + + _jacobianOplusXi(1,0) = (1+y*y*invz_2) *fy; + _jacobianOplusXi(1,1) = -x*y*invz_2 *fy; + _jacobianOplusXi(1,2) = -x*invz *fy; + _jacobianOplusXi(1,3) = 0; + _jacobianOplusXi(1,4) = -invz *fy; + _jacobianOplusXi(1,5) = y*invz_2 *fy; +} + +Vector2d EdgeSE3ProjectXYZOnlyPose::cam_project(const Vector3d & trans_xyz) const{ + Vector2d proj = project2d(trans_xyz); + Vector2d res; + res[0] = proj[0]*fx + cx; + res[1] = proj[1]*fy + cy; + return res; +} + + +Vector3d EdgeStereoSE3ProjectXYZOnlyPose::cam_project(const Vector3d & trans_xyz) const{ + const float invz = 1.0f/trans_xyz[2]; + Vector3d res; + res[0] = trans_xyz[0]*invz*fx + cx; + res[1] = trans_xyz[1]*invz*fy + cy; + res[2] = res[0] - bf*invz; + return res; +} + + +bool EdgeStereoSE3ProjectXYZOnlyPose::read(std::istream& is){ + for (int i=0; i<=3; i++){ + is >> _measurement[i]; + } + for (int i=0; i<=2; i++) + for (int j=i; j<=2; j++) { + is >> information()(i,j); + if (i!=j) + information()(j,i)=information()(i,j); + } + return true; +} + +bool EdgeStereoSE3ProjectXYZOnlyPose::write(std::ostream& os) const { + + for (int i=0; i<=3; i++){ + os << measurement()[i] << " "; + } + + for (int i=0; i<=2; i++) + for (int j=i; j<=2; j++){ + os << " " << information()(i,j); + } + return os.good(); +} + +void EdgeStereoSE3ProjectXYZOnlyPose::linearizeOplus() { + VertexSE3Expmap * vi = static_cast(_vertices[0]); + Vector3d xyz_trans = vi->estimate().map(Xw); + + double x = xyz_trans[0]; + double y = xyz_trans[1]; + double invz = 1.0/xyz_trans[2]; + double invz_2 = invz*invz; + + _jacobianOplusXi(0,0) = x*y*invz_2 *fx; + _jacobianOplusXi(0,1) = -(1+(x*x*invz_2)) *fx; + _jacobianOplusXi(0,2) = y*invz *fx; + _jacobianOplusXi(0,3) = -invz *fx; + _jacobianOplusXi(0,4) = 0; + _jacobianOplusXi(0,5) = x*invz_2 *fx; + + _jacobianOplusXi(1,0) = (1+y*y*invz_2) *fy; + _jacobianOplusXi(1,1) = -x*y*invz_2 *fy; + _jacobianOplusXi(1,2) = -x*invz *fy; + _jacobianOplusXi(1,3) = 0; + _jacobianOplusXi(1,4) = -invz *fy; + _jacobianOplusXi(1,5) = y*invz_2 *fy; + + _jacobianOplusXi(2,0) = _jacobianOplusXi(0,0)-bf*y*invz_2; + _jacobianOplusXi(2,1) = _jacobianOplusXi(0,1)+bf*x*invz_2; + _jacobianOplusXi(2,2) = _jacobianOplusXi(0,2); + _jacobianOplusXi(2,3) = _jacobianOplusXi(0,3); + _jacobianOplusXi(2,4) = 0; + _jacobianOplusXi(2,5) = _jacobianOplusXi(0,5)-bf*invz_2; +} + + +} // end namespace diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/types/types_six_dof_expmap.h b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/types/types_six_dof_expmap.h new file mode 100644 index 0000000..5d54e06 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/g2o/types/types_six_dof_expmap.h @@ -0,0 +1,242 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 H. Strasdat +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +// Modified by Raúl Mur Artal (2014) +// Added EdgeSE3ProjectXYZ (project using focal_length in x,y directions) +// Modified by Raúl Mur Artal (2016) +// Added EdgeStereoSE3ProjectXYZ (project using focal_length in x,y directions) +// Added EdgeSE3ProjectXYZOnlyPose (unary edge to optimize only the camera pose) +// Added EdgeStereoSE3ProjectXYZOnlyPose (unary edge to optimize only the camera pose) + +#ifndef G2O_SIX_DOF_TYPES_EXPMAP +#define G2O_SIX_DOF_TYPES_EXPMAP + +#include "../core/base_vertex.h" +#include "../core/base_binary_edge.h" +#include "../core/base_unary_edge.h" +#include "se3_ops.h" +#include "se3quat.h" +#include "types_sba.h" +#include + +namespace g2o { +namespace types_six_dof_expmap { +void init(); +} + +using namespace Eigen; + +typedef Matrix Matrix6d; + + +/** + * \brief SE3 Vertex parameterized internally with a transformation matrix + and externally with its exponential map + */ +class VertexSE3Expmap : public BaseVertex<6, SE3Quat>{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + VertexSE3Expmap(); + + bool read(std::istream& is); + + bool write(std::ostream& os) const; + + virtual void setToOriginImpl() { + _estimate = SE3Quat(); + } + + virtual void oplusImpl(const double* update_) { + Eigen::Map update(update_); + setEstimate(SE3Quat::exp(update)*estimate()); + } +}; + + +/** +* \brief 6D edge between two Vertex6 +*/ +class EdgeSE3 : public BaseBinaryEdge<6, SE3Quat, VertexSE3Expmap, VertexSE3Expmap> +{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + EdgeSE3(); + virtual bool read(std::istream& is); + virtual bool write(std::ostream& os) const; + + void computeError() + { + const VertexSE3Expmap* v1 = static_cast(_vertices[0]); + const VertexSE3Expmap* v2 = static_cast(_vertices[1]); + + SE3Quat C(_measurement); + SE3Quat error_=C*v1->estimate()*v2->estimate().inverse(); + _error = error_.log(); + } + + virtual double initialEstimatePossible(const OptimizableGraph::VertexSet& , OptimizableGraph::Vertex* ) { return 1.;} + + virtual void initialEstimate(const OptimizableGraph::VertexSet& from, OptimizableGraph::Vertex* /*to*/) + { + VertexSE3Expmap* v1 = static_cast(_vertices[0]); + VertexSE3Expmap* v2 = static_cast(_vertices[1]); + if (from.count(v1) > 0) + v2->setEstimate(measurement()*v1->estimate()); + else + v1->setEstimate(measurement().inverse()*v2->estimate()); + } +}; + +class EdgeSE3ProjectXYZ: public BaseBinaryEdge<2, Vector2d, VertexSBAPointXYZ, VertexSE3Expmap>{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + EdgeSE3ProjectXYZ(); + + bool read(std::istream& is); + + bool write(std::ostream& os) const; + + void computeError() { + const VertexSE3Expmap* v1 = static_cast(_vertices[1]); + const VertexSBAPointXYZ* v2 = static_cast(_vertices[0]); + Vector2d obs(_measurement); + _error = obs-cam_project(v1->estimate().map(v2->estimate())); + } + + bool isDepthPositive() { + const VertexSE3Expmap* v1 = static_cast(_vertices[1]); + const VertexSBAPointXYZ* v2 = static_cast(_vertices[0]); + return (v1->estimate().map(v2->estimate()))(2)>0.0; + } + + + virtual void linearizeOplus(); + + Vector2d cam_project(const Vector3d & trans_xyz) const; + + double fx, fy, cx, cy; +}; + + +class EdgeStereoSE3ProjectXYZ: public BaseBinaryEdge<3, Vector3d, VertexSBAPointXYZ, VertexSE3Expmap>{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + EdgeStereoSE3ProjectXYZ(); + + bool read(std::istream& is); + + bool write(std::ostream& os) const; + + void computeError() { + const VertexSE3Expmap* v1 = static_cast(_vertices[1]); + const VertexSBAPointXYZ* v2 = static_cast(_vertices[0]); + Vector3d obs(_measurement); + _error = obs - cam_project(v1->estimate().map(v2->estimate()),bf); + } + + bool isDepthPositive() { + const VertexSE3Expmap* v1 = static_cast(_vertices[1]); + const VertexSBAPointXYZ* v2 = static_cast(_vertices[0]); + return (v1->estimate().map(v2->estimate()))(2)>0.0; + } + + + virtual void linearizeOplus(); + + Vector3d cam_project(const Vector3d & trans_xyz, const float &bf) const; + + double fx, fy, cx, cy, bf; +}; + +class EdgeSE3ProjectXYZOnlyPose: public BaseUnaryEdge<2, Vector2d, VertexSE3Expmap>{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + EdgeSE3ProjectXYZOnlyPose(){} + + bool read(std::istream& is); + + bool write(std::ostream& os) const; + + void computeError() { + const VertexSE3Expmap* v1 = static_cast(_vertices[0]); + Vector2d obs(_measurement); + _error = obs-cam_project(v1->estimate().map(Xw)); + } + + bool isDepthPositive() { + const VertexSE3Expmap* v1 = static_cast(_vertices[0]); + return (v1->estimate().map(Xw))(2)>0.0; + } + + + virtual void linearizeOplus(); + + Vector2d cam_project(const Vector3d & trans_xyz) const; + + Vector3d Xw; + double fx, fy, cx, cy; +}; + + +class EdgeStereoSE3ProjectXYZOnlyPose: public BaseUnaryEdge<3, Vector3d, VertexSE3Expmap>{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + EdgeStereoSE3ProjectXYZOnlyPose(){} + + bool read(std::istream& is); + + bool write(std::ostream& os) const; + + void computeError() { + const VertexSE3Expmap* v1 = static_cast(_vertices[0]); + Vector3d obs(_measurement); + _error = obs - cam_project(v1->estimate().map(Xw)); + } + + bool isDepthPositive() { + const VertexSE3Expmap* v1 = static_cast(_vertices[0]); + return (v1->estimate().map(Xw))(2)>0.0; + } + + + virtual void linearizeOplus(); + + Vector3d cam_project(const Vector3d & trans_xyz) const; + + Vector3d Xw; + double fx, fy, cx, cy, bf; +}; + + + +} // end namespace + +#endif diff --git a/third_party/ORB_SLAM3/Thirdparty/g2o/license-bsd.txt b/third_party/ORB_SLAM3/Thirdparty/g2o/license-bsd.txt new file mode 100644 index 0000000..b9b8846 --- /dev/null +++ b/third_party/ORB_SLAM3/Thirdparty/g2o/license-bsd.txt @@ -0,0 +1,27 @@ +g2o - General Graph Optimization +Copyright (C) 2011 Rainer Kuemmerle, Giorgio Grisetti, Hauke Strasdat, +Kurt Konolige, and Wolfram Burgard +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are +met: + +* Redistributions of source code must retain the above copyright notice, + this list of conditions and the following disclaimer. +* Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in the + documentation and/or other materials provided with the distribution. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + diff --git a/third_party/ORB_SLAM3/build.sh b/third_party/ORB_SLAM3/build.sh new file mode 100755 index 0000000..9aadf59 --- /dev/null +++ b/third_party/ORB_SLAM3/build.sh @@ -0,0 +1,31 @@ +echo "Configuring and building Thirdparty/DBoW2 ..." + +cd Thirdparty/DBoW2 +mkdir build +cd build +cmake .. -DCMAKE_BUILD_TYPE=Release +make -j + +cd ../../g2o + +echo "Configuring and building Thirdparty/g2o ..." + +mkdir build +cd build +cmake .. -DCMAKE_BUILD_TYPE=Release +make -j + +cd ../../../ + +echo "Uncompress vocabulary ..." + +cd Vocabulary +tar -xf ORBvoc.txt.tar.gz +cd .. + +echo "Configuring and building ORB_SLAM3 ..." + +mkdir build +cd build +cmake .. -DCMAKE_BUILD_TYPE=Release +make -j diff --git a/third_party/ORB_SLAM3/build_ros.sh b/third_party/ORB_SLAM3/build_ros.sh new file mode 100755 index 0000000..1f13d21 --- /dev/null +++ b/third_party/ORB_SLAM3/build_ros.sh @@ -0,0 +1,7 @@ +echo "Building ROS nodes" + +cd Examples/ROS/ORB_SLAM3 +mkdir build +cd build +cmake .. -DROS_BUILD_TYPE=Release +make -j diff --git a/third_party/ORB_SLAM3/euroc_eval_examples.sh b/third_party/ORB_SLAM3/euroc_eval_examples.sh new file mode 100755 index 0000000..bbe3317 --- /dev/null +++ b/third_party/ORB_SLAM3/euroc_eval_examples.sh @@ -0,0 +1,36 @@ +#!/bin/bash +pathDatasetEuroc='/Datasets/EuRoC' #Example, it is necesary to change it by the dataset path + +# Single Session Example (Pure visual) +echo "Launching MH01 with Stereo sensor" +./Examples/Stereo/stereo_euroc ./Vocabulary/ORBvoc.txt ./Examples/Stereo/EuRoC.yaml "$pathDatasetEuroc"/MH01 ./Examples/Stereo/EuRoC_TimeStamps/MH01.txt dataset-MH01_stereo +echo "------------------------------------" +echo "Evaluation of MH01 trajectory with Stereo sensor" +python evaluation/evaluate_ate_scale.py evaluation/Ground_truth/EuRoC_left_cam/MH01_GT.txt f_dataset-MH01_stereo.txt --plot MH01_stereo.pdf + + + +# MultiSession Example (Pure visual) +echo "Launching Machine Hall with Stereo sensor" +./Examples/Stereo/stereo_euroc ./Vocabulary/ORBvoc.txt ./Examples/Stereo/EuRoC.yaml "$pathDatasetEuroc"/MH01 ./Examples/Stereo/EuRoC_TimeStamps/MH01.txt "$pathDatasetEuroc"/MH02 ./Examples/Stereo/EuRoC_TimeStamps/MH02.txt "$pathDatasetEuroc"/MH03 ./Examples/Stereo/EuRoC_TimeStamps/MH03.txt "$pathDatasetEuroc"/MH04 ./Examples/Stereo/EuRoC_TimeStamps/MH04.txt "$pathDatasetEuroc"/MH05 ./Examples/Stereo/EuRoC_TimeStamps/MH05.txt dataset-MH01_to_MH05_stereo +echo "------------------------------------" +echo "Evaluation of MAchine Hall trajectory with Stereo sensor" +python evaluation/evaluate_ate_scale.py evaluation/Ground_truth/EuRoC_left_cam/MH_GT.txt f_dataset-MH01_to_MH05_stereo.txt --plot MH01_to_MH05_stereo.pdf + + +# Single Session Example (Visual-Inertial) +echo "Launching V102 with Monocular-Inertial sensor" +./Examples/Monocular-Inertial/mono_inertial_euroc ./Vocabulary/ORBvoc.txt ./Examples/Monocular-Inertial/EuRoC.yaml "$pathDatasetEuroc"/V102 ./Examples/Monocular-Inertial/EuRoC_TimeStamps/V102.txt dataset-V102_monoi +echo "------------------------------------" +echo "Evaluation of V102 trajectory with Monocular-Inertial sensor" +python evaluation/evaluate_ate_scale.py "$pathDatasetEuroc"/V102/mav0/state_groundtruth_estimate0/data.csv f_dataset-V102_monoi.txt --plot V102_monoi.pdf + + +# MultiSession Monocular Examples + +echo "Launching Vicon Room 2 with Monocular-Inertial sensor" +./Examples/Monocular-Inertial/mono_inertial_euroc ./Vocabulary/ORBvoc.txt ./Examples/Monocular-Inertial/EuRoC.yaml "$pathDatasetEuroc"/V201 ./Examples/Monocular-Inertial/EuRoC_TimeStamps/V201.txt "$pathDatasetEuroc"/V202 ./Examples/Monocular-Inertial/EuRoC_TimeStamps/V202.txt "$pathDatasetEuroc"/V203 ./Examples/Monocular-Inertial/EuRoC_TimeStamps/V203.txt dataset-V201_to_V203_monoi +echo "------------------------------------" +echo "Evaluation of Vicon Room 2 trajectory with Stereo sensor" +python evaluation/evaluate_ate_scale.py evaluation/Ground_truth/EuRoC_imu/V2_GT.txt f_dataset-V201_to_V203_monoi.txt --plot V201_to_V203_monoi.pdf + diff --git a/third_party/ORB_SLAM3/euroc_examples.sh b/third_party/ORB_SLAM3/euroc_examples.sh new file mode 100755 index 0000000..d678ada --- /dev/null +++ b/third_party/ORB_SLAM3/euroc_examples.sh @@ -0,0 +1,182 @@ +#!/bin/bash +pathDatasetEuroc='/Datasets/EuRoC' #Example, it is necesary to change it by the dataset path + +#------------------------------------ +# Monocular Examples +echo "Launching MH01 with Monocular sensor" +./Examples/Monocular/mono_euroc ./Vocabulary/ORBvoc.txt ./Examples/Monocular/EuRoC.yaml "$pathDatasetEuroc"/MH01 ./Examples/Monocular/EuRoC_TimeStamps/MH01.txt dataset-MH01_mono + +echo "Launching MH02 with Monocular sensor" +./Examples/Monocular/mono_euroc ./Vocabulary/ORBvoc.txt ./Examples/Monocular/EuRoC.yaml "$pathDatasetEuroc"/MH02 ./Examples/Monocular/EuRoC_TimeStamps/MH02.txt dataset-MH02_mono + +echo "Launching MH03 with Monocular sensor" +./Examples/Monocular/mono_euroc ./Vocabulary/ORBvoc.txt ./Examples/Monocular/EuRoC.yaml "$pathDatasetEuroc"/MH03 ./Examples/Monocular/EuRoC_TimeStamps/MH03.txt dataset-MH03_mono + +echo "Launching MH04 with Monocular sensor" +./Examples/Monocular/mono_euroc ./Vocabulary/ORBvoc.txt ./Examples/Monocular/EuRoC.yaml "$pathDatasetEuroc"/MH04 ./Examples/Monocular/EuRoC_TimeStamps/MH04.txt dataset-MH04_mono + +echo "Launching MH05 with Monocular sensor" +./Examples/Monocular/mono_euroc ./Vocabulary/ORBvoc.txt ./Examples/Monocular/EuRoC.yaml "$pathDatasetEuroc"/MH05 ./Examples/Monocular/EuRoC_TimeStamps/MH05.txt dataset-MH05_mono + +echo "Launching V101 with Monocular sensor" +./Examples/Monocular/mono_euroc ./Vocabulary/ORBvoc.txt ./Examples/Monocular/EuRoC.yaml "$pathDatasetEuroc"/V101 ./Examples/Monocular/EuRoC_TimeStamps/V101.txt dataset-V101_mono + +echo "Launching V102 with Monocular sensor" +./Examples/Monocular/mono_euroc ./Vocabulary/ORBvoc.txt ./Examples/Monocular/EuRoC.yaml "$pathDatasetEuroc"/V102 ./Examples/Monocular/EuRoC_TimeStamps/V102.txt dataset-V102_mono + +echo "Launching V103 with Monocular sensor" +./Examples/Monocular/mono_euroc ./Vocabulary/ORBvoc.txt ./Examples/Monocular/EuRoC.yaml "$pathDatasetEuroc"/V103 ./Examples/Monocular/EuRoC_TimeStamps/V103.txt dataset-V103_mono + +echo "Launching V201 with Monocular sensor" +./Examples/Monocular/mono_euroc ./Vocabulary/ORBvoc.txt ./Examples/Monocular/EuRoC.yaml "$pathDatasetEuroc"/V201 ./Examples/Monocular/EuRoC_TimeStamps/V201.txt dataset-V201_mono + +echo "Launching V202 with Monocular sensor" +./Examples/Monocular/mono_euroc ./Vocabulary/ORBvoc.txt ./Examples/Monocular/EuRoC.yaml "$pathDatasetEuroc"/V202 ./Examples/Monocular/EuRoC_TimeStamps/V202.txt dataset-V202_mono + +echo "Launching V203 with Monocular sensor" +./Examples/Monocular/mono_euroc ./Vocabulary/ORBvoc.txt ./Examples/Monocular/EuRoC.yaml "$pathDatasetEuroc"/V203 ./Examples/Monocular/EuRoC_TimeStamps/V203.txt dataset-V203_mono + +# MultiSession Monocular Examples +echo "Launching Machine Hall with Monocular sensor" +./Examples/Monocular/mono_euroc ./Vocabulary/ORBvoc.txt ./Examples/Monocular/EuRoC.yaml "$pathDatasetEuroc"/MH01 ./Examples/Monocular/EuRoC_TimeStamps/MH01.txt "$pathDatasetEuroc"/MH02 ./Examples/Monocular/EuRoC_TimeStamps/MH02.txt "$pathDatasetEuroc"/MH03 ./Examples/Monocular/EuRoC_TimeStamps/MH03.txt "$pathDatasetEuroc"/MH04 ./Examples/Monocular/EuRoC_TimeStamps/MH04.txt "$pathDatasetEuroc"/MH05 ./Examples/Monocular/EuRoC_TimeStamps/MH05.txt dataset-MH01_to_MH05_mono + +echo "Launching Vicon Room 1 with Monocular sensor" +./Examples/Monocular/mono_euroc ./Vocabulary/ORBvoc.txt ./Examples/Monocular/EuRoC.yaml "$pathDatasetEuroc"/V101 ./Examples/Monocular/EuRoC_TimeStamps/V101.txt "$pathDatasetEuroc"/V102 ./Examples/Monocular/EuRoC_TimeStamps/V102.txt "$pathDatasetEuroc"/V103 ./Examples/Monocular/EuRoC_TimeStamps/V103.txt dataset-V101_to_V103_mono + +echo "Launching Vicon Room 2 with Monocular sensor" +./Examples/Monocular/mono_euroc ./Vocabulary/ORBvoc.txt ./Examples/Monocular/EuRoC.yaml "$pathDatasetEuroc"/V201 ./Examples/Monocular/EuRoC_TimeStamps/V201.txt "$pathDatasetEuroc"/V202 ./Examples/Monocular/EuRoC_TimeStamps/V202.txt "$pathDatasetEuroc"/V203 ./Examples/Monocular/EuRoC_TimeStamps/V203.txt dataset-V201_to_V203_mono + +#------------------------------------ +# Stereo Examples +echo "Launching MH01 with Stereo sensor" +./Examples/Stereo/stereo_euroc ./Vocabulary/ORBvoc.txt ./Examples/Stereo/EuRoC.yaml "$pathDatasetEuroc"/MH01 ./Examples/Stereo/EuRoC_TimeStamps/MH01.txt dataset-MH01_stereo + +echo "Launching MH02 with Stereo sensor" +./Examples/Stereo/stereo_euroc ./Vocabulary/ORBvoc.txt ./Examples/Stereo/EuRoC.yaml "$pathDatasetEuroc"/MH02 ./Examples/Stereo/EuRoC_TimeStamps/MH02.txt dataset-MH02_stereo + +echo "Launching MH03 with Stereo sensor" +./Examples/Stereo/stereo_euroc ./Vocabulary/ORBvoc.txt ./Examples/Stereo/EuRoC.yaml "$pathDatasetEuroc"/MH03 ./Examples/Stereo/EuRoC_TimeStamps/MH03.txt dataset-MH03_stereo + +echo "Launching MH04 with Stereo sensor" +./Examples/Stereo/stereo_euroc ./Vocabulary/ORBvoc.txt ./Examples/Stereo/EuRoC.yaml "$pathDatasetEuroc"/MH04 ./Examples/Stereo/EuRoC_TimeStamps/MH04.txt dataset-MH04_stereo + +echo "Launching MH05 with Stereo sensor" +./Examples/Stereo/stereo_euroc ./Vocabulary/ORBvoc.txt ./Examples/Stereo/EuRoC.yaml "$pathDatasetEuroc"/MH05 ./Examples/Stereo/EuRoC_TimeStamps/MH05.txt dataset-MH05_stereo + +echo "Launching V101 with Stereo sensor" +./Examples/Stereo/stereo_euroc ./Vocabulary/ORBvoc.txt ./Examples/Stereo/EuRoC.yaml "$pathDatasetEuroc"/V101 ./Examples/Stereo/EuRoC_TimeStamps/V101.txt dataset-V101_stereo + +echo "Launching V102 with Stereo sensor" +./Examples/Stereo/stereo_euroc ./Vocabulary/ORBvoc.txt ./Examples/Stereo/EuRoC.yaml "$pathDatasetEuroc"/V102 ./Examples/Stereo/EuRoC_TimeStamps/V102.txt dataset-V102_stereo + +echo "Launching V103 with Stereo sensor" +./Examples/Stereo/stereo_euroc ./Vocabulary/ORBvoc.txt ./Examples/Stereo/EuRoC.yaml "$pathDatasetEuroc"/V103 ./Examples/Stereo/EuRoC_TimeStamps/V103.txt dataset-V103_stereo + +echo "Launching V201 with Stereo sensor" +./Examples/Stereo/stereo_euroc ./Vocabulary/ORBvoc.txt ./Examples/Stereo/EuRoC.yaml "$pathDatasetEuroc"/V201 ./Examples/Stereo/EuRoC_TimeStamps/V201.txt dataset-V201_stereo + +echo "Launching V202 with Stereo sensor" +./Examples/Stereo/stereo_euroc ./Vocabulary/ORBvoc.txt ./Examples/Stereo/EuRoC.yaml "$pathDatasetEuroc"/V202 ./Examples/Stereo/EuRoC_TimeStamps/V202.txt dataset-V202_stereo + +echo "Launching V203 with Stereo sensor" +./Examples/Stereo/stereo_euroc ./Vocabulary/ORBvoc.txt ./Examples/Stereo/EuRoC.yaml "$pathDatasetEuroc"/V203 ./Examples/Stereo/EuRoC_TimeStamps/V203.txt dataset-V203_stereo + +# MultiSession Stereo Examples +echo "Launching Machine Hall with Stereo sensor" +./Examples/Stereo/stereo_euroc ./Vocabulary/ORBvoc.txt ./Examples/Stereo/EuRoC.yaml "$pathDatasetEuroc"/MH01 ./Examples/Stereo/EuRoC_TimeStamps/MH01.txt "$pathDatasetEuroc"/MH02 ./Examples/Stereo/EuRoC_TimeStamps/MH02.txt "$pathDatasetEuroc"/MH03 ./Examples/Stereo/EuRoC_TimeStamps/MH03.txt "$pathDatasetEuroc"/MH04 ./Examples/Stereo/EuRoC_TimeStamps/MH04.txt "$pathDatasetEuroc"/MH05 ./Examples/Stereo/EuRoC_TimeStamps/MH05.txt dataset-MH01_to_MH05_stereo + +echo "Launching Vicon Room 1 with Stereo sensor" +./Examples/Stereo/stereo_euroc ./Vocabulary/ORBvoc.txt ./Examples/Stereo/EuRoC.yaml "$pathDatasetEuroc"/V101 ./Examples/Stereo/EuRoC_TimeStamps/V101.txt "$pathDatasetEuroc"/V102 ./Examples/Stereo/EuRoC_TimeStamps/V102.txt "$pathDatasetEuroc"/V103 ./Examples/Stereo/EuRoC_TimeStamps/V103.txt dataset-V101_to_V103_stereo + +echo "Launching Vicon Room 2 with Stereo sensor" +./Examples/Stereo/stereo_euroc ./Vocabulary/ORBvoc.txt ./Examples/Stereo/EuRoC.yaml "$pathDatasetEuroc"/V201 ./Examples/Stereo/EuRoC_TimeStamps/V201.txt "$pathDatasetEuroc"/V202 ./Examples/Stereo/EuRoC_TimeStamps/V202.txt "$pathDatasetEuroc"/V203 ./Examples/Stereo/EuRoC_TimeStamps/V203.txt dataset-V201_to_V203_stereo + +#------------------------------------ +# Monocular-Inertial Examples +echo "Launching MH01 with Monocular-Inertial sensor" +./Examples/Monocular-Inertial/mono_inertial_euroc ./Vocabulary/ORBvoc.txt ./Examples/Monocular-Inertial/EuRoC.yaml "$pathDatasetEuroc"/MH01 ./Examples/Monocular-Inertial/EuRoC_TimeStamps/MH01.txt dataset-MH01_monoi + +echo "Launching MH02 with Monocular-Inertial sensor" +./Examples/Monocular-Inertial/mono_inertial_euroc ./Vocabulary/ORBvoc.txt ./Examples/Monocular-Inertial/EuRoC.yaml "$pathDatasetEuroc"/MH02 ./Examples/Monocular-Inertial/EuRoC_TimeStamps/MH02.txt dataset-MH02_monoi + +echo "Launching MH03 with Monocular-Inertial sensor" +./Examples/Monocular-Inertial/mono_inertial_euroc ./Vocabulary/ORBvoc.txt ./Examples/Monocular-Inertial/EuRoC.yaml "$pathDatasetEuroc"/MH03 ./Examples/Monocular-Inertial/EuRoC_TimeStamps/MH03.txt dataset-MH03_monoi + +echo "Launching MH04 with Monocular-Inertial sensor" +./Examples/Monocular-Inertial/mono_inertial_euroc ./Vocabulary/ORBvoc.txt ./Examples/Monocular-Inertial/EuRoC.yaml "$pathDatasetEuroc"/MH04 ./Examples/Monocular-Inertial/EuRoC_TimeStamps/MH04.txt dataset-MH04_monoi + +echo "Launching MH05 with Monocular-Inertial sensor" +./Examples/Monocular-Inertial/mono_inertial_euroc ./Vocabulary/ORBvoc.txt ./Examples/Monocular-Inertial/EuRoC.yaml "$pathDatasetEuroc"/MH05 ./Examples/Monocular-Inertial/EuRoC_TimeStamps/MH05.txt dataset-MH05_monoi + +echo "Launching V101 with Monocular-Inertial sensor" +./Examples/Monocular-Inertial/mono_inertial_euroc ./Vocabulary/ORBvoc.txt ./Examples/Monocular-Inertial/EuRoC.yaml "$pathDatasetEuroc"/V101 ./Examples/Monocular-Inertial/EuRoC_TimeStamps/V101.txt dataset-V101_monoi + +echo "Launching V102 with Monocular-Inertial sensor" +./Examples/Monocular-Inertial/mono_inertial_euroc ./Vocabulary/ORBvoc.txt ./Examples/Monocular-Inertial/EuRoC.yaml "$pathDatasetEuroc"/V102 ./Examples/Monocular-Inertial/EuRoC_TimeStamps/V102.txt dataset-V102_monoi + +echo "Launching V103 with Monocular-Inertial sensor" +./Examples/Monocular-Inertial/mono_inertial_euroc ./Vocabulary/ORBvoc.txt ./Examples/Monocular-Inertial/EuRoC.yaml "$pathDatasetEuroc"/V103 ./Examples/Monocular-Inertial/EuRoC_TimeStamps/V103.txt dataset-V103_monoi + +echo "Launching V201 with Monocular-Inertial sensor" +./Examples/Monocular-Inertial/mono_inertial_euroc ./Vocabulary/ORBvoc.txt ./Examples/Monocular-Inertial/EuRoC.yaml "$pathDatasetEuroc"/V201 ./Examples/Monocular-Inertial/EuRoC_TimeStamps/V201.txt dataset-V201_monoi + +echo "Launching V202 with Monocular-Inertial sensor" +./Examples/Monocular-Inertial/mono_inertial_euroc ./Vocabulary/ORBvoc.txt ./Examples/Monocular-Inertial/EuRoC.yaml "$pathDatasetEuroc"/V202 ./Examples/Monocular-Inertial/EuRoC_TimeStamps/V202.txt dataset-V202_monoi + +echo "Launching V203 with Monocular-Inertial sensor" +./Examples/Monocular-Inertial/mono_inertial_euroc ./Vocabulary/ORBvoc.txt ./Examples/Monocular-Inertial/EuRoC.yaml "$pathDatasetEuroc"/V203 ./Examples/Monocular-Inertial/EuRoC_TimeStamps/V203.txt dataset-V203_monoi + +# MultiSession Monocular Examples +echo "Launching Machine Hall with Monocular-Inertial sensor" +./Examples/Monocular-Inertial/mono_inertial_euroc ./Vocabulary/ORBvoc.txt ./Examples/Monocular-Inertial/EuRoC.yaml "$pathDatasetEuroc"/MH01 ./Examples/Monocular-Inertial/EuRoC_TimeStamps/MH01.txt "$pathDatasetEuroc"/MH02 ./Examples/Monocular-Inertial/EuRoC_TimeStamps/MH02.txt "$pathDatasetEuroc"/MH03 ./Examples/Monocular-Inertial/EuRoC_TimeStamps/MH03.txt "$pathDatasetEuroc"/MH04 ./Examples/Monocular-Inertial/EuRoC_TimeStamps/MH04.txt "$pathDatasetEuroc"/MH05 ./Examples/Monocular-Inertial/EuRoC_TimeStamps/MH05.txt dataset-MH01_to_MH05_monoi + +echo "Launching Vicon Room 1 with Monocular-Inertial sensor" +./Examples/Monocular-Inertial/mono_inertial_euroc ./Vocabulary/ORBvoc.txt ./Examples/Monocular-Inertial/EuRoC.yaml "$pathDatasetEuroc"/V101 ./Examples/Monocular-Inertial/EuRoC_TimeStamps/V101.txt "$pathDatasetEuroc"/V102 ./Examples/Monocular-Inertial/EuRoC_TimeStamps/V102.txt "$pathDatasetEuroc"/V103 ./Examples/Monocular-Inertial/EuRoC_TimeStamps/V103.txt dataset-V101_to_V103_monoi + +echo "Launching Vicon Room 2 with Monocular-Inertial sensor" +./Examples/Monocular-Inertial/mono_inertial_euroc ./Vocabulary/ORBvoc.txt ./Examples/Monocular-Inertial/EuRoC.yaml "$pathDatasetEuroc"/V201 ./Examples/Monocular-Inertial/EuRoC_TimeStamps/V201.txt "$pathDatasetEuroc"/V202 ./Examples/Monocular-Inertial/EuRoC_TimeStamps/V202.txt "$pathDatasetEuroc"/V203 ./Examples/Monocular-Inertial/EuRoC_TimeStamps/V203.txt dataset-V201_to_V203_monoi + +#------------------------------------ +# Stereo-Inertial Examples +echo "Launching MH01 with Stereo-Inertial sensor" +./Examples/Stereo-Inertial/stereo_inertial_euroc ./Vocabulary/ORBvoc.txt ./Examples/Stereo-Inertial/EuRoC.yaml "$pathDatasetEuroc"/MH01 ./Examples/Stereo-Inertial/EuRoC_TimeStamps/MH01.txt dataset-MH01_stereoi + +echo "Launching MH02 with Stereo-Inertial sensor" +./Examples/Stereo-Inertial/stereo_inertial_euroc ./Vocabulary/ORBvoc.txt ./Examples/Stereo-Inertial/EuRoC.yaml "$pathDatasetEuroc"/MH02 ./Examples/Stereo-Inertial/EuRoC_TimeStamps/MH02.txt dataset-MH02_stereoi + +echo "Launching MH03 with Stereo-Inertial sensor" +./Examples/Stereo-Inertial/stereo_inertial_euroc ./Vocabulary/ORBvoc.txt ./Examples/Stereo-Inertial/EuRoC.yaml "$pathDatasetEuroc"/MH03 ./Examples/Stereo-Inertial/EuRoC_TimeStamps/MH03.txt dataset-MH03_stereoi + +echo "Launching MH04 with Stereo-Inertial sensor" +./Examples/Stereo-Inertial/stereo_inertial_euroc ./Vocabulary/ORBvoc.txt ./Examples/Stereo-Inertial/EuRoC.yaml "$pathDatasetEuroc"/MH04 ./Examples/Stereo-Inertial/EuRoC_TimeStamps/MH04.txt dataset-MH04_stereoi + +echo "Launching MH05 with Stereo-Inertial sensor" +./Examples/Stereo-Inertial/stereo_inertial_euroc ./Vocabulary/ORBvoc.txt ./Examples/Stereo-Inertial/EuRoC.yaml "$pathDatasetEuroc"/MH05 ./Examples/Stereo-Inertial/EuRoC_TimeStamps/MH05.txt dataset-MH05_stereoi + +echo "Launching V101 with Stereo-Inertial sensor" +./Examples/Stereo-Inertial/stereo_inertial_euroc ./Vocabulary/ORBvoc.txt ./Examples/Stereo-Inertial/EuRoC.yaml "$pathDatasetEuroc"/V101 ./Examples/Stereo-Inertial/EuRoC_TimeStamps/V101.txt dataset-V101_stereoi + +echo "Launching V102 with Stereo-Inertial sensor" +./Examples/Stereo-Inertial/stereo_inertial_euroc ./Vocabulary/ORBvoc.txt ./Examples/Stereo-Inertial/EuRoC.yaml "$pathDatasetEuroc"/V102 ./Examples/Stereo-Inertial/EuRoC_TimeStamps/V102.txt dataset-V102_stereoi + +echo "Launching V103 with Stereo-Inertial sensor" +./Examples/Stereo-Inertial/stereo_inertial_euroc ./Vocabulary/ORBvoc.txt ./Examples/Stereo-Inertial/EuRoC.yaml "$pathDatasetEuroc"/V103 ./Examples/Stereo-Inertial/EuRoC_TimeStamps/V103.txt dataset-V103_stereoi + +echo "Launching V201 with Stereo-Inertial sensor" +./Examples/Stereo-Inertial/stereo_inertial_euroc ./Vocabulary/ORBvoc.txt ./Examples/Stereo-Inertial/EuRoC.yaml "$pathDatasetEuroc"/V201 ./Examples/Stereo-Inertial/EuRoC_TimeStamps/V201.txt dataset-V201_stereoi + +echo "Launching V202 with Stereo-Inertial sensor" +./Examples/Stereo-Inertial/stereo_inertial_euroc ./Vocabulary/ORBvoc.txt ./Examples/Stereo-Inertial/EuRoC.yaml "$pathDatasetEuroc"/V202 ./Examples/Stereo-Inertial/EuRoC_TimeStamps/V202.txt dataset-V202_stereoi + +echo "Launching V203 with Stereo-Inertial sensor" +./Examples/Stereo-Inertial/stereo_inertial_euroc ./Vocabulary/ORBvoc.txt ./Examples/Stereo-Inertial/EuRoC.yaml "$pathDatasetEuroc"/V203 ./Examples/Stereo-Inertial/EuRoC_TimeStamps/V203.txt dataset-V203_stereoi + +# MultiSession Stereo-Inertial Examples +echo "Launching Machine Hall with Stereo-Inertial sensor" +./Examples/Stereo-Inertial/stereo_inertial_euroc ./Vocabulary/ORBvoc.txt ./Examples/Stereo-Inertial/EuRoC.yaml "$pathDatasetEuroc"/MH01 ./Examples/Stereo-Inertial/EuRoC_TimeStamps/MH01.txt "$pathDatasetEuroc"/MH02 ./Examples/Stereo-Inertial/EuRoC_TimeStamps/MH02.txt "$pathDatasetEuroc"/MH03 ./Examples/Stereo-Inertial/EuRoC_TimeStamps/MH03.txt "$pathDatasetEuroc"/MH04 ./Examples/Stereo-Inertial/EuRoC_TimeStamps/MH04.txt "$pathDatasetEuroc"/MH05 ./Examples/Stereo-Inertial/EuRoC_TimeStamps/MH05.txt dataset-MH01_to_MH05_stereoi + +echo "Launching Vicon Room 1 with Stereo-Inertial sensor" +./Examples/Stereo-Inertial/stereo_inertial_euroc ./Vocabulary/ORBvoc.txt ./Examples/Stereo-Inertial/EuRoC.yaml "$pathDatasetEuroc"/V101 ./Examples/Stereo-Inertial/EuRoC_TimeStamps/V101.txt "$pathDatasetEuroc"/V102 ./Examples/Stereo-Inertial/EuRoC_TimeStamps/V102.txt "$pathDatasetEuroc"/V103 ./Examples/Stereo-Inertial/EuRoC_TimeStamps/V103.txt dataset-V101_to_V103_stereoi + +echo "Launching Vicon Room 2 with Stereo-Inertial sensor" +./Examples/Stereo-Inertial/stereo_inertial_euroc ./Vocabulary/ORBvoc.txt ./Examples/Stereo-Inertial/EuRoC.yaml "$pathDatasetEuroc"/V201 ./Examples/Stereo-Inertial/EuRoC_TimeStamps/V201.txt "$pathDatasetEuroc"/V202 ./Examples/Stereo-Inertial/EuRoC_TimeStamps/V202.txt "$pathDatasetEuroc"/V203 ./Examples/Stereo-Inertial/EuRoC_TimeStamps/V203.txt dataset-V201_to_V203_stereoi diff --git a/third_party/ORB_SLAM3/include/Atlas.h b/third_party/ORB_SLAM3/include/Atlas.h new file mode 100644 index 0000000..b8abb67 --- /dev/null +++ b/third_party/ORB_SLAM3/include/Atlas.h @@ -0,0 +1,168 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + +#ifndef ATLAS_H +#define ATLAS_H + +#include "Map.h" +#include "MapPoint.h" +#include "KeyFrame.h" +#include "GeometricCamera.h" +#include "Pinhole.h" +#include "KannalaBrandt8.h" + +#include +#include +#include +#include + + +namespace ORB_SLAM3 +{ +class Viewer; +class Map; +class MapPoint; +class KeyFrame; +class KeyFrameDatabase; +class Frame; +class KannalaBrandt8; +class Pinhole; + +//BOOST_CLASS_EXPORT_GUID(Pinhole, "Pinhole") +//BOOST_CLASS_EXPORT_GUID(KannalaBrandt8, "KannalaBrandt8") + +class Atlas +{ + friend class boost::serialization::access; + + template + void serialize(Archive &ar, const unsigned int version) + { + //ar.template register_type(); + //ar.template register_type(); + + // Save/load the set of maps, the set is broken in libboost 1.58 for ubuntu 16.04 + //ar & mspMaps; + ar & mvpBackupMaps; + ar & mvpCameras; + //ar & mvpBackupCamPin; + //ar & mvpBackupCamKan; + // Need to save/load the static Id from Frame, KeyFrame, MapPoint and Map + ar & Map::nNextId; + ar & Frame::nNextId; + ar & KeyFrame::nNextId; + ar & MapPoint::nNextId; + ar & GeometricCamera::nNextId; + ar & mnLastInitKFidMap; + } + +public: + Atlas(); + Atlas(int initKFid); // When its initialization the first map is created + ~Atlas(); + + void CreateNewMap(); + void ChangeMap(Map* pMap); + + unsigned long int GetLastInitKFid(); + + void SetViewer(Viewer* pViewer); + + // Method for change components in the current map + void AddKeyFrame(KeyFrame* pKF); + void AddMapPoint(MapPoint* pMP); + //void EraseMapPoint(MapPoint* pMP); + //void EraseKeyFrame(KeyFrame* pKF); + + void AddCamera(GeometricCamera* pCam); + + /* All methods without Map pointer work on current map */ + void SetReferenceMapPoints(const std::vector &vpMPs); + void InformNewBigChange(); + int GetLastBigChangeIdx(); + + long unsigned int MapPointsInMap(); + long unsigned KeyFramesInMap(); + + // Method for get data in current map + std::vector GetAllKeyFrames(); + std::vector GetAllMapPoints(); + std::vector GetReferenceMapPoints(); + + vector GetAllMaps(); + + int CountMaps(); + + void clearMap(); + + void clearAtlas(); + + Map* GetCurrentMap(); + + void SetMapBad(Map* pMap); + void RemoveBadMaps(); + + bool isInertial(); + void SetInertialSensor(); + void SetImuInitialized(); + bool isImuInitialized(); + + // Function for garantee the correction of serialization of this object + void PreSave(); + void PostLoad(); + + void SetKeyFrameDababase(KeyFrameDatabase* pKFDB); + KeyFrameDatabase* GetKeyFrameDatabase(); + + void SetORBVocabulary(ORBVocabulary* pORBVoc); + ORBVocabulary* GetORBVocabulary(); + + long unsigned int GetNumLivedKF(); + + long unsigned int GetNumLivedMP(); + +protected: + + std::set mspMaps; + std::set mspBadMaps; + // Its necessary change the container from set to vector because libboost 1.58 and Ubuntu 16.04 have an error with this cointainer + std::vector mvpBackupMaps; + Map* mpCurrentMap; + + std::vector mvpCameras; + std::vector mvpBackupCamKan; + std::vector mvpBackupCamPin; + + //Pinhole testCam; + std::mutex mMutexAtlas; + + unsigned long int mnLastInitKFidMap; + + Viewer* mpViewer; + bool mHasViewer; + + // Class references for the map reconstruction from the save file + KeyFrameDatabase* mpKeyFrameDB; + ORBVocabulary* mpORBVocabulary; + + +}; // class Atlas + +} // namespace ORB_SLAM3 + +#endif // ATLAS_H diff --git a/third_party/ORB_SLAM3/include/CameraModels/GeometricCamera.h b/third_party/ORB_SLAM3/include/CameraModels/GeometricCamera.h new file mode 100644 index 0000000..1149bed --- /dev/null +++ b/third_party/ORB_SLAM3/include/CameraModels/GeometricCamera.h @@ -0,0 +1,106 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + +#ifndef CAMERAMODELS_GEOMETRICCAMERA_H +#define CAMERAMODELS_GEOMETRICCAMERA_H + +#include + +#include +#include + +#include +#include +#include +#include +#include +#include + +#include + +namespace ORB_SLAM3 { + class GeometricCamera { + + friend class boost::serialization::access; + + template + void serialize(Archive& ar, const unsigned int version) + { + ar & mnId; + ar & mnType; + ar & mvParameters; + } + + + public: + GeometricCamera() {} + GeometricCamera(const std::vector &_vParameters) : mvParameters(_vParameters) {} + ~GeometricCamera() {} + + virtual cv::Point2f project(const cv::Point3f &p3D) = 0; + virtual cv::Point2f project(const cv::Mat& m3D) = 0; + virtual Eigen::Vector2d project(const Eigen::Vector3d & v3D) = 0; + virtual cv::Mat projectMat(const cv::Point3f& p3D) = 0; + + virtual float uncertainty2(const Eigen::Matrix &p2D) = 0; + + virtual cv::Point3f unproject(const cv::Point2f &p2D) = 0; + virtual cv::Mat unprojectMat(const cv::Point2f &p2D) = 0; + + virtual cv::Mat projectJac(const cv::Point3f &p3D) = 0; + virtual Eigen::Matrix projectJac(const Eigen::Vector3d& v3D) = 0; + + virtual cv::Mat unprojectJac(const cv::Point2f &p2D) = 0; + + virtual bool ReconstructWithTwoViews(const std::vector& vKeys1, const std::vector& vKeys2, const std::vector &vMatches12, + cv::Mat &R21, cv::Mat &t21, std::vector &vP3D, std::vector &vbTriangulated) = 0; + + virtual cv::Mat toK() = 0; + + virtual bool epipolarConstrain(GeometricCamera* otherCamera, const cv::KeyPoint& kp1, const cv::KeyPoint& kp2, const cv::Mat& R12, const cv::Mat& t12, const float sigmaLevel, const float unc) = 0; + + float getParameter(const int i){return mvParameters[i];} + void setParameter(const float p, const size_t i){mvParameters[i] = p;} + + size_t size(){return mvParameters.size();} + + virtual bool matchAndtriangulate(const cv::KeyPoint& kp1, const cv::KeyPoint& kp2, GeometricCamera* pOther, + cv::Mat& Tcw1, cv::Mat& Tcw2, + const float sigmaLevel1, const float sigmaLevel2, + cv::Mat& x3Dtriangulated) = 0; + + unsigned int GetId() { return mnId; } + + unsigned int GetType() { return mnType; } + + const unsigned int CAM_PINHOLE = 0; + const unsigned int CAM_FISHEYE = 1; + + static long unsigned int nNextId; + + protected: + std::vector mvParameters; + + unsigned int mnId; + + unsigned int mnType; + }; +} + + +#endif //CAMERAMODELS_GEOMETRICCAMERA_H diff --git a/third_party/ORB_SLAM3/include/CameraModels/KannalaBrandt8.h b/third_party/ORB_SLAM3/include/CameraModels/KannalaBrandt8.h new file mode 100644 index 0000000..9ac39ac --- /dev/null +++ b/third_party/ORB_SLAM3/include/CameraModels/KannalaBrandt8.h @@ -0,0 +1,118 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + +#ifndef CAMERAMODELS_KANNALABRANDT8_H +#define CAMERAMODELS_KANNALABRANDT8_H + + +#include +#include +#include + +#include +#include +#include + +#include "GeometricCamera.h" + +#include "TwoViewReconstruction.h" + +namespace ORB_SLAM3 { + class KannalaBrandt8 final : public GeometricCamera { + + friend class boost::serialization::access; + + template + void serialize(Archive& ar, const unsigned int version) + { + ar & boost::serialization::base_object(*this); + ar & const_cast(precision); + } + + public: + KannalaBrandt8() : precision(1e-6) { + mvParameters.resize(8); + mnId=nNextId++; + mnType = CAM_FISHEYE; + } + KannalaBrandt8(const std::vector _vParameters) : GeometricCamera(_vParameters), precision(1e-6), mvLappingArea(2,0) ,tvr(nullptr) { + assert(mvParameters.size() == 8); + mnId=nNextId++; + mnType = CAM_FISHEYE; + } + + KannalaBrandt8(const std::vector _vParameters, const float _precision) : GeometricCamera(_vParameters), + precision(_precision), mvLappingArea(2,0) { + assert(mvParameters.size() == 8); + mnId=nNextId++; + mnType = CAM_FISHEYE; + } + KannalaBrandt8(KannalaBrandt8* pKannala) : GeometricCamera(pKannala->mvParameters), precision(pKannala->precision), mvLappingArea(2,0) ,tvr(nullptr) { + assert(mvParameters.size() == 8); + mnId=nNextId++; + mnType = CAM_FISHEYE; + } + + cv::Point2f project(const cv::Point3f &p3D); + cv::Point2f project(const cv::Mat& m3D); + Eigen::Vector2d project(const Eigen::Vector3d & v3D); + cv::Mat projectMat(const cv::Point3f& p3D); + + float uncertainty2(const Eigen::Matrix &p2D); + + cv::Point3f unproject(const cv::Point2f &p2D); + cv::Mat unprojectMat(const cv::Point2f &p2D); + + cv::Mat projectJac(const cv::Point3f &p3D); + Eigen::Matrix projectJac(const Eigen::Vector3d& v3D); + + cv::Mat unprojectJac(const cv::Point2f &p2D); + + bool ReconstructWithTwoViews(const std::vector& vKeys1, const std::vector& vKeys2, const std::vector &vMatches12, + cv::Mat &R21, cv::Mat &t21, std::vector &vP3D, std::vector &vbTriangulated); + + cv::Mat toK(); + + bool epipolarConstrain(GeometricCamera* pCamera2, const cv::KeyPoint& kp1, const cv::KeyPoint& kp2, const cv::Mat& R12, const cv::Mat& t12, const float sigmaLevel, const float unc); + + float TriangulateMatches(GeometricCamera* pCamera2, const cv::KeyPoint& kp1, const cv::KeyPoint& kp2, const cv::Mat& R12, const cv::Mat& t12, const float sigmaLevel, const float unc, cv::Mat& p3D); + + std::vector mvLappingArea; + + bool matchAndtriangulate(const cv::KeyPoint& kp1, const cv::KeyPoint& kp2, GeometricCamera* pOther, + cv::Mat& Tcw1, cv::Mat& Tcw2, + const float sigmaLevel1, const float sigmaLevel2, + cv::Mat& x3Dtriangulated); + + friend std::ostream& operator<<(std::ostream& os, const KannalaBrandt8& kb); + friend std::istream& operator>>(std::istream& is, KannalaBrandt8& kb); + private: + const float precision; + + //Parameters vector corresponds to + //[fx, fy, cx, cy, k0, k1, k2, k3] + + TwoViewReconstruction* tvr; + + void Triangulate(const cv::Point2f &p1, const cv::Point2f &p2, const cv::Mat &Tcw1, const cv::Mat &Tcw2,cv::Mat &x3D); + }; +} + +//BOOST_CLASS_EXPORT_KEY(ORBSLAM2::KannalaBrandt8) + +#endif //CAMERAMODELS_KANNALABRANDT8_H diff --git a/third_party/ORB_SLAM3/include/CameraModels/Pinhole.h b/third_party/ORB_SLAM3/include/CameraModels/Pinhole.h new file mode 100644 index 0000000..542ea66 --- /dev/null +++ b/third_party/ORB_SLAM3/include/CameraModels/Pinhole.h @@ -0,0 +1,110 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + +#ifndef CAMERAMODELS_PINHOLE_H +#define CAMERAMODELS_PINHOLE_H + +#include +#include +#include + +#include +#include +#include +#include + +#include "GeometricCamera.h" + +#include "TwoViewReconstruction.h" + +namespace ORB_SLAM3 { + class Pinhole : public GeometricCamera { + + friend class boost::serialization::access; + + template + void serialize(Archive& ar, const unsigned int version) + { + ar & boost::serialization::base_object(*this); + } + + public: + Pinhole() { + mvParameters.resize(4); + mnId=nNextId++; + mnType = CAM_PINHOLE; + } + Pinhole(const std::vector _vParameters) : GeometricCamera(_vParameters), tvr(nullptr) { + assert(mvParameters.size() == 4); + mnId=nNextId++; + mnType = CAM_PINHOLE; + } + + Pinhole(Pinhole* pPinhole) : GeometricCamera(pPinhole->mvParameters), tvr(nullptr) { + assert(mvParameters.size() == 4); + mnId=nNextId++; + mnType = CAM_PINHOLE; + } + + + ~Pinhole(){ + if(tvr) delete tvr; + } + + cv::Point2f project(const cv::Point3f &p3D); + cv::Point2f project(const cv::Mat &m3D); + Eigen::Vector2d project(const Eigen::Vector3d & v3D); + cv::Mat projectMat(const cv::Point3f& p3D); + + float uncertainty2(const Eigen::Matrix &p2D); + + cv::Point3f unproject(const cv::Point2f &p2D); + cv::Mat unprojectMat(const cv::Point2f &p2D); + + cv::Mat projectJac(const cv::Point3f &p3D); + Eigen::Matrix projectJac(const Eigen::Vector3d& v3D); + + cv::Mat unprojectJac(const cv::Point2f &p2D); + + bool ReconstructWithTwoViews(const std::vector& vKeys1, const std::vector& vKeys2, const std::vector &vMatches12, + cv::Mat &R21, cv::Mat &t21, std::vector &vP3D, std::vector &vbTriangulated); + + cv::Mat toK(); + + bool epipolarConstrain(GeometricCamera* pCamera2, const cv::KeyPoint& kp1, const cv::KeyPoint& kp2, const cv::Mat& R12, const cv::Mat& t12, const float sigmaLevel, const float unc); + + bool matchAndtriangulate(const cv::KeyPoint& kp1, const cv::KeyPoint& kp2, GeometricCamera* pOther, + cv::Mat& Tcw1, cv::Mat& Tcw2, + const float sigmaLevel1, const float sigmaLevel2, + cv::Mat& x3Dtriangulated) { return false;} + + friend std::ostream& operator<<(std::ostream& os, const Pinhole& ph); + friend std::istream& operator>>(std::istream& os, Pinhole& ph); + private: + cv::Mat SkewSymmetricMatrix(const cv::Mat &v); + + //Parameters vector corresponds to + // [fx, fy, cx, cy] + + TwoViewReconstruction* tvr; + }; +} + +//BOOST_CLASS_EXPORT_KEY(ORBSLAM2::Pinhole) + +#endif //CAMERAMODELS_PINHOLE_H diff --git a/third_party/ORB_SLAM3/include/Converter.h b/third_party/ORB_SLAM3/include/Converter.h new file mode 100644 index 0000000..48438f7 --- /dev/null +++ b/third_party/ORB_SLAM3/include/Converter.h @@ -0,0 +1,63 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + + +#ifndef CONVERTER_H +#define CONVERTER_H + +#include + +#include +#include"Thirdparty/g2o/g2o/types/types_six_dof_expmap.h" +#include"Thirdparty/g2o/g2o/types/types_seven_dof_expmap.h" + +namespace ORB_SLAM3 +{ + +class Converter +{ +public: + static std::vector toDescriptorVector(const cv::Mat &Descriptors); + + static g2o::SE3Quat toSE3Quat(const cv::Mat &cvT); + static g2o::SE3Quat toSE3Quat(const g2o::Sim3 &gSim3); + + static cv::Mat toCvMat(const g2o::SE3Quat &SE3); + static cv::Mat toCvMat(const g2o::Sim3 &Sim3); + static cv::Mat toCvMat(const Eigen::Matrix &m); + static cv::Mat toCvMat(const Eigen::Matrix3d &m); + static cv::Mat toCvMat(const Eigen::Matrix &m); + static cv::Mat toCvMat(const Eigen::MatrixXd &m); + + static cv::Mat toCvSE3(const Eigen::Matrix &R, const Eigen::Matrix &t); + static cv::Mat tocvSkewMatrix(const cv::Mat &v); + + static Eigen::Matrix toVector3d(const cv::Mat &cvVector); + static Eigen::Matrix toVector3d(const cv::Point3f &cvPoint); + static Eigen::Matrix toMatrix3d(const cv::Mat &cvMat3); + static Eigen::Matrix toMatrix4d(const cv::Mat &cvMat4); + static std::vector toQuaternion(const cv::Mat &M); + + static bool isRotationMatrix(const cv::Mat &R); + static std::vector toEuler(const cv::Mat &R); + +}; + +}// namespace ORB_SLAM + +#endif // CONVERTER_H diff --git a/third_party/ORB_SLAM3/include/Frame.h b/third_party/ORB_SLAM3/include/Frame.h new file mode 100644 index 0000000..c896bc2 --- /dev/null +++ b/third_party/ORB_SLAM3/include/Frame.h @@ -0,0 +1,325 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + + +#ifndef FRAME_H +#define FRAME_H + +//#define SAVE_TIMES + +#include + +#include "Thirdparty/DBoW2/DBoW2/BowVector.h" +#include "Thirdparty/DBoW2/DBoW2/FeatureVector.h" + +#include "ImuTypes.h" +#include "ORBVocabulary.h" + +#include +#include + +namespace ORB_SLAM3 +{ +#define FRAME_GRID_ROWS 48 +#define FRAME_GRID_COLS 64 + +class MapPoint; +class KeyFrame; +class ConstraintPoseImu; +class GeometricCamera; +class ORBextractor; + +class Frame +{ +public: + Frame(); + + // Copy constructor. + Frame(const Frame &frame); + + // Constructor for stereo cameras. + Frame(const cv::Mat &imLeft, const cv::Mat &imRight, const double &timeStamp, ORBextractor* extractorLeft, ORBextractor* extractorRight, ORBVocabulary* voc, cv::Mat &K, cv::Mat &distCoef, const float &bf, const float &thDepth, GeometricCamera* pCamera,Frame* pPrevF = static_cast(NULL), const IMU::Calib &ImuCalib = IMU::Calib()); + + // Constructor for RGB-D cameras. + Frame(const cv::Mat &imGray, const cv::Mat &imDepth, const double &timeStamp, ORBextractor* extractor,ORBVocabulary* voc, cv::Mat &K, cv::Mat &distCoef, const float &bf, const float &thDepth, GeometricCamera* pCamera,Frame* pPrevF = static_cast(NULL), const IMU::Calib &ImuCalib = IMU::Calib()); + + // Constructor for Monocular cameras. + Frame(const cv::Mat &imGray, const double &timeStamp, ORBextractor* extractor,ORBVocabulary* voc, GeometricCamera* pCamera, cv::Mat &distCoef, const float &bf, const float &thDepth, Frame* pPrevF = static_cast(NULL), const IMU::Calib &ImuCalib = IMU::Calib()); + + // Destructor + // ~Frame(); + + // Extract ORB on the image. 0 for left image and 1 for right image. + void ExtractORB(int flag, const cv::Mat &im, const int x0, const int x1); + + // Compute Bag of Words representation. + void ComputeBoW(); + + // Set the camera pose. (Imu pose is not modified!) + void SetPose(cv::Mat Tcw); + void GetPose(cv::Mat &Tcw); + + // Set IMU velocity + void SetVelocity(const cv::Mat &Vwb); + + // Set IMU pose and velocity (implicitly changes camera pose) + void SetImuPoseVelocity(const cv::Mat &Rwb, const cv::Mat &twb, const cv::Mat &Vwb); + + + // Computes rotation, translation and camera center matrices from the camera pose. + void UpdatePoseMatrices(); + + // Returns the camera center. + inline cv::Mat GetCameraCenter(){ + return mOw.clone(); + } + + // Returns inverse of rotation + inline cv::Mat GetRotationInverse(){ + return mRwc.clone(); + } + + cv::Mat GetImuPosition(); + cv::Mat GetImuRotation(); + cv::Mat GetImuPose(); + + void SetNewBias(const IMU::Bias &b); + + // Check if a MapPoint is in the frustum of the camera + // and fill variables of the MapPoint to be used by the tracking + bool isInFrustum(MapPoint* pMP, float viewingCosLimit); + + bool ProjectPointDistort(MapPoint* pMP, cv::Point2f &kp, float &u, float &v); + + cv::Mat inRefCoordinates(cv::Mat pCw); + + // Compute the cell of a keypoint (return false if outside the grid) + bool PosInGrid(const cv::KeyPoint &kp, int &posX, int &posY); + + vector GetFeaturesInArea(const float &x, const float &y, const float &r, const int minLevel=-1, const int maxLevel=-1, const bool bRight = false) const; + + // Search a match for each keypoint in the left image to a keypoint in the right image. + // If there is a match, depth is computed and the right coordinate associated to the left keypoint is stored. + void ComputeStereoMatches(); + + // Associate a "right" coordinate to a keypoint if there is valid depth in the depthmap. + void ComputeStereoFromRGBD(const cv::Mat &imDepth); + + // Backprojects a keypoint (if stereo/depth info available) into 3D world coordinates. + cv::Mat UnprojectStereo(const int &i); + + ConstraintPoseImu* mpcpi; + + bool imuIsPreintegrated(); + void setIntegrated(); + + cv::Mat mRwc; + cv::Mat mOw; +public: + // Vocabulary used for relocalization. + ORBVocabulary* mpORBvocabulary; + + // Feature extractor. The right is used only in the stereo case. + ORBextractor* mpORBextractorLeft, *mpORBextractorRight; + + // Frame timestamp. + double mTimeStamp; + + // Calibration matrix and OpenCV distortion parameters. + cv::Mat mK; + static float fx; + static float fy; + static float cx; + static float cy; + static float invfx; + static float invfy; + cv::Mat mDistCoef; + + // Stereo baseline multiplied by fx. + float mbf; + + // Stereo baseline in meters. + float mb; + + // Threshold close/far points. Close points are inserted from 1 view. + // Far points are inserted as in the monocular case from 2 views. + float mThDepth; + + // Number of KeyPoints. + int N; + + // Vector of keypoints (original for visualization) and undistorted (actually used by the system). + // In the stereo case, mvKeysUn is redundant as images must be rectified. + // In the RGB-D case, RGB images can be distorted. + std::vector mvKeys, mvKeysRight; + std::vector mvKeysUn; + + // Corresponding stereo coordinate and depth for each keypoint. + std::vector mvpMapPoints; + // "Monocular" keypoints have a negative value. + std::vector mvuRight; + std::vector mvDepth; + + // Bag of Words Vector structures. + DBoW2::BowVector mBowVec; + DBoW2::FeatureVector mFeatVec; + + // ORB descriptor, each row associated to a keypoint. + cv::Mat mDescriptors, mDescriptorsRight; + + // MapPoints associated to keypoints, NULL pointer if no association. + // Flag to identify outlier associations. + std::vector mvbOutlier; + int mnCloseMPs; + + // Keypoints are assigned to cells in a grid to reduce matching complexity when projecting MapPoints. + static float mfGridElementWidthInv; + static float mfGridElementHeightInv; + std::vector mGrid[FRAME_GRID_COLS][FRAME_GRID_ROWS]; + + + // Camera pose. + cv::Mat mTcw; + + // IMU linear velocity + cv::Mat mVw; + + cv::Mat mPredRwb, mPredtwb, mPredVwb; + IMU::Bias mPredBias; + + // IMU bias + IMU::Bias mImuBias; + + // Imu calibration + IMU::Calib mImuCalib; + + // Imu preintegration from last keyframe + IMU::Preintegrated* mpImuPreintegrated; + KeyFrame* mpLastKeyFrame; + + // Pointer to previous frame + Frame* mpPrevFrame; + IMU::Preintegrated* mpImuPreintegratedFrame; + + // Current and Next Frame id. + static long unsigned int nNextId; + long unsigned int mnId; + + // Reference Keyframe. + KeyFrame* mpReferenceKF; + + // Scale pyramid info. + int mnScaleLevels; + float mfScaleFactor; + float mfLogScaleFactor; + vector mvScaleFactors; + vector mvInvScaleFactors; + vector mvLevelSigma2; + vector mvInvLevelSigma2; + + // Undistorted Image Bounds (computed once). + static float mnMinX; + static float mnMaxX; + static float mnMinY; + static float mnMaxY; + + static bool mbInitialComputations; + + map mmProjectPoints; + map mmMatchedInImage; + + string mNameFile; + + int mnDataset; + + double mTimeStereoMatch; + double mTimeORB_Ext; + + +private: + + // Undistort keypoints given OpenCV distortion parameters. + // Only for the RGB-D case. Stereo must be already rectified! + // (called in the constructor). + void UndistortKeyPoints(); + + // Computes image bounds for the undistorted image (called in the constructor). + void ComputeImageBounds(const cv::Mat &imLeft); + + // Assign keypoints to the grid for speed up feature matching (called in the constructor). + void AssignFeaturesToGrid(); + + // Rotation, translation and camera center + cv::Mat mRcw; + cv::Mat mtcw; + //==mtwc + + bool mbImuPreintegrated; + + std::mutex *mpMutexImu; + +public: + GeometricCamera* mpCamera, *mpCamera2; + + //Number of KeyPoints extracted in the left and right images + int Nleft, Nright; + //Number of Non Lapping Keypoints + int monoLeft, monoRight; + + //For stereo matching + std::vector mvLeftToRightMatch, mvRightToLeftMatch; + + //For stereo fisheye matching + static cv::BFMatcher BFmatcher; + + //Triangulated stereo observations using as reference the left camera. These are + //computed during ComputeStereoFishEyeMatches + std::vector mvStereo3Dpoints; + + //Grid for the right image + std::vector mGridRight[FRAME_GRID_COLS][FRAME_GRID_ROWS]; + + cv::Mat mTlr, mRlr, mtlr, mTrl; + + Frame(const cv::Mat &imLeft, const cv::Mat &imRight, const double &timeStamp, ORBextractor* extractorLeft, ORBextractor* extractorRight, ORBVocabulary* voc, cv::Mat &K, cv::Mat &distCoef, const float &bf, const float &thDepth, GeometricCamera* pCamera, GeometricCamera* pCamera2, cv::Mat& Tlr,Frame* pPrevF = static_cast(NULL), const IMU::Calib &ImuCalib = IMU::Calib()); + + //Stereo fisheye + void ComputeStereoFishEyeMatches(); + + bool isInFrustumChecks(MapPoint* pMP, float viewingCosLimit, bool bRight = false); + + cv::Mat UnprojectStereoFishEye(const int &i); + + cv::Mat imgLeft, imgRight; + + void PrintPointDistribution(){ + int left = 0, right = 0; + int Nlim = (Nleft != -1) ? Nleft : N; + for(int i = 0; i < N; i++){ + if(mvpMapPoints[i] && !mvbOutlier[i]){ + if(i < Nlim) left++; + else right++; + } + } + cout << "Point distribution in Frame: left-> " << left << " --- right-> " << right << endl; + } +}; + +}// namespace ORB_SLAM + +#endif // FRAME_H diff --git a/third_party/ORB_SLAM3/include/FrameDrawer.h b/third_party/ORB_SLAM3/include/FrameDrawer.h new file mode 100644 index 0000000..774568b --- /dev/null +++ b/third_party/ORB_SLAM3/include/FrameDrawer.h @@ -0,0 +1,88 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + + +#ifndef FRAMEDRAWER_H +#define FRAMEDRAWER_H + +#include "Tracking.h" +#include "MapPoint.h" +#include "Atlas.h" + +#include +#include + +#include +#include + + +namespace ORB_SLAM3 +{ + +class Tracking; +class Viewer; + +class FrameDrawer +{ +public: + FrameDrawer(Atlas* pAtlas); + + // Update info from the last processed frame. + void Update(Tracking *pTracker); + + // Draw last processed frame. + cv::Mat DrawFrame(bool bOldFeatures=true); + cv::Mat DrawRightFrame(); + + bool both; + +protected: + + void DrawTextInfo(cv::Mat &im, int nState, cv::Mat &imText); + + // Info of the frame to be drawn + cv::Mat mIm, mImRight; + int N; + vector mvCurrentKeys,mvCurrentKeysRight; + vector mvbMap, mvbVO; + bool mbOnlyTracking; + int mnTracked, mnTrackedVO; + vector mvIniKeys; + vector mvIniMatches; + int mState; + + Atlas* mpAtlas; + + std::mutex mMutex; + vector > mvTracks; + + Frame mCurrentFrame; + vector mvpLocalMap; + vector mvMatchedKeys; + vector mvpMatchedMPs; + vector mvOutlierKeys; + vector mvpOutlierMPs; + + map mmProjectPoints; + map mmMatchedInImage; + +}; + +} //namespace ORB_SLAM + +#endif // FRAMEDRAWER_H diff --git a/third_party/ORB_SLAM3/include/G2oTypes.h b/third_party/ORB_SLAM3/include/G2oTypes.h new file mode 100644 index 0000000..3f7113f --- /dev/null +++ b/third_party/ORB_SLAM3/include/G2oTypes.h @@ -0,0 +1,863 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + + +#ifndef G2OTYPES_H +#define G2OTYPES_H + +#include "Thirdparty/g2o/g2o/core/base_vertex.h" +#include "Thirdparty/g2o/g2o/core/base_binary_edge.h" +#include "Thirdparty/g2o/g2o/types/types_sba.h" +#include "Thirdparty/g2o/g2o/core/base_multi_edge.h" +#include "Thirdparty/g2o/g2o/core/base_unary_edge.h" + +#include + +#include +#include +#include + +#include +#include + +#include"Converter.h" +#include + +namespace ORB_SLAM3 +{ + +class KeyFrame; +class Frame; +class GeometricCamera; + +typedef Eigen::Matrix Vector6d; +typedef Eigen::Matrix Vector9d; +typedef Eigen::Matrix Vector12d; +typedef Eigen::Matrix Vector15d; +typedef Eigen::Matrix Matrix12d; +typedef Eigen::Matrix Matrix15d; +typedef Eigen::Matrix Matrix9d; + +Eigen::Matrix3d ExpSO3(const double x, const double y, const double z); +Eigen::Matrix3d ExpSO3(const Eigen::Vector3d &w); + +Eigen::Vector3d LogSO3(const Eigen::Matrix3d &R); + +Eigen::Matrix3d InverseRightJacobianSO3(const Eigen::Vector3d &v); +Eigen::Matrix3d RightJacobianSO3(const Eigen::Vector3d &v); +Eigen::Matrix3d RightJacobianSO3(const double x, const double y, const double z); + +Eigen::Matrix3d Skew(const Eigen::Vector3d &w); +Eigen::Matrix3d InverseRightJacobianSO3(const double x, const double y, const double z); + +Eigen::Matrix3d NormalizeRotation(const Eigen::Matrix3d &R); + + +class ImuCamPose +{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + ImuCamPose(){} + ImuCamPose(KeyFrame* pKF); + ImuCamPose(Frame* pF); + ImuCamPose(Eigen::Matrix3d &_Rwc, Eigen::Vector3d &_twc, KeyFrame* pKF); + + void SetParam(const std::vector &_Rcw, const std::vector &_tcw, const std::vector &_Rbc, + const std::vector &_tbc, const double &_bf); + + void Update(const double *pu); // update in the imu reference + void UpdateW(const double *pu); // update in the world reference + Eigen::Vector2d Project(const Eigen::Vector3d &Xw, int cam_idx=0) const; // Mono + Eigen::Vector3d ProjectStereo(const Eigen::Vector3d &Xw, int cam_idx=0) const; // Stereo + bool isDepthPositive(const Eigen::Vector3d &Xw, int cam_idx=0) const; + +public: + // For IMU + Eigen::Matrix3d Rwb; + Eigen::Vector3d twb; + + // For set of cameras + std::vector Rcw; + std::vector tcw; + std::vector Rcb, Rbc; + std::vector tcb, tbc; + double bf; + std::vector pCamera; + + // For posegraph 4DoF + Eigen::Matrix3d Rwb0; + Eigen::Matrix3d DR; + + int its; +}; + +class InvDepthPoint +{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + InvDepthPoint(){} + InvDepthPoint(double _rho, double _u, double _v, KeyFrame* pHostKF); + + void Update(const double *pu); + + double rho; + double u, v; // they are not variables, observation in the host frame + + double fx, fy, cx, cy, bf; // from host frame + + int its; +}; + +// Optimizable parameters are IMU pose +class VertexPose : public g2o::BaseVertex<6,ImuCamPose> +{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + VertexPose(){} + VertexPose(KeyFrame* pKF){ + setEstimate(ImuCamPose(pKF)); + } + VertexPose(Frame* pF){ + setEstimate(ImuCamPose(pF)); + } + + + virtual bool read(std::istream& is); + virtual bool write(std::ostream& os) const; + + virtual void setToOriginImpl() { + } + + virtual void oplusImpl(const double* update_){ + _estimate.Update(update_); + updateCache(); + } +}; + +class VertexPose4DoF : public g2o::BaseVertex<4,ImuCamPose> +{ + // Translation and yaw are the only optimizable variables +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + VertexPose4DoF(){} + VertexPose4DoF(KeyFrame* pKF){ + setEstimate(ImuCamPose(pKF)); + } + VertexPose4DoF(Frame* pF){ + setEstimate(ImuCamPose(pF)); + } + VertexPose4DoF(Eigen::Matrix3d &_Rwc, Eigen::Vector3d &_twc, KeyFrame* pKF){ + + setEstimate(ImuCamPose(_Rwc, _twc, pKF)); + } + + virtual bool read(std::istream& is){return false;} + virtual bool write(std::ostream& os) const{return false;} + + virtual void setToOriginImpl() { + } + + virtual void oplusImpl(const double* update_){ + double update6DoF[6]; + update6DoF[0] = 0; + update6DoF[1] = 0; + update6DoF[2] = update_[0]; + update6DoF[3] = update_[1]; + update6DoF[4] = update_[2]; + update6DoF[5] = update_[3]; + _estimate.UpdateW(update6DoF); + updateCache(); + } +}; + +class VertexVelocity : public g2o::BaseVertex<3,Eigen::Vector3d> +{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + VertexVelocity(){} + VertexVelocity(KeyFrame* pKF); + VertexVelocity(Frame* pF); + + virtual bool read(std::istream& is){return false;} + virtual bool write(std::ostream& os) const{return false;} + + virtual void setToOriginImpl() { + } + + virtual void oplusImpl(const double* update_){ + Eigen::Vector3d uv; + uv << update_[0], update_[1], update_[2]; + setEstimate(estimate()+uv); + } +}; + +class VertexGyroBias : public g2o::BaseVertex<3,Eigen::Vector3d> +{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + VertexGyroBias(){} + VertexGyroBias(KeyFrame* pKF); + VertexGyroBias(Frame* pF); + + virtual bool read(std::istream& is){return false;} + virtual bool write(std::ostream& os) const{return false;} + + virtual void setToOriginImpl() { + } + + virtual void oplusImpl(const double* update_){ + Eigen::Vector3d ubg; + ubg << update_[0], update_[1], update_[2]; + setEstimate(estimate()+ubg); + } +}; + + +class VertexAccBias : public g2o::BaseVertex<3,Eigen::Vector3d> +{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + VertexAccBias(){} + VertexAccBias(KeyFrame* pKF); + VertexAccBias(Frame* pF); + + virtual bool read(std::istream& is){return false;} + virtual bool write(std::ostream& os) const{return false;} + + virtual void setToOriginImpl() { + } + + virtual void oplusImpl(const double* update_){ + Eigen::Vector3d uba; + uba << update_[0], update_[1], update_[2]; + setEstimate(estimate()+uba); + } +}; + + +// Gravity direction vertex +class GDirection +{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GDirection(){} + GDirection(Eigen::Matrix3d pRwg): Rwg(pRwg){} + + void Update(const double *pu) + { + Rwg=Rwg*ExpSO3(pu[0],pu[1],0.0); + } + + Eigen::Matrix3d Rwg, Rgw; + + int its; +}; + +class VertexGDir : public g2o::BaseVertex<2,GDirection> +{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + VertexGDir(){} + VertexGDir(Eigen::Matrix3d pRwg){ + setEstimate(GDirection(pRwg)); + } + + virtual bool read(std::istream& is){return false;} + virtual bool write(std::ostream& os) const{return false;} + + virtual void setToOriginImpl() { + } + + virtual void oplusImpl(const double* update_){ + _estimate.Update(update_); + updateCache(); + } +}; + +// scale vertex +class VertexScale : public g2o::BaseVertex<1,double> +{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + VertexScale(){ + setEstimate(1.0); + } + VertexScale(double ps){ + setEstimate(ps); + } + + virtual bool read(std::istream& is){return false;} + virtual bool write(std::ostream& os) const{return false;} + + virtual void setToOriginImpl(){ + setEstimate(1.0); + } + + virtual void oplusImpl(const double *update_){ + setEstimate(estimate()*exp(*update_)); + } +}; + + +// Inverse depth point (just one parameter, inverse depth at the host frame) +class VertexInvDepth : public g2o::BaseVertex<1,InvDepthPoint> +{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + VertexInvDepth(){} + VertexInvDepth(double invDepth, double u, double v, KeyFrame* pHostKF){ + setEstimate(InvDepthPoint(invDepth, u, v, pHostKF)); + } + + virtual bool read(std::istream& is){return false;} + virtual bool write(std::ostream& os) const{return false;} + + virtual void setToOriginImpl() { + } + + virtual void oplusImpl(const double* update_){ + _estimate.Update(update_); + updateCache(); + } +}; + +class EdgeMono : public g2o::BaseBinaryEdge<2,Eigen::Vector2d,g2o::VertexSBAPointXYZ,VertexPose> +{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + EdgeMono(int cam_idx_=0): cam_idx(cam_idx_){ + } + + virtual bool read(std::istream& is){return false;} + virtual bool write(std::ostream& os) const{return false;} + + void computeError(){ + const g2o::VertexSBAPointXYZ* VPoint = static_cast(_vertices[0]); + const VertexPose* VPose = static_cast(_vertices[1]); + const Eigen::Vector2d obs(_measurement); + _error = obs - VPose->estimate().Project(VPoint->estimate(),cam_idx); + } + + + virtual void linearizeOplus(); + + bool isDepthPositive() + { + const g2o::VertexSBAPointXYZ* VPoint = static_cast(_vertices[0]); + const VertexPose* VPose = static_cast(_vertices[1]); + return VPose->estimate().isDepthPositive(VPoint->estimate(),cam_idx); + } + + Eigen::Matrix GetJacobian(){ + linearizeOplus(); + Eigen::Matrix J; + J.block<2,3>(0,0) = _jacobianOplusXi; + J.block<2,6>(0,3) = _jacobianOplusXj; + return J; + } + + Eigen::Matrix GetHessian(){ + linearizeOplus(); + Eigen::Matrix J; + J.block<2,3>(0,0) = _jacobianOplusXi; + J.block<2,6>(0,3) = _jacobianOplusXj; + return J.transpose()*information()*J; + } + +public: + const int cam_idx; +}; + +class EdgeMonoOnlyPose : public g2o::BaseUnaryEdge<2,Eigen::Vector2d,VertexPose> +{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + EdgeMonoOnlyPose(const cv::Mat &Xw_, int cam_idx_=0):Xw(Converter::toVector3d(Xw_)), + cam_idx(cam_idx_){} + + virtual bool read(std::istream& is){return false;} + virtual bool write(std::ostream& os) const{return false;} + + void computeError(){ + const VertexPose* VPose = static_cast(_vertices[0]); + const Eigen::Vector2d obs(_measurement); + _error = obs - VPose->estimate().Project(Xw,cam_idx); + } + + virtual void linearizeOplus(); + + bool isDepthPositive() + { + const VertexPose* VPose = static_cast(_vertices[0]); + return VPose->estimate().isDepthPositive(Xw,cam_idx); + } + + Eigen::Matrix GetHessian(){ + linearizeOplus(); + return _jacobianOplusXi.transpose()*information()*_jacobianOplusXi; + } + +public: + const Eigen::Vector3d Xw; + const int cam_idx; +}; + +class EdgeStereo : public g2o::BaseBinaryEdge<3,Eigen::Vector3d,g2o::VertexSBAPointXYZ,VertexPose> +{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + EdgeStereo(int cam_idx_=0): cam_idx(cam_idx_){} + + virtual bool read(std::istream& is){return false;} + virtual bool write(std::ostream& os) const{return false;} + + void computeError(){ + const g2o::VertexSBAPointXYZ* VPoint = static_cast(_vertices[0]); + const VertexPose* VPose = static_cast(_vertices[1]); + const Eigen::Vector3d obs(_measurement); + _error = obs - VPose->estimate().ProjectStereo(VPoint->estimate(),cam_idx); + } + + + virtual void linearizeOplus(); + + Eigen::Matrix GetJacobian(){ + linearizeOplus(); + Eigen::Matrix J; + J.block<3,3>(0,0) = _jacobianOplusXi; + J.block<3,6>(0,3) = _jacobianOplusXj; + return J; + } + + Eigen::Matrix GetHessian(){ + linearizeOplus(); + Eigen::Matrix J; + J.block<3,3>(0,0) = _jacobianOplusXi; + J.block<3,6>(0,3) = _jacobianOplusXj; + return J.transpose()*information()*J; + } + +public: + const int cam_idx; +}; + + +class EdgeStereoOnlyPose : public g2o::BaseUnaryEdge<3,Eigen::Vector3d,VertexPose> +{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + EdgeStereoOnlyPose(const cv::Mat &Xw_, int cam_idx_=0): + Xw(Converter::toVector3d(Xw_)), cam_idx(cam_idx_){} + + virtual bool read(std::istream& is){return false;} + virtual bool write(std::ostream& os) const{return false;} + + void computeError(){ + const VertexPose* VPose = static_cast(_vertices[0]); + const Eigen::Vector3d obs(_measurement); + _error = obs - VPose->estimate().ProjectStereo(Xw, cam_idx); + } + + virtual void linearizeOplus(); + + Eigen::Matrix GetHessian(){ + linearizeOplus(); + return _jacobianOplusXi.transpose()*information()*_jacobianOplusXi; + } + +public: + const Eigen::Vector3d Xw; // 3D point coordinates + const int cam_idx; +}; + +class EdgeInertial : public g2o::BaseMultiEdge<9,Vector9d> +{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + EdgeInertial(IMU::Preintegrated* pInt); + + virtual bool read(std::istream& is){return false;} + virtual bool write(std::ostream& os) const{return false;} + + void computeError(); + virtual void linearizeOplus(); + + Eigen::Matrix GetHessian(){ + linearizeOplus(); + Eigen::Matrix J; + J.block<9,6>(0,0) = _jacobianOplus[0]; + J.block<9,3>(0,6) = _jacobianOplus[1]; + J.block<9,3>(0,9) = _jacobianOplus[2]; + J.block<9,3>(0,12) = _jacobianOplus[3]; + J.block<9,6>(0,15) = _jacobianOplus[4]; + J.block<9,3>(0,21) = _jacobianOplus[5]; + return J.transpose()*information()*J; + } + + Eigen::Matrix GetHessianNoPose1(){ + linearizeOplus(); + Eigen::Matrix J; + J.block<9,3>(0,0) = _jacobianOplus[1]; + J.block<9,3>(0,3) = _jacobianOplus[2]; + J.block<9,3>(0,6) = _jacobianOplus[3]; + J.block<9,6>(0,9) = _jacobianOplus[4]; + J.block<9,3>(0,15) = _jacobianOplus[5]; + return J.transpose()*information()*J; + } + + Eigen::Matrix GetHessian2(){ + linearizeOplus(); + Eigen::Matrix J; + J.block<9,6>(0,0) = _jacobianOplus[4]; + J.block<9,3>(0,6) = _jacobianOplus[5]; + return J.transpose()*information()*J; + } + + const Eigen::Matrix3d JRg, JVg, JPg; + const Eigen::Matrix3d JVa, JPa; + IMU::Preintegrated* mpInt; + const double dt; + Eigen::Vector3d g; +}; + + +// Edge inertial whre gravity is included as optimizable variable and it is not supposed to be pointing in -z axis, as well as scale +class EdgeInertialGS : public g2o::BaseMultiEdge<9,Vector9d> +{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + // EdgeInertialGS(IMU::Preintegrated* pInt); + EdgeInertialGS(IMU::Preintegrated* pInt); + + virtual bool read(std::istream& is){return false;} + virtual bool write(std::ostream& os) const{return false;} + + void computeError(); + virtual void linearizeOplus(); + + const Eigen::Matrix3d JRg, JVg, JPg; + const Eigen::Matrix3d JVa, JPa; + IMU::Preintegrated* mpInt; + const double dt; + Eigen::Vector3d g, gI; + + Eigen::Matrix GetHessian(){ + linearizeOplus(); + Eigen::Matrix J; + J.block<9,6>(0,0) = _jacobianOplus[0]; + J.block<9,3>(0,6) = _jacobianOplus[1]; + J.block<9,3>(0,9) = _jacobianOplus[2]; + J.block<9,3>(0,12) = _jacobianOplus[3]; + J.block<9,6>(0,15) = _jacobianOplus[4]; + J.block<9,3>(0,21) = _jacobianOplus[5]; + J.block<9,2>(0,24) = _jacobianOplus[6]; + J.block<9,1>(0,26) = _jacobianOplus[7]; + return J.transpose()*information()*J; + } + + Eigen::Matrix GetHessian2(){ + linearizeOplus(); + Eigen::Matrix J; + J.block<9,3>(0,0) = _jacobianOplus[2]; + J.block<9,3>(0,3) = _jacobianOplus[3]; + J.block<9,2>(0,6) = _jacobianOplus[6]; + J.block<9,1>(0,8) = _jacobianOplus[7]; + J.block<9,3>(0,9) = _jacobianOplus[1]; + J.block<9,3>(0,12) = _jacobianOplus[5]; + J.block<9,6>(0,15) = _jacobianOplus[0]; + J.block<9,6>(0,21) = _jacobianOplus[4]; + return J.transpose()*information()*J; + } + + Eigen::Matrix GetHessian3(){ + linearizeOplus(); + Eigen::Matrix J; + J.block<9,3>(0,0) = _jacobianOplus[2]; + J.block<9,3>(0,3) = _jacobianOplus[3]; + J.block<9,2>(0,6) = _jacobianOplus[6]; + J.block<9,1>(0,8) = _jacobianOplus[7]; + return J.transpose()*information()*J; + } + + + + Eigen::Matrix GetHessianScale(){ + linearizeOplus(); + Eigen::Matrix J = _jacobianOplus[7]; + return J.transpose()*information()*J; + } + + Eigen::Matrix GetHessianBiasGyro(){ + linearizeOplus(); + Eigen::Matrix J = _jacobianOplus[2]; + return J.transpose()*information()*J; + } + + Eigen::Matrix GetHessianBiasAcc(){ + linearizeOplus(); + Eigen::Matrix J = _jacobianOplus[3]; + return J.transpose()*information()*J; + } + + Eigen::Matrix GetHessianGDir(){ + linearizeOplus(); + Eigen::Matrix J = _jacobianOplus[6]; + return J.transpose()*information()*J; + } +}; + + + +class EdgeGyroRW : public g2o::BaseBinaryEdge<3,Eigen::Vector3d,VertexGyroBias,VertexGyroBias> +{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + EdgeGyroRW(){} + + virtual bool read(std::istream& is){return false;} + virtual bool write(std::ostream& os) const{return false;} + + void computeError(){ + const VertexGyroBias* VG1= static_cast(_vertices[0]); + const VertexGyroBias* VG2= static_cast(_vertices[1]); + _error = VG2->estimate()-VG1->estimate(); + } + + virtual void linearizeOplus(){ + _jacobianOplusXi = -Eigen::Matrix3d::Identity(); + _jacobianOplusXj.setIdentity(); + } + + Eigen::Matrix GetHessian(){ + linearizeOplus(); + Eigen::Matrix J; + J.block<3,3>(0,0) = _jacobianOplusXi; + J.block<3,3>(0,3) = _jacobianOplusXj; + return J.transpose()*information()*J; + } + + Eigen::Matrix3d GetHessian2(){ + linearizeOplus(); + return _jacobianOplusXj.transpose()*information()*_jacobianOplusXj; + } +}; + + +class EdgeAccRW : public g2o::BaseBinaryEdge<3,Eigen::Vector3d,VertexAccBias,VertexAccBias> +{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + EdgeAccRW(){} + + virtual bool read(std::istream& is){return false;} + virtual bool write(std::ostream& os) const{return false;} + + void computeError(){ + const VertexAccBias* VA1= static_cast(_vertices[0]); + const VertexAccBias* VA2= static_cast(_vertices[1]); + _error = VA2->estimate()-VA1->estimate(); + } + + virtual void linearizeOplus(){ + _jacobianOplusXi = -Eigen::Matrix3d::Identity(); + _jacobianOplusXj.setIdentity(); + } + + Eigen::Matrix GetHessian(){ + linearizeOplus(); + Eigen::Matrix J; + J.block<3,3>(0,0) = _jacobianOplusXi; + J.block<3,3>(0,3) = _jacobianOplusXj; + return J.transpose()*information()*J; + } + + Eigen::Matrix3d GetHessian2(){ + linearizeOplus(); + return _jacobianOplusXj.transpose()*information()*_jacobianOplusXj; + } +}; + +class ConstraintPoseImu +{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + ConstraintPoseImu(const Eigen::Matrix3d &Rwb_, const Eigen::Vector3d &twb_, const Eigen::Vector3d &vwb_, + const Eigen::Vector3d &bg_, const Eigen::Vector3d &ba_, const Matrix15d &H_): + Rwb(Rwb_), twb(twb_), vwb(vwb_), bg(bg_), ba(ba_), H(H_) + { + H = (H+H)/2; + Eigen::SelfAdjointEigenSolver > es(H); + Eigen::Matrix eigs = es.eigenvalues(); + for(int i=0;i<15;i++) + if(eigs[i]<1e-12) + eigs[i]=0; + H = es.eigenvectors()*eigs.asDiagonal()*es.eigenvectors().transpose(); + } + ConstraintPoseImu(const cv::Mat &Rwb_, const cv::Mat &twb_, const cv::Mat &vwb_, + const IMU::Bias &b, const cv::Mat &H_) + { + Rwb = Converter::toMatrix3d(Rwb_); + twb = Converter::toVector3d(twb_); + vwb = Converter::toVector3d(vwb_); + bg << b.bwx, b.bwy, b.bwz; + ba << b.bax, b.bay, b.baz; + for(int i=0;i<15;i++) + for(int j=0;j<15;j++) + H(i,j)=H_.at(i,j); + H = (H+H)/2; + Eigen::SelfAdjointEigenSolver > es(H); + Eigen::Matrix eigs = es.eigenvalues(); + for(int i=0;i<15;i++) + if(eigs[i]<1e-12) + eigs[i]=0; + H = es.eigenvectors()*eigs.asDiagonal()*es.eigenvectors().transpose(); + } + + Eigen::Matrix3d Rwb; + Eigen::Vector3d twb; + Eigen::Vector3d vwb; + Eigen::Vector3d bg; + Eigen::Vector3d ba; + Matrix15d H; +}; + +class EdgePriorPoseImu : public g2o::BaseMultiEdge<15,Vector15d> +{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + EdgePriorPoseImu(ConstraintPoseImu* c); + + virtual bool read(std::istream& is){return false;} + virtual bool write(std::ostream& os) const{return false;} + + void computeError(); + virtual void linearizeOplus(); + + Eigen::Matrix GetHessian(){ + linearizeOplus(); + Eigen::Matrix J; + J.block<15,6>(0,0) = _jacobianOplus[0]; + J.block<15,3>(0,6) = _jacobianOplus[1]; + J.block<15,3>(0,9) = _jacobianOplus[2]; + J.block<15,3>(0,12) = _jacobianOplus[3]; + return J.transpose()*information()*J; + } + + Eigen::Matrix GetHessianNoPose(){ + linearizeOplus(); + Eigen::Matrix J; + J.block<15,3>(0,0) = _jacobianOplus[1]; + J.block<15,3>(0,3) = _jacobianOplus[2]; + J.block<15,3>(0,6) = _jacobianOplus[3]; + return J.transpose()*information()*J; + } + Eigen::Matrix3d Rwb; + Eigen::Vector3d twb, vwb; + Eigen::Vector3d bg, ba; +}; + +// Priors for biases +class EdgePriorAcc : public g2o::BaseUnaryEdge<3,Eigen::Vector3d,VertexAccBias> +{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + EdgePriorAcc(const cv::Mat &bprior_):bprior(Converter::toVector3d(bprior_)){} + + virtual bool read(std::istream& is){return false;} + virtual bool write(std::ostream& os) const{return false;} + + void computeError(){ + const VertexAccBias* VA = static_cast(_vertices[0]); + _error = bprior - VA->estimate(); + } + virtual void linearizeOplus(); + + Eigen::Matrix GetHessian(){ + linearizeOplus(); + return _jacobianOplusXi.transpose()*information()*_jacobianOplusXi; + } + + const Eigen::Vector3d bprior; +}; + +class EdgePriorGyro : public g2o::BaseUnaryEdge<3,Eigen::Vector3d,VertexGyroBias> +{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + EdgePriorGyro(const cv::Mat &bprior_):bprior(Converter::toVector3d(bprior_)){} + + virtual bool read(std::istream& is){return false;} + virtual bool write(std::ostream& os) const{return false;} + + void computeError(){ + const VertexGyroBias* VG = static_cast(_vertices[0]); + _error = bprior - VG->estimate(); + } + virtual void linearizeOplus(); + + Eigen::Matrix GetHessian(){ + linearizeOplus(); + return _jacobianOplusXi.transpose()*information()*_jacobianOplusXi; + } + + const Eigen::Vector3d bprior; +}; + + +class Edge4DoF : public g2o::BaseBinaryEdge<6,Vector6d,VertexPose4DoF,VertexPose4DoF> +{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + Edge4DoF(const Eigen::Matrix4d &deltaT){ + dTij = deltaT; + dRij = deltaT.block<3,3>(0,0); + dtij = deltaT.block<3,1>(0,3); + } + + virtual bool read(std::istream& is){return false;} + virtual bool write(std::ostream& os) const{return false;} + + void computeError(){ + const VertexPose4DoF* VPi = static_cast(_vertices[0]); + const VertexPose4DoF* VPj = static_cast(_vertices[1]); + _error << LogSO3(VPi->estimate().Rcw[0]*VPj->estimate().Rcw[0].transpose()*dRij.transpose()), + VPi->estimate().Rcw[0]*(-VPj->estimate().Rcw[0].transpose()*VPj->estimate().tcw[0])+VPi->estimate().tcw[0] - dtij; + } + + // virtual void linearizeOplus(); // numerical implementation + + Eigen::Matrix4d dTij; + Eigen::Matrix3d dRij; + Eigen::Vector3d dtij; +}; + +} //namespace ORB_SLAM2 + +#endif // G2OTYPES_H diff --git a/third_party/ORB_SLAM3/include/ImuTypes.h b/third_party/ORB_SLAM3/include/ImuTypes.h new file mode 100644 index 0000000..d3da0a8 --- /dev/null +++ b/third_party/ORB_SLAM3/include/ImuTypes.h @@ -0,0 +1,285 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + + +#ifndef IMUTYPES_H +#define IMUTYPES_H + +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +namespace ORB_SLAM3 +{ + +namespace IMU +{ + +const float GRAVITY_VALUE=9.81; + +//IMU measurement (gyro, accelerometer and timestamp) +class Point +{ +public: + Point(const float &acc_x, const float &acc_y, const float &acc_z, + const float &ang_vel_x, const float &ang_vel_y, const float &ang_vel_z, + const double ×tamp): a(acc_x,acc_y,acc_z), w(ang_vel_x,ang_vel_y,ang_vel_z), t(timestamp){} + Point(const cv::Point3f Acc, const cv::Point3f Gyro, const double ×tamp): + a(Acc.x,Acc.y,Acc.z), w(Gyro.x,Gyro.y,Gyro.z), t(timestamp){} +public: + cv::Point3f a; + cv::Point3f w; + double t; +}; + +//IMU biases (gyro and accelerometer) +class Bias +{ + friend class boost::serialization::access; + template + void serialize(Archive & ar, const unsigned int version) + { + ar & bax; + ar & bay; + ar & baz; + + ar & bwx; + ar & bwy; + ar & bwz; + } + +public: + Bias():bax(0),bay(0),baz(0),bwx(0),bwy(0),bwz(0){} + Bias(const float &b_acc_x, const float &b_acc_y, const float &b_acc_z, + const float &b_ang_vel_x, const float &b_ang_vel_y, const float &b_ang_vel_z): + bax(b_acc_x), bay(b_acc_y), baz(b_acc_z), bwx(b_ang_vel_x), bwy(b_ang_vel_y), bwz(b_ang_vel_z){} + void CopyFrom(Bias &b); + friend std::ostream& operator<< (std::ostream &out, const Bias &b); + +public: + float bax, bay, baz; + float bwx, bwy, bwz; +}; + +//IMU calibration (Tbc, Tcb, noise) +class Calib +{ + template + void serializeMatrix(Archive &ar, cv::Mat& mat, const unsigned int version) + { + int cols, rows, type; + bool continuous; + + if (Archive::is_saving::value) { + cols = mat.cols; rows = mat.rows; type = mat.type(); + continuous = mat.isContinuous(); + } + + ar & cols & rows & type & continuous; + if (Archive::is_loading::value) + mat.create(rows, cols, type); + + if (continuous) { + const unsigned int data_size = rows * cols * mat.elemSize(); + ar & boost::serialization::make_array(mat.ptr(), data_size); + } else { + const unsigned int row_size = cols*mat.elemSize(); + for (int i = 0; i < rows; i++) { + ar & boost::serialization::make_array(mat.ptr(i), row_size); + } + } + } + + friend class boost::serialization::access; + template + void serialize(Archive & ar, const unsigned int version) + { + serializeMatrix(ar,Tcb,version); + serializeMatrix(ar,Tbc,version); + serializeMatrix(ar,Cov,version); + serializeMatrix(ar,CovWalk,version); + } + +public: + Calib(const cv::Mat &Tbc_, const float &ng, const float &na, const float &ngw, const float &naw) + { + Set(Tbc_,ng,na,ngw,naw); + } + Calib(const Calib &calib); + Calib(){} + + void Set(const cv::Mat &Tbc_, const float &ng, const float &na, const float &ngw, const float &naw); + +public: + cv::Mat Tcb; + cv::Mat Tbc; + cv::Mat Cov, CovWalk; +}; + +//Integration of 1 gyro measurement +class IntegratedRotation +{ +public: + IntegratedRotation(){} + IntegratedRotation(const cv::Point3f &angVel, const Bias &imuBias, const float &time); + +public: + float deltaT; //integration time + cv::Mat deltaR; //integrated rotation + cv::Mat rightJ; // right jacobian +}; + +//Preintegration of Imu Measurements +class Preintegrated +{ + template + void serializeMatrix(Archive &ar, cv::Mat& mat, const unsigned int version) + { + int cols, rows, type; + bool continuous; + + if (Archive::is_saving::value) { + cols = mat.cols; rows = mat.rows; type = mat.type(); + continuous = mat.isContinuous(); + } + + ar & cols & rows & type & continuous; + if (Archive::is_loading::value) + mat.create(rows, cols, type); + + if (continuous) { + const unsigned int data_size = rows * cols * mat.elemSize(); + ar & boost::serialization::make_array(mat.ptr(), data_size); + } else { + const unsigned int row_size = cols*mat.elemSize(); + for (int i = 0; i < rows; i++) { + ar & boost::serialization::make_array(mat.ptr(i), row_size); + } + } + } + + friend class boost::serialization::access; + template + void serialize(Archive & ar, const unsigned int version) + { + ar & dT; + serializeMatrix(ar,C,version); + serializeMatrix(ar,Info,version); + serializeMatrix(ar,Nga,version); + serializeMatrix(ar,NgaWalk,version); + ar & b; + serializeMatrix(ar,dR,version); + serializeMatrix(ar,dV,version); + serializeMatrix(ar,dP,version); + serializeMatrix(ar,JRg,version); + serializeMatrix(ar,JVg,version); + serializeMatrix(ar,JVa,version); + serializeMatrix(ar,JPg,version); + serializeMatrix(ar,JPa,version); + serializeMatrix(ar,avgA,version); + serializeMatrix(ar,avgW,version); + + ar & bu; + serializeMatrix(ar,db,version); + ar & mvMeasurements; + } + +public: + Preintegrated(const Bias &b_, const Calib &calib); + Preintegrated(Preintegrated* pImuPre); + Preintegrated() {} + ~Preintegrated() {} + void CopyFrom(Preintegrated* pImuPre); + void Initialize(const Bias &b_); + void IntegrateNewMeasurement(const cv::Point3f &acceleration, const cv::Point3f &angVel, const float &dt); + void Reintegrate(); + void MergePrevious(Preintegrated* pPrev); + void SetNewBias(const Bias &bu_); + IMU::Bias GetDeltaBias(const Bias &b_); + cv::Mat GetDeltaRotation(const Bias &b_); + cv::Mat GetDeltaVelocity(const Bias &b_); + cv::Mat GetDeltaPosition(const Bias &b_); + cv::Mat GetUpdatedDeltaRotation(); + cv::Mat GetUpdatedDeltaVelocity(); + cv::Mat GetUpdatedDeltaPosition(); + cv::Mat GetOriginalDeltaRotation(); + cv::Mat GetOriginalDeltaVelocity(); + cv::Mat GetOriginalDeltaPosition(); + Eigen::Matrix GetInformationMatrix(); + cv::Mat GetDeltaBias(); + Bias GetOriginalBias(); + Bias GetUpdatedBias(); + +public: + float dT; + cv::Mat C; + cv::Mat Info; + cv::Mat Nga, NgaWalk; + + // Values for the original bias (when integration was computed) + Bias b; + cv::Mat dR, dV, dP; + cv::Mat JRg, JVg, JVa, JPg, JPa; + cv::Mat avgA; + cv::Mat avgW; + + +private: + // Updated bias + Bias bu; + // Dif between original and updated bias + // This is used to compute the updated values of the preintegration + cv::Mat db; + + struct integrable + { + integrable(const cv::Point3f &a_, const cv::Point3f &w_ , const float &t_):a(a_),w(w_),t(t_){} + cv::Point3f a; + cv::Point3f w; + float t; + }; + + std::vector mvMeasurements; + + std::mutex mMutex; +}; + +// Lie Algebra Functions +cv::Mat ExpSO3(const float &x, const float &y, const float &z); +Eigen::Matrix ExpSO3(const double &x, const double &y, const double &z); +cv::Mat ExpSO3(const cv::Mat &v); +cv::Mat LogSO3(const cv::Mat &R); +cv::Mat RightJacobianSO3(const float &x, const float &y, const float &z); +cv::Mat RightJacobianSO3(const cv::Mat &v); +cv::Mat InverseRightJacobianSO3(const float &x, const float &y, const float &z); +cv::Mat InverseRightJacobianSO3(const cv::Mat &v); +cv::Mat Skew(const cv::Mat &v); +cv::Mat NormalizeRotation(const cv::Mat &R); + +} + +} //namespace ORB_SLAM2 + +#endif // IMUTYPES_H diff --git a/third_party/ORB_SLAM3/include/Initializer.h b/third_party/ORB_SLAM3/include/Initializer.h new file mode 100644 index 0000000..0f866c4 --- /dev/null +++ b/third_party/ORB_SLAM3/include/Initializer.h @@ -0,0 +1,106 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + + +#ifndef INITIALIZER_H +#define INITIALIZER_H + +#include +#include "Frame.h" + +#include + +namespace ORB_SLAM3 +{ + +class Map; + +// THIS IS THE INITIALIZER FOR MONOCULAR SLAM. NOT USED IN THE STEREO OR RGBD CASE. +class Initializer +{ + typedef pair Match; + +public: + + // Fix the reference frame + Initializer(const Frame &ReferenceFrame, float sigma = 1.0, int iterations = 200); + + // Computes in parallel a fundamental matrix and a homography + // Selects a model and tries to recover the motion and the structure from motion + bool Initialize(const Frame &CurrentFrame, const vector &vMatches12, cv::Mat &R21, + cv::Mat &t21, vector &vP3D, vector &vbTriangulated); + +private: + + void FindHomography(vector &vbMatchesInliers, float &score, cv::Mat &H21); + void FindFundamental(vector &vbInliers, float &score, cv::Mat &F21); + + cv::Mat ComputeH21(const vector &vP1, const vector &vP2); + cv::Mat ComputeF21(const vector &vP1, const vector &vP2); + + float CheckHomography(const cv::Mat &H21, const cv::Mat &H12, vector &vbMatchesInliers, float sigma); + + float CheckFundamental(const cv::Mat &F21, vector &vbMatchesInliers, float sigma); + + bool ReconstructF(vector &vbMatchesInliers, cv::Mat &F21, cv::Mat &K, + cv::Mat &R21, cv::Mat &t21, vector &vP3D, vector &vbTriangulated, float minParallax, int minTriangulated); + + bool ReconstructH(vector &vbMatchesInliers, cv::Mat &H21, cv::Mat &K, + cv::Mat &R21, cv::Mat &t21, vector &vP3D, vector &vbTriangulated, float minParallax, int minTriangulated); + + void Triangulate(const cv::KeyPoint &kp1, const cv::KeyPoint &kp2, const cv::Mat &P1, const cv::Mat &P2, cv::Mat &x3D); + + void Normalize(const vector &vKeys, vector &vNormalizedPoints, cv::Mat &T); + // void Normalize(const vector &vKeys, vector &vNormalizedPoints, cv::Mat &T); + + int CheckRT(const cv::Mat &R, const cv::Mat &t, const vector &vKeys1, const vector &vKeys2, + const vector &vMatches12, vector &vbInliers, + const cv::Mat &K, vector &vP3D, float th2, vector &vbGood, float ¶llax); + + void DecomposeE(const cv::Mat &E, cv::Mat &R1, cv::Mat &R2, cv::Mat &t); + + + // Keypoints from Reference Frame (Frame 1) + vector mvKeys1; + + // Keypoints from Current Frame (Frame 2) + vector mvKeys2; + + // Current Matches from Reference to Current + vector mvMatches12; + vector mvbMatched1; + + // Calibration + cv::Mat mK; + + // Standard Deviation and Variance + float mSigma, mSigma2; + + // Ransac max iterations + int mMaxIterations; + + // Ransac sets + vector > mvSets; + + GeometricCamera* mpCamera; + +}; + +} //namespace ORB_SLAM + +#endif // INITIALIZER_H diff --git a/third_party/ORB_SLAM3/include/KeyFrame.h b/third_party/ORB_SLAM3/include/KeyFrame.h new file mode 100644 index 0000000..578ba86 --- /dev/null +++ b/third_party/ORB_SLAM3/include/KeyFrame.h @@ -0,0 +1,623 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + + +#ifndef KEYFRAME_H +#define KEYFRAME_H + +#include "MapPoint.h" +#include "Thirdparty/DBoW2/DBoW2/BowVector.h" +#include "Thirdparty/DBoW2/DBoW2/FeatureVector.h" +#include "ORBVocabulary.h" +#include "ORBextractor.h" +#include "Frame.h" +#include "KeyFrameDatabase.h" +#include "ImuTypes.h" + +#include "GeometricCamera.h" + +#include + +#include +#include +#include + + +namespace ORB_SLAM3 +{ + +class Map; +class MapPoint; +class Frame; +class KeyFrameDatabase; + +class GeometricCamera; + +class KeyFrame +{ + + + template + void serializeMatrix(Archive& ar, cv::Mat& mat, const unsigned int version) + { + int cols, rows, type; + bool continuous; + + if (Archive::is_saving::value) { + cols = mat.cols; rows = mat.rows; type = mat.type(); + continuous = mat.isContinuous(); + } + + ar & cols & rows & type & continuous; + + if (Archive::is_loading::value) + mat.create(rows, cols, type); + + if (continuous) { + const unsigned int data_size = rows * cols * mat.elemSize(); + ar & boost::serialization::make_array(mat.ptr(), data_size); + } else { + const unsigned int row_size = cols*mat.elemSize(); + for (int i = 0; i < rows; i++) { + ar & boost::serialization::make_array(mat.ptr(i), row_size); + } + } + } + + + template + void serializeMatrix(Archive& ar, const cv::Mat& mat, const unsigned int version) + { + cv::Mat matAux = mat; + + serializeMatrix(ar, matAux,version); + + if (Archive::is_loading::value) + { + cv::Mat* ptr; + ptr = (cv::Mat*)( &mat ); + *ptr = matAux; + } + } + + friend class boost::serialization::access; + template + void serializeVectorKeyPoints(Archive& ar, const vector& vKP, const unsigned int version) + { + int NumEl; + + if (Archive::is_saving::value) { + NumEl = vKP.size(); + } + + ar & NumEl; + + vector vKPaux = vKP; + if (Archive::is_loading::value) + vKPaux.reserve(NumEl); + + for(int i=0; i < NumEl; ++i) + { + cv::KeyPoint KPi; + + if (Archive::is_loading::value) + KPi = cv::KeyPoint(); + + if (Archive::is_saving::value) + KPi = vKPaux[i]; + + ar & KPi.angle; + ar & KPi.response; + ar & KPi.size; + ar & KPi.pt.x; + ar & KPi.pt.y; + ar & KPi.class_id; + ar & KPi.octave; + + if (Archive::is_loading::value) + vKPaux.push_back(KPi); + } + + + if (Archive::is_loading::value) + { + vector *ptr; + ptr = (vector*)( &vKP ); + *ptr = vKPaux; + } + } + + template + void serialize(Archive& ar, const unsigned int version) + { + ar & mnId; + ar & const_cast(mnFrameId); + ar & const_cast(mTimeStamp); + // Grid + ar & const_cast(mnGridCols); + ar & const_cast(mnGridRows); + ar & const_cast(mfGridElementWidthInv); + ar & const_cast(mfGridElementHeightInv); + // Variables of tracking + ar & mnTrackReferenceForFrame; + ar & mnFuseTargetForKF; + // Variables of local mapping + ar & mnBALocalForKF; + ar & mnBAFixedForKF; + ar & mnNumberOfOpt; + // Variables used by KeyFrameDatabase + ar & mnLoopQuery; + ar & mnLoopWords; + ar & mLoopScore; + ar & mnRelocQuery; + ar & mnRelocWords; + ar & mRelocScore; + ar & mnMergeQuery; + ar & mnMergeWords; + ar & mMergeScore; + ar & mnPlaceRecognitionQuery; + ar & mnPlaceRecognitionWords; + ar & mPlaceRecognitionScore; + ar & mbCurrentPlaceRecognition; + // Variables of loop closing + serializeMatrix(ar,mTcwGBA,version); + serializeMatrix(ar,mTcwBefGBA,version); + serializeMatrix(ar,mVwbGBA,version); + serializeMatrix(ar,mVwbBefGBA,version); + ar & mBiasGBA; + ar & mnBAGlobalForKF; + // Variables of Merging + serializeMatrix(ar,mTcwMerge,version); + serializeMatrix(ar,mTcwBefMerge,version); + serializeMatrix(ar,mTwcBefMerge,version); + serializeMatrix(ar,mVwbMerge,version); + serializeMatrix(ar,mVwbBefMerge,version); + ar & mBiasMerge; + ar & mnMergeCorrectedForKF; + ar & mnMergeForKF; + ar & mfScaleMerge; + ar & mnBALocalForMerge; + // Scale + ar & mfScale; + // Calibration parameters + ar & const_cast(fx); + ar & const_cast(fy); + ar & const_cast(invfx); + ar & const_cast(invfy); + ar & const_cast(cx); + ar & const_cast(cy); + ar & const_cast(mbf); + ar & const_cast(mb); + ar & const_cast(mThDepth); + serializeMatrix(ar,mDistCoef,version); + // Number of Keypoints + ar & const_cast(N); + // KeyPoints + serializeVectorKeyPoints(ar,mvKeys,version); + serializeVectorKeyPoints(ar,mvKeysUn,version); + ar & const_cast& >(mvuRight); + ar & const_cast& >(mvDepth); + serializeMatrix(ar,mDescriptors,version); + // BOW + ar & mBowVec; + ar & mFeatVec; + // Pose relative to parent + serializeMatrix(ar,mTcp,version); + // Scale + ar & const_cast(mnScaleLevels); + ar & const_cast(mfScaleFactor); + ar & const_cast(mfLogScaleFactor); + ar & const_cast& >(mvScaleFactors); + ar & const_cast& >(mvLevelSigma2); + ar & const_cast& >(mvInvLevelSigma2); + // Image bounds and calibration + ar & const_cast(mnMinX); + ar & const_cast(mnMinY); + ar & const_cast(mnMaxX); + ar & const_cast(mnMaxY); + serializeMatrix(ar,mK,version); + // Pose + serializeMatrix(ar,Tcw,version); + // MapPointsId associated to keypoints + ar & mvBackupMapPointsId; + // Grid + ar & mGrid; + // Connected KeyFrameWeight + ar & mBackupConnectedKeyFrameIdWeights; + // Spanning Tree and Loop Edges + ar & mbFirstConnection; + ar & mBackupParentId; + ar & mvBackupChildrensId; + ar & mvBackupLoopEdgesId; + ar & mvBackupMergeEdgesId; + // Bad flags + ar & mbNotErase; + ar & mbToBeErased; + ar & mbBad; + + ar & mHalfBaseline; + + // Camera variables + ar & mnBackupIdCamera; + ar & mnBackupIdCamera2; + + // Fisheye variables + /*ar & mvLeftToRightMatch; + ar & mvRightToLeftMatch; + ar & NLeft; + ar & NRight; + serializeMatrix(ar, mTlr, version); + //serializeMatrix(ar, mTrl, version); + serializeVectorKeyPoints(ar, mvKeysRight, version); + ar & mGridRight; + + // Inertial variables + ar & mImuBias; + ar & mBackupImuPreintegrated; + ar & mImuCalib; + ar & mBackupPrevKFId; + ar & mBackupNextKFId; + ar & bImu; + serializeMatrix(ar, Vw, version); + serializeMatrix(ar, Owb, version);*/ + + } + +public: + KeyFrame(); + KeyFrame(Frame &F, Map* pMap, KeyFrameDatabase* pKFDB); + + // Pose functions + void SetPose(const cv::Mat &Tcw); + void SetVelocity(const cv::Mat &Vw_); + + cv::Mat GetPose(); + cv::Mat GetPoseInverse(); + cv::Mat GetCameraCenter(); + cv::Mat GetImuPosition(); + cv::Mat GetImuRotation(); + cv::Mat GetImuPose(); + cv::Mat GetStereoCenter(); + cv::Mat GetRotation(); + cv::Mat GetTranslation(); + cv::Mat GetVelocity(); + + // Bag of Words Representation + void ComputeBoW(); + + // Covisibility graph functions + void AddConnection(KeyFrame* pKF, const int &weight); + void EraseConnection(KeyFrame* pKF); + + void UpdateConnections(bool upParent=true); + void UpdateBestCovisibles(); + std::set GetConnectedKeyFrames(); + std::vector GetVectorCovisibleKeyFrames(); + std::vector GetBestCovisibilityKeyFrames(const int &N); + std::vector GetCovisiblesByWeight(const int &w); + int GetWeight(KeyFrame* pKF); + + // Spanning tree functions + void AddChild(KeyFrame* pKF); + void EraseChild(KeyFrame* pKF); + void ChangeParent(KeyFrame* pKF); + std::set GetChilds(); + KeyFrame* GetParent(); + bool hasChild(KeyFrame* pKF); + void SetFirstConnection(bool bFirst); + + // Loop Edges + void AddLoopEdge(KeyFrame* pKF); + std::set GetLoopEdges(); + + // Merge Edges + void AddMergeEdge(KeyFrame* pKF); + set GetMergeEdges(); + + // MapPoint observation functions + int GetNumberMPs(); + void AddMapPoint(MapPoint* pMP, const size_t &idx); + void EraseMapPointMatch(const int &idx); + void EraseMapPointMatch(MapPoint* pMP); + void ReplaceMapPointMatch(const int &idx, MapPoint* pMP); + std::set GetMapPoints(); + std::vector GetMapPointMatches(); + int TrackedMapPoints(const int &minObs); + MapPoint* GetMapPoint(const size_t &idx); + + // KeyPoint functions + std::vector GetFeaturesInArea(const float &x, const float &y, const float &r, const bool bRight = false) const; + cv::Mat UnprojectStereo(int i); + + // Image + bool IsInImage(const float &x, const float &y) const; + + // Enable/Disable bad flag changes + void SetNotErase(); + void SetErase(); + + // Set/check bad flag + void SetBadFlag(); + bool isBad(); + + // Compute Scene Depth (q=2 median). Used in monocular. + float ComputeSceneMedianDepth(const int q); + + static bool weightComp( int a, int b){ + return a>b; + } + + static bool lId(KeyFrame* pKF1, KeyFrame* pKF2){ + return pKF1->mnIdmnId; + } + + Map* GetMap(); + void UpdateMap(Map* pMap); + + void SetNewBias(const IMU::Bias &b); + cv::Mat GetGyroBias(); + cv::Mat GetAccBias(); + IMU::Bias GetImuBias(); + + bool ProjectPointDistort(MapPoint* pMP, cv::Point2f &kp, float &u, float &v); + bool ProjectPointUnDistort(MapPoint* pMP, cv::Point2f &kp, float &u, float &v); + + void PreSave(set& spKF,set& spMP, set& spCam); + void PostLoad(map& mpKFid, map& mpMPid, map& mpCamId); + + + void SetORBVocabulary(ORBVocabulary* pORBVoc); + void SetKeyFrameDatabase(KeyFrameDatabase* pKFDB); + + bool bImu; + + // The following variables are accesed from only 1 thread or never change (no mutex needed). +public: + + static long unsigned int nNextId; + long unsigned int mnId; + const long unsigned int mnFrameId; + + const double mTimeStamp; + + // Grid (to speed up feature matching) + const int mnGridCols; + const int mnGridRows; + const float mfGridElementWidthInv; + const float mfGridElementHeightInv; + + // Variables used by the tracking + long unsigned int mnTrackReferenceForFrame; + long unsigned int mnFuseTargetForKF; + + // Variables used by the local mapping + long unsigned int mnBALocalForKF; + long unsigned int mnBAFixedForKF; + + //Number of optimizations by BA(amount of iterations in BA) + long unsigned int mnNumberOfOpt; + + // Variables used by the keyframe database + long unsigned int mnLoopQuery; + int mnLoopWords; + float mLoopScore; + long unsigned int mnRelocQuery; + int mnRelocWords; + float mRelocScore; + long unsigned int mnMergeQuery; + int mnMergeWords; + float mMergeScore; + long unsigned int mnPlaceRecognitionQuery; + int mnPlaceRecognitionWords; + float mPlaceRecognitionScore; + + bool mbCurrentPlaceRecognition; + + + // Variables used by loop closing + cv::Mat mTcwGBA; + cv::Mat mTcwBefGBA; + cv::Mat mVwbGBA; + cv::Mat mVwbBefGBA; + IMU::Bias mBiasGBA; + long unsigned int mnBAGlobalForKF; + + // Variables used by merging + cv::Mat mTcwMerge; + cv::Mat mTcwBefMerge; + cv::Mat mTwcBefMerge; + cv::Mat mVwbMerge; + cv::Mat mVwbBefMerge; + IMU::Bias mBiasMerge; + long unsigned int mnMergeCorrectedForKF; + long unsigned int mnMergeForKF; + float mfScaleMerge; + long unsigned int mnBALocalForMerge; + + float mfScale; + + // Calibration parameters + const float fx, fy, cx, cy, invfx, invfy, mbf, mb, mThDepth; + cv::Mat mDistCoef; + + // Number of KeyPoints + const int N; + + // KeyPoints, stereo coordinate and descriptors (all associated by an index) + const std::vector mvKeys; + const std::vector mvKeysUn; + const std::vector mvuRight; // negative value for monocular points + const std::vector mvDepth; // negative value for monocular points + const cv::Mat mDescriptors; + + //BoW + DBoW2::BowVector mBowVec; + DBoW2::FeatureVector mFeatVec; + + // Pose relative to parent (this is computed when bad flag is activated) + cv::Mat mTcp; + + // Scale + const int mnScaleLevels; + const float mfScaleFactor; + const float mfLogScaleFactor; + const std::vector mvScaleFactors; + const std::vector mvLevelSigma2; + const std::vector mvInvLevelSigma2; + + // Image bounds and calibration + const int mnMinX; + const int mnMinY; + const int mnMaxX; + const int mnMaxY; + const cv::Mat mK; + + // Preintegrated IMU measurements from previous keyframe + KeyFrame* mPrevKF; + KeyFrame* mNextKF; + + IMU::Preintegrated* mpImuPreintegrated; + IMU::Calib mImuCalib; + + + unsigned int mnOriginMapId; + + string mNameFile; + + int mnDataset; + + std::vector mvpLoopCandKFs; + std::vector mvpMergeCandKFs; + + bool mbHasHessian; + cv::Mat mHessianPose; + + // The following variables need to be accessed trough a mutex to be thread safe. +protected: + + // SE3 Pose and camera center + cv::Mat Tcw; + cv::Mat Twc; + cv::Mat Ow; + cv::Mat Cw; // Stereo middel point. Only for visualization + + // IMU position + cv::Mat Owb; + + // Velocity (Only used for inertial SLAM) + cv::Mat Vw; + + // Imu bias + IMU::Bias mImuBias; + + // MapPoints associated to keypoints + std::vector mvpMapPoints; + // For save relation without pointer, this is necessary for save/load function + std::vector mvBackupMapPointsId; + + // BoW + KeyFrameDatabase* mpKeyFrameDB; + ORBVocabulary* mpORBvocabulary; + + // Grid over the image to speed up feature matching + std::vector< std::vector > > mGrid; + + std::map mConnectedKeyFrameWeights; + std::vector mvpOrderedConnectedKeyFrames; + std::vector mvOrderedWeights; + // For save relation without pointer, this is necessary for save/load function + std::map mBackupConnectedKeyFrameIdWeights; + + // Spanning Tree and Loop Edges + bool mbFirstConnection; + KeyFrame* mpParent; + std::set mspChildrens; + std::set mspLoopEdges; + std::set mspMergeEdges; + // For save relation without pointer, this is necessary for save/load function + long long int mBackupParentId; + std::vector mvBackupChildrensId; + std::vector mvBackupLoopEdgesId; + std::vector mvBackupMergeEdgesId; + + // Bad flags + bool mbNotErase; + bool mbToBeErased; + bool mbBad; + + float mHalfBaseline; // Only for visualization + + Map* mpMap; + + std::mutex mMutexPose; // for pose, velocity and biases + std::mutex mMutexConnections; + std::mutex mMutexFeatures; + std::mutex mMutexMap; + + // Backup variables for inertial + long long int mBackupPrevKFId; + long long int mBackupNextKFId; + IMU::Preintegrated mBackupImuPreintegrated; + + // Backup for Cameras + unsigned int mnBackupIdCamera, mnBackupIdCamera2; + +public: + GeometricCamera* mpCamera, *mpCamera2; + + //Indexes of stereo observations correspondences + std::vector mvLeftToRightMatch, mvRightToLeftMatch; + + //Transformation matrix between cameras in stereo fisheye + cv::Mat mTlr; + cv::Mat mTrl; + + //KeyPoints in the right image (for stereo fisheye, coordinates are needed) + const std::vector mvKeysRight; + + const int NLeft, NRight; + + std::vector< std::vector > > mGridRight; + + cv::Mat GetRightPose(); + cv::Mat GetRightPoseInverse(); + cv::Mat GetRightPoseInverseH(); + cv::Mat GetRightCameraCenter(); + cv::Mat GetRightRotation(); + cv::Mat GetRightTranslation(); + + cv::Mat imgLeft, imgRight; //TODO Backup?? + + void PrintPointDistribution(){ + int left = 0, right = 0; + int Nlim = (NLeft != -1) ? NLeft : N; + for(int i = 0; i < N; i++){ + if(mvpMapPoints[i]){ + if(i < Nlim) left++; + else right++; + } + } + cout << "Point distribution in KeyFrame: left-> " << left << " --- right-> " << right << endl; + } + + +}; + +} //namespace ORB_SLAM + +#endif // KEYFRAME_H diff --git a/third_party/ORB_SLAM3/include/KeyFrameDatabase.h b/third_party/ORB_SLAM3/include/KeyFrameDatabase.h new file mode 100644 index 0000000..f991020 --- /dev/null +++ b/third_party/ORB_SLAM3/include/KeyFrameDatabase.h @@ -0,0 +1,100 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + + +#ifndef KEYFRAMEDATABASE_H +#define KEYFRAMEDATABASE_H + +#include +#include +#include + +#include "KeyFrame.h" +#include "Frame.h" +#include "ORBVocabulary.h" +#include "Map.h" + +#include +#include +#include + +#include + + +namespace ORB_SLAM3 +{ + +class KeyFrame; +class Frame; +class Map; + + +class KeyFrameDatabase +{ + friend class boost::serialization::access; + + template + void serialize(Archive& ar, const unsigned int version) + { + ar & mvBackupInvertedFileId; + } + +public: + + KeyFrameDatabase(const ORBVocabulary &voc); + + void add(KeyFrame* pKF); + + void erase(KeyFrame* pKF); + + void clear(); + void clearMap(Map* pMap); + + // Loop Detection(DEPRECATED) + std::vector DetectLoopCandidates(KeyFrame* pKF, float minScore); + + // Loop and Merge Detection + void DetectCandidates(KeyFrame* pKF, float minScore,vector& vpLoopCand, vector& vpMergeCand); + void DetectBestCandidates(KeyFrame *pKF, vector &vpLoopCand, vector &vpMergeCand, int nMinWords); + void DetectNBestCandidates(KeyFrame *pKF, vector &vpLoopCand, vector &vpMergeCand, int nNumCandidates); + + // Relocalization + std::vector DetectRelocalizationCandidates(Frame* F, Map* pMap); + + void PreSave(); + void PostLoad(map mpKFid); + void SetORBVocabulary(ORBVocabulary* pORBVoc); + +protected: + + // Associated vocabulary + const ORBVocabulary* mpVoc; + + // Inverted file + std::vector > mvInvertedFile; + + // For save relation without pointer, this is necessary for save/load function + std::vector > mvBackupInvertedFileId; + + // Mutex + std::mutex mMutex; +}; + +} //namespace ORB_SLAM + +#endif diff --git a/third_party/ORB_SLAM3/include/LocalMapping.h b/third_party/ORB_SLAM3/include/LocalMapping.h new file mode 100644 index 0000000..11330e8 --- /dev/null +++ b/third_party/ORB_SLAM3/include/LocalMapping.h @@ -0,0 +1,185 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + + +#ifndef LOCALMAPPING_H +#define LOCALMAPPING_H + +#include "KeyFrame.h" +#include "Atlas.h" +#include "LoopClosing.h" +#include "Tracking.h" +#include "KeyFrameDatabase.h" +#include "Initializer.h" + +#include + + +namespace ORB_SLAM3 +{ + +class System; +class Tracking; +class LoopClosing; +class Atlas; + +class LocalMapping +{ +public: + LocalMapping(System* pSys, Atlas* pAtlas, const float bMonocular, bool bInertial, const string &_strSeqName=std::string()); + + void SetLoopCloser(LoopClosing* pLoopCloser); + + void SetTracker(Tracking* pTracker); + + // Main function + void Run(); + + void InsertKeyFrame(KeyFrame* pKF); + void EmptyQueue(); + + // Thread Synch + void RequestStop(); + void RequestReset(); + void RequestResetActiveMap(Map* pMap); + bool Stop(); + void Release(); + bool isStopped(); + bool stopRequested(); + bool AcceptKeyFrames(); + void SetAcceptKeyFrames(bool flag); + bool SetNotStop(bool flag); + + void InterruptBA(); + + void RequestFinish(); + bool isFinished(); + + int KeyframesInQueue(){ + unique_lock lock(mMutexNewKFs); + return mlNewKeyFrames.size(); + } + + bool IsInitializing(); + double GetCurrKFTime(); + KeyFrame* GetCurrKF(); + + std::mutex mMutexImuInit; + + Eigen::MatrixXd mcovInertial; + Eigen::Matrix3d mRwg; + Eigen::Vector3d mbg; + Eigen::Vector3d mba; + double mScale; + double mInitTime; + double mCostTime; + bool mbNewInit; + unsigned int mInitSect; + unsigned int mIdxInit; + unsigned int mnKFs; + double mFirstTs; + int mnMatchesInliers; + + // For debugging (erase in normal mode) + int mInitFr; + int mIdxIteration; + string strSequence; + + bool mbNotBA1; + bool mbNotBA2; + bool mbBadImu; + + bool mbWriteStats; + + // not consider far points (clouds) + bool mbFarPoints; + float mThFarPoints; +protected: + + bool CheckNewKeyFrames(); + void ProcessNewKeyFrame(); + void CreateNewMapPoints(); + + void MapPointCulling(); + void SearchInNeighbors(); + void KeyFrameCulling(); + + cv::Mat ComputeF12(KeyFrame* &pKF1, KeyFrame* &pKF2); + + cv::Mat SkewSymmetricMatrix(const cv::Mat &v); + + System *mpSystem; + + bool mbMonocular; + bool mbInertial; + + void ResetIfRequested(); + bool mbResetRequested; + bool mbResetRequestedActiveMap; + Map* mpMapToReset; + std::mutex mMutexReset; + + bool CheckFinish(); + void SetFinish(); + bool mbFinishRequested; + bool mbFinished; + std::mutex mMutexFinish; + + Atlas* mpAtlas; + + LoopClosing* mpLoopCloser; + Tracking* mpTracker; + + std::list mlNewKeyFrames; + + KeyFrame* mpCurrentKeyFrame; + + std::list mlpRecentAddedMapPoints; + + std::mutex mMutexNewKFs; + + bool mbAbortBA; + + bool mbStopped; + bool mbStopRequested; + bool mbNotStop; + std::mutex mMutexStop; + + bool mbAcceptKeyFrames; + std::mutex mMutexAccept; + + void InitializeIMU(float priorG = 1e2, float priorA = 1e6, bool bFirst = false); + void ScaleRefinement(); + + bool bInitializing; + + Eigen::MatrixXd infoInertial; + int mNumLM; + int mNumKFCulling; + + float mTinit; + + int countRefinement; + + //DEBUG + ofstream f_lm; +}; + +} //namespace ORB_SLAM + +#endif // LOCALMAPPING_H diff --git a/third_party/ORB_SLAM3/include/LoopClosing.h b/third_party/ORB_SLAM3/include/LoopClosing.h new file mode 100644 index 0000000..89639b3 --- /dev/null +++ b/third_party/ORB_SLAM3/include/LoopClosing.h @@ -0,0 +1,208 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + + +#ifndef LOOPCLOSING_H +#define LOOPCLOSING_H + +#include "KeyFrame.h" +#include "LocalMapping.h" +#include "Atlas.h" +#include "ORBVocabulary.h" +#include "Tracking.h" + +#include "KeyFrameDatabase.h" + +#include +#include +#include +#include "Thirdparty/g2o/g2o/types/types_seven_dof_expmap.h" + +namespace ORB_SLAM3 +{ + +class Tracking; +class LocalMapping; +class KeyFrameDatabase; +class Map; + + +class LoopClosing +{ +public: + + typedef pair,int> ConsistentGroup; + typedef map, + Eigen::aligned_allocator > > KeyFrameAndPose; + +public: + + LoopClosing(Atlas* pAtlas, KeyFrameDatabase* pDB, ORBVocabulary* pVoc,const bool bFixScale); + + void SetTracker(Tracking* pTracker); + + void SetLocalMapper(LocalMapping* pLocalMapper); + + // Main function + void Run(); + + void InsertKeyFrame(KeyFrame *pKF); + + void RequestReset(); + void RequestResetActiveMap(Map* pMap); + + // This function will run in a separate thread + void RunGlobalBundleAdjustment(Map* pActiveMap, unsigned long nLoopKF); + + bool isRunningGBA(){ + unique_lock lock(mMutexGBA); + return mbRunningGBA; + } + bool isFinishedGBA(){ + unique_lock lock(mMutexGBA); + return mbFinishedGBA; + } + + void RequestFinish(); + + bool isFinished(); + + Viewer* mpViewer; + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + +protected: + + bool CheckNewKeyFrames(); + + + //Methods to implement the new place recognition algorithm + bool NewDetectCommonRegions(); + bool DetectAndReffineSim3FromLastKF(KeyFrame* pCurrentKF, KeyFrame* pMatchedKF, g2o::Sim3 &gScw, int &nNumProjMatches, + std::vector &vpMPs, std::vector &vpMatchedMPs); + bool DetectCommonRegionsFromBoW(std::vector &vpBowCand, KeyFrame* &pMatchedKF, KeyFrame* &pLastCurrentKF, g2o::Sim3 &g2oScw, + int &nNumCoincidences, std::vector &vpMPs, std::vector &vpMatchedMPs); + bool DetectCommonRegionsFromLastKF(KeyFrame* pCurrentKF, KeyFrame* pMatchedKF, g2o::Sim3 &gScw, int &nNumProjMatches, + std::vector &vpMPs, std::vector &vpMatchedMPs); + int FindMatchesByProjection(KeyFrame* pCurrentKF, KeyFrame* pMatchedKFw, g2o::Sim3 &g2oScw, + set &spMatchedMPinOrigin, vector &vpMapPoints, + vector &vpMatchedMapPoints); + + + void SearchAndFuse(const KeyFrameAndPose &CorrectedPosesMap, vector &vpMapPoints); + void SearchAndFuse(const vector &vConectedKFs, vector &vpMapPoints); + + void CorrectLoop(); + + void MergeLocal(); + void MergeLocal2(); + + void CheckObservations(set &spKFsMap1, set &spKFsMap2); + void printReprojectionError(set &spLocalWindowKFs, KeyFrame* mpCurrentKF, string &name); + + void ResetIfRequested(); + bool mbResetRequested; + bool mbResetActiveMapRequested; + Map* mpMapToReset; + std::mutex mMutexReset; + + bool CheckFinish(); + void SetFinish(); + bool mbFinishRequested; + bool mbFinished; + std::mutex mMutexFinish; + + Atlas* mpAtlas; + Tracking* mpTracker; + + KeyFrameDatabase* mpKeyFrameDB; + ORBVocabulary* mpORBVocabulary; + + LocalMapping *mpLocalMapper; + + std::list mlpLoopKeyFrameQueue; + + std::mutex mMutexLoopQueue; + + // Loop detector parameters + float mnCovisibilityConsistencyTh; + + // Loop detector variables + KeyFrame* mpCurrentKF; + KeyFrame* mpLastCurrentKF; + KeyFrame* mpMatchedKF; + std::vector mvConsistentGroups; + std::vector mvpEnoughConsistentCandidates; + std::vector mvpCurrentConnectedKFs; + std::vector mvpCurrentMatchedPoints; + std::vector mvpLoopMapPoints; + cv::Mat mScw; + g2o::Sim3 mg2oScw; + + //------- + Map* mpLastMap; + + bool mbLoopDetected; + int mnLoopNumCoincidences; + int mnLoopNumNotFound; + KeyFrame* mpLoopLastCurrentKF; + g2o::Sim3 mg2oLoopSlw; + g2o::Sim3 mg2oLoopScw; + KeyFrame* mpLoopMatchedKF; + std::vector mvpLoopMPs; + std::vector mvpLoopMatchedMPs; + bool mbMergeDetected; + int mnMergeNumCoincidences; + int mnMergeNumNotFound; + KeyFrame* mpMergeLastCurrentKF; + g2o::Sim3 mg2oMergeSlw; + g2o::Sim3 mg2oMergeSmw; + g2o::Sim3 mg2oMergeScw; + KeyFrame* mpMergeMatchedKF; + std::vector mvpMergeMPs; + std::vector mvpMergeMatchedMPs; + std::vector mvpMergeConnectedKFs; + + g2o::Sim3 mSold_new; + //------- + + long unsigned int mLastLoopKFid; + + // Variables related to Global Bundle Adjustment + bool mbRunningGBA; + bool mbFinishedGBA; + bool mbStopGBA; + std::mutex mMutexGBA; + std::thread* mpThreadGBA; + + // Fix scale in the stereo/RGB-D case + bool mbFixScale; + + + int mnFullBAIdx; + + + + vector vdPR_CurrentTime; + vector vdPR_MatchedTime; + vector vnPR_TypeRecogn; +}; + +} //namespace ORB_SLAM + +#endif // LOOPCLOSING_H diff --git a/third_party/ORB_SLAM3/include/MLPnPsolver.h b/third_party/ORB_SLAM3/include/MLPnPsolver.h new file mode 100644 index 0000000..cede745 --- /dev/null +++ b/third_party/ORB_SLAM3/include/MLPnPsolver.h @@ -0,0 +1,256 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + +/****************************************************************************** +* Author: Steffen Urban * +* Contact: urbste@gmail.com * +* License: Copyright (c) 2016 Steffen Urban, ANU. All rights reserved. * +* * +* Redistribution and use in source and binary forms, with or without * +* modification, are permitted provided that the following conditions * +* are met: * +* * Redistributions of source code must retain the above copyright * +* notice, this list of conditions and the following disclaimer. * +* * Redistributions in binary form must reproduce the above copyright * +* notice, this list of conditions and the following disclaimer in the * +* documentation and/or other materials provided with the distribution. * +* * Neither the name of ANU nor the names of its contributors may be * +* used to endorse or promote products derived from this software without * +* specific prior written permission. * +* * +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * +* ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * +* OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * +* SUCH DAMAGE. * +******************************************************************************/ + +#ifndef ORB_SLAM3_MLPNPSOLVER_H +#define ORB_SLAM3_MLPNPSOLVER_H + +#include "MapPoint.h" +#include "Frame.h" + +#include +#include + +namespace ORB_SLAM3{ + class MLPnPsolver { + public: + MLPnPsolver(const Frame &F, const vector &vpMapPointMatches); + + ~MLPnPsolver(); + + void SetRansacParameters(double probability = 0.99, int minInliers = 8, int maxIterations = 300, int minSet = 6, float epsilon = 0.4, + float th2 = 5.991); + + //Find metod is necessary? + + cv::Mat iterate(int nIterations, bool &bNoMore, vector &vbInliers, int &nInliers); + + //Type definitions needed by the original code + + /** A 3-vector of unit length used to describe landmark observations/bearings + * in camera frames (always expressed in camera frames) + */ + typedef Eigen::Vector3d bearingVector_t; + + /** An array of bearing-vectors */ + typedef std::vector > + bearingVectors_t; + + /** A 2-matrix containing the 2D covariance information of a bearing vector + */ + typedef Eigen::Matrix2d cov2_mat_t; + + /** A 3-matrix containing the 3D covariance information of a bearing vector */ + typedef Eigen::Matrix3d cov3_mat_t; + + /** An array of 3D covariance matrices */ + typedef std::vector > + cov3_mats_t; + + /** A 3-vector describing a point in 3D-space */ + typedef Eigen::Vector3d point_t; + + /** An array of 3D-points */ + typedef std::vector > + points_t; + + /** A homogeneous 3-vector describing a point in 3D-space */ + typedef Eigen::Vector4d point4_t; + + /** An array of homogeneous 3D-points */ + typedef std::vector > + points4_t; + + /** A 3-vector containing the rodrigues parameters of a rotation matrix */ + typedef Eigen::Vector3d rodrigues_t; + + /** A rotation matrix */ + typedef Eigen::Matrix3d rotation_t; + + /** A 3x4 transformation matrix containing rotation \f$ \mathbf{R} \f$ and + * translation \f$ \mathbf{t} \f$ as follows: + * \f$ \left( \begin{array}{cc} \mathbf{R} & \mathbf{t} \end{array} \right) \f$ + */ + typedef Eigen::Matrix transformation_t; + + /** A 3-vector describing a translation/camera position */ + typedef Eigen::Vector3d translation_t; + + + + private: + void CheckInliers(); + bool Refine(); + + //Functions from de original MLPnP code + + /* + * Computes the camera pose given 3D points coordinates (in the camera reference + * system), the camera rays and (optionally) the covariance matrix of those camera rays. + * Result is stored in solution + */ + void computePose( + const bearingVectors_t & f, + const points_t & p, + const cov3_mats_t & covMats, + const std::vector& indices, + transformation_t & result); + + void mlpnp_gn(Eigen::VectorXd& x, + const points_t& pts, + const std::vector& nullspaces, + const Eigen::SparseMatrix Kll, + bool use_cov); + + void mlpnp_residuals_and_jacs( + const Eigen::VectorXd& x, + const points_t& pts, + const std::vector& nullspaces, + Eigen::VectorXd& r, + Eigen::MatrixXd& fjac, + bool getJacs); + + void mlpnpJacs( + const point_t& pt, + const Eigen::Vector3d& nullspace_r, + const Eigen::Vector3d& nullspace_s, + const rodrigues_t& w, + const translation_t& t, + Eigen::MatrixXd& jacs); + + //Auxiliar methods + + /** + * \brief Compute a rotation matrix from Rodrigues axis angle. + * + * \param[in] omega The Rodrigues-parameters of a rotation. + * \return The 3x3 rotation matrix. + */ + Eigen::Matrix3d rodrigues2rot(const Eigen::Vector3d & omega); + + /** + * \brief Compute the Rodrigues-parameters of a rotation matrix. + * + * \param[in] R The 3x3 rotation matrix. + * \return The Rodrigues-parameters. + */ + Eigen::Vector3d rot2rodrigues(const Eigen::Matrix3d & R); + + //---------------------------------------------------- + //Fields of the solver + //---------------------------------------------------- + vector mvpMapPointMatches; + + // 2D Points + vector mvP2D; + //Substitued by bearing vectors + bearingVectors_t mvBearingVecs; + + vector mvSigma2; + + // 3D Points + //vector mvP3Dw; + points_t mvP3Dw; + + // Index in Frame + vector mvKeyPointIndices; + + // Current Estimation + double mRi[3][3]; + double mti[3]; + cv::Mat mTcwi; + vector mvbInliersi; + int mnInliersi; + + // Current Ransac State + int mnIterations; + vector mvbBestInliers; + int mnBestInliers; + cv::Mat mBestTcw; + + // Refined + cv::Mat mRefinedTcw; + vector mvbRefinedInliers; + int mnRefinedInliers; + + // Number of Correspondences + int N; + + // Indices for random selection [0 .. N-1] + vector mvAllIndices; + + // RANSAC probability + double mRansacProb; + + // RANSAC min inliers + int mRansacMinInliers; + + // RANSAC max iterations + int mRansacMaxIts; + + // RANSAC expected inliers/total ratio + float mRansacEpsilon; + + // RANSAC Threshold inlier/outlier. Max error e = dist(P1,T_12*P2)^2 + float mRansacTh; + + // RANSAC Minimun Set used at each iteration + int mRansacMinSet; + + // Max square error associated with scale level. Max error = th*th*sigma(level)*sigma(level) + vector mvMaxError; + + GeometricCamera* mpCamera; + + }; + +} + + + + +#endif //ORB_SLAM3_MLPNPSOLVER_H diff --git a/third_party/ORB_SLAM3/include/Map.h b/third_party/ORB_SLAM3/include/Map.h new file mode 100644 index 0000000..00396ba --- /dev/null +++ b/third_party/ORB_SLAM3/include/Map.h @@ -0,0 +1,205 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + + +#ifndef MAP_H +#define MAP_H + +#include "MapPoint.h" +#include "KeyFrame.h" + +#include +#include +#include + +#include + + +namespace ORB_SLAM3 +{ + +class MapPoint; +class KeyFrame; +class Atlas; +class KeyFrameDatabase; + +class Map +{ + friend class boost::serialization::access; + + template + void serialize(Archive &ar, const unsigned int version) + { + ar & mnId; + ar & mnInitKFid; + ar & mnMaxKFid; + ar & mnBigChangeIdx; + // Set of KeyFrames and MapPoints, in this version the set serializator is not working + //ar & mspKeyFrames; + //ar & mspMapPoints; + + ar & mvpBackupKeyFrames; + ar & mvpBackupMapPoints; + + ar & mvBackupKeyFrameOriginsId; + + ar & mnBackupKFinitialID; + ar & mnBackupKFlowerID; + + ar & mbImuInitialized; + ar & mbIsInertial; + ar & mbIMU_BA1; + ar & mbIMU_BA2; + + ar & mnInitKFid; + ar & mnMaxKFid; + ar & mnLastLoopKFid; + } + +public: + Map(); + Map(int initKFid); + ~Map(); + + void AddKeyFrame(KeyFrame* pKF); + void AddMapPoint(MapPoint* pMP); + void EraseMapPoint(MapPoint* pMP); + void EraseKeyFrame(KeyFrame* pKF); + void SetReferenceMapPoints(const std::vector &vpMPs); + void InformNewBigChange(); + int GetLastBigChangeIdx(); + + std::vector GetAllKeyFrames(); + std::vector GetAllMapPoints(); + std::vector GetReferenceMapPoints(); + + long unsigned int MapPointsInMap(); + long unsigned KeyFramesInMap(); + + long unsigned int GetId(); + + long unsigned int GetInitKFid(); + void SetInitKFid(long unsigned int initKFif); + long unsigned int GetMaxKFid(); + + KeyFrame* GetOriginKF(); + + void SetCurrentMap(); + void SetStoredMap(); + + bool HasThumbnail(); + bool IsInUse(); + + void SetBad(); + bool IsBad(); + + void clear(); + + int GetMapChangeIndex(); + void IncreaseChangeIndex(); + int GetLastMapChange(); + void SetLastMapChange(int currentChangeId); + + void SetImuInitialized(); + bool isImuInitialized(); + + void RotateMap(const cv::Mat &R); + void ApplyScaledRotation(const cv::Mat &R, const float s, const bool bScaledVel=false, const cv::Mat t=cv::Mat::zeros(cv::Size(1,3),CV_32F)); + + void SetInertialSensor(); + bool IsInertial(); + void SetIniertialBA1(); + void SetIniertialBA2(); + bool GetIniertialBA1(); + bool GetIniertialBA2(); + + void PrintEssentialGraph(); + bool CheckEssentialGraph(); + void ChangeId(long unsigned int nId); + + unsigned int GetLowerKFID(); + + void PreSave(std::set &spCams); + void PostLoad(KeyFrameDatabase* pKFDB, ORBVocabulary* pORBVoc, map& mpKeyFrameId, map &mpCams); + + void printReprojectionError(list &lpLocalWindowKFs, KeyFrame* mpCurrentKF, string &name, string &name_folder); + + vector mvpKeyFrameOrigins; + vector mvBackupKeyFrameOriginsId; + KeyFrame* mpFirstRegionKF; + std::mutex mMutexMapUpdate; + + // This avoid that two points are created simultaneously in separate threads (id conflict) + std::mutex mMutexPointCreation; + + bool mbFail; + + // Size of the thumbnail (always in power of 2) + static const int THUMB_WIDTH = 512; + static const int THUMB_HEIGHT = 512; + + static long unsigned int nNextId; + +protected: + + long unsigned int mnId; + + std::set mspMapPoints; + std::set mspKeyFrames; + + std::vector mvpBackupMapPoints; + std::vector mvpBackupKeyFrames; + + KeyFrame* mpKFinitial; + KeyFrame* mpKFlowerID; + + unsigned long int mnBackupKFinitialID; + unsigned long int mnBackupKFlowerID; + + std::vector mvpReferenceMapPoints; + + bool mbImuInitialized; + + int mnMapChange; + int mnMapChangeNotified; + + long unsigned int mnInitKFid; + long unsigned int mnMaxKFid; + long unsigned int mnLastLoopKFid; + + // Index related to a big change in the map (loop closure, global BA) + int mnBigChangeIdx; + + + // View of the map in aerial sight (for the AtlasViewer) + GLubyte* mThumbnail; + + bool mIsInUse; + bool mHasTumbnail; + bool mbBad = false; + + bool mbIsInertial; + bool mbIMU_BA1; + bool mbIMU_BA2; + + std::mutex mMutexMap; +}; + +} //namespace ORB_SLAM3 + +#endif // MAP_H diff --git a/third_party/ORB_SLAM3/include/MapDrawer.h b/third_party/ORB_SLAM3/include/MapDrawer.h new file mode 100644 index 0000000..88f256a --- /dev/null +++ b/third_party/ORB_SLAM3/include/MapDrawer.h @@ -0,0 +1,73 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + + +#ifndef MAPDRAWER_H +#define MAPDRAWER_H + +#include"Atlas.h" +#include"MapPoint.h" +#include"KeyFrame.h" +#include + +#include + +namespace ORB_SLAM3 +{ + +class MapDrawer +{ +public: + MapDrawer(Atlas* pAtlas, const string &strSettingPath); + + Atlas* mpAtlas; + + void DrawMapPoints(); + void DrawKeyFrames(const bool bDrawKF, const bool bDrawGraph, const bool bDrawInertialGraph); + void DrawCurrentCamera(pangolin::OpenGlMatrix &Twc); + void SetCurrentCameraPose(const cv::Mat &Tcw); + void SetReferenceKeyFrame(KeyFrame *pKF); + void GetCurrentOpenGLCameraMatrix(pangolin::OpenGlMatrix &M, pangolin::OpenGlMatrix &MOw); + void GetCurrentOpenGLCameraMatrix(pangolin::OpenGlMatrix &M, pangolin::OpenGlMatrix &MOw, pangolin::OpenGlMatrix &MTwwp); + +private: + + bool ParseViewerParamFile(cv::FileStorage &fSettings); + + float mKeyFrameSize; + float mKeyFrameLineWidth; + float mGraphLineWidth; + float mPointSize; + float mCameraSize; + float mCameraLineWidth; + + cv::Mat mCameraPose; + + std::mutex mMutexCamera; + + float mfFrameColors[6][3] = {{0.0f, 0.0f, 1.0f}, + {0.8f, 0.4f, 1.0f}, + {1.0f, 0.2f, 0.4f}, + {0.6f, 0.0f, 1.0f}, + {1.0f, 1.0f, 0.0f}, + {0.0f, 1.0f, 1.0f}}; +}; + +} //namespace ORB_SLAM + +#endif // MAPDRAWER_H diff --git a/third_party/ORB_SLAM3/include/MapPoint.h b/third_party/ORB_SLAM3/include/MapPoint.h new file mode 100644 index 0000000..4ab4180 --- /dev/null +++ b/third_party/ORB_SLAM3/include/MapPoint.h @@ -0,0 +1,274 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + + +#ifndef MAPPOINT_H +#define MAPPOINT_H + +#include"KeyFrame.h" +#include"Frame.h" +#include"Map.h" + +#include +#include + +#include +#include +#include + +namespace ORB_SLAM3 +{ + +class KeyFrame; +class Map; +class Frame; + +class MapPoint +{ + template + void serializeMatrix(Archive &ar, cv::Mat& mat, const unsigned int version) + { + int cols, rows, type; + bool continuous; + + if (Archive::is_saving::value) { + cols = mat.cols; rows = mat.rows; type = mat.type(); + continuous = mat.isContinuous(); + } + + ar & cols & rows & type & continuous; + if (Archive::is_loading::value) + mat.create(rows, cols, type); + + if (continuous) { + const unsigned int data_size = rows * cols * mat.elemSize(); + ar & boost::serialization::make_array(mat.ptr(), data_size); + } else { + const unsigned int row_size = cols*mat.elemSize(); + for (int i = 0; i < rows; i++) { + ar & boost::serialization::make_array(mat.ptr(i), row_size); + } + } + } + + friend class boost::serialization::access; + template + void serialize(Archive & ar, const unsigned int version) + { + ar & mnId; + ar & mnFirstKFid; + ar & mnFirstFrame; + ar & nObs; + // Variables used by the tracking + ar & mTrackProjX; + ar & mTrackProjY; + ar & mTrackDepth; + ar & mTrackDepthR; + ar & mTrackProjXR; + ar & mTrackProjYR; + ar & mbTrackInView; + ar & mbTrackInViewR; + ar & mnTrackScaleLevel; + ar & mnTrackScaleLevelR; + ar & mTrackViewCos; + ar & mTrackViewCosR; + ar & mnTrackReferenceForFrame; + ar & mnLastFrameSeen; + + // Variables used by local mapping + ar & mnBALocalForKF; + ar & mnFuseCandidateForKF; + + // Variables used by loop closing and merging + ar & mnLoopPointForKF; + ar & mnCorrectedByKF; + ar & mnCorrectedReference; + serializeMatrix(ar,mPosGBA,version); + ar & mnBAGlobalForKF; + ar & mnBALocalForMerge; + serializeMatrix(ar,mPosMerge,version); + serializeMatrix(ar,mNormalVectorMerge,version); + + // Protected variables + serializeMatrix(ar,mWorldPos,version); + //ar & BOOST_SERIALIZATION_NVP(mBackupObservationsId); + ar & mBackupObservationsId1; + ar & mBackupObservationsId2; + serializeMatrix(ar,mNormalVector,version); + serializeMatrix(ar,mDescriptor,version); + ar & mBackupRefKFId; + ar & mnVisible; + ar & mnFound; + + ar & mbBad; + ar & mBackupReplacedId; + + ar & mfMinDistance; + ar & mfMaxDistance; + + } + + +public: + MapPoint(); + + MapPoint(const cv::Mat &Pos, KeyFrame* pRefKF, Map* pMap); + MapPoint(const double invDepth, cv::Point2f uv_init, KeyFrame* pRefKF, KeyFrame* pHostKF, Map* pMap); + MapPoint(const cv::Mat &Pos, Map* pMap, Frame* pFrame, const int &idxF); + + void SetWorldPos(const cv::Mat &Pos); + + cv::Mat GetWorldPos(); + + cv::Mat GetNormal(); + KeyFrame* GetReferenceKeyFrame(); + + std::map> GetObservations(); + int Observations(); + + void AddObservation(KeyFrame* pKF,int idx); + void EraseObservation(KeyFrame* pKF); + + std::tuple GetIndexInKeyFrame(KeyFrame* pKF); + bool IsInKeyFrame(KeyFrame* pKF); + + void SetBadFlag(); + bool isBad(); + + void Replace(MapPoint* pMP); + MapPoint* GetReplaced(); + + void IncreaseVisible(int n=1); + void IncreaseFound(int n=1); + float GetFoundRatio(); + inline int GetFound(){ + return mnFound; + } + + void ComputeDistinctiveDescriptors(); + + cv::Mat GetDescriptor(); + + void UpdateNormalAndDepth(); + void SetNormalVector(cv::Mat& normal); + + float GetMinDistanceInvariance(); + float GetMaxDistanceInvariance(); + int PredictScale(const float ¤tDist, KeyFrame*pKF); + int PredictScale(const float ¤tDist, Frame* pF); + + Map* GetMap(); + void UpdateMap(Map* pMap); + + void PrintObservations(); + + void PreSave(set& spKF,set& spMP); + void PostLoad(map& mpKFid, map& mpMPid); + +public: + long unsigned int mnId; + static long unsigned int nNextId; + long int mnFirstKFid; + long int mnFirstFrame; + int nObs; + + // Variables used by the tracking + float mTrackProjX; + float mTrackProjY; + float mTrackDepth; + float mTrackDepthR; + float mTrackProjXR; + float mTrackProjYR; + bool mbTrackInView, mbTrackInViewR; + int mnTrackScaleLevel, mnTrackScaleLevelR; + float mTrackViewCos, mTrackViewCosR; + long unsigned int mnTrackReferenceForFrame; + long unsigned int mnLastFrameSeen; + + // Variables used by local mapping + long unsigned int mnBALocalForKF; + long unsigned int mnFuseCandidateForKF; + + // Variables used by loop closing + long unsigned int mnLoopPointForKF; + long unsigned int mnCorrectedByKF; + long unsigned int mnCorrectedReference; + cv::Mat mPosGBA; + long unsigned int mnBAGlobalForKF; + long unsigned int mnBALocalForMerge; + + // Variable used by merging + cv::Mat mPosMerge; + cv::Mat mNormalVectorMerge; + + + // Fopr inverse depth optimization + double mInvDepth; + double mInitU; + double mInitV; + KeyFrame* mpHostKF; + + static std::mutex mGlobalMutex; + + unsigned int mnOriginMapId; + +protected: + + // Position in absolute coordinates + cv::Mat mWorldPos; + + // Keyframes observing the point and associated index in keyframe + std::map > mObservations; + // For save relation without pointer, this is necessary for save/load function + std::map mBackupObservationsId1; + std::map mBackupObservationsId2; + + // Mean viewing direction + cv::Mat mNormalVector; + + // Best descriptor to fast matching + cv::Mat mDescriptor; + + // Reference KeyFrame + KeyFrame* mpRefKF; + long unsigned int mBackupRefKFId; + + // Tracking counters + int mnVisible; + int mnFound; + + // Bad flag (we do not currently erase MapPoint from memory) + bool mbBad; + MapPoint* mpReplaced; + // For save relation without pointer, this is necessary for save/load function + long long int mBackupReplacedId; + + // Scale invariance distances + float mfMinDistance; + float mfMaxDistance; + + Map* mpMap; + + std::mutex mMutexPos; + std::mutex mMutexFeatures; + std::mutex mMutexMap; +}; + +} //namespace ORB_SLAM + +#endif // MAPPOINT_H diff --git a/third_party/ORB_SLAM3/include/ORBVocabulary.h b/third_party/ORB_SLAM3/include/ORBVocabulary.h new file mode 100644 index 0000000..24929d0 --- /dev/null +++ b/third_party/ORB_SLAM3/include/ORBVocabulary.h @@ -0,0 +1,34 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + + +#ifndef ORBVOCABULARY_H +#define ORBVOCABULARY_H + +#include"Thirdparty/DBoW2/DBoW2/FORB.h" +#include"Thirdparty/DBoW2/DBoW2/TemplatedVocabulary.h" + +namespace ORB_SLAM3 +{ + +typedef DBoW2::TemplatedVocabulary + ORBVocabulary; + +} //namespace ORB_SLAM + +#endif // ORBVOCABULARY_H diff --git a/third_party/ORB_SLAM3/include/ORBextractor.h b/third_party/ORB_SLAM3/include/ORBextractor.h new file mode 100644 index 0000000..2c4ca47 --- /dev/null +++ b/third_party/ORB_SLAM3/include/ORBextractor.h @@ -0,0 +1,114 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + +#ifndef ORBEXTRACTOR_H +#define ORBEXTRACTOR_H + +#include +#include +#include + + +namespace ORB_SLAM3 +{ + +class ExtractorNode +{ +public: + ExtractorNode():bNoMore(false){} + + void DivideNode(ExtractorNode &n1, ExtractorNode &n2, ExtractorNode &n3, ExtractorNode &n4); + + std::vector vKeys; + cv::Point2i UL, UR, BL, BR; + std::list::iterator lit; + bool bNoMore; +}; + +class ORBextractor +{ +public: + + enum {HARRIS_SCORE=0, FAST_SCORE=1 }; + + ORBextractor(int nfeatures, float scaleFactor, int nlevels, + int iniThFAST, int minThFAST); + + ~ORBextractor(){} + + // Compute the ORB features and descriptors on an image. + // ORB are dispersed on the image using an octree. + // Mask is ignored in the current implementation. + int operator()( cv::InputArray _image, cv::InputArray _mask, + std::vector& _keypoints, + cv::OutputArray _descriptors, std::vector &vLappingArea); + + int inline GetLevels(){ + return nlevels;} + + float inline GetScaleFactor(){ + return scaleFactor;} + + std::vector inline GetScaleFactors(){ + return mvScaleFactor; + } + + std::vector inline GetInverseScaleFactors(){ + return mvInvScaleFactor; + } + + std::vector inline GetScaleSigmaSquares(){ + return mvLevelSigma2; + } + + std::vector inline GetInverseScaleSigmaSquares(){ + return mvInvLevelSigma2; + } + + std::vector mvImagePyramid; + +protected: + + void ComputePyramid(cv::Mat image); + void ComputeKeyPointsOctTree(std::vector >& allKeypoints); + std::vector DistributeOctTree(const std::vector& vToDistributeKeys, const int &minX, + const int &maxX, const int &minY, const int &maxY, const int &nFeatures, const int &level); + + void ComputeKeyPointsOld(std::vector >& allKeypoints); + std::vector pattern; + + int nfeatures; + double scaleFactor; + int nlevels; + int iniThFAST; + int minThFAST; + + std::vector mnFeaturesPerLevel; + + std::vector umax; + + std::vector mvScaleFactor; + std::vector mvInvScaleFactor; + std::vector mvLevelSigma2; + std::vector mvInvLevelSigma2; +}; + +} //namespace ORB_SLAM + +#endif + diff --git a/third_party/ORB_SLAM3/include/ORBmatcher.h b/third_party/ORB_SLAM3/include/ORBmatcher.h new file mode 100644 index 0000000..44241b1 --- /dev/null +++ b/third_party/ORB_SLAM3/include/ORBmatcher.h @@ -0,0 +1,112 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + + +#ifndef ORBMATCHER_H +#define ORBMATCHER_H + +#include +#include +#include + +#include"MapPoint.h" +#include"KeyFrame.h" +#include"Frame.h" + + +namespace ORB_SLAM3 +{ + +class ORBmatcher +{ +public: + + ORBmatcher(float nnratio=0.6, bool checkOri=true); + + // Computes the Hamming distance between two ORB descriptors + static int DescriptorDistance(const cv::Mat &a, const cv::Mat &b); + + // Search matches between Frame keypoints and projected MapPoints. Returns number of matches + // Used to track the local map (Tracking) + int SearchByProjection(Frame &F, const std::vector &vpMapPoints, const float th=3, const bool bFarPoints = false, const float thFarPoints = 50.0f); + + // Project MapPoints tracked in last frame into the current frame and search matches. + // Used to track from previous frame (Tracking) + int SearchByProjection(Frame &CurrentFrame, const Frame &LastFrame, const float th, const bool bMono); + + // Project MapPoints seen in KeyFrame into the Frame and search matches. + // Used in relocalisation (Tracking) + int SearchByProjection(Frame &CurrentFrame, KeyFrame* pKF, const std::set &sAlreadyFound, const float th, const int ORBdist); + + // Project MapPoints using a Similarity Transformation and search matches. + // Used in loop detection (Loop Closing) + int SearchByProjection(KeyFrame* pKF, cv::Mat Scw, const std::vector &vpPoints, std::vector &vpMatched, int th, float ratioHamming=1.0); + + // Project MapPoints using a Similarity Transformation and search matches. + // Used in Place Recognition (Loop Closing and Merging) + int SearchByProjection(KeyFrame* pKF, cv::Mat Scw, const std::vector &vpPoints, const std::vector &vpPointsKFs, std::vector &vpMatched, std::vector &vpMatchedKF, int th, float ratioHamming=1.0); + + // Search matches between MapPoints in a KeyFrame and ORB in a Frame. + // Brute force constrained to ORB that belong to the same vocabulary node (at a certain level) + // Used in Relocalisation and Loop Detection + int SearchByBoW(KeyFrame *pKF, Frame &F, std::vector &vpMapPointMatches); + int SearchByBoW(KeyFrame *pKF1, KeyFrame* pKF2, std::vector &vpMatches12); + + // Matching for the Map Initialization (only used in the monocular case) + int SearchForInitialization(Frame &F1, Frame &F2, std::vector &vbPrevMatched, std::vector &vnMatches12, int windowSize=10); + + // Matching to triangulate new MapPoints. Check Epipolar Constraint. + int SearchForTriangulation(KeyFrame *pKF1, KeyFrame* pKF2, cv::Mat F12, + std::vector > &vMatchedPairs, const bool bOnlyStereo, const bool bCoarse = false); + + int SearchForTriangulation(KeyFrame *pKF1, KeyFrame *pKF2, cv::Mat F12, + vector > &vMatchedPairs, const bool bOnlyStereo, vector &vMatchedPoints); + + // Search matches between MapPoints seen in KF1 and KF2 transforming by a Sim3 [s12*R12|t12] + // In the stereo and RGB-D case, s12=1 + int SearchBySim3(KeyFrame* pKF1, KeyFrame* pKF2, std::vector &vpMatches12, const float &s12, const cv::Mat &R12, const cv::Mat &t12, const float th); + + // Project MapPoints into KeyFrame and search for duplicated MapPoints. + int Fuse(KeyFrame* pKF, const vector &vpMapPoints, const float th=3.0, const bool bRight = false); + + // Project MapPoints into KeyFrame using a given Sim3 and search for duplicated MapPoints. + int Fuse(KeyFrame* pKF, cv::Mat Scw, const std::vector &vpPoints, float th, vector &vpReplacePoint); + +public: + + static const int TH_LOW; + static const int TH_HIGH; + static const int HISTO_LENGTH; + + +protected: + + bool CheckDistEpipolarLine(const cv::KeyPoint &kp1, const cv::KeyPoint &kp2, const cv::Mat &F12, const KeyFrame *pKF, const bool b1=false); + bool CheckDistEpipolarLine2(const cv::KeyPoint &kp1, const cv::KeyPoint &kp2, const cv::Mat &F12, const KeyFrame *pKF, const float unc); + + float RadiusByViewingCos(const float &viewCos); + + void ComputeThreeMaxima(std::vector* histo, const int L, int &ind1, int &ind2, int &ind3); + + float mfNNratio; + bool mbCheckOrientation; +}; + +}// namespace ORB_SLAM + +#endif // ORBMATCHER_H diff --git a/third_party/ORB_SLAM3/include/OptimizableTypes.h b/third_party/ORB_SLAM3/include/OptimizableTypes.h new file mode 100644 index 0000000..c2321b7 --- /dev/null +++ b/third_party/ORB_SLAM3/include/OptimizableTypes.h @@ -0,0 +1,219 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + +#ifndef ORB_SLAM3_OPTIMIZABLETYPES_H +#define ORB_SLAM3_OPTIMIZABLETYPES_H + +#include "Thirdparty/g2o/g2o/core/base_unary_edge.h" +#include +#include + +#include +#include + + +namespace ORB_SLAM3 { +class EdgeSE3ProjectXYZOnlyPose: public g2o::BaseUnaryEdge<2, Eigen::Vector2d, g2o::VertexSE3Expmap>{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + EdgeSE3ProjectXYZOnlyPose(){} + + bool read(std::istream& is); + + bool write(std::ostream& os) const; + + void computeError() { + const g2o::VertexSE3Expmap* v1 = static_cast(_vertices[0]); + Eigen::Vector2d obs(_measurement); + _error = obs-pCamera->project(v1->estimate().map(Xw)); + } + + bool isDepthPositive() { + const g2o::VertexSE3Expmap* v1 = static_cast(_vertices[0]); + return (v1->estimate().map(Xw))(2)>0.0; + } + + + virtual void linearizeOplus(); + + Eigen::Vector3d Xw; + GeometricCamera* pCamera; +}; + +class EdgeSE3ProjectXYZOnlyPoseToBody: public g2o::BaseUnaryEdge<2, Eigen::Vector2d, g2o::VertexSE3Expmap>{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + EdgeSE3ProjectXYZOnlyPoseToBody(){} + + bool read(std::istream& is); + + bool write(std::ostream& os) const; + + void computeError() { + const g2o::VertexSE3Expmap* v1 = static_cast(_vertices[0]); + Eigen::Vector2d obs(_measurement); + _error = obs-pCamera->project((mTrl * v1->estimate()).map(Xw)); + } + + bool isDepthPositive() { + const g2o::VertexSE3Expmap* v1 = static_cast(_vertices[0]); + return ((mTrl * v1->estimate()).map(Xw))(2)>0.0; + } + + + virtual void linearizeOplus(); + + Eigen::Vector3d Xw; + GeometricCamera* pCamera; + + g2o::SE3Quat mTrl; +}; + +class EdgeSE3ProjectXYZ: public g2o::BaseBinaryEdge<2, Eigen::Vector2d, g2o::VertexSBAPointXYZ, g2o::VertexSE3Expmap>{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + EdgeSE3ProjectXYZ(); + + bool read(std::istream& is); + + bool write(std::ostream& os) const; + + void computeError() { + const g2o::VertexSE3Expmap* v1 = static_cast(_vertices[1]); + const g2o::VertexSBAPointXYZ* v2 = static_cast(_vertices[0]); + Eigen::Vector2d obs(_measurement); + _error = obs-pCamera->project(v1->estimate().map(v2->estimate())); + } + + bool isDepthPositive() { + const g2o::VertexSE3Expmap* v1 = static_cast(_vertices[1]); + const g2o::VertexSBAPointXYZ* v2 = static_cast(_vertices[0]); + return ((v1->estimate().map(v2->estimate()))(2)>0.0); + } + + virtual void linearizeOplus(); + + GeometricCamera* pCamera; +}; + +class EdgeSE3ProjectXYZToBody: public g2o::BaseBinaryEdge<2, Eigen::Vector2d, g2o::VertexSBAPointXYZ, g2o::VertexSE3Expmap>{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + EdgeSE3ProjectXYZToBody(); + + bool read(std::istream& is); + + bool write(std::ostream& os) const; + + void computeError() { + const g2o::VertexSE3Expmap* v1 = static_cast(_vertices[1]); + const g2o::VertexSBAPointXYZ* v2 = static_cast(_vertices[0]); + Eigen::Vector2d obs(_measurement); + _error = obs-pCamera->project((mTrl * v1->estimate()).map(v2->estimate())); + } + + bool isDepthPositive() { + const g2o::VertexSE3Expmap* v1 = static_cast(_vertices[1]); + const g2o::VertexSBAPointXYZ* v2 = static_cast(_vertices[0]); + return ((mTrl * v1->estimate()).map(v2->estimate()))(2)>0.0; + } + + virtual void linearizeOplus(); + + GeometricCamera* pCamera; + g2o::SE3Quat mTrl; +}; + +class VertexSim3Expmap : public g2o::BaseVertex<7, g2o::Sim3> +{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + VertexSim3Expmap(); + virtual bool read(std::istream& is); + virtual bool write(std::ostream& os) const; + + virtual void setToOriginImpl() { + _estimate = g2o::Sim3(); + } + + virtual void oplusImpl(const double* update_) + { + Eigen::Map update(const_cast(update_)); + + if (_fix_scale) + update[6] = 0; + + g2o::Sim3 s(update); + setEstimate(s*estimate()); + } + + GeometricCamera* pCamera1, *pCamera2; + + bool _fix_scale; +}; + + +class EdgeSim3ProjectXYZ : public g2o::BaseBinaryEdge<2, Eigen::Vector2d, g2o::VertexSBAPointXYZ, ORB_SLAM3::VertexSim3Expmap> +{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + EdgeSim3ProjectXYZ(); + virtual bool read(std::istream& is); + virtual bool write(std::ostream& os) const; + + void computeError() + { + const ORB_SLAM3::VertexSim3Expmap* v1 = static_cast(_vertices[1]); + const g2o::VertexSBAPointXYZ* v2 = static_cast(_vertices[0]); + + Eigen::Vector2d obs(_measurement); + _error = obs-v1->pCamera1->project(v1->estimate().map(v2->estimate())); + } + + // virtual void linearizeOplus(); + +}; + +class EdgeInverseSim3ProjectXYZ : public g2o::BaseBinaryEdge<2, Eigen::Vector2d, g2o::VertexSBAPointXYZ, VertexSim3Expmap> +{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + EdgeInverseSim3ProjectXYZ(); + virtual bool read(std::istream& is); + virtual bool write(std::ostream& os) const; + + void computeError() + { + const ORB_SLAM3::VertexSim3Expmap* v1 = static_cast(_vertices[1]); + const g2o::VertexSBAPointXYZ* v2 = static_cast(_vertices[0]); + + Eigen::Vector2d obs(_measurement); + _error = obs-v1->pCamera2->project((v1->estimate().inverse().map(v2->estimate()))); + } + + // virtual void linearizeOplus(); + +}; + +} + +#endif //ORB_SLAM3_OPTIMIZABLETYPES_H diff --git a/third_party/ORB_SLAM3/include/Optimizer.h b/third_party/ORB_SLAM3/include/Optimizer.h new file mode 100644 index 0000000..f56c1a0 --- /dev/null +++ b/third_party/ORB_SLAM3/include/Optimizer.h @@ -0,0 +1,123 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + + +#ifndef OPTIMIZER_H +#define OPTIMIZER_H + +#include "Map.h" +#include "MapPoint.h" +#include "KeyFrame.h" +#include "LoopClosing.h" +#include "Frame.h" + +#include + +#include "Thirdparty/g2o/g2o/types/types_seven_dof_expmap.h" +#include "Thirdparty/g2o/g2o/core/sparse_block_matrix.h" +#include "Thirdparty/g2o/g2o/core/block_solver.h" +#include "Thirdparty/g2o/g2o/core/optimization_algorithm_levenberg.h" +#include "Thirdparty/g2o/g2o/core/optimization_algorithm_gauss_newton.h" +#include "Thirdparty/g2o/g2o/solvers/linear_solver_eigen.h" +#include "Thirdparty/g2o/g2o/types/types_six_dof_expmap.h" +#include "Thirdparty/g2o/g2o/core/robust_kernel_impl.h" +#include "Thirdparty/g2o/g2o/solvers/linear_solver_dense.h" + +namespace ORB_SLAM3 +{ + +class LoopClosing; + +class Optimizer +{ +public: + + void static BundleAdjustment(const std::vector &vpKF, const std::vector &vpMP, + int nIterations = 5, bool *pbStopFlag=NULL, const unsigned long nLoopKF=0, + const bool bRobust = true); + void static GlobalBundleAdjustemnt(Map* pMap, int nIterations=5, bool *pbStopFlag=NULL, + const unsigned long nLoopKF=0, const bool bRobust = true); + void static FullInertialBA(Map *pMap, int its, const bool bFixLocal=false, const unsigned long nLoopKF=0, bool *pbStopFlag=NULL, bool bInit=false, float priorG = 1e2, float priorA=1e6, Eigen::VectorXd *vSingVal = NULL, bool *bHess=NULL); + + void static LocalBundleAdjustment(KeyFrame* pKF, bool *pbStopFlag, vector &vpNonEnoughOptKFs); + void static LocalBundleAdjustment(KeyFrame* pKF, bool *pbStopFlag, Map *pMap, int& num_fixedKF); + + void static MergeBundleAdjustmentVisual(KeyFrame* pCurrentKF, vector vpWeldingKFs, vector vpFixedKFs, bool *pbStopFlag); + + int static PoseOptimization(Frame* pFrame); + + int static PoseInertialOptimizationLastKeyFrame(Frame* pFrame, bool bRecInit = false); + int static PoseInertialOptimizationLastFrame(Frame *pFrame, bool bRecInit = false); + + // if bFixScale is true, 6DoF optimization (stereo,rgbd), 7DoF otherwise (mono) + void static OptimizeEssentialGraph(Map* pMap, KeyFrame* pLoopKF, KeyFrame* pCurKF, + const LoopClosing::KeyFrameAndPose &NonCorrectedSim3, + const LoopClosing::KeyFrameAndPose &CorrectedSim3, + const map > &LoopConnections, + const bool &bFixScale); + void static OptimizeEssentialGraph6DoF(KeyFrame* pCurKF, vector &vpFixedKFs, vector &vpFixedCorrectedKFs, + vector &vpNonFixedKFs, vector &vpNonCorrectedMPs, double scale); + void static OptimizeEssentialGraph(KeyFrame* pCurKF, vector &vpFixedKFs, vector &vpFixedCorrectedKFs, + vector &vpNonFixedKFs, vector &vpNonCorrectedMPs); + void static OptimizeEssentialGraph(KeyFrame* pCurKF, + const LoopClosing::KeyFrameAndPose &NonCorrectedSim3, + const LoopClosing::KeyFrameAndPose &CorrectedSim3); + // For inetial loopclosing + void static OptimizeEssentialGraph4DoF(Map* pMap, KeyFrame* pLoopKF, KeyFrame* pCurKF, + const LoopClosing::KeyFrameAndPose &NonCorrectedSim3, + const LoopClosing::KeyFrameAndPose &CorrectedSim3, + const map > &LoopConnections); + + // if bFixScale is true, optimize SE3 (stereo,rgbd), Sim3 otherwise (mono) (OLD) + static int OptimizeSim3(KeyFrame* pKF1, KeyFrame* pKF2, std::vector &vpMatches1, + g2o::Sim3 &g2oS12, const float th2, const bool bFixScale); + // if bFixScale is true, optimize SE3 (stereo,rgbd), Sim3 otherwise (mono) (NEW) + static int OptimizeSim3(KeyFrame* pKF1, KeyFrame* pKF2, std::vector &vpMatches1, + g2o::Sim3 &g2oS12, const float th2, const bool bFixScale, + Eigen::Matrix &mAcumHessian, const bool bAllPoints=false); + static int OptimizeSim3(KeyFrame *pKF1, KeyFrame *pKF2, vector &vpMatches1, vector &vpMatches1KF, + g2o::Sim3 &g2oS12, const float th2, const bool bFixScale, Eigen::Matrix &mAcumHessian, + const bool bAllPoints = false); + + // For inertial systems + + void static LocalInertialBA(KeyFrame* pKF, bool *pbStopFlag, Map *pMap, bool bLarge = false, bool bRecInit = false); + + void static MergeInertialBA(KeyFrame* pCurrKF, KeyFrame* pMergeKF, bool *pbStopFlag, Map *pMap, LoopClosing::KeyFrameAndPose &corrPoses); + + // Local BA in welding area when two maps are merged + void static LocalBundleAdjustment(KeyFrame* pMainKF,vector vpAdjustKF, vector vpFixedKF, bool *pbStopFlag); + + // Marginalize block element (start:end,start:end). Perform Schur complement. + // Marginalized elements are filled with zeros. + static Eigen::MatrixXd Marginalize(const Eigen::MatrixXd &H, const int &start, const int &end); + // Condition block element (start:end,start:end). Fill with zeros. + static Eigen::MatrixXd Condition(const Eigen::MatrixXd &H, const int &start, const int &end); + // Remove link between element 1 and 2. Given elements 1,2 and 3 must define the whole matrix. + static Eigen::MatrixXd Sparsify(const Eigen::MatrixXd &H, const int &start1, const int &end1, const int &start2, const int &end2); + + // Inertial pose-graph + void static InertialOptimization(Map *pMap, Eigen::Matrix3d &Rwg, double &scale, Eigen::Vector3d &bg, Eigen::Vector3d &ba, bool bMono, Eigen::MatrixXd &covInertial, bool bFixedVel=false, bool bGauss=false, float priorG = 1e2, float priorA = 1e6); + void static InertialOptimization(Map *pMap, Eigen::Vector3d &bg, Eigen::Vector3d &ba, float priorG = 1e2, float priorA = 1e6); + void static InertialOptimization(vector vpKFs, Eigen::Vector3d &bg, Eigen::Vector3d &ba, float priorG = 1e2, float priorA = 1e6); + void static InertialOptimization(Map *pMap, Eigen::Matrix3d &Rwg, double &scale); +}; + +} //namespace ORB_SLAM3 + +#endif // OPTIMIZER_H diff --git a/third_party/ORB_SLAM3/include/PnPsolver.h b/third_party/ORB_SLAM3/include/PnPsolver.h new file mode 100644 index 0000000..c6d2adc --- /dev/null +++ b/third_party/ORB_SLAM3/include/PnPsolver.h @@ -0,0 +1,196 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + +/** +* Copyright (c) 2009, V. Lepetit, EPFL +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* 1. Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* 2. Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR +* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +* +* The views and conclusions contained in the software and documentation are those +* of the authors and should not be interpreted as representing official policies, +* either expressed or implied, of the FreeBSD Project +*/ + +#ifndef PNPSOLVER_H +#define PNPSOLVER_H + +#include +#include +#include "MapPoint.h" +#include "Frame.h" + +namespace ORB_SLAM3 +{ + +class PnPsolver { + public: + PnPsolver(const Frame &F, const vector &vpMapPointMatches); + + ~PnPsolver(); + + void SetRansacParameters(double probability = 0.99, int minInliers = 8 , int maxIterations = 300, int minSet = 4, float epsilon = 0.4, + float th2 = 5.991); + + cv::Mat find(vector &vbInliers, int &nInliers); + + cv::Mat iterate(int nIterations, bool &bNoMore, vector &vbInliers, int &nInliers); + + private: + + void CheckInliers(); + bool Refine(); + + // Functions from the original EPnP code + void set_maximum_number_of_correspondences(const int n); + void reset_correspondences(void); + void add_correspondence(const double X, const double Y, const double Z, + const double u, const double v); + + double compute_pose(double R[3][3], double T[3]); + + void relative_error(double & rot_err, double & transl_err, + const double Rtrue[3][3], const double ttrue[3], + const double Rest[3][3], const double test[3]); + + void print_pose(const double R[3][3], const double t[3]); + double reprojection_error(const double R[3][3], const double t[3]); + + void choose_control_points(void); + void compute_barycentric_coordinates(void); + void fill_M(CvMat * M, const int row, const double * alphas, const double u, const double v); + void compute_ccs(const double * betas, const double * ut); + void compute_pcs(void); + + void solve_for_sign(void); + + void find_betas_approx_1(const CvMat * L_6x10, const CvMat * Rho, double * betas); + void find_betas_approx_2(const CvMat * L_6x10, const CvMat * Rho, double * betas); + void find_betas_approx_3(const CvMat * L_6x10, const CvMat * Rho, double * betas); + void qr_solve(CvMat * A, CvMat * b, CvMat * X); + + double dot(const double * v1, const double * v2); + double dist2(const double * p1, const double * p2); + + void compute_rho(double * rho); + void compute_L_6x10(const double * ut, double * l_6x10); + + void gauss_newton(const CvMat * L_6x10, const CvMat * Rho, double current_betas[4]); + void compute_A_and_b_gauss_newton(const double * l_6x10, const double * rho, + double cb[4], CvMat * A, CvMat * b); + + double compute_R_and_t(const double * ut, const double * betas, + double R[3][3], double t[3]); + + void estimate_R_and_t(double R[3][3], double t[3]); + + void copy_R_and_t(const double R_dst[3][3], const double t_dst[3], + double R_src[3][3], double t_src[3]); + + void mat_to_quat(const double R[3][3], double q[4]); + + + double uc, vc, fu, fv; + + double * pws, * us, * alphas, * pcs; + int maximum_number_of_correspondences; + int number_of_correspondences; + + double cws[4][3], ccs[4][3]; + double cws_determinant; + + vector mvpMapPointMatches; + + // 2D Points + vector mvP2D; + vector mvSigma2; + + // 3D Points + vector mvP3Dw; + + // Index in Frame + vector mvKeyPointIndices; + + // Current Estimation + double mRi[3][3]; + double mti[3]; + cv::Mat mTcwi; + vector mvbInliersi; + int mnInliersi; + + // Current Ransac State + int mnIterations; + vector mvbBestInliers; + int mnBestInliers; + cv::Mat mBestTcw; + + // Refined + cv::Mat mRefinedTcw; + vector mvbRefinedInliers; + int mnRefinedInliers; + + // Number of Correspondences + int N; + + // Indices for random selection [0 .. N-1] + vector mvAllIndices; + + // RANSAC probability + double mRansacProb; + + // RANSAC min inliers + int mRansacMinInliers; + + // RANSAC max iterations + int mRansacMaxIts; + + // RANSAC expected inliers/total ratio + float mRansacEpsilon; + + // RANSAC Threshold inlier/outlier. Max error e = dist(P1,T_12*P2)^2 + float mRansacTh; + + // RANSAC Minimun Set used at each iteration + int mRansacMinSet; + + // Max square error associated with scale level. Max error = th*th*sigma(level)*sigma(level) + vector mvMaxError; + +}; + +} //namespace ORB_SLAM + +#endif //PNPSOLVER_H diff --git a/third_party/ORB_SLAM3/include/Sim3Solver.h b/third_party/ORB_SLAM3/include/Sim3Solver.h new file mode 100644 index 0000000..aeba8cf --- /dev/null +++ b/third_party/ORB_SLAM3/include/Sim3Solver.h @@ -0,0 +1,134 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + + +#ifndef SIM3SOLVER_H +#define SIM3SOLVER_H + +#include +#include + +#include "KeyFrame.h" + + + +namespace ORB_SLAM3 +{ + +class Sim3Solver +{ +public: + + Sim3Solver(KeyFrame* pKF1, KeyFrame* pKF2, const std::vector &vpMatched12, const bool bFixScale = true, + const vector vpKeyFrameMatchedMP = vector()); + + void SetRansacParameters(double probability = 0.99, int minInliers = 6 , int maxIterations = 300); + + cv::Mat find(std::vector &vbInliers12, int &nInliers); + + cv::Mat iterate(int nIterations, bool &bNoMore, std::vector &vbInliers, int &nInliers); + cv::Mat iterate(int nIterations, bool &bNoMore, vector &vbInliers, int &nInliers, bool &bConverge); + + cv::Mat GetEstimatedRotation(); + cv::Mat GetEstimatedTranslation(); + float GetEstimatedScale(); + + +protected: + + void ComputeCentroid(cv::Mat &P, cv::Mat &Pr, cv::Mat &C); + + void ComputeSim3(cv::Mat &P1, cv::Mat &P2); + + void CheckInliers(); + + void Project(const std::vector &vP3Dw, std::vector &vP2D, cv::Mat Tcw, GeometricCamera* pCamera); + void FromCameraToImage(const std::vector &vP3Dc, std::vector &vP2D, GeometricCamera* pCamera); + + +protected: + + // KeyFrames and matches + KeyFrame* mpKF1; + KeyFrame* mpKF2; + + std::vector mvX3Dc1; + std::vector mvX3Dc2; + std::vector mvpMapPoints1; + std::vector mvpMapPoints2; + std::vector mvpMatches12; + std::vector mvnIndices1; + std::vector mvSigmaSquare1; + std::vector mvSigmaSquare2; + std::vector mvnMaxError1; + std::vector mvnMaxError2; + + int N; + int mN1; + + // Current Estimation + cv::Mat mR12i; + cv::Mat mt12i; + float ms12i; + cv::Mat mT12i; + cv::Mat mT21i; + std::vector mvbInliersi; + int mnInliersi; + + // Current Ransac State + int mnIterations; + std::vector mvbBestInliers; + int mnBestInliers; + cv::Mat mBestT12; + cv::Mat mBestRotation; + cv::Mat mBestTranslation; + float mBestScale; + + // Scale is fixed to 1 in the stereo/RGBD case + bool mbFixScale; + + // Indices for random selection + std::vector mvAllIndices; + + // Projections + std::vector mvP1im1; + std::vector mvP2im2; + + // RANSAC probability + double mRansacProb; + + // RANSAC min inliers + int mRansacMinInliers; + + // RANSAC max iterations + int mRansacMaxIts; + + // Threshold inlier/outlier. e = dist(Pi,T_ij*Pj)^2 < 5.991*mSigma2 + float mTh; + float mSigma2; + + // Calibration + cv::Mat mK1; + cv::Mat mK2; + + GeometricCamera* pCamera1, *pCamera2; +}; + +} //namespace ORB_SLAM + +#endif // SIM3SOLVER_H diff --git a/third_party/ORB_SLAM3/include/System.h b/third_party/ORB_SLAM3/include/System.h new file mode 100644 index 0000000..a4becb6 --- /dev/null +++ b/third_party/ORB_SLAM3/include/System.h @@ -0,0 +1,244 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + + +#ifndef SYSTEM_H +#define SYSTEM_H + +//#define SAVE_TIMES + +#include +#include +#include +#include +#include +#include + +#include "Tracking.h" +#include "FrameDrawer.h" +#include "MapDrawer.h" +#include "Atlas.h" +#include "LocalMapping.h" +#include "LoopClosing.h" +#include "KeyFrameDatabase.h" +#include "ORBVocabulary.h" +#include "Viewer.h" +#include "ImuTypes.h" + + +namespace ORB_SLAM3 +{ + +class Verbose +{ +public: + enum eLevel + { + VERBOSITY_QUIET=0, + VERBOSITY_NORMAL=1, + VERBOSITY_VERBOSE=2, + VERBOSITY_VERY_VERBOSE=3, + VERBOSITY_DEBUG=4 + }; + + static eLevel th; + +public: + static void PrintMess(std::string str, eLevel lev) + { + if(lev <= th) + cout << str << endl; + } + + static void SetTh(eLevel _th) + { + th = _th; + } +}; + +class Viewer; +class FrameDrawer; +class Atlas; +class Tracking; +class LocalMapping; +class LoopClosing; + +class System +{ +public: + // Input sensor + enum eSensor{ + MONOCULAR=0, + STEREO=1, + RGBD=2, + IMU_MONOCULAR=3, + IMU_STEREO=4 + }; + + // File type + enum eFileType{ + TEXT_FILE=0, + BINARY_FILE=1, + }; + +public: + + // Initialize the SLAM system. It launches the Local Mapping, Loop Closing and Viewer threads. + System(const string &strVocFile, const string &strSettingsFile, const eSensor sensor, const bool bUseViewer = true, const int initFr = 0, const string &strSequence = std::string(), const string &strLoadingFile = std::string()); + + // Proccess the given stereo frame. Images must be synchronized and rectified. + // Input images: RGB (CV_8UC3) or grayscale (CV_8U). RGB is converted to grayscale. + // Returns the camera pose (empty if tracking fails). + cv::Mat TrackStereo(const cv::Mat &imLeft, const cv::Mat &imRight, const double ×tamp, const vector& vImuMeas = vector(), string filename=""); + + // Process the given rgbd frame. Depthmap must be registered to the RGB frame. + // Input image: RGB (CV_8UC3) or grayscale (CV_8U). RGB is converted to grayscale. + // Input depthmap: Float (CV_32F). + // Returns the camera pose (empty if tracking fails). + cv::Mat TrackRGBD(const cv::Mat &im, const cv::Mat &depthmap, const double ×tamp, string filename=""); + + // Proccess the given monocular frame and optionally imu data + // Input images: RGB (CV_8UC3) or grayscale (CV_8U). RGB is converted to grayscale. + // Returns the camera pose (empty if tracking fails). + cv::Mat TrackMonocular(const cv::Mat &im, const double ×tamp, const vector& vImuMeas = vector(), string filename=""); + + + // This stops local mapping thread (map building) and performs only camera tracking. + void ActivateLocalizationMode(); + // This resumes local mapping thread and performs SLAM again. + void DeactivateLocalizationMode(); + + // Returns true if there have been a big map change (loop closure, global BA) + // since last call to this function + bool MapChanged(); + + // Reset the system (clear Atlas or the active map) + void Reset(); + void ResetActiveMap(); + + // All threads will be requested to finish. + // It waits until all threads have finished. + // This function must be called before saving the trajectory. + void Shutdown(); + + // Save camera trajectory in the TUM RGB-D dataset format. + // Only for stereo and RGB-D. This method does not work for monocular. + // Call first Shutdown() + // See format details at: http://vision.in.tum.de/data/datasets/rgbd-dataset + void SaveTrajectoryTUM(const string &filename); + + // Save keyframe poses in the TUM RGB-D dataset format. + // This method works for all sensor input. + // Call first Shutdown() + // See format details at: http://vision.in.tum.de/data/datasets/rgbd-dataset + void SaveKeyFrameTrajectoryTUM(const string &filename); + + void SaveTrajectoryEuRoC(const string &filename); + void SaveKeyFrameTrajectoryEuRoC(const string &filename); + + // Save data used for initialization debug + void SaveDebugData(const int &iniIdx); + + // Save camera trajectory in the KITTI dataset format. + // Only for stereo and RGB-D. This method does not work for monocular. + // Call first Shutdown() + // See format details at: http://www.cvlibs.net/datasets/kitti/eval_odometry.php + void SaveTrajectoryKITTI(const string &filename); + + // TODO: Save/Load functions + // SaveMap(const string &filename); + // LoadMap(const string &filename); + + // Information from most recent processed frame + // You can call this right after TrackMonocular (or stereo or RGBD) + int GetTrackingState(); + std::vector GetTrackedMapPoints(); + std::vector GetTrackedKeyPointsUn(); + + // For debugging + double GetTimeFromIMUInit(); + bool isLost(); + bool isFinished(); + + void ChangeDataset(); + + //void SaveAtlas(int type); + +private: + + //bool LoadAtlas(string filename, int type); + + //string CalculateCheckSum(string filename, int type); + + // Input sensor + eSensor mSensor; + + // ORB vocabulary used for place recognition and feature matching. + ORBVocabulary* mpVocabulary; + + // KeyFrame database for place recognition (relocalization and loop detection). + KeyFrameDatabase* mpKeyFrameDatabase; + + // Map structure that stores the pointers to all KeyFrames and MapPoints. + //Map* mpMap; + Atlas* mpAtlas; + + // Tracker. It receives a frame and computes the associated camera pose. + // It also decides when to insert a new keyframe, create some new MapPoints and + // performs relocalization if tracking fails. + Tracking* mpTracker; + + // Local Mapper. It manages the local map and performs local bundle adjustment. + LocalMapping* mpLocalMapper; + + // Loop Closer. It searches loops with every new keyframe. If there is a loop it performs + // a pose graph optimization and full bundle adjustment (in a new thread) afterwards. + LoopClosing* mpLoopCloser; + + // The viewer draws the map and the current camera pose. It uses Pangolin. + Viewer* mpViewer; + + FrameDrawer* mpFrameDrawer; + MapDrawer* mpMapDrawer; + + // System threads: Local Mapping, Loop Closing, Viewer. + // The Tracking thread "lives" in the main execution thread that creates the System object. + std::thread* mptLocalMapping; + std::thread* mptLoopClosing; + std::thread* mptViewer; + + // Reset flag + std::mutex mMutexReset; + bool mbReset; + bool mbResetActiveMap; + + // Change mode flags + std::mutex mMutexMode; + bool mbActivateLocalizationMode; + bool mbDeactivateLocalizationMode; + + // Tracking state + int mTrackingState; + std::vector mTrackedMapPoints; + std::vector mTrackedKeyPointsUn; + std::mutex mMutexState; +}; + +}// namespace ORB_SLAM + +#endif // SYSTEM_H diff --git a/third_party/ORB_SLAM3/include/Tracking.h b/third_party/ORB_SLAM3/include/Tracking.h new file mode 100644 index 0000000..9ed8d5c --- /dev/null +++ b/third_party/ORB_SLAM3/include/Tracking.h @@ -0,0 +1,337 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + + +#ifndef TRACKING_H +#define TRACKING_H + +#include +#include +#include + +#include"Viewer.h" +#include"FrameDrawer.h" +#include"Atlas.h" +#include"LocalMapping.h" +#include"LoopClosing.h" +#include"Frame.h" +#include "ORBVocabulary.h" +#include"KeyFrameDatabase.h" +#include"ORBextractor.h" +#include "Initializer.h" +#include "MapDrawer.h" +#include "System.h" +#include "ImuTypes.h" + +#include "GeometricCamera.h" + +#include +#include + +namespace ORB_SLAM3 +{ + +class Viewer; +class FrameDrawer; +class Atlas; +class LocalMapping; +class LoopClosing; +class System; + +class Tracking +{ + +public: + Tracking(System* pSys, ORBVocabulary* pVoc, FrameDrawer* pFrameDrawer, MapDrawer* pMapDrawer, Atlas* pAtlas, + KeyFrameDatabase* pKFDB, const string &strSettingPath, const int sensor, const string &_nameSeq=std::string()); + + ~Tracking(); + + // Parse the config file + bool ParseCamParamFile(cv::FileStorage &fSettings); + bool ParseORBParamFile(cv::FileStorage &fSettings); + bool ParseIMUParamFile(cv::FileStorage &fSettings); + + // Preprocess the input and call Track(). Extract features and performs stereo matching. + cv::Mat GrabImageStereo(const cv::Mat &imRectLeft,const cv::Mat &imRectRight, const double ×tamp, string filename); + cv::Mat GrabImageRGBD(const cv::Mat &imRGB,const cv::Mat &imD, const double ×tamp, string filename); + cv::Mat GrabImageMonocular(const cv::Mat &im, const double ×tamp, string filename); + // cv::Mat GrabImageImuMonocular(const cv::Mat &im, const double ×tamp); + + void GrabImuData(const IMU::Point &imuMeasurement); + + void SetLocalMapper(LocalMapping* pLocalMapper); + void SetLoopClosing(LoopClosing* pLoopClosing); + void SetViewer(Viewer* pViewer); + void SetStepByStep(bool bSet); + + // Load new settings + // The focal lenght should be similar or scale prediction will fail when projecting points + void ChangeCalibration(const string &strSettingPath); + + // Use this function if you have deactivated local mapping and you only want to localize the camera. + void InformOnlyTracking(const bool &flag); + + void UpdateFrameIMU(const float s, const IMU::Bias &b, KeyFrame* pCurrentKeyFrame); + KeyFrame* GetLastKeyFrame() + { + return mpLastKeyFrame; + } + + void CreateMapInAtlas(); + std::mutex mMutexTracks; + + //-- + void NewDataset(); + int GetNumberDataset(); + int GetMatchesInliers(); +public: + + // Tracking states + enum eTrackingState{ + SYSTEM_NOT_READY=-1, + NO_IMAGES_YET=0, + NOT_INITIALIZED=1, + OK=2, + RECENTLY_LOST=3, + LOST=4, + OK_KLT=5 + }; + + eTrackingState mState; + eTrackingState mLastProcessedState; + + // Input sensor + int mSensor; + + // Current Frame + Frame mCurrentFrame; + Frame mLastFrame; + + cv::Mat mImGray; + + // Initialization Variables (Monocular) + std::vector mvIniLastMatches; + std::vector mvIniMatches; + std::vector mvbPrevMatched; + std::vector mvIniP3D; + Frame mInitialFrame; + + // Lists used to recover the full camera trajectory at the end of the execution. + // Basically we store the reference keyframe for each frame and its relative transformation + list mlRelativeFramePoses; + list mlpReferences; + list mlFrameTimes; + list mlbLost; + + // frames with estimated pose + int mTrackedFr; + bool mbStep; + + // True if local mapping is deactivated and we are performing only localization + bool mbOnlyTracking; + + void Reset(bool bLocMap = false); + void ResetActiveMap(bool bLocMap = false); + + float mMeanTrack; + bool mbInitWith3KFs; + double t0; // time-stamp of first read frame + double t0vis; // time-stamp of first inserted keyframe + double t0IMU; // time-stamp of IMU initialization + + + vector GetLocalMapMPS(); + + + //TEST-- + bool mbNeedRectify; + //cv::Mat M1l, M2l; + //cv::Mat M1r, M2r; + + bool mbWriteStats; + +protected: + + // Main tracking function. It is independent of the input sensor. + void Track(); + + // Map initialization for stereo and RGB-D + void StereoInitialization(); + + // Map initialization for monocular + void MonocularInitialization(); + void CreateNewMapPoints(); + cv::Mat ComputeF12(KeyFrame *&pKF1, KeyFrame *&pKF2); + void CreateInitialMapMonocular(); + + void CheckReplacedInLastFrame(); + bool TrackReferenceKeyFrame(); + void UpdateLastFrame(); + bool TrackWithMotionModel(); + bool PredictStateIMU(); + + bool Relocalization(); + + void UpdateLocalMap(); + void UpdateLocalPoints(); + void UpdateLocalKeyFrames(); + + bool TrackLocalMap(); + bool TrackLocalMap_old(); + void SearchLocalPoints(); + + bool NeedNewKeyFrame(); + void CreateNewKeyFrame(); + + // Perform preintegration from last frame + void PreintegrateIMU(); + + // Reset IMU biases and compute frame velocity + void ResetFrameIMU(); + void ComputeGyroBias(const vector &vpFs, float &bwx, float &bwy, float &bwz); + void ComputeVelocitiesAccBias(const vector &vpFs, float &bax, float &bay, float &baz); + + + bool mbMapUpdated; + + // Imu preintegration from last frame + IMU::Preintegrated *mpImuPreintegratedFromLastKF; + + // Queue of IMU measurements between frames + std::list mlQueueImuData; + + // Vector of IMU measurements from previous to current frame (to be filled by PreintegrateIMU) + std::vector mvImuFromLastFrame; + std::mutex mMutexImuQueue; + + // Imu calibration parameters + IMU::Calib *mpImuCalib; + + // Last Bias Estimation (at keyframe creation) + IMU::Bias mLastBias; + + // In case of performing only localization, this flag is true when there are no matches to + // points in the map. Still tracking will continue if there are enough matches with temporal points. + // In that case we are doing visual odometry. The system will try to do relocalization to recover + // "zero-drift" localization to the map. + bool mbVO; + + //Other Thread Pointers + LocalMapping* mpLocalMapper; + LoopClosing* mpLoopClosing; + + //ORB + ORBextractor* mpORBextractorLeft, *mpORBextractorRight; + ORBextractor* mpIniORBextractor; + + //BoW + ORBVocabulary* mpORBVocabulary; + KeyFrameDatabase* mpKeyFrameDB; + + // Initalization (only for monocular) + Initializer* mpInitializer; + bool mbSetInit; + + //Local Map + KeyFrame* mpReferenceKF; + std::vector mvpLocalKeyFrames; + std::vector mvpLocalMapPoints; + + // System + System* mpSystem; + + //Drawers + Viewer* mpViewer; + FrameDrawer* mpFrameDrawer; + MapDrawer* mpMapDrawer; + bool bStepByStep; + + //Atlas + Atlas* mpAtlas; + + //Calibration matrix + cv::Mat mK; + cv::Mat mDistCoef; + float mbf; + + //New KeyFrame rules (according to fps) + int mMinFrames; + int mMaxFrames; + + int mnFirstImuFrameId; + int mnFramesToResetIMU; + + // Threshold close/far points + // Points seen as close by the stereo/RGBD sensor are considered reliable + // and inserted from just one frame. Far points requiere a match in two keyframes. + float mThDepth; + + // For RGB-D inputs only. For some datasets (e.g. TUM) the depthmap values are scaled. + float mDepthMapFactor; + + //Current matches in frame + int mnMatchesInliers; + + //Last Frame, KeyFrame and Relocalisation Info + KeyFrame* mpLastKeyFrame; + unsigned int mnLastKeyFrameId; + unsigned int mnLastRelocFrameId; + double mTimeStampLost; + double time_recently_lost; + + unsigned int mnFirstFrameId; + unsigned int mnInitialFrameId; + unsigned int mnLastInitFrameId; + + bool mbCreatedMap; + + + //Motion Model + cv::Mat mVelocity; + + //Color order (true RGB, false BGR, ignored if grayscale) + bool mbRGB; + + list mlpTemporalPoints; + + //int nMapChangeIndex; + + int mnNumDataset; + + ofstream f_track_stats; + + ofstream f_track_times; + double mTime_PreIntIMU; + double mTime_PosePred; + double mTime_LocalMapTrack; + double mTime_NewKF_Dec; + + GeometricCamera* mpCamera, *mpCamera2; + + int initID, lastID; + + cv::Mat mTlr; + +public: + cv::Mat mImRight; +}; + +} //namespace ORB_SLAM + +#endif // TRACKING_H diff --git a/third_party/ORB_SLAM3/include/TwoViewReconstruction.h b/third_party/ORB_SLAM3/include/TwoViewReconstruction.h new file mode 100644 index 0000000..b2dbad9 --- /dev/null +++ b/third_party/ORB_SLAM3/include/TwoViewReconstruction.h @@ -0,0 +1,99 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + +#ifndef TwoViewReconstruction_H +#define TwoViewReconstruction_H + +#include + +#include + +namespace ORB_SLAM3 +{ + +class TwoViewReconstruction +{ + typedef std::pair Match; + +public: + + // Fix the reference frame + TwoViewReconstruction(cv::Mat& k, float sigma = 1.0, int iterations = 200); + + // Computes in parallel a fundamental matrix and a homography + // Selects a model and tries to recover the motion and the structure from motion + bool Reconstruct(const std::vector& vKeys1, const std::vector& vKeys2, const std::vector &vMatches12, + cv::Mat &R21, cv::Mat &t21, std::vector &vP3D, std::vector &vbTriangulated); + +private: + + void FindHomography(std::vector &vbMatchesInliers, float &score, cv::Mat &H21); + void FindFundamental(std::vector &vbInliers, float &score, cv::Mat &F21); + + cv::Mat ComputeH21(const std::vector &vP1, const std::vector &vP2); + cv::Mat ComputeF21(const std::vector &vP1, const std::vector &vP2); + + float CheckHomography(const cv::Mat &H21, const cv::Mat &H12, std::vector &vbMatchesInliers, float sigma); + + float CheckFundamental(const cv::Mat &F21, std::vector &vbMatchesInliers, float sigma); + + bool ReconstructF(std::vector &vbMatchesInliers, cv::Mat &F21, cv::Mat &K, + cv::Mat &R21, cv::Mat &t21, std::vector &vP3D, std::vector &vbTriangulated, float minParallax, int minTriangulated); + + bool ReconstructH(std::vector &vbMatchesInliers, cv::Mat &H21, cv::Mat &K, + cv::Mat &R21, cv::Mat &t21, std::vector &vP3D,std:: vector &vbTriangulated, float minParallax, int minTriangulated); + + void Triangulate(const cv::KeyPoint &kp1, const cv::KeyPoint &kp2, const cv::Mat &P1, const cv::Mat &P2, cv::Mat &x3D); + + void Normalize(const std::vector &vKeys, std::vector &vNormalizedPoints, cv::Mat &T); + + + int CheckRT(const cv::Mat &R, const cv::Mat &t, const std::vector &vKeys1, const std::vector &vKeys2, + const std::vector &vMatches12, std::vector &vbInliers, + const cv::Mat &K, std::vector &vP3D, float th2, std::vector &vbGood, float ¶llax); + + void DecomposeE(const cv::Mat &E, cv::Mat &R1, cv::Mat &R2, cv::Mat &t); + + + // Keypoints from Reference Frame (Frame 1) + std::vector mvKeys1; + + // Keypoints from Current Frame (Frame 2) + std::vector mvKeys2; + + // Current Matches from Reference to Current + std::vector mvMatches12; + std::vector mvbMatched1; + + // Calibration + cv::Mat mK; + + // Standard Deviation and Variance + float mSigma, mSigma2; + + // Ransac max iterations + int mMaxIterations; + + // Ransac sets + std::vector > mvSets; + +}; + +} //namespace ORB_SLAM + +#endif // TwoViewReconstruction_H diff --git a/third_party/ORB_SLAM3/include/Viewer.h b/third_party/ORB_SLAM3/include/Viewer.h new file mode 100644 index 0000000..5eb1f38 --- /dev/null +++ b/third_party/ORB_SLAM3/include/Viewer.h @@ -0,0 +1,98 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + + +#ifndef VIEWER_H +#define VIEWER_H + +#include "FrameDrawer.h" +#include "MapDrawer.h" +#include "Tracking.h" +#include "System.h" + +#include + +namespace ORB_SLAM3 +{ + +class Tracking; +class FrameDrawer; +class MapDrawer; +class System; + +class Viewer +{ +public: + Viewer(System* pSystem, FrameDrawer* pFrameDrawer, MapDrawer* pMapDrawer, Tracking *pTracking, const string &strSettingPath); + + // Main thread function. Draw points, keyframes, the current camera pose and the last processed + // frame. Drawing is refreshed according to the camera fps. We use Pangolin. + void Run(); + + void RequestFinish(); + + void RequestStop(); + + bool isFinished(); + + bool isStopped(); + + bool isStepByStep(); + + void Release(); + + void SetTrackingPause(); + + bool both; +private: + + bool ParseViewerParamFile(cv::FileStorage &fSettings); + + bool Stop(); + + System* mpSystem; + FrameDrawer* mpFrameDrawer; + MapDrawer* mpMapDrawer; + Tracking* mpTracker; + + // 1/fps in ms + double mT; + float mImageWidth, mImageHeight; + + float mViewpointX, mViewpointY, mViewpointZ, mViewpointF; + + bool CheckFinish(); + void SetFinish(); + bool mbFinishRequested; + bool mbFinished; + std::mutex mMutexFinish; + + bool mbStopped; + bool mbStopRequested; + std::mutex mMutexStop; + + bool mbStopTrack; + +}; + +} + + +#endif // VIEWER_H + + diff --git a/third_party/ORB_SLAM3/src/Atlas.cc b/third_party/ORB_SLAM3/src/Atlas.cc new file mode 100644 index 0000000..a9c6334 --- /dev/null +++ b/third_party/ORB_SLAM3/src/Atlas.cc @@ -0,0 +1,379 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + +#include "Atlas.h" +#include "Viewer.h" + +#include "GeometricCamera.h" +#include "Pinhole.h" +#include "KannalaBrandt8.h" + +namespace ORB_SLAM3 +{ + +Atlas::Atlas(){ + mpCurrentMap = static_cast(NULL); +} + +Atlas::Atlas(int initKFid): mnLastInitKFidMap(initKFid), mHasViewer(false) +{ + mpCurrentMap = static_cast(NULL); + CreateNewMap(); +} + +Atlas::~Atlas() +{ + for(std::set::iterator it = mspMaps.begin(), end = mspMaps.end(); it != end;) + { + Map* pMi = *it; + + if(pMi) + { + delete pMi; + pMi = static_cast(NULL); + + it = mspMaps.erase(it); + } + else + ++it; + + } +} + +void Atlas::CreateNewMap() +{ + unique_lock lock(mMutexAtlas); + cout << "Creation of new map with id: " << Map::nNextId << endl; + if(mpCurrentMap){ + cout << "Exits current map " << endl; + if(!mspMaps.empty() && mnLastInitKFidMap < mpCurrentMap->GetMaxKFid()) + mnLastInitKFidMap = mpCurrentMap->GetMaxKFid()+1; //The init KF is the next of current maximum + + mpCurrentMap->SetStoredMap(); + cout << "Saved map with ID: " << mpCurrentMap->GetId() << endl; + + //if(mHasViewer) + // mpViewer->AddMapToCreateThumbnail(mpCurrentMap); + } + cout << "Creation of new map with last KF id: " << mnLastInitKFidMap << endl; + + mpCurrentMap = new Map(mnLastInitKFidMap); + mpCurrentMap->SetCurrentMap(); + mspMaps.insert(mpCurrentMap); +} + +void Atlas::ChangeMap(Map* pMap) +{ + unique_lock lock(mMutexAtlas); + cout << "Chage to map with id: " << pMap->GetId() << endl; + if(mpCurrentMap){ + mpCurrentMap->SetStoredMap(); + } + + mpCurrentMap = pMap; + mpCurrentMap->SetCurrentMap(); +} + +unsigned long int Atlas::GetLastInitKFid() +{ + unique_lock lock(mMutexAtlas); + return mnLastInitKFidMap; +} + +void Atlas::SetViewer(Viewer* pViewer) +{ + mpViewer = pViewer; + mHasViewer = true; +} + +void Atlas::AddKeyFrame(KeyFrame* pKF) +{ + Map* pMapKF = pKF->GetMap(); + pMapKF->AddKeyFrame(pKF); +} + +void Atlas::AddMapPoint(MapPoint* pMP) +{ + Map* pMapMP = pMP->GetMap(); + pMapMP->AddMapPoint(pMP); +} + +void Atlas::AddCamera(GeometricCamera* pCam) +{ + mvpCameras.push_back(pCam); +} + +void Atlas::SetReferenceMapPoints(const std::vector &vpMPs) +{ + unique_lock lock(mMutexAtlas); + mpCurrentMap->SetReferenceMapPoints(vpMPs); +} + +void Atlas::InformNewBigChange() +{ + unique_lock lock(mMutexAtlas); + mpCurrentMap->InformNewBigChange(); +} + +int Atlas::GetLastBigChangeIdx() +{ + unique_lock lock(mMutexAtlas); + return mpCurrentMap->GetLastBigChangeIdx(); +} + +long unsigned int Atlas::MapPointsInMap() +{ + unique_lock lock(mMutexAtlas); + return mpCurrentMap->MapPointsInMap(); +} + +long unsigned Atlas::KeyFramesInMap() +{ + unique_lock lock(mMutexAtlas); + return mpCurrentMap->KeyFramesInMap(); +} + +std::vector Atlas::GetAllKeyFrames() +{ + unique_lock lock(mMutexAtlas); + return mpCurrentMap->GetAllKeyFrames(); +} + +std::vector Atlas::GetAllMapPoints() +{ + unique_lock lock(mMutexAtlas); + return mpCurrentMap->GetAllMapPoints(); +} + +std::vector Atlas::GetReferenceMapPoints() +{ + unique_lock lock(mMutexAtlas); + return mpCurrentMap->GetReferenceMapPoints(); +} + +vector Atlas::GetAllMaps() +{ + unique_lock lock(mMutexAtlas); + struct compFunctor + { + inline bool operator()(Map* elem1 ,Map* elem2) + { + return elem1->GetId() < elem2->GetId(); + } + }; + vector vMaps(mspMaps.begin(),mspMaps.end()); + sort(vMaps.begin(), vMaps.end(), compFunctor()); + return vMaps; +} + +int Atlas::CountMaps() +{ + unique_lock lock(mMutexAtlas); + return mspMaps.size(); +} + +void Atlas::clearMap() +{ + unique_lock lock(mMutexAtlas); + mpCurrentMap->clear(); +} + +void Atlas::clearAtlas() +{ + unique_lock lock(mMutexAtlas); + /*for(std::set::iterator it=mspMaps.begin(), send=mspMaps.end(); it!=send; it++) + { + (*it)->clear(); + delete *it; + }*/ + mspMaps.clear(); + mpCurrentMap = static_cast(NULL); + mnLastInitKFidMap = 0; +} + +Map* Atlas::GetCurrentMap() +{ + unique_lock lock(mMutexAtlas); + if(!mpCurrentMap) + CreateNewMap(); + while(mpCurrentMap->IsBad()) + usleep(3000); + + return mpCurrentMap; +} + +void Atlas::SetMapBad(Map* pMap) +{ + mspMaps.erase(pMap); + pMap->SetBad(); + + mspBadMaps.insert(pMap); +} + +void Atlas::RemoveBadMaps() +{ + /*for(Map* pMap : mspBadMaps) + { + delete pMap; + pMap = static_cast(NULL); + }*/ + mspBadMaps.clear(); +} + +bool Atlas::isInertial() +{ + unique_lock lock(mMutexAtlas); + return mpCurrentMap->IsInertial(); +} + +void Atlas::SetInertialSensor() +{ + unique_lock lock(mMutexAtlas); + mpCurrentMap->SetInertialSensor(); +} + +void Atlas::SetImuInitialized() +{ + unique_lock lock(mMutexAtlas); + mpCurrentMap->SetImuInitialized(); +} + +bool Atlas::isImuInitialized() +{ + unique_lock lock(mMutexAtlas); + return mpCurrentMap->isImuInitialized(); +} + +void Atlas::PreSave() +{ + if(mpCurrentMap){ + if(!mspMaps.empty() && mnLastInitKFidMap < mpCurrentMap->GetMaxKFid()) + mnLastInitKFidMap = mpCurrentMap->GetMaxKFid()+1; //The init KF is the next of current maximum + } + + struct compFunctor + { + inline bool operator()(Map* elem1 ,Map* elem2) + { + return elem1->GetId() < elem2->GetId(); + } + }; + std::copy(mspMaps.begin(), mspMaps.end(), std::back_inserter(mvpBackupMaps)); + sort(mvpBackupMaps.begin(), mvpBackupMaps.end(), compFunctor()); + + std::set spCams(mvpCameras.begin(), mvpCameras.end()); + cout << "There are " << spCams.size() << " cameras in the atlas" << endl; + for(Map* pMi : mvpBackupMaps) + { + cout << "Pre-save of map " << pMi->GetId() << endl; + pMi->PreSave(spCams); + } + cout << "Maps stored" << endl; + for(GeometricCamera* pCam : mvpCameras) + { + cout << "Pre-save of camera " << pCam->GetId() << endl; + if(pCam->GetType() == pCam->CAM_PINHOLE) + { + mvpBackupCamPin.push_back((Pinhole*) pCam); + } + else if(pCam->GetType() == pCam->CAM_FISHEYE) + { + mvpBackupCamKan.push_back((KannalaBrandt8*) pCam); + } + } + +} + +void Atlas::PostLoad() +{ + mvpCameras.clear(); + map mpCams; + for(Pinhole* pCam : mvpBackupCamPin) + { + //mvpCameras.push_back((GeometricCamera*)pCam); + mvpCameras.push_back(pCam); + mpCams[pCam->GetId()] = pCam; + } + for(KannalaBrandt8* pCam : mvpBackupCamKan) + { + //mvpCameras.push_back((GeometricCamera*)pCam); + mvpCameras.push_back(pCam); + mpCams[pCam->GetId()] = pCam; + } + + mspMaps.clear(); + unsigned long int numKF = 0, numMP = 0; + map mpAllKeyFrameId; + for(Map* pMi : mvpBackupMaps) + { + cout << "Map id:" << pMi->GetId() << endl; + mspMaps.insert(pMi); + map mpKeyFrameId; + pMi->PostLoad(mpKeyFrameDB, mpORBVocabulary, mpKeyFrameId, mpCams); + mpAllKeyFrameId.insert(mpKeyFrameId.begin(), mpKeyFrameId.end()); + numKF += pMi->GetAllKeyFrames().size(); + numMP += pMi->GetAllMapPoints().size(); + } + + cout << "Number KF:" << numKF << "; number MP:" << numMP << endl; + mvpBackupMaps.clear(); +} + +void Atlas::SetKeyFrameDababase(KeyFrameDatabase* pKFDB) +{ + mpKeyFrameDB = pKFDB; +} + +KeyFrameDatabase* Atlas::GetKeyFrameDatabase() +{ + return mpKeyFrameDB; +} + +void Atlas::SetORBVocabulary(ORBVocabulary* pORBVoc) +{ + mpORBVocabulary = pORBVoc; +} + +ORBVocabulary* Atlas::GetORBVocabulary() +{ + return mpORBVocabulary; +} + +long unsigned int Atlas::GetNumLivedKF() +{ + unique_lock lock(mMutexAtlas); + long unsigned int num = 0; + for(Map* mMAPi : mspMaps) + { + num += mMAPi->GetAllKeyFrames().size(); + } + + return num; +} + +long unsigned int Atlas::GetNumLivedMP() { + unique_lock lock(mMutexAtlas); + long unsigned int num = 0; + for (Map *mMAPi : mspMaps) { + num += mMAPi->GetAllMapPoints().size(); + } + + return num; +} + +} //namespace ORB_SLAM3 diff --git a/third_party/ORB_SLAM3/src/CameraModels/KannalaBrandt8.cpp b/third_party/ORB_SLAM3/src/CameraModels/KannalaBrandt8.cpp new file mode 100644 index 0000000..6651fdc --- /dev/null +++ b/third_party/ORB_SLAM3/src/CameraModels/KannalaBrandt8.cpp @@ -0,0 +1,436 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + +#include "KannalaBrandt8.h" + +#include + +//BOOST_CLASS_EXPORT_IMPLEMENT(ORB_SLAM3::KannalaBrandt8) + +namespace ORB_SLAM3 { +//BOOST_CLASS_EXPORT_GUID(KannalaBrandt8, "KannalaBrandt8") + + cv::Point2f KannalaBrandt8::project(const cv::Point3f &p3D) { + const float x2_plus_y2 = p3D.x * p3D.x + p3D.y * p3D.y; + const float theta = atan2f(sqrtf(x2_plus_y2), p3D.z); + const float psi = atan2f(p3D.y, p3D.x); + + const float theta2 = theta * theta; + const float theta3 = theta * theta2; + const float theta5 = theta3 * theta2; + const float theta7 = theta5 * theta2; + const float theta9 = theta7 * theta2; + const float r = theta + mvParameters[4] * theta3 + mvParameters[5] * theta5 + + mvParameters[6] * theta7 + mvParameters[7] * theta9; + + return cv::Point2f(mvParameters[0] * r * cos(psi) + mvParameters[2], + mvParameters[1] * r * sin(psi) + mvParameters[3]); + + } + + cv::Point2f KannalaBrandt8::project(const cv::Mat &m3D) { + const float* p3D = m3D.ptr(); + + return this->project(cv::Point3f(p3D[0],p3D[1],p3D[2])); + } + + Eigen::Vector2d KannalaBrandt8::project(const Eigen::Vector3d &v3D) { + const double x2_plus_y2 = v3D[0] * v3D[0] + v3D[1] * v3D[1]; + const double theta = atan2f(sqrtf(x2_plus_y2), v3D[2]); + const double psi = atan2f(v3D[1], v3D[0]); + + const double theta2 = theta * theta; + const double theta3 = theta * theta2; + const double theta5 = theta3 * theta2; + const double theta7 = theta5 * theta2; + const double theta9 = theta7 * theta2; + const double r = theta + mvParameters[4] * theta3 + mvParameters[5] * theta5 + + mvParameters[6] * theta7 + mvParameters[7] * theta9; + + Eigen::Vector2d res; + res[0] = mvParameters[0] * r * cos(psi) + mvParameters[2]; + res[1] = mvParameters[1] * r * sin(psi) + mvParameters[3]; + + return res; + + /*cv::Point2f cvres = this->project(cv::Point3f(v3D[0],v3D[1],v3D[2])); + + Eigen::Vector2d res; + res[0] = cvres.x; + res[1] = cvres.y; + + return res;*/ + } + + cv::Mat KannalaBrandt8::projectMat(const cv::Point3f &p3D) { + cv::Point2f point = this->project(p3D); + cv::Mat ret = (cv::Mat_(2,1) << point.x, point.y); + return ret.clone(); + } + + float KannalaBrandt8::uncertainty2(const Eigen::Matrix &p2D) + { + /*Eigen::Matrix c; + c << mvParameters[2], mvParameters[3]; + if ((p2D-c).squaredNorm()>57600) // 240*240 (256) + return 100.f; + else + return 1.0f;*/ + return 1.f; + } + + cv::Mat KannalaBrandt8::unprojectMat(const cv::Point2f &p2D){ + cv::Point3f ray = this->unproject(p2D); + cv::Mat ret = (cv::Mat_(3,1) << ray.x, ray.y, ray.z); + return ret.clone(); + } + + cv::Point3f KannalaBrandt8::unproject(const cv::Point2f &p2D) { + //Use Newthon method to solve for theta with good precision (err ~ e-6) + cv::Point2f pw((p2D.x - mvParameters[2]) / mvParameters[0], (p2D.y - mvParameters[3]) / mvParameters[1]); + float scale = 1.f; + float theta_d = sqrtf(pw.x * pw.x + pw.y * pw.y); + theta_d = fminf(fmaxf(-CV_PI / 2.f, theta_d), CV_PI / 2.f); + + if (theta_d > 1e-8) { + //Compensate distortion iteratively + float theta = theta_d; + + for (int j = 0; j < 10; j++) { + float theta2 = theta * theta, theta4 = theta2 * theta2, theta6 = theta4 * theta2, theta8 = + theta4 * theta4; + float k0_theta2 = mvParameters[4] * theta2, k1_theta4 = mvParameters[5] * theta4; + float k2_theta6 = mvParameters[6] * theta6, k3_theta8 = mvParameters[7] * theta8; + float theta_fix = (theta * (1 + k0_theta2 + k1_theta4 + k2_theta6 + k3_theta8) - theta_d) / + (1 + 3 * k0_theta2 + 5 * k1_theta4 + 7 * k2_theta6 + 9 * k3_theta8); + theta = theta - theta_fix; + if (fabsf(theta_fix) < precision) + break; + } + //scale = theta - theta_d; + scale = std::tan(theta) / theta_d; + } + + return cv::Point3f(pw.x * scale, pw.y * scale, 1.f); + } + + cv::Mat KannalaBrandt8::projectJac(const cv::Point3f &p3D) { + float x2 = p3D.x * p3D.x, y2 = p3D.y * p3D.y, z2 = p3D.z * p3D.z; + float r2 = x2 + y2; + float r = sqrt(r2); + float r3 = r2 * r; + float theta = atan2(r, p3D.z); + + float theta2 = theta * theta, theta3 = theta2 * theta; + float theta4 = theta2 * theta2, theta5 = theta4 * theta; + float theta6 = theta2 * theta4, theta7 = theta6 * theta; + float theta8 = theta4 * theta4, theta9 = theta8 * theta; + + float f = theta + theta3 * mvParameters[4] + theta5 * mvParameters[5] + theta7 * mvParameters[6] + + theta9 * mvParameters[7]; + float fd = 1 + 3 * mvParameters[4] * theta2 + 5 * mvParameters[5] * theta4 + 7 * mvParameters[6] * theta6 + + 9 * mvParameters[7] * theta8; + + cv::Mat Jac(2, 3, CV_32F); + Jac.at(0, 0) = mvParameters[0] * (fd * p3D.z * x2 / (r2 * (r2 + z2)) + f * y2 / r3); + Jac.at(1, 0) = + mvParameters[1] * (fd * p3D.z * p3D.y * p3D.x / (r2 * (r2 + z2)) - f * p3D.y * p3D.x / r3); + + Jac.at(0, 1) = + mvParameters[0] * (fd * p3D.z * p3D.y * p3D.x / (r2 * (r2 + z2)) - f * p3D.y * p3D.x / r3); + Jac.at(1, 1) = mvParameters[1] * (fd * p3D.z * y2 / (r2 * (r2 + z2)) + f * x2 / r3); + + Jac.at(0, 2) = -mvParameters[0] * fd * p3D.x / (r2 + z2); + Jac.at(1, 2) = -mvParameters[1] * fd * p3D.y / (r2 + z2); + + std::cout << "CV JAC: " << Jac << std::endl; + + return Jac.clone(); + } + + Eigen::Matrix KannalaBrandt8::projectJac(const Eigen::Vector3d &v3D) { + double x2 = v3D[0] * v3D[0], y2 = v3D[1] * v3D[1], z2 = v3D[2] * v3D[2]; + double r2 = x2 + y2; + double r = sqrt(r2); + double r3 = r2 * r; + double theta = atan2(r, v3D[2]); + + double theta2 = theta * theta, theta3 = theta2 * theta; + double theta4 = theta2 * theta2, theta5 = theta4 * theta; + double theta6 = theta2 * theta4, theta7 = theta6 * theta; + double theta8 = theta4 * theta4, theta9 = theta8 * theta; + + double f = theta + theta3 * mvParameters[4] + theta5 * mvParameters[5] + theta7 * mvParameters[6] + + theta9 * mvParameters[7]; + double fd = 1 + 3 * mvParameters[4] * theta2 + 5 * mvParameters[5] * theta4 + 7 * mvParameters[6] * theta6 + + 9 * mvParameters[7] * theta8; + + Eigen::Matrix JacGood; + JacGood(0, 0) = mvParameters[0] * (fd * v3D[2] * x2 / (r2 * (r2 + z2)) + f * y2 / r3); + JacGood(1, 0) = + mvParameters[1] * (fd * v3D[2] * v3D[1] * v3D[0] / (r2 * (r2 + z2)) - f * v3D[1] * v3D[0] / r3); + + JacGood(0, 1) = + mvParameters[0] * (fd * v3D[2] * v3D[1] * v3D[0] / (r2 * (r2 + z2)) - f * v3D[1] * v3D[0] / r3); + JacGood(1, 1) = mvParameters[1] * (fd * v3D[2] * y2 / (r2 * (r2 + z2)) + f * x2 / r3); + + JacGood(0, 2) = -mvParameters[0] * fd * v3D[0] / (r2 + z2); + JacGood(1, 2) = -mvParameters[1] * fd * v3D[1] / (r2 + z2); + + return JacGood; + } + + cv::Mat KannalaBrandt8::unprojectJac(const cv::Point2f &p2D) { + return cv::Mat(); + } + + bool KannalaBrandt8::ReconstructWithTwoViews(const std::vector& vKeys1, const std::vector& vKeys2, const std::vector &vMatches12, + cv::Mat &R21, cv::Mat &t21, std::vector &vP3D, std::vector &vbTriangulated){ + if(!tvr){ + cv::Mat K = this->toK(); + tvr = new TwoViewReconstruction(K); + } + + //Correct FishEye distortion + std::vector vKeysUn1 = vKeys1, vKeysUn2 = vKeys2; + std::vector vPts1(vKeys1.size()), vPts2(vKeys2.size()); + + for(size_t i = 0; i < vKeys1.size(); i++) vPts1[i] = vKeys1[i].pt; + for(size_t i = 0; i < vKeys2.size(); i++) vPts2[i] = vKeys2[i].pt; + + cv::Mat D = (cv::Mat_(4,1) << mvParameters[4], mvParameters[5], mvParameters[6], mvParameters[7]); + cv::Mat R = cv::Mat::eye(3,3,CV_32F); + cv::Mat K = this->toK(); + cv::fisheye::undistortPoints(vPts1,vPts1,K,D,R,K); + cv::fisheye::undistortPoints(vPts2,vPts2,K,D,R,K); + + for(size_t i = 0; i < vKeys1.size(); i++) vKeysUn1[i].pt = vPts1[i]; + for(size_t i = 0; i < vKeys2.size(); i++) vKeysUn2[i].pt = vPts2[i]; + + return tvr->Reconstruct(vKeysUn1,vKeysUn2,vMatches12,R21,t21,vP3D,vbTriangulated); + } + + + cv::Mat KannalaBrandt8::toK() { + cv::Mat K = (cv::Mat_(3, 3) + << mvParameters[0], 0.f, mvParameters[2], 0.f, mvParameters[1], mvParameters[3], 0.f, 0.f, 1.f); + return K; + } + + bool KannalaBrandt8::epipolarConstrain(GeometricCamera* pCamera2, const cv::KeyPoint &kp1, const cv::KeyPoint &kp2, const cv::Mat &R12, const cv::Mat &t12, const float sigmaLevel, const float unc) { + cv::Mat p3D; + return this->TriangulateMatches(pCamera2,kp1,kp2,R12,t12,sigmaLevel,unc,p3D) > 0.0001f; + } + + bool KannalaBrandt8::matchAndtriangulate(const cv::KeyPoint& kp1, const cv::KeyPoint& kp2, GeometricCamera* pOther, + cv::Mat& Tcw1, cv::Mat& Tcw2, + const float sigmaLevel1, const float sigmaLevel2, + cv::Mat& x3Dtriangulated){ + cv::Mat Rcw1 = Tcw1.colRange(0,3).rowRange(0,3); + cv::Mat Rwc1 = Rcw1.t(); + cv::Mat tcw1 = Tcw1.rowRange(0,3).col(3); + + cv::Mat Rcw2 = Tcw2.colRange(0,3).rowRange(0,3); + cv::Mat Rwc2 = Rcw2.t(); + cv::Mat tcw2 = Tcw2.rowRange(0,3).col(3); + + cv::Point3f ray1c = this->unproject(kp1.pt); + cv::Point3f ray2c = pOther->unproject(kp2.pt); + + cv::Mat r1(3,1,CV_32F); + r1.at(0) = ray1c.x; + r1.at(1) = ray1c.y; + r1.at(2) = ray1c.z; + + cv::Mat r2(3,1,CV_32F); + r2.at(0) = ray2c.x; + r2.at(1) = ray2c.y; + r2.at(2) = ray2c.z; + + //Check parallax between rays + cv::Mat ray1 = Rwc1*r1; + cv::Mat ray2 = Rwc2*r2; + + const float cosParallaxRays = ray1.dot(ray2)/(cv::norm(ray1)*cv::norm(ray2)); + + //If parallax is lower than 0.9998, reject this match + if(cosParallaxRays > 0.9998){ + return false; + } + + //Parallax is good, so we try to triangulate + cv::Point2f p11,p22; + + p11.x = ray1c.x; + p11.y = ray1c.y; + + p22.x = ray2c.x; + p22.y = ray2c.y; + + cv::Mat x3D; + + Triangulate(p11,p22,Tcw1,Tcw2,x3D); + + cv::Mat x3Dt = x3D.t(); + + //Check triangulation in front of cameras + float z1 = Rcw1.row(2).dot(x3Dt)+tcw1.at(2); + if(z1<=0){ //Point is not in front of the first camera + return false; + } + + + float z2 = Rcw2.row(2).dot(x3Dt)+tcw2.at(2); + if(z2<=0){ //Point is not in front of the first camera + return false; + } + + //Check reprojection error in first keyframe + // -Transform point into camera reference system + cv::Mat x3D1 = Rcw1 * x3D + tcw1; + cv::Point2f uv1 = this->project(x3D1); + + float errX1 = uv1.x - kp1.pt.x; + float errY1 = uv1.y - kp1.pt.y; + + if((errX1*errX1+errY1*errY1)>5.991*sigmaLevel1){ //Reprojection error is high + return false; + } + + //Check reprojection error in second keyframe; + // -Transform point into camera reference system + cv::Mat x3D2 = Rcw2 * x3D + tcw2; + cv::Point2f uv2 = pOther->project(x3D2); + + float errX2 = uv2.x - kp2.pt.x; + float errY2 = uv2.y - kp2.pt.y; + + if((errX2*errX2+errY2*errY2)>5.991*sigmaLevel2){ //Reprojection error is high + return false; + } + + //Since parallax is big enough and reprojection errors are low, this pair of points + //can be considered as a match + x3Dtriangulated = x3D.clone(); + + return true; + } + + float KannalaBrandt8::TriangulateMatches(GeometricCamera *pCamera2, const cv::KeyPoint &kp1, const cv::KeyPoint &kp2, const cv::Mat &R12, const cv::Mat &t12, const float sigmaLevel, const float unc, cv::Mat& p3D) { + cv::Mat r1 = this->unprojectMat(kp1.pt); + cv::Mat r2 = pCamera2->unprojectMat(kp2.pt); + + //Check parallax + cv::Mat r21 = R12*r2; + + const float cosParallaxRays = r1.dot(r21)/(cv::norm(r1)*cv::norm(r21)); + + if(cosParallaxRays > 0.9998){ + return -1; + } + + //Parallax is good, so we try to triangulate + cv::Point2f p11,p22; + const float* pr1 = r1.ptr(); + const float* pr2 = r2.ptr(); + + p11.x = pr1[0]; + p11.y = pr1[1]; + + p22.x = pr2[0]; + p22.y = pr2[1]; + + cv::Mat x3D; + cv::Mat Tcw1 = (cv::Mat_(3,4) << 1.f,0.f,0.f,0.f, + 0.f,1.f,0.f,0.f, + 0.f,0.f,1.f,0.f); + cv::Mat Tcw2; + cv::Mat R21 = R12.t(); + cv::Mat t21 = -R21*t12; + cv::hconcat(R21,t21,Tcw2); + + Triangulate(p11,p22,Tcw1,Tcw2,x3D); + cv::Mat x3Dt = x3D.t(); + + float z1 = x3D.at(2); + if(z1 <= 0){ + return -1; + } + + float z2 = R21.row(2).dot(x3Dt)+t21.at(2); + if(z2<=0){ + return -1; + } + + //Check reprojection error + cv::Point2f uv1 = this->project(x3D); + + float errX1 = uv1.x - kp1.pt.x; + float errY1 = uv1.y - kp1.pt.y; + + if((errX1*errX1+errY1*errY1)>5.991 * sigmaLevel){ //Reprojection error is high + return -1; + } + + cv::Mat x3D2 = R21 * x3D + t21; + cv::Point2f uv2 = pCamera2->project(x3D2); + + float errX2 = uv2.x - kp2.pt.x; + float errY2 = uv2.y - kp2.pt.y; + + if((errX2*errX2+errY2*errY2)>5.991 * unc){ //Reprojection error is high + return -1; + } + + p3D = x3D.clone(); + + return z1; + } + + std::ostream & operator<<(std::ostream &os, const KannalaBrandt8 &kb) { + os << kb.mvParameters[0] << " " << kb.mvParameters[1] << " " << kb.mvParameters[2] << " " << kb.mvParameters[3] << " " + << kb.mvParameters[4] << " " << kb.mvParameters[5] << " " << kb.mvParameters[6] << " " << kb.mvParameters[7]; + return os; + } + + std::istream & operator>>(std::istream &is, KannalaBrandt8 &kb) { + float nextParam; + for(size_t i = 0; i < 8; i++){ + assert(is.good()); //Make sure the input stream is good + is >> nextParam; + kb.mvParameters[i] = nextParam; + + } + return is; + } + + void KannalaBrandt8::Triangulate(const cv::Point2f &p1, const cv::Point2f &p2, const cv::Mat &Tcw1, const cv::Mat &Tcw2, cv::Mat &x3D) + { + cv::Mat A(4,4,CV_32F); + + A.row(0) = p1.x*Tcw1.row(2)-Tcw1.row(0); + A.row(1) = p1.y*Tcw1.row(2)-Tcw1.row(1); + A.row(2) = p2.x*Tcw2.row(2)-Tcw2.row(0); + A.row(3) = p2.y*Tcw2.row(2)-Tcw2.row(1); + + cv::Mat u,w,vt; + cv::SVD::compute(A,w,u,vt,cv::SVD::MODIFY_A| cv::SVD::FULL_UV); + x3D = vt.row(3).t(); + x3D = x3D.rowRange(0,3)/x3D.at(3); + } +} diff --git a/third_party/ORB_SLAM3/src/CameraModels/Pinhole.cpp b/third_party/ORB_SLAM3/src/CameraModels/Pinhole.cpp new file mode 100644 index 0000000..ab9a8b4 --- /dev/null +++ b/third_party/ORB_SLAM3/src/CameraModels/Pinhole.cpp @@ -0,0 +1,168 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + +#include "Pinhole.h" + +#include + +//BOOST_CLASS_EXPORT_IMPLEMENT(ORB_SLAM3::Pinhole) + +namespace ORB_SLAM3 { +//BOOST_CLASS_EXPORT_GUID(Pinhole, "Pinhole") + + long unsigned int GeometricCamera::nNextId=0; + + cv::Point2f Pinhole::project(const cv::Point3f &p3D) { + return cv::Point2f(mvParameters[0] * p3D.x / p3D.z + mvParameters[2], + mvParameters[1] * p3D.y / p3D.z + mvParameters[3]); + } + + cv::Point2f Pinhole::project(const cv::Mat &m3D) { + const float* p3D = m3D.ptr(); + + return this->project(cv::Point3f(p3D[0],p3D[1],p3D[2])); + } + + Eigen::Vector2d Pinhole::project(const Eigen::Vector3d &v3D) { + Eigen::Vector2d res; + res[0] = mvParameters[0] * v3D[0] / v3D[2] + mvParameters[2]; + res[1] = mvParameters[1] * v3D[1] / v3D[2] + mvParameters[3]; + + return res; + } + + cv::Mat Pinhole::projectMat(const cv::Point3f &p3D) { + cv::Point2f point = this->project(p3D); + return (cv::Mat_(2,1) << point.x, point.y); + } + + float Pinhole::uncertainty2(const Eigen::Matrix &p2D) + { + return 1.0; + } + + cv::Point3f Pinhole::unproject(const cv::Point2f &p2D) { + return cv::Point3f((p2D.x - mvParameters[2]) / mvParameters[0], (p2D.y - mvParameters[3]) / mvParameters[1], + 1.f); + } + + cv::Mat Pinhole::unprojectMat(const cv::Point2f &p2D){ + cv::Point3f ray = this->unproject(p2D); + return (cv::Mat_(3,1) << ray.x, ray.y, ray.z); + } + + cv::Mat Pinhole::projectJac(const cv::Point3f &p3D) { + cv::Mat Jac(2, 3, CV_32F); + Jac.at(0, 0) = mvParameters[0] / p3D.z; + Jac.at(0, 1) = 0.f; + Jac.at(0, 2) = -mvParameters[0] * p3D.x / (p3D.z * p3D.z); + Jac.at(1, 0) = 0.f; + Jac.at(1, 1) = mvParameters[1] / p3D.z; + Jac.at(1, 2) = -mvParameters[1] * p3D.y / (p3D.z * p3D.z); + + return Jac; + } + + Eigen::Matrix Pinhole::projectJac(const Eigen::Vector3d &v3D) { + Eigen::Matrix Jac; + Jac(0, 0) = mvParameters[0] / v3D[2]; + Jac(0, 1) = 0.f; + Jac(0, 2) = -mvParameters[0] * v3D[0] / (v3D[2] * v3D[2]); + Jac(1, 0) = 0.f; + Jac(1, 1) = mvParameters[1] / v3D[2]; + Jac(1, 2) = -mvParameters[1] * v3D[1] / (v3D[2] * v3D[2]); + + return Jac; + } + + cv::Mat Pinhole::unprojectJac(const cv::Point2f &p2D) { + cv::Mat Jac(3, 2, CV_32F); + Jac.at(0, 0) = 1 / mvParameters[0]; + Jac.at(0, 1) = 0.f; + Jac.at(1, 0) = 0.f; + Jac.at(1, 1) = 1 / mvParameters[1]; + Jac.at(2, 0) = 0.f; + Jac.at(2, 1) = 0.f; + + return Jac; + } + + bool Pinhole::ReconstructWithTwoViews(const std::vector& vKeys1, const std::vector& vKeys2, const std::vector &vMatches12, + cv::Mat &R21, cv::Mat &t21, std::vector &vP3D, std::vector &vbTriangulated){ + if(!tvr){ + cv::Mat K = this->toK(); + tvr = new TwoViewReconstruction(K); + } + + return tvr->Reconstruct(vKeys1,vKeys2,vMatches12,R21,t21,vP3D,vbTriangulated); + } + + + cv::Mat Pinhole::toK() { + cv::Mat K = (cv::Mat_(3, 3) + << mvParameters[0], 0.f, mvParameters[2], 0.f, mvParameters[1], mvParameters[3], 0.f, 0.f, 1.f); + return K; + } + + bool Pinhole::epipolarConstrain(GeometricCamera* pCamera2, const cv::KeyPoint &kp1, const cv::KeyPoint &kp2, const cv::Mat &R12, const cv::Mat &t12, const float sigmaLevel, const float unc) { + //Compute Fundamental Matrix + cv::Mat t12x = SkewSymmetricMatrix(t12); + cv::Mat K1 = this->toK(); + cv::Mat K2 = pCamera2->toK(); + cv::Mat F12 = K1.t().inv()*t12x*R12*K2.inv(); + + // Epipolar line in second image l = x1'F12 = [a b c] + const float a = kp1.pt.x*F12.at(0,0)+kp1.pt.y*F12.at(1,0)+F12.at(2,0); + const float b = kp1.pt.x*F12.at(0,1)+kp1.pt.y*F12.at(1,1)+F12.at(2,1); + const float c = kp1.pt.x*F12.at(0,2)+kp1.pt.y*F12.at(1,2)+F12.at(2,2); + + const float num = a*kp2.pt.x+b*kp2.pt.y+c; + + const float den = a*a+b*b; + + if(den==0) + return false; + + const float dsqr = num*num/den; + + return dsqr<3.84*unc; + } + + std::ostream & operator<<(std::ostream &os, const Pinhole &ph) { + os << ph.mvParameters[0] << " " << ph.mvParameters[1] << " " << ph.mvParameters[2] << " " << ph.mvParameters[3]; + return os; + } + + std::istream & operator>>(std::istream &is, Pinhole &ph) { + float nextParam; + for(size_t i = 0; i < 4; i++){ + assert(is.good()); //Make sure the input stream is good + is >> nextParam; + ph.mvParameters[i] = nextParam; + + } + return is; + } + + cv::Mat Pinhole::SkewSymmetricMatrix(const cv::Mat &v) + { + return (cv::Mat_(3,3) << 0, -v.at(2), v.at(1), + v.at(2), 0,-v.at(0), + -v.at(1), v.at(0), 0); + } +} diff --git a/third_party/ORB_SLAM3/src/Converter.cc b/third_party/ORB_SLAM3/src/Converter.cc new file mode 100644 index 0000000..cbdb9f8 --- /dev/null +++ b/third_party/ORB_SLAM3/src/Converter.cc @@ -0,0 +1,217 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + +#include "Converter.h" + +namespace ORB_SLAM3 +{ + +std::vector Converter::toDescriptorVector(const cv::Mat &Descriptors) +{ + std::vector vDesc; + vDesc.reserve(Descriptors.rows); + for (int j=0;j R; + R << cvT.at(0,0), cvT.at(0,1), cvT.at(0,2), + cvT.at(1,0), cvT.at(1,1), cvT.at(1,2), + cvT.at(2,0), cvT.at(2,1), cvT.at(2,2); + + Eigen::Matrix t(cvT.at(0,3), cvT.at(1,3), cvT.at(2,3)); + + return g2o::SE3Quat(R,t); +} + +cv::Mat Converter::toCvMat(const g2o::SE3Quat &SE3) +{ + Eigen::Matrix eigMat = SE3.to_homogeneous_matrix(); + return toCvMat(eigMat); +} + +cv::Mat Converter::toCvMat(const g2o::Sim3 &Sim3) +{ + Eigen::Matrix3d eigR = Sim3.rotation().toRotationMatrix(); + Eigen::Vector3d eigt = Sim3.translation(); + double s = Sim3.scale(); + return toCvSE3(s*eigR,eigt); +} + +cv::Mat Converter::toCvMat(const Eigen::Matrix &m) +{ + cv::Mat cvMat(4,4,CV_32F); + for(int i=0;i<4;i++) + for(int j=0; j<4; j++) + cvMat.at(i,j)=m(i,j); + + return cvMat.clone(); +} + +cv::Mat Converter::toCvMat(const Eigen::Matrix3d &m) +{ + cv::Mat cvMat(3,3,CV_32F); + for(int i=0;i<3;i++) + for(int j=0; j<3; j++) + cvMat.at(i,j)=m(i,j); + + return cvMat.clone(); +} + +cv::Mat Converter::toCvMat(const Eigen::MatrixXd &m) +{ + cv::Mat cvMat(m.rows(),m.cols(),CV_32F); + for(int i=0;i(i,j)=m(i,j); + + return cvMat.clone(); +} + +cv::Mat Converter::toCvMat(const Eigen::Matrix &m) +{ + cv::Mat cvMat(3,1,CV_32F); + for(int i=0;i<3;i++) + cvMat.at(i)=m(i); + + return cvMat.clone(); +} + +cv::Mat Converter::toCvSE3(const Eigen::Matrix &R, const Eigen::Matrix &t) +{ + cv::Mat cvMat = cv::Mat::eye(4,4,CV_32F); + for(int i=0;i<3;i++) + { + for(int j=0;j<3;j++) + { + cvMat.at(i,j)=R(i,j); + } + } + for(int i=0;i<3;i++) + { + cvMat.at(i,3)=t(i); + } + + return cvMat.clone(); +} + +Eigen::Matrix Converter::toVector3d(const cv::Mat &cvVector) +{ + Eigen::Matrix v; + v << cvVector.at(0), cvVector.at(1), cvVector.at(2); + + return v; +} + +Eigen::Matrix Converter::toVector3d(const cv::Point3f &cvPoint) +{ + Eigen::Matrix v; + v << cvPoint.x, cvPoint.y, cvPoint.z; + + return v; +} + +Eigen::Matrix Converter::toMatrix3d(const cv::Mat &cvMat3) +{ + Eigen::Matrix M; + + M << cvMat3.at(0,0), cvMat3.at(0,1), cvMat3.at(0,2), + cvMat3.at(1,0), cvMat3.at(1,1), cvMat3.at(1,2), + cvMat3.at(2,0), cvMat3.at(2,1), cvMat3.at(2,2); + + return M; +} + +Eigen::Matrix Converter::toMatrix4d(const cv::Mat &cvMat4) +{ + Eigen::Matrix M; + + M << cvMat4.at(0,0), cvMat4.at(0,1), cvMat4.at(0,2), cvMat4.at(0,3), + cvMat4.at(1,0), cvMat4.at(1,1), cvMat4.at(1,2), cvMat4.at(1,3), + cvMat4.at(2,0), cvMat4.at(2,1), cvMat4.at(2,2), cvMat4.at(2,3), + cvMat4.at(3,0), cvMat4.at(3,1), cvMat4.at(3,2), cvMat4.at(3,3); + return M; +} + + +std::vector Converter::toQuaternion(const cv::Mat &M) +{ + Eigen::Matrix eigMat = toMatrix3d(M); + Eigen::Quaterniond q(eigMat); + + std::vector v(4); + v[0] = q.x(); + v[1] = q.y(); + v[2] = q.z(); + v[3] = q.w(); + + return v; +} + +cv::Mat Converter::tocvSkewMatrix(const cv::Mat &v) +{ + return (cv::Mat_(3,3) << 0, -v.at(2), v.at(1), + v.at(2), 0,-v.at(0), + -v.at(1), v.at(0), 0); +} + +bool Converter::isRotationMatrix(const cv::Mat &R) +{ + cv::Mat Rt; + cv::transpose(R, Rt); + cv::Mat shouldBeIdentity = Rt * R; + cv::Mat I = cv::Mat::eye(3,3, shouldBeIdentity.type()); + + return cv::norm(I, shouldBeIdentity) < 1e-6; + +} + +std::vector Converter::toEuler(const cv::Mat &R) +{ + assert(isRotationMatrix(R)); + float sy = sqrt(R.at(0,0) * R.at(0,0) + R.at(1,0) * R.at(1,0) ); + + bool singular = sy < 1e-6; // If + + float x, y, z; + if (!singular) + { + x = atan2(R.at(2,1) , R.at(2,2)); + y = atan2(-R.at(2,0), sy); + z = atan2(R.at(1,0), R.at(0,0)); + } + else + { + x = atan2(-R.at(1,2), R.at(1,1)); + y = atan2(-R.at(2,0), sy); + z = 0; + } + + std::vector v_euler(3); + v_euler[0] = x; + v_euler[1] = y; + v_euler[2] = z; + + return v_euler; +} + +} //namespace ORB_SLAM diff --git a/third_party/ORB_SLAM3/src/Frame.cc b/third_party/ORB_SLAM3/src/Frame.cc new file mode 100644 index 0000000..bfef60c --- /dev/null +++ b/third_party/ORB_SLAM3/src/Frame.cc @@ -0,0 +1,1243 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + +#include "Frame.h" + +#include "G2oTypes.h" +#include "MapPoint.h" +#include "KeyFrame.h" +#include "ORBextractor.h" +#include "Converter.h" +#include "ORBmatcher.h" +#include "GeometricCamera.h" + +#include +#include +#include + +namespace ORB_SLAM3 +{ + +long unsigned int Frame::nNextId=0; +bool Frame::mbInitialComputations=true; +float Frame::cx, Frame::cy, Frame::fx, Frame::fy, Frame::invfx, Frame::invfy; +float Frame::mnMinX, Frame::mnMinY, Frame::mnMaxX, Frame::mnMaxY; +float Frame::mfGridElementWidthInv, Frame::mfGridElementHeightInv; + +//For stereo fisheye matching +cv::BFMatcher Frame::BFmatcher = cv::BFMatcher(cv::NORM_HAMMING); + +Frame::Frame(): mpcpi(NULL), mpImuPreintegrated(NULL), mpPrevFrame(NULL), mpImuPreintegratedFrame(NULL), mpReferenceKF(static_cast(NULL)), mbImuPreintegrated(false) +{ +} + + +//Copy Constructor +Frame::Frame(const Frame &frame) + :mpcpi(frame.mpcpi),mpORBvocabulary(frame.mpORBvocabulary), mpORBextractorLeft(frame.mpORBextractorLeft), mpORBextractorRight(frame.mpORBextractorRight), + mTimeStamp(frame.mTimeStamp), mK(frame.mK.clone()), mDistCoef(frame.mDistCoef.clone()), + mbf(frame.mbf), mb(frame.mb), mThDepth(frame.mThDepth), N(frame.N), mvKeys(frame.mvKeys), + mvKeysRight(frame.mvKeysRight), mvKeysUn(frame.mvKeysUn), mvuRight(frame.mvuRight), + mvDepth(frame.mvDepth), mBowVec(frame.mBowVec), mFeatVec(frame.mFeatVec), + mDescriptors(frame.mDescriptors.clone()), mDescriptorsRight(frame.mDescriptorsRight.clone()), + mvpMapPoints(frame.mvpMapPoints), mvbOutlier(frame.mvbOutlier), mImuCalib(frame.mImuCalib), mnCloseMPs(frame.mnCloseMPs), + mpImuPreintegrated(frame.mpImuPreintegrated), mpImuPreintegratedFrame(frame.mpImuPreintegratedFrame), mImuBias(frame.mImuBias), + mnId(frame.mnId), mpReferenceKF(frame.mpReferenceKF), mnScaleLevels(frame.mnScaleLevels), + mfScaleFactor(frame.mfScaleFactor), mfLogScaleFactor(frame.mfLogScaleFactor), + mvScaleFactors(frame.mvScaleFactors), mvInvScaleFactors(frame.mvInvScaleFactors), mNameFile(frame.mNameFile), mnDataset(frame.mnDataset), + mvLevelSigma2(frame.mvLevelSigma2), mvInvLevelSigma2(frame.mvInvLevelSigma2), mpPrevFrame(frame.mpPrevFrame), mpLastKeyFrame(frame.mpLastKeyFrame), mbImuPreintegrated(frame.mbImuPreintegrated), mpMutexImu(frame.mpMutexImu), + mpCamera(frame.mpCamera), mpCamera2(frame.mpCamera2), Nleft(frame.Nleft), Nright(frame.Nright), + monoLeft(frame.monoLeft), monoRight(frame.monoRight), mvLeftToRightMatch(frame.mvLeftToRightMatch), + mvRightToLeftMatch(frame.mvRightToLeftMatch), mvStereo3Dpoints(frame.mvStereo3Dpoints), + mTlr(frame.mTlr.clone()), mRlr(frame.mRlr.clone()), mtlr(frame.mtlr.clone()), mTrl(frame.mTrl.clone()), mTimeStereoMatch(frame.mTimeStereoMatch), mTimeORB_Ext(frame.mTimeORB_Ext) +{ + for(int i=0;i 0){ + mGridRight[i][j] = frame.mGridRight[i][j]; + } + } + + if(!frame.mTcw.empty()) + SetPose(frame.mTcw); + + if(!frame.mVw.empty()) + mVw = frame.mVw.clone(); + + mmProjectPoints = frame.mmProjectPoints; + mmMatchedInImage = frame.mmMatchedInImage; +} + + +Frame::Frame(const cv::Mat &imLeft, const cv::Mat &imRight, const double &timeStamp, ORBextractor* extractorLeft, ORBextractor* extractorRight, ORBVocabulary* voc, cv::Mat &K, cv::Mat &distCoef, const float &bf, const float &thDepth, GeometricCamera* pCamera, Frame* pPrevF, const IMU::Calib &ImuCalib) + :mpcpi(NULL), mpORBvocabulary(voc),mpORBextractorLeft(extractorLeft),mpORBextractorRight(extractorRight), mTimeStamp(timeStamp), mK(K.clone()), mDistCoef(distCoef.clone()), mbf(bf), mThDepth(thDepth), + mImuCalib(ImuCalib), mpImuPreintegrated(NULL), mpPrevFrame(pPrevF),mpImuPreintegratedFrame(NULL), mpReferenceKF(static_cast(NULL)), mbImuPreintegrated(false), + mpCamera(pCamera) ,mpCamera2(nullptr), mTimeStereoMatch(0), mTimeORB_Ext(0) +{ + // Frame ID + mnId=nNextId++; + + // Scale Level Info + mnScaleLevels = mpORBextractorLeft->GetLevels(); + mfScaleFactor = mpORBextractorLeft->GetScaleFactor(); + mfLogScaleFactor = log(mfScaleFactor); + mvScaleFactors = mpORBextractorLeft->GetScaleFactors(); + mvInvScaleFactors = mpORBextractorLeft->GetInverseScaleFactors(); + mvLevelSigma2 = mpORBextractorLeft->GetScaleSigmaSquares(); + mvInvLevelSigma2 = mpORBextractorLeft->GetInverseScaleSigmaSquares(); + + // ORB extraction +#ifdef SAVE_TIMES + std::chrono::steady_clock::time_point time_StartExtORB = std::chrono::steady_clock::now(); +#endif + thread threadLeft(&Frame::ExtractORB,this,0,imLeft,0,0); + thread threadRight(&Frame::ExtractORB,this,1,imRight,0,0); + threadLeft.join(); + threadRight.join(); +#ifdef SAVE_TIMES + std::chrono::steady_clock::time_point time_EndExtORB = std::chrono::steady_clock::now(); + + mTimeORB_Ext = std::chrono::duration_cast >(time_EndExtORB - time_StartExtORB).count(); +#endif + + + N = mvKeys.size(); + if(mvKeys.empty()) + return; + + UndistortKeyPoints(); + +#ifdef SAVE_TIMES + std::chrono::steady_clock::time_point time_StartStereoMatches = std::chrono::steady_clock::now(); +#endif + ComputeStereoMatches(); +#ifdef SAVE_TIMES + std::chrono::steady_clock::time_point time_EndStereoMatches = std::chrono::steady_clock::now(); + + mTimeStereoMatch = std::chrono::duration_cast >(time_EndStereoMatches - time_StartStereoMatches).count(); +#endif + + + mvpMapPoints = vector(N,static_cast(NULL)); + mvbOutlier = vector(N,false); + mmProjectPoints.clear();// = map(N, static_cast(NULL)); + mmMatchedInImage.clear(); + + + // This is done only for the first Frame (or after a change in the calibration) + if(mbInitialComputations) + { + ComputeImageBounds(imLeft); + + mfGridElementWidthInv=static_cast(FRAME_GRID_COLS)/(mnMaxX-mnMinX); + mfGridElementHeightInv=static_cast(FRAME_GRID_ROWS)/(mnMaxY-mnMinY); + + + + fx = K.at(0,0); + fy = K.at(1,1); + cx = K.at(0,2); + cy = K.at(1,2); + invfx = 1.0f/fx; + invfy = 1.0f/fy; + + mbInitialComputations=false; + } + + mb = mbf/fx; + + if(pPrevF) + { + if(!pPrevF->mVw.empty()) + mVw = pPrevF->mVw.clone(); + } + else + { + mVw = cv::Mat::zeros(3,1,CV_32F); + } + + AssignFeaturesToGrid(); + + mpMutexImu = new std::mutex(); + + //Set no stereo fisheye information + Nleft = -1; + Nright = -1; + mvLeftToRightMatch = vector(0); + mvRightToLeftMatch = vector(0); + mTlr = cv::Mat(3,4,CV_32F); + mTrl = cv::Mat(3,4,CV_32F); + mvStereo3Dpoints = vector(0); + monoLeft = -1; + monoRight = -1; +} + +Frame::Frame(const cv::Mat &imGray, const cv::Mat &imDepth, const double &timeStamp, ORBextractor* extractor,ORBVocabulary* voc, cv::Mat &K, cv::Mat &distCoef, const float &bf, const float &thDepth, GeometricCamera* pCamera,Frame* pPrevF, const IMU::Calib &ImuCalib) + :mpcpi(NULL),mpORBvocabulary(voc),mpORBextractorLeft(extractor),mpORBextractorRight(static_cast(NULL)), + mTimeStamp(timeStamp), mK(K.clone()),mDistCoef(distCoef.clone()), mbf(bf), mThDepth(thDepth), + mImuCalib(ImuCalib), mpImuPreintegrated(NULL), mpPrevFrame(pPrevF), mpImuPreintegratedFrame(NULL), mpReferenceKF(static_cast(NULL)), mbImuPreintegrated(false), + mpCamera(pCamera),mpCamera2(nullptr), mTimeStereoMatch(0), mTimeORB_Ext(0) +{ + // Frame ID + mnId=nNextId++; + + // Scale Level Info + mnScaleLevels = mpORBextractorLeft->GetLevels(); + mfScaleFactor = mpORBextractorLeft->GetScaleFactor(); + mfLogScaleFactor = log(mfScaleFactor); + mvScaleFactors = mpORBextractorLeft->GetScaleFactors(); + mvInvScaleFactors = mpORBextractorLeft->GetInverseScaleFactors(); + mvLevelSigma2 = mpORBextractorLeft->GetScaleSigmaSquares(); + mvInvLevelSigma2 = mpORBextractorLeft->GetInverseScaleSigmaSquares(); + + // ORB extraction +#ifdef SAVE_TIMES + std::chrono::steady_clock::time_point time_StartExtORB = std::chrono::steady_clock::now(); +#endif + ExtractORB(0,imGray,0,0); +#ifdef SAVE_TIMES + std::chrono::steady_clock::time_point time_EndExtORB = std::chrono::steady_clock::now(); + + mTimeORB_Ext = std::chrono::duration_cast >(time_EndExtORB - time_StartExtORB).count(); +#endif + + + N = mvKeys.size(); + + if(mvKeys.empty()) + return; + + UndistortKeyPoints(); + + ComputeStereoFromRGBD(imDepth); + + mvpMapPoints = vector(N,static_cast(NULL)); + + mmProjectPoints.clear();// = map(N, static_cast(NULL)); + mmMatchedInImage.clear(); + + mvbOutlier = vector(N,false); + + // This is done only for the first Frame (or after a change in the calibration) + if(mbInitialComputations) + { + ComputeImageBounds(imGray); + + mfGridElementWidthInv=static_cast(FRAME_GRID_COLS)/static_cast(mnMaxX-mnMinX); + mfGridElementHeightInv=static_cast(FRAME_GRID_ROWS)/static_cast(mnMaxY-mnMinY); + + fx = K.at(0,0); + fy = K.at(1,1); + cx = K.at(0,2); + cy = K.at(1,2); + invfx = 1.0f/fx; + invfy = 1.0f/fy; + + mbInitialComputations=false; + } + + mb = mbf/fx; + + mpMutexImu = new std::mutex(); + + //Set no stereo fisheye information + Nleft = -1; + Nright = -1; + mvLeftToRightMatch = vector(0); + mvRightToLeftMatch = vector(0); + mTlr = cv::Mat(3,4,CV_32F); + mTrl = cv::Mat(3,4,CV_32F); + mvStereo3Dpoints = vector(0); + monoLeft = -1; + monoRight = -1; + + AssignFeaturesToGrid(); +} + + +Frame::Frame(const cv::Mat &imGray, const double &timeStamp, ORBextractor* extractor,ORBVocabulary* voc, GeometricCamera* pCamera, cv::Mat &distCoef, const float &bf, const float &thDepth, Frame* pPrevF, const IMU::Calib &ImuCalib) + :mpcpi(NULL),mpORBvocabulary(voc),mpORBextractorLeft(extractor),mpORBextractorRight(static_cast(NULL)), + mTimeStamp(timeStamp), mK(static_cast(pCamera)->toK()), mDistCoef(distCoef.clone()), mbf(bf), mThDepth(thDepth), + mImuCalib(ImuCalib), mpImuPreintegrated(NULL),mpPrevFrame(pPrevF),mpImuPreintegratedFrame(NULL), mpReferenceKF(static_cast(NULL)), mbImuPreintegrated(false), mpCamera(pCamera), + mpCamera2(nullptr), mTimeStereoMatch(0), mTimeORB_Ext(0) +{ + // Frame ID + mnId=nNextId++; + + // Scale Level Info + mnScaleLevels = mpORBextractorLeft->GetLevels(); + mfScaleFactor = mpORBextractorLeft->GetScaleFactor(); + mfLogScaleFactor = log(mfScaleFactor); + mvScaleFactors = mpORBextractorLeft->GetScaleFactors(); + mvInvScaleFactors = mpORBextractorLeft->GetInverseScaleFactors(); + mvLevelSigma2 = mpORBextractorLeft->GetScaleSigmaSquares(); + mvInvLevelSigma2 = mpORBextractorLeft->GetInverseScaleSigmaSquares(); + + // ORB extraction +#ifdef SAVE_TIMES + std::chrono::steady_clock::time_point time_StartExtORB = std::chrono::steady_clock::now(); +#endif + ExtractORB(0,imGray,0,1000); +#ifdef SAVE_TIMES + std::chrono::steady_clock::time_point time_EndExtORB = std::chrono::steady_clock::now(); + + mTimeORB_Ext = std::chrono::duration_cast >(time_EndExtORB - time_StartExtORB).count(); +#endif + + + N = mvKeys.size(); + if(mvKeys.empty()) + return; + + UndistortKeyPoints(); + + // Set no stereo information + mvuRight = vector(N,-1); + mvDepth = vector(N,-1); + mnCloseMPs = 0; + + mvpMapPoints = vector(N,static_cast(NULL)); + + mmProjectPoints.clear();// = map(N, static_cast(NULL)); + mmMatchedInImage.clear(); + + mvbOutlier = vector(N,false); + + // This is done only for the first Frame (or after a change in the calibration) + if(mbInitialComputations) + { + ComputeImageBounds(imGray); + + mfGridElementWidthInv=static_cast(FRAME_GRID_COLS)/static_cast(mnMaxX-mnMinX); + mfGridElementHeightInv=static_cast(FRAME_GRID_ROWS)/static_cast(mnMaxY-mnMinY); + + fx = static_cast(mpCamera)->toK().at(0,0); + fy = static_cast(mpCamera)->toK().at(1,1); + cx = static_cast(mpCamera)->toK().at(0,2); + cy = static_cast(mpCamera)->toK().at(1,2); + invfx = 1.0f/fx; + invfy = 1.0f/fy; + + mbInitialComputations=false; + } + + + mb = mbf/fx; + + //Set no stereo fisheye information + Nleft = -1; + Nright = -1; + mvLeftToRightMatch = vector(0); + mvRightToLeftMatch = vector(0); + mTlr = cv::Mat(3,4,CV_32F); + mTrl = cv::Mat(3,4,CV_32F); + mvStereo3Dpoints = vector(0); + monoLeft = -1; + monoRight = -1; + + AssignFeaturesToGrid(); + + // mVw = cv::Mat::zeros(3,1,CV_32F); + if(pPrevF) + { + if(!pPrevF->mVw.empty()) + mVw = pPrevF->mVw.clone(); + } + else + { + mVw = cv::Mat::zeros(3,1,CV_32F); + } + + mpMutexImu = new std::mutex(); +} + + +void Frame::AssignFeaturesToGrid() +{ + // Fill matrix with points + const int nCells = FRAME_GRID_COLS*FRAME_GRID_ROWS; + + int nReserve = 0.5f*N/(nCells); + + for(unsigned int i=0; i vLapping = {x0,x1}; + if(flag==0) + monoLeft = (*mpORBextractorLeft)(im,cv::Mat(),mvKeys,mDescriptors,vLapping); + else + monoRight = (*mpORBextractorRight)(im,cv::Mat(),mvKeysRight,mDescriptorsRight,vLapping); +} + +void Frame::SetPose(cv::Mat Tcw) +{ + mTcw = Tcw.clone(); + UpdatePoseMatrices(); +} + +void Frame::GetPose(cv::Mat &Tcw) +{ + Tcw = mTcw.clone(); +} + +void Frame::SetNewBias(const IMU::Bias &b) +{ + mImuBias = b; + if(mpImuPreintegrated) + mpImuPreintegrated->SetNewBias(b); +} + +void Frame::SetVelocity(const cv::Mat &Vwb) +{ + mVw = Vwb.clone(); +} + +void Frame::SetImuPoseVelocity(const cv::Mat &Rwb, const cv::Mat &twb, const cv::Mat &Vwb) +{ + mVw = Vwb.clone(); + cv::Mat Rbw = Rwb.t(); + cv::Mat tbw = -Rbw*twb; + cv::Mat Tbw = cv::Mat::eye(4,4,CV_32F); + Rbw.copyTo(Tbw.rowRange(0,3).colRange(0,3)); + tbw.copyTo(Tbw.rowRange(0,3).col(3)); + mTcw = mImuCalib.Tcb*Tbw; + UpdatePoseMatrices(); +} + + + +void Frame::UpdatePoseMatrices() +{ + mRcw = mTcw.rowRange(0,3).colRange(0,3); + mRwc = mRcw.t(); + mtcw = mTcw.rowRange(0,3).col(3); + mOw = -mRcw.t()*mtcw; +} + +cv::Mat Frame::GetImuPosition() +{ + return mRwc*mImuCalib.Tcb.rowRange(0,3).col(3)+mOw; +} + +cv::Mat Frame::GetImuRotation() +{ + return mRwc*mImuCalib.Tcb.rowRange(0,3).colRange(0,3); +} + +cv::Mat Frame::GetImuPose() +{ + cv::Mat Twb = cv::Mat::eye(4,4,CV_32F); + Twb.rowRange(0,3).colRange(0,3) = mRwc*mImuCalib.Tcb.rowRange(0,3).colRange(0,3); + Twb.rowRange(0,3).col(3) = mRwc*mImuCalib.Tcb.rowRange(0,3).col(3)+mOw; + return Twb.clone(); +} + + +bool Frame::isInFrustum(MapPoint *pMP, float viewingCosLimit) +{ + if(Nleft == -1){ + // cout << "\na"; + pMP->mbTrackInView = false; + pMP->mTrackProjX = -1; + pMP->mTrackProjY = -1; + + // 3D in absolute coordinates + cv::Mat P = pMP->GetWorldPos(); + + // cout << "b"; + + // 3D in camera coordinates + const cv::Mat Pc = mRcw*P+mtcw; + const float Pc_dist = cv::norm(Pc); + + // Check positive depth + const float &PcZ = Pc.at(2); + const float invz = 1.0f/PcZ; + if(PcZ<0.0f) + return false; + + const cv::Point2f uv = mpCamera->project(Pc); + + // cout << "c"; + + if(uv.xmnMaxX) + return false; + if(uv.ymnMaxY) + return false; + + // cout << "d"; + pMP->mTrackProjX = uv.x; + pMP->mTrackProjY = uv.y; + + // Check distance is in the scale invariance region of the MapPoint + const float maxDistance = pMP->GetMaxDistanceInvariance(); + const float minDistance = pMP->GetMinDistanceInvariance(); + const cv::Mat PO = P-mOw; + const float dist = cv::norm(PO); + + if(distmaxDistance) + return false; + + // cout << "e"; + + // Check viewing angle + cv::Mat Pn = pMP->GetNormal(); + + // cout << "f"; + + const float viewCos = PO.dot(Pn)/dist; + + if(viewCosPredictScale(dist,this); + + // cout << "g"; + + // Data used by the tracking + pMP->mbTrackInView = true; + pMP->mTrackProjX = uv.x; + pMP->mTrackProjXR = uv.x - mbf*invz; + + pMP->mTrackDepth = Pc_dist; + // cout << "h"; + + pMP->mTrackProjY = uv.y; + pMP->mnTrackScaleLevel= nPredictedLevel; + pMP->mTrackViewCos = viewCos; + + // cout << "i"; + + return true; + } + else{ + pMP->mbTrackInView = false; + pMP->mbTrackInViewR = false; + pMP -> mnTrackScaleLevel = -1; + pMP -> mnTrackScaleLevelR = -1; + + pMP->mbTrackInView = isInFrustumChecks(pMP,viewingCosLimit); + pMP->mbTrackInViewR = isInFrustumChecks(pMP,viewingCosLimit,true); + + return pMP->mbTrackInView || pMP->mbTrackInViewR; + } +} + +bool Frame::ProjectPointDistort(MapPoint* pMP, cv::Point2f &kp, float &u, float &v) +{ + + // 3D in absolute coordinates + cv::Mat P = pMP->GetWorldPos(); + + // 3D in camera coordinates + const cv::Mat Pc = mRcw*P+mtcw; + const float &PcX = Pc.at(0); + const float &PcY= Pc.at(1); + const float &PcZ = Pc.at(2); + + // Check positive depth + if(PcZ<0.0f) + { + cout << "Negative depth: " << PcZ << endl; + return false; + } + + // Project in image and check it is not outside + const float invz = 1.0f/PcZ; + u=fx*PcX*invz+cx; + v=fy*PcY*invz+cy; + + // cout << "c"; + + if(umnMaxX) + return false; + if(vmnMaxY) + return false; + + float u_distort, v_distort; + + float x = (u - cx) * invfx; + float y = (v - cy) * invfy; + float r2 = x * x + y * y; + float k1 = mDistCoef.at(0); + float k2 = mDistCoef.at(1); + float p1 = mDistCoef.at(2); + float p2 = mDistCoef.at(3); + float k3 = 0; + if(mDistCoef.total() == 5) + { + k3 = mDistCoef.at(4); + } + + // Radial distorsion + float x_distort = x * (1 + k1 * r2 + k2 * r2 * r2 + k3 * r2 * r2 * r2); + float y_distort = y * (1 + k1 * r2 + k2 * r2 * r2 + k3 * r2 * r2 * r2); + + // Tangential distorsion + x_distort = x_distort + (2 * p1 * x * y + p2 * (r2 + 2 * x * x)); + y_distort = y_distort + (p1 * (r2 + 2 * y * y) + 2 * p2 * x * y); + + u_distort = x_distort * fx + cx; + v_distort = y_distort * fy + cy; + + + u = u_distort; + v = v_distort; + + kp = cv::Point2f(u, v); + + return true; +} + +cv::Mat Frame::inRefCoordinates(cv::Mat pCw) +{ + return mRcw*pCw+mtcw; +} + +vector Frame::GetFeaturesInArea(const float &x, const float &y, const float &r, const int minLevel, const int maxLevel, const bool bRight) const +{ + vector vIndices; + vIndices.reserve(N); + + float factorX = r; + float factorY = r; + + /*cout << "fX " << factorX << endl; + cout << "fY " << factorY << endl;*/ + + const int nMinCellX = max(0,(int)floor((x-mnMinX-factorX)*mfGridElementWidthInv)); + if(nMinCellX>=FRAME_GRID_COLS) + { + return vIndices; + } + + const int nMaxCellX = min((int)FRAME_GRID_COLS-1,(int)ceil((x-mnMinX+factorX)*mfGridElementWidthInv)); + if(nMaxCellX<0) + { + return vIndices; + } + + const int nMinCellY = max(0,(int)floor((y-mnMinY-factorY)*mfGridElementHeightInv)); + if(nMinCellY>=FRAME_GRID_ROWS) + { + return vIndices; + } + + const int nMaxCellY = min((int)FRAME_GRID_ROWS-1,(int)ceil((y-mnMinY+factorY)*mfGridElementHeightInv)); + if(nMaxCellY<0) + { + return vIndices; + } + + const bool bCheckLevels = (minLevel>0) || (maxLevel>=0); + + for(int ix = nMinCellX; ix<=nMaxCellX; ix++) + { + for(int iy = nMinCellY; iy<=nMaxCellY; iy++) + { + const vector vCell = (!bRight) ? mGrid[ix][iy] : mGridRight[ix][iy]; + if(vCell.empty()) + continue; + + for(size_t j=0, jend=vCell.size(); j=0) + if(kpUn.octave>maxLevel) + continue; + } + + const float distx = kpUn.pt.x-x; + const float disty = kpUn.pt.y-y; + + if(fabs(distx)=FRAME_GRID_COLS || posY<0 || posY>=FRAME_GRID_ROWS) + return false; + + return true; +} + + +void Frame::ComputeBoW() +{ + if(mBowVec.empty()) + { + vector vCurrentDesc = Converter::toDescriptorVector(mDescriptors); + mpORBvocabulary->transform(vCurrentDesc,mBowVec,mFeatVec,4); + } +} + +void Frame::UndistortKeyPoints() +{ + if(mDistCoef.at(0)==0.0) + { + mvKeysUn=mvKeys; + return; + } + + // Fill matrix with points + cv::Mat mat(N,2,CV_32F); + + for(int i=0; i(i,0)=mvKeys[i].pt.x; + mat.at(i,1)=mvKeys[i].pt.y; + } + + // Undistort points + mat=mat.reshape(2); + cv::undistortPoints(mat,mat, static_cast(mpCamera)->toK(),mDistCoef,cv::Mat(),mK); + mat=mat.reshape(1); + + + // Fill undistorted keypoint vector + mvKeysUn.resize(N); + for(int i=0; i(i,0); + kp.pt.y=mat.at(i,1); + mvKeysUn[i]=kp; + } + +} + +void Frame::ComputeImageBounds(const cv::Mat &imLeft) +{ + if(mDistCoef.at(0)!=0.0) + { + cv::Mat mat(4,2,CV_32F); + mat.at(0,0)=0.0; mat.at(0,1)=0.0; + mat.at(1,0)=imLeft.cols; mat.at(1,1)=0.0; + mat.at(2,0)=0.0; mat.at(2,1)=imLeft.rows; + mat.at(3,0)=imLeft.cols; mat.at(3,1)=imLeft.rows; + + mat=mat.reshape(2); + cv::undistortPoints(mat,mat,static_cast(mpCamera)->toK(),mDistCoef,cv::Mat(),mK); + mat=mat.reshape(1); + + // Undistort corners + mnMinX = min(mat.at(0,0),mat.at(2,0)); + mnMaxX = max(mat.at(1,0),mat.at(3,0)); + mnMinY = min(mat.at(0,1),mat.at(1,1)); + mnMaxY = max(mat.at(2,1),mat.at(3,1)); + } + else + { + mnMinX = 0.0f; + mnMaxX = imLeft.cols; + mnMinY = 0.0f; + mnMaxY = imLeft.rows; + } +} + +void Frame::ComputeStereoMatches() +{ + mvuRight = vector(N,-1.0f); + mvDepth = vector(N,-1.0f); + + const int thOrbDist = (ORBmatcher::TH_HIGH+ORBmatcher::TH_LOW)/2; + + const int nRows = mpORBextractorLeft->mvImagePyramid[0].rows; + + //Assign keypoints to row table + vector > vRowIndices(nRows,vector()); + + for(int i=0; i > vDistIdx; + vDistIdx.reserve(N); + + for(int iL=0; iL &vCandidates = vRowIndices[vL]; + + if(vCandidates.empty()) + continue; + + const float minU = uL-maxD; + const float maxU = uL-minD; + + if(maxU<0) + continue; + + int bestDist = ORBmatcher::TH_HIGH; + size_t bestIdxR = 0; + + const cv::Mat &dL = mDescriptors.row(iL); + + // Compare descriptor to right keypoints + for(size_t iC=0; iClevelL+1) + continue; + + const float &uR = kpR.pt.x; + + if(uR>=minU && uR<=maxU) + { + const cv::Mat &dR = mDescriptorsRight.row(iR); + const int dist = ORBmatcher::DescriptorDistance(dL,dR); + + if(distmvImagePyramid[kpL.octave].rowRange(scaledvL-w,scaledvL+w+1).colRange(scaleduL-w,scaleduL+w+1); + //IL.convertTo(IL,CV_32F); + //IL = IL - IL.at(w,w) *cv::Mat::ones(IL.rows,IL.cols,CV_32F); + IL.convertTo(IL,CV_16S); + IL = IL - IL.at(w,w); + + int bestDist = INT_MAX; + int bestincR = 0; + const int L = 5; + vector vDists; + vDists.resize(2*L+1); + + const float iniu = scaleduR0+L-w; + const float endu = scaleduR0+L+w+1; + if(iniu<0 || endu >= mpORBextractorRight->mvImagePyramid[kpL.octave].cols) + continue; + + for(int incR=-L; incR<=+L; incR++) + { + cv::Mat IR = mpORBextractorRight->mvImagePyramid[kpL.octave].rowRange(scaledvL-w,scaledvL+w+1).colRange(scaleduR0+incR-w,scaleduR0+incR+w+1); + //IR.convertTo(IR,CV_32F); + //IR = IR - IR.at(w,w) *cv::Mat::ones(IR.rows,IR.cols,CV_32F); + IR.convertTo(IR,CV_16S); + IR = IR - IR.at(w,w); + + float dist = cv::norm(IL,IR,cv::NORM_L1); + if(dist1) + continue; + + // Re-scaled coordinate + float bestuR = mvScaleFactors[kpL.octave]*((float)scaleduR0+(float)bestincR+deltaR); + + float disparity = (uL-bestuR); + + if(disparity>=minD && disparity(bestDist,iL)); + } + } + } + + sort(vDistIdx.begin(),vDistIdx.end()); + const float median = vDistIdx[vDistIdx.size()/2].first; + const float thDist = 1.5f*1.4f*median; + + for(int i=vDistIdx.size()-1;i>=0;i--) + { + if(vDistIdx[i].first(N,-1); + mvDepth = vector(N,-1); + + for(int i=0; i(v,u); + + if(d>0) + { + mvDepth[i] = d; + mvuRight[i] = kpU.pt.x-mbf/d; + } + } +} + +cv::Mat Frame::UnprojectStereo(const int &i) +{ + const float z = mvDepth[i]; + if(z>0) + { + const float u = mvKeysUn[i].pt.x; + const float v = mvKeysUn[i].pt.y; + const float x = (u-cx)*z*invfx; + const float y = (v-cy)*z*invfy; + cv::Mat x3Dc = (cv::Mat_(3,1) << x, y, z); + return mRwc*x3Dc+mOw; + } + else + return cv::Mat(); +} + +bool Frame::imuIsPreintegrated() +{ + unique_lock lock(*mpMutexImu); + return mbImuPreintegrated; +} + +void Frame::setIntegrated() +{ + unique_lock lock(*mpMutexImu); + mbImuPreintegrated = true; +} + +Frame::Frame(const cv::Mat &imLeft, const cv::Mat &imRight, const double &timeStamp, ORBextractor* extractorLeft, ORBextractor* extractorRight, ORBVocabulary* voc, cv::Mat &K, cv::Mat &distCoef, const float &bf, const float &thDepth, GeometricCamera* pCamera, GeometricCamera* pCamera2, cv::Mat& Tlr,Frame* pPrevF, const IMU::Calib &ImuCalib) + :mpcpi(NULL), mpORBvocabulary(voc),mpORBextractorLeft(extractorLeft),mpORBextractorRight(extractorRight), mTimeStamp(timeStamp), mK(K.clone()), mDistCoef(distCoef.clone()), mbf(bf), mThDepth(thDepth), + mImuCalib(ImuCalib), mpImuPreintegrated(NULL), mpPrevFrame(pPrevF),mpImuPreintegratedFrame(NULL), mpReferenceKF(static_cast(NULL)), mbImuPreintegrated(false), mpCamera(pCamera), mpCamera2(pCamera2), mTlr(Tlr) +{ + std::chrono::steady_clock::time_point t0 = std::chrono::steady_clock::now(); + imgLeft = imLeft.clone(); + imgRight = imRight.clone(); + std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now(); + + // Frame ID + mnId=nNextId++; + + // Scale Level Info + mnScaleLevels = mpORBextractorLeft->GetLevels(); + mfScaleFactor = mpORBextractorLeft->GetScaleFactor(); + mfLogScaleFactor = log(mfScaleFactor); + mvScaleFactors = mpORBextractorLeft->GetScaleFactors(); + mvInvScaleFactors = mpORBextractorLeft->GetInverseScaleFactors(); + mvLevelSigma2 = mpORBextractorLeft->GetScaleSigmaSquares(); + mvInvLevelSigma2 = mpORBextractorLeft->GetInverseScaleSigmaSquares(); + + // ORB extraction + thread threadLeft(&Frame::ExtractORB,this,0,imLeft,static_cast(mpCamera)->mvLappingArea[0],static_cast(mpCamera)->mvLappingArea[1]); + thread threadRight(&Frame::ExtractORB,this,1,imRight,static_cast(mpCamera2)->mvLappingArea[0],static_cast(mpCamera2)->mvLappingArea[1]); + threadLeft.join(); + threadRight.join(); + std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now(); + + Nleft = mvKeys.size(); + Nright = mvKeysRight.size(); + N = Nleft + Nright; + + if(N == 0) + return; + + // This is done only for the first Frame (or after a change in the calibration) + if(mbInitialComputations) + { + ComputeImageBounds(imLeft); + + mfGridElementWidthInv=static_cast(FRAME_GRID_COLS)/(mnMaxX-mnMinX); + mfGridElementHeightInv=static_cast(FRAME_GRID_ROWS)/(mnMaxY-mnMinY); + + fx = K.at(0,0); + fy = K.at(1,1); + cx = K.at(0,2); + cy = K.at(1,2); + invfx = 1.0f/fx; + invfy = 1.0f/fy; + + mbInitialComputations=false; + } + + mb = mbf / fx; + + mRlr = mTlr.rowRange(0,3).colRange(0,3); + mtlr = mTlr.col(3); + + cv::Mat Rrl = mTlr.rowRange(0,3).colRange(0,3).t(); + cv::Mat trl = Rrl * (-1 * mTlr.col(3)); + + cv::hconcat(Rrl,trl,mTrl); + + ComputeStereoFishEyeMatches(); + std::chrono::steady_clock::time_point t3 = std::chrono::steady_clock::now(); + + //Put all descriptors in the same matrix + cv::vconcat(mDescriptors,mDescriptorsRight,mDescriptors); + + mvpMapPoints = vector(N,static_cast(nullptr)); + mvbOutlier = vector(N,false); + + AssignFeaturesToGrid(); + std::chrono::steady_clock::time_point t4 = std::chrono::steady_clock::now(); + + mpMutexImu = new std::mutex(); + + UndistortKeyPoints(); + std::chrono::steady_clock::time_point t5 = std::chrono::steady_clock::now(); + + double t_read = std::chrono::duration_cast >(t1 - t0).count(); + double t_orbextract = std::chrono::duration_cast >(t2 - t1).count(); + double t_stereomatches = std::chrono::duration_cast >(t3 - t2).count(); + double t_assign = std::chrono::duration_cast >(t4 - t3).count(); + double t_undistort = std::chrono::duration_cast >(t5 - t4).count(); + + /*cout << "Reading time: " << t_read << endl; + cout << "Extraction time: " << t_orbextract << endl; + cout << "Matching time: " << t_stereomatches << endl; + cout << "Assignment time: " << t_assign << endl; + cout << "Undistortion time: " << t_undistort << endl;*/ + +} + +void Frame::ComputeStereoFishEyeMatches() { + //Speed it up by matching keypoints in the lapping area + vector stereoLeft(mvKeys.begin() + monoLeft, mvKeys.end()); + vector stereoRight(mvKeysRight.begin() + monoRight, mvKeysRight.end()); + + cv::Mat stereoDescLeft = mDescriptors.rowRange(monoLeft, mDescriptors.rows); + cv::Mat stereoDescRight = mDescriptorsRight.rowRange(monoRight, mDescriptorsRight.rows); + + mvLeftToRightMatch = vector(Nleft,-1); + mvRightToLeftMatch = vector(Nright,-1); + mvDepth = vector(Nleft,-1.0f); + mvuRight = vector(Nleft,-1); + mvStereo3Dpoints = vector(Nleft); + mnCloseMPs = 0; + + //Perform a brute force between Keypoint in the left and right image + vector> matches; + + BFmatcher.knnMatch(stereoDescLeft,stereoDescRight,matches,2); + + int nMatches = 0; + int descMatches = 0; + + //Check matches using Lowe's ratio + for(vector>::iterator it = matches.begin(); it != matches.end(); ++it){ + if((*it).size() >= 2 && (*it)[0].distance < (*it)[1].distance * 0.7){ + //For every good match, check parallax and reprojection error to discard spurious matches + cv::Mat p3D; + descMatches++; + float sigma1 = mvLevelSigma2[mvKeys[(*it)[0].queryIdx + monoLeft].octave], sigma2 = mvLevelSigma2[mvKeysRight[(*it)[0].trainIdx + monoRight].octave]; + float depth = static_cast(mpCamera)->TriangulateMatches(mpCamera2,mvKeys[(*it)[0].queryIdx + monoLeft],mvKeysRight[(*it)[0].trainIdx + monoRight],mRlr,mtlr,sigma1,sigma2,p3D); + if(depth > 0.0001f){ + mvLeftToRightMatch[(*it)[0].queryIdx + monoLeft] = (*it)[0].trainIdx + monoRight; + mvRightToLeftMatch[(*it)[0].trainIdx + monoRight] = (*it)[0].queryIdx + monoLeft; + mvStereo3Dpoints[(*it)[0].queryIdx + monoLeft] = p3D.clone(); + mvDepth[(*it)[0].queryIdx + monoLeft] = depth; + nMatches++; + } + } + } +} + +bool Frame::isInFrustumChecks(MapPoint *pMP, float viewingCosLimit, bool bRight) { + // 3D in absolute coordinates + cv::Mat P = pMP->GetWorldPos(); + + cv::Mat mR, mt, twc; + if(bRight){ + cv::Mat Rrl = mTrl.colRange(0,3).rowRange(0,3); + cv::Mat trl = mTrl.col(3); + mR = Rrl * mRcw; + mt = Rrl * mtcw + trl; + twc = mRwc * mTlr.rowRange(0,3).col(3) + mOw; + } + else{ + mR = mRcw; + mt = mtcw; + twc = mOw; + } + + // 3D in camera coordinates + cv::Mat Pc = mR*P+mt; + const float Pc_dist = cv::norm(Pc); + const float &PcZ = Pc.at(2); + + // Check positive depth + if(PcZ<0.0f) + return false; + + // Project in image and check it is not outside + cv::Point2f uv; + if(bRight) uv = mpCamera2->project(Pc); + else uv = mpCamera->project(Pc); + + if(uv.xmnMaxX) + return false; + if(uv.ymnMaxY) + return false; + + // Check distance is in the scale invariance region of the MapPoint + const float maxDistance = pMP->GetMaxDistanceInvariance(); + const float minDistance = pMP->GetMinDistanceInvariance(); + const cv::Mat PO = P-twc; + const float dist = cv::norm(PO); + + if(distmaxDistance) + return false; + + // Check viewing angle + cv::Mat Pn = pMP->GetNormal(); + + const float viewCos = PO.dot(Pn)/dist; + + if(viewCosPredictScale(dist,this); + + if(bRight){ + pMP->mTrackProjXR = uv.x; + pMP->mTrackProjYR = uv.y; + pMP->mnTrackScaleLevelR= nPredictedLevel; + pMP->mTrackViewCosR = viewCos; + pMP->mTrackDepthR = Pc_dist; + } + else{ + pMP->mTrackProjX = uv.x; + pMP->mTrackProjY = uv.y; + pMP->mnTrackScaleLevel= nPredictedLevel; + pMP->mTrackViewCos = viewCos; + pMP->mTrackDepth = Pc_dist; + } + + return true; +} + +cv::Mat Frame::UnprojectStereoFishEye(const int &i){ + return mRwc*mvStereo3Dpoints[i]+mOw; +} + +} //namespace ORB_SLAM diff --git a/third_party/ORB_SLAM3/src/FrameDrawer.cc b/third_party/ORB_SLAM3/src/FrameDrawer.cc new file mode 100644 index 0000000..2678e72 --- /dev/null +++ b/third_party/ORB_SLAM3/src/FrameDrawer.cc @@ -0,0 +1,489 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + +#include "FrameDrawer.h" +#include "Tracking.h" + +#include +#include +#include +#include + +#include + +namespace ORB_SLAM3 +{ + +FrameDrawer::FrameDrawer(Atlas* pAtlas):both(false),mpAtlas(pAtlas) +{ + mState=Tracking::SYSTEM_NOT_READY; + mIm = cv::Mat(480,640,CV_8UC3, cv::Scalar(0,0,0)); + mImRight = cv::Mat(480,640,CV_8UC3, cv::Scalar(0,0,0)); +} + +cv::Mat FrameDrawer::DrawFrame(bool bOldFeatures) +{ + // std::cout << "0" << std::endl; + cv::Mat im; + vector vIniKeys; // Initialization: KeyPoints in reference frame + vector vMatches; // Initialization: correspondeces with reference keypoints + vector vCurrentKeys; // KeyPoints in current frame + vector vbVO, vbMap; // Tracked MapPoints in current frame + vector > vTracks; + int state; // Tracking state + + // + Frame currentFrame; + vector vpLocalMap; + vector vMatchesKeys; + vector vpMatchedMPs; + vector vOutlierKeys; + vector vpOutlierMPs; + map mProjectPoints; + map mMatchedInImage; + + //Copy variables within scoped mutex + { + unique_lock lock(mMutex); + state=mState; + if(mState==Tracking::SYSTEM_NOT_READY) + mState=Tracking::NO_IMAGES_YET; + + mIm.copyTo(im); + + if(mState==Tracking::NOT_INITIALIZED) + { + vCurrentKeys = mvCurrentKeys; + vIniKeys = mvIniKeys; + vMatches = mvIniMatches; + vTracks = mvTracks; + } + else if(mState==Tracking::OK /*&& bOldFeatures*/) + { + vCurrentKeys = mvCurrentKeys; + vbVO = mvbVO; + vbMap = mvbMap; + + currentFrame = mCurrentFrame; + vpLocalMap = mvpLocalMap; + vMatchesKeys = mvMatchedKeys; + vpMatchedMPs = mvpMatchedMPs; + vOutlierKeys = mvOutlierKeys; + vpOutlierMPs = mvpOutlierMPs; + mProjectPoints = mmProjectPoints; + mMatchedInImage = mmMatchedInImage; + + } + else if(mState==Tracking::LOST) + { + vCurrentKeys = mvCurrentKeys; + } + } + + if(im.channels()<3) //this should be always true + cvtColor(im,im,CV_GRAY2BGR); + + //Draw + if(state==Tracking::NOT_INITIALIZED) + { + for(unsigned int i=0; i=0) + { + cv::line(im,vIniKeys[i].pt,vCurrentKeys[vMatches[i]].pt, + cv::Scalar(0,255,0)); + } + } + for(vector >::iterator it=vTracks.begin(); it!=vTracks.end(); it++) + cv::line(im,(*it).first,(*it).second, cv::Scalar(0,255,0),5); + + } + else if(state==Tracking::OK && bOldFeatures) //TRACKING + { + mnTracked=0; + mnTrackedVO=0; + const float r = 5; + int n = vCurrentKeys.size(); + for(int i=0;i::iterator it_match = mMatchedInImage.begin(); + while(it_match != mMatchedInImage.end()) + { + long unsigned int mp_id = it_match->first; + cv::Point2f p_image = it_match->second; + + if(mProjectPoints.find(mp_id) != mProjectPoints.end()) + { + cv::Point2f p_proj = mMatchedInImage[mp_id]; + cv::line(im, p_proj, p_image, cv::Scalar(0, 255, 0), 2); + nTracked2++; + } + else + { + cv::circle(im,p_image,2,cv::Scalar(0,0,255),-1); + } + + + it_match++; + //it_proj = mProjectPoints.erase(it_proj); + } + //for(int i=0; i < n; ++i) + //{ + /*if(!vpMatchedMPs[i]) + continue;*/ + + //cv::circle(im,vProjectPoints[i],2,cv::Scalar(255,0,0),-1); + /*cv::Point2f point3d_proy; + float u, v; + bool bIsInImage = currentFrame.ProjectPointDistort(vpMatchedMPs[i] , point3d_proy, u, v); + if(bIsInImage) + { + //cout << "-Point is out of the image" << point3d_proy.x << ", " << point3d_proy.y << endl; + cv::circle(im,vMatchesKeys[i].pt,2,cv::Scalar(255,0,0),-1); + continue; + } + + //cout << "+Point CV " << point3d_proy.x << ", " << point3d_proy.y << endl; + //cout << "+Point coord " << u << ", " << v << endl; + cv::Point2f point_im = vMatchesKeys[i].pt; + + cv::line(im,cv::Point2f(u, v), point_im,cv::Scalar(0, 255, 0), 1);*/ + + //} + + /*cout << "Number of tracker in old method: " << mnTracked << endl; + cout << "Number of tracker in new method: " << nTracked2 << endl;*/ + + n = vOutlierKeys.size(); + //cout << "Number of outliers: " << n << endl; + for(int i=0; i < n; ++i) + { + cv::Point2f point3d_proy; + float u, v; + currentFrame.ProjectPointDistort(vpOutlierMPs[i] , point3d_proy, u, v); + + cv::Point2f point_im = vOutlierKeys[i].pt; + + cv::line(im,cv::Point2f(u, v), point_im,cv::Scalar(0, 0, 255), 1); + } + +// for(int i=0;i vIniKeys; // Initialization: KeyPoints in reference frame + vector vMatches; // Initialization: correspondeces with reference keypoints + vector vCurrentKeys; // KeyPoints in current frame + vector vbVO, vbMap; // Tracked MapPoints in current frame + int state; // Tracking state + + //Copy variables within scoped mutex + { + unique_lock lock(mMutex); + state=mState; + if(mState==Tracking::SYSTEM_NOT_READY) + mState=Tracking::NO_IMAGES_YET; + + mImRight.copyTo(im); + + if(mState==Tracking::NOT_INITIALIZED) + { + vCurrentKeys = mvCurrentKeysRight; + vIniKeys = mvIniKeys; + vMatches = mvIniMatches; + } + else if(mState==Tracking::OK) + { + vCurrentKeys = mvCurrentKeysRight; + vbVO = mvbVO; + vbMap = mvbMap; + } + else if(mState==Tracking::LOST) + { + vCurrentKeys = mvCurrentKeysRight; + } + } // destroy scoped mutex -> release mutex + + if(im.channels()<3) //this should be always true + cvtColor(im,im,CV_GRAY2BGR); + + //Draw + if(state==Tracking::NOT_INITIALIZED) //INITIALIZING + { + for(unsigned int i=0; i=0) + { + cv::line(im,vIniKeys[i].pt,vCurrentKeys[vMatches[i]].pt, + cv::Scalar(0,255,0)); + } + } + } + else if(state==Tracking::OK) //TRACKING + { + mnTracked=0; + mnTrackedVO=0; + const float r = 5; + const int n = mvCurrentKeysRight.size(); + const int Nleft = mvCurrentKeys.size(); + + for(int i=0;iCountMaps(); + int nKFs = mpAtlas->KeyFramesInMap(); + int nMPs = mpAtlas->MapPointsInMap(); + s << "Maps: " << nMaps << ", KFs: " << nKFs << ", MPs: " << nMPs << ", Matches: " << mnTracked; + if(mnTrackedVO>0) + s << ", + VO matches: " << mnTrackedVO; + } + else if(nState==Tracking::LOST) + { + s << " TRACK LOST. TRYING TO RELOCALIZE "; + } + else if(nState==Tracking::SYSTEM_NOT_READY) + { + s << " LOADING ORB VOCABULARY. PLEASE WAIT..."; + } + + int baseline=0; + cv::Size textSize = cv::getTextSize(s.str(),cv::FONT_HERSHEY_PLAIN,1,1,&baseline); + + imText = cv::Mat(im.rows+textSize.height+10,im.cols,im.type()); + im.copyTo(imText.rowRange(0,im.rows).colRange(0,im.cols)); + imText.rowRange(im.rows,imText.rows) = cv::Mat::zeros(textSize.height+10,im.cols,im.type()); + cv::putText(imText,s.str(),cv::Point(5,imText.rows-5),cv::FONT_HERSHEY_PLAIN,1,cv::Scalar(255,255,255),1,8); + +} + +void FrameDrawer::Update(Tracking *pTracker) +{ + unique_lock lock(mMutex); + pTracker->mImGray.copyTo(mIm); + mvCurrentKeys=pTracker->mCurrentFrame.mvKeys; + + if(both){ + mvCurrentKeysRight = pTracker->mCurrentFrame.mvKeysRight; + pTracker->mImRight.copyTo(mImRight); + N = mvCurrentKeys.size() + mvCurrentKeysRight.size(); + } + else{ + N = mvCurrentKeys.size(); + } + + //cout << "Number of matches in frame: " << N << endl; + // cout << "Number of matches in frame: " << N << endl; + mvbVO = vector(N,false); + mvbMap = vector(N,false); + mbOnlyTracking = pTracker->mbOnlyTracking; + + //Variables for the new visualization + mCurrentFrame = pTracker->mCurrentFrame; + mmProjectPoints = mCurrentFrame.mmProjectPoints; + //mmMatchedInImage = mCurrentFrame.mmMatchedInImage; + mmMatchedInImage.clear(); + + mvpLocalMap = pTracker->GetLocalMapMPS(); + mvMatchedKeys.clear(); + mvMatchedKeys.reserve(N); + mvpMatchedMPs.clear(); + mvpMatchedMPs.reserve(N); + mvOutlierKeys.clear(); + mvOutlierKeys.reserve(N); + mvpOutlierMPs.clear(); + mvpOutlierMPs.reserve(N); + //mvProjectPoints.clear(); + //mvProjectPoints.reserve(N); + + if(pTracker->mLastProcessedState==Tracking::NOT_INITIALIZED) + { + mvIniKeys=pTracker->mInitialFrame.mvKeys; + mvIniMatches=pTracker->mvIniMatches; + } + else if(pTracker->mLastProcessedState==Tracking::OK) + { + for(int i=0;imCurrentFrame.mvpMapPoints[i]; + if(pMP) + { + if(!pTracker->mCurrentFrame.mvbOutlier[i]) + { + if(pMP->Observations()>0) + mvbMap[i]=true; + else + mvbVO[i]=true; + + //mvpMatchedMPs.push_back(pMP); + //mvMatchedKeys.push_back(mvCurrentKeys[i]); + mmMatchedInImage[pMP->mnId] = mvCurrentKeys[i].pt; + + //cv::Point2f point3d_proy; + //float u, v; + //bool bIsInImage = mCurrentFrame.ProjectPointDistort(pMP, point3d_proy, u, v); + //if(bIsInImage) + //{ + //mvMatchedKeys.push_back(mvCurrentKeys[i]); + //mvProjectPoints.push_back(cv::Point2f(u, v)); + //} + } + else + { + mvpOutlierMPs.push_back(pMP); + mvOutlierKeys.push_back(mvCurrentKeys[i]); + } + } + } + + } + mState=static_cast(pTracker->mLastProcessedState); +} + +} //namespace ORB_SLAM diff --git a/third_party/ORB_SLAM3/src/G2oTypes.cc b/third_party/ORB_SLAM3/src/G2oTypes.cc new file mode 100644 index 0000000..c1ad448 --- /dev/null +++ b/third_party/ORB_SLAM3/src/G2oTypes.cc @@ -0,0 +1,1077 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + +#include "G2oTypes.h" +#include "ImuTypes.h" +#include "Converter.h" +namespace ORB_SLAM3 +{ + +ImuCamPose::ImuCamPose(KeyFrame *pKF):its(0) +{ + // Load IMU pose + twb = Converter::toVector3d(pKF->GetImuPosition()); + Rwb = Converter::toMatrix3d(pKF->GetImuRotation()); + + // Load camera poses + int num_cams; + if(pKF->mpCamera2) + num_cams=2; + else + num_cams=1; + + tcw.resize(num_cams); + Rcw.resize(num_cams); + tcb.resize(num_cams); + Rcb.resize(num_cams); + Rbc.resize(num_cams); + tbc.resize(num_cams); + pCamera.resize(num_cams); + + // Left camera + tcw[0] = Converter::toVector3d(pKF->GetTranslation()); + Rcw[0] = Converter::toMatrix3d(pKF->GetRotation()); + tcb[0] = Converter::toVector3d(pKF->mImuCalib.Tcb.rowRange(0,3).col(3)); + Rcb[0] = Converter::toMatrix3d(pKF->mImuCalib.Tcb.rowRange(0,3).colRange(0,3)); + Rbc[0] = Rcb[0].transpose(); + tbc[0] = Converter::toVector3d(pKF->mImuCalib.Tbc.rowRange(0,3).col(3)); + pCamera[0] = pKF->mpCamera; + bf = pKF->mbf; + + if(num_cams>1) + { + Eigen::Matrix4d Trl = Converter::toMatrix4d(pKF->mTrl); + Rcw[1] = Trl.block<3,3>(0,0)*Rcw[0]; + tcw[1] = Trl.block<3,3>(0,0)*tcw[0]+Trl.block<3,1>(0,3); + tcb[1] = Trl.block<3,3>(0,0)*tcb[0]+Trl.block<3,1>(0,3); + Rcb[1] = Trl.block<3,3>(0,0)*Rcb[0]; + Rbc[1] = Rcb[1].transpose(); + tbc[1] = -Rbc[1]*tcb[1]; + pCamera[1] = pKF->mpCamera2; + } + + // For posegraph 4DoF + Rwb0 = Rwb; + DR.setIdentity(); +} + +ImuCamPose::ImuCamPose(Frame *pF):its(0) +{ + // Load IMU pose + twb = Converter::toVector3d(pF->GetImuPosition()); + Rwb = Converter::toMatrix3d(pF->GetImuRotation()); + + // Load camera poses + int num_cams; + if(pF->mpCamera2) + num_cams=2; + else + num_cams=1; + + tcw.resize(num_cams); + Rcw.resize(num_cams); + tcb.resize(num_cams); + Rcb.resize(num_cams); + Rbc.resize(num_cams); + tbc.resize(num_cams); + pCamera.resize(num_cams); + + // Left camera + tcw[0] = Converter::toVector3d(pF->mTcw.rowRange(0,3).col(3)); + Rcw[0] = Converter::toMatrix3d(pF->mTcw.rowRange(0,3).colRange(0,3)); + tcb[0] = Converter::toVector3d(pF->mImuCalib.Tcb.rowRange(0,3).col(3)); + Rcb[0] = Converter::toMatrix3d(pF->mImuCalib.Tcb.rowRange(0,3).colRange(0,3)); + Rbc[0] = Rcb[0].transpose(); + tbc[0] = Converter::toVector3d(pF->mImuCalib.Tbc.rowRange(0,3).col(3)); + pCamera[0] = pF->mpCamera; + bf = pF->mbf; + + if(num_cams>1) + { + Eigen::Matrix4d Trl = Converter::toMatrix4d(pF->mTrl); + Rcw[1] = Trl.block<3,3>(0,0)*Rcw[0]; + tcw[1] = Trl.block<3,3>(0,0)*tcw[0]+Trl.block<3,1>(0,3); + tcb[1] = Trl.block<3,3>(0,0)*tcb[0]+Trl.block<3,1>(0,3); + Rcb[1] = Trl.block<3,3>(0,0)*Rcb[0]; + Rbc[1] = Rcb[1].transpose(); + tbc[1] = -Rbc[1]*tcb[1]; + pCamera[1] = pF->mpCamera2; + } + + // For posegraph 4DoF + Rwb0 = Rwb; + DR.setIdentity(); +} + +ImuCamPose::ImuCamPose(Eigen::Matrix3d &_Rwc, Eigen::Vector3d &_twc, KeyFrame* pKF): its(0) +{ + // This is only for posegrpah, we do not care about multicamera + tcw.resize(1); + Rcw.resize(1); + tcb.resize(1); + Rcb.resize(1); + Rbc.resize(1); + tbc.resize(1); + pCamera.resize(1); + + tcb[0] = Converter::toVector3d(pKF->mImuCalib.Tcb.rowRange(0,3).col(3)); + Rcb[0] = Converter::toMatrix3d(pKF->mImuCalib.Tcb.rowRange(0,3).colRange(0,3)); + Rbc[0] = Rcb[0].transpose(); + tbc[0] = Converter::toVector3d(pKF->mImuCalib.Tbc.rowRange(0,3).col(3)); + twb = _Rwc*tcb[0]+_twc; + Rwb = _Rwc*Rcb[0]; + Rcw[0] = _Rwc.transpose(); + tcw[0] = -Rcw[0]*_twc; + pCamera[0] = pKF->mpCamera; + bf = pKF->mbf; + + // For posegraph 4DoF + Rwb0 = Rwb; + DR.setIdentity(); +} + +void ImuCamPose::SetParam(const std::vector &_Rcw, const std::vector &_tcw, const std::vector &_Rbc, + const std::vector &_tbc, const double &_bf) +{ + Rbc = _Rbc; + tbc = _tbc; + Rcw = _Rcw; + tcw = _tcw; + const int num_cams = Rbc.size(); + Rcb.resize(num_cams); + tcb.resize(num_cams); + + for(int i=0; iproject(Xc); +} + +Eigen::Vector3d ImuCamPose::ProjectStereo(const Eigen::Vector3d &Xw, int cam_idx) const +{ + Eigen::Vector3d Pc = Rcw[cam_idx]*Xw+tcw[cam_idx]; + Eigen::Vector3d pc; + double invZ = 1/Pc(2); + pc.head(2) = pCamera[cam_idx]->project(Pc); + pc(2) = pc(0) - bf*invZ; + return pc; +} + +bool ImuCamPose::isDepthPositive(const Eigen::Vector3d &Xw, int cam_idx) const +{ + return (Rcw[cam_idx].row(2)*Xw+tcw[cam_idx](2))>0.0; +} + +void ImuCamPose::Update(const double *pu) +{ + Eigen::Vector3d ur, ut; + ur << pu[0], pu[1], pu[2]; + ut << pu[3], pu[4], pu[5]; + + // Update body pose + twb += Rwb*ut; + Rwb = Rwb*ExpSO3(ur); + + // Normalize rotation after 5 updates + its++; + if(its>=3) + { + NormalizeRotation(Rwb); + its=0; + } + + // Update camera poses + const Eigen::Matrix3d Rbw = Rwb.transpose(); + const Eigen::Vector3d tbw = -Rbw*twb; + + for(int i=0; i=5) + { + DR(0,2)=0.0; + DR(1,2)=0.0; + DR(2,0)=0.0; + DR(2,1)=0.0; + NormalizeRotation(DR); + its=0; + } + + // Update camera pose + const Eigen::Matrix3d Rbw = Rwb.transpose(); + const Eigen::Vector3d tbw = -Rbw*twb; + + for(int i=0; ifx), fy(pHostKF->fy), cx(pHostKF->cx), cy(pHostKF->cy), bf(pHostKF->mbf) +{ +} + +void InvDepthPoint::Update(const double *pu) +{ + rho += *pu; +} + + +bool VertexPose::read(std::istream& is) +{ + std::vector > Rcw; + std::vector > tcw; + std::vector > Rbc; + std::vector > tbc; + + const int num_cams = _estimate.Rbc.size(); + for(int idx = 0; idx> Rcw[idx](i,j); + } + for (int i=0; i<3; i++){ + is >> tcw[idx](i); + } + + for (int i=0; i<3; i++){ + for (int j=0; j<3; j++) + is >> Rbc[idx](i,j); + } + for (int i=0; i<3; i++){ + is >> tbc[idx](i); + } + + float nextParam; + for(size_t i = 0; i < _estimate.pCamera[idx]->size(); i++){ + is >> nextParam; + _estimate.pCamera[idx]->setParameter(nextParam,i); + } + } + + double bf; + is >> bf; + _estimate.SetParam(Rcw,tcw,Rbc,tbc,bf); + updateCache(); + + return true; +} + +bool VertexPose::write(std::ostream& os) const +{ + std::vector > Rcw = _estimate.Rcw; + std::vector > tcw = _estimate.tcw; + + std::vector > Rbc = _estimate.Rbc; + std::vector > tbc = _estimate.tbc; + + const int num_cams = tcw.size(); + + for(int idx = 0; idxsize(); i++){ + os << _estimate.pCamera[idx]->getParameter(i) << " "; + } + } + + os << _estimate.bf << " "; + + return os.good(); +} + + +void EdgeMono::linearizeOplus() +{ + const VertexPose* VPose = static_cast(_vertices[1]); + const g2o::VertexSBAPointXYZ* VPoint = static_cast(_vertices[0]); + + const Eigen::Matrix3d &Rcw = VPose->estimate().Rcw[cam_idx]; + const Eigen::Vector3d &tcw = VPose->estimate().tcw[cam_idx]; + const Eigen::Vector3d Xc = Rcw*VPoint->estimate() + tcw; + const Eigen::Vector3d Xb = VPose->estimate().Rbc[cam_idx]*Xc+VPose->estimate().tbc[cam_idx]; + const Eigen::Matrix3d &Rcb = VPose->estimate().Rcb[cam_idx]; + + const Eigen::Matrix proj_jac = VPose->estimate().pCamera[cam_idx]->projectJac(Xc); + _jacobianOplusXi = -proj_jac * Rcw; + + Eigen::Matrix SE3deriv; + double x = Xb(0); + double y = Xb(1); + double z = Xb(2); + + SE3deriv << 0.0, z, -y, 1.0, 0.0, 0.0, + -z , 0.0, x, 0.0, 1.0, 0.0, + y , -x , 0.0, 0.0, 0.0, 1.0; + + _jacobianOplusXj = proj_jac * Rcb * SE3deriv; // TODO optimize this product +} + +void EdgeMonoOnlyPose::linearizeOplus() +{ + const VertexPose* VPose = static_cast(_vertices[0]); + + const Eigen::Matrix3d &Rcw = VPose->estimate().Rcw[cam_idx]; + const Eigen::Vector3d &tcw = VPose->estimate().tcw[cam_idx]; + const Eigen::Vector3d Xc = Rcw*Xw + tcw; + const Eigen::Vector3d Xb = VPose->estimate().Rbc[cam_idx]*Xc+VPose->estimate().tbc[cam_idx]; + const Eigen::Matrix3d &Rcb = VPose->estimate().Rcb[cam_idx]; + + Eigen::Matrix proj_jac = VPose->estimate().pCamera[cam_idx]->projectJac(Xc); + + Eigen::Matrix SE3deriv; + double x = Xb(0); + double y = Xb(1); + double z = Xb(2); + SE3deriv << 0.0, z, -y, 1.0, 0.0, 0.0, + -z , 0.0, x, 0.0, 1.0, 0.0, + y , -x , 0.0, 0.0, 0.0, 1.0; + _jacobianOplusXi = proj_jac * Rcb * SE3deriv; // symbol different becasue of update mode +} + +void EdgeStereo::linearizeOplus() +{ + const VertexPose* VPose = static_cast(_vertices[1]); + const g2o::VertexSBAPointXYZ* VPoint = static_cast(_vertices[0]); + + const Eigen::Matrix3d &Rcw = VPose->estimate().Rcw[cam_idx]; + const Eigen::Vector3d &tcw = VPose->estimate().tcw[cam_idx]; + const Eigen::Vector3d Xc = Rcw*VPoint->estimate() + tcw; + const Eigen::Vector3d Xb = VPose->estimate().Rbc[cam_idx]*Xc+VPose->estimate().tbc[cam_idx]; + const Eigen::Matrix3d &Rcb = VPose->estimate().Rcb[cam_idx]; + const double bf = VPose->estimate().bf; + const double inv_z2 = 1.0/(Xc(2)*Xc(2)); + + Eigen::Matrix proj_jac; + proj_jac.block<2,3>(0,0) = VPose->estimate().pCamera[cam_idx]->projectJac(Xc); + proj_jac.block<1,3>(2,0) = proj_jac.block<1,3>(0,0); + proj_jac(2,2) += bf*inv_z2; + + _jacobianOplusXi = -proj_jac * Rcw; + + Eigen::Matrix SE3deriv; + double x = Xb(0); + double y = Xb(1); + double z = Xb(2); + + SE3deriv << 0.0, z, -y, 1.0, 0.0, 0.0, + -z , 0.0, x, 0.0, 1.0, 0.0, + y , -x , 0.0, 0.0, 0.0, 1.0; + + _jacobianOplusXj = proj_jac * Rcb * SE3deriv; + + + /*const VertexPose* VPose = static_cast(_vertices[1]); + const g2o::VertexSBAPointXYZ* VPoint = static_cast(_vertices[0]); + + const Eigen::Matrix3d &Rcw = VPose->estimate().Rcw; + const Eigen::Vector3d &tcw = VPose->estimate().tcw; + const Eigen::Vector3d Xc = Rcw*VPoint->estimate() + tcw; + const double &xc = Xc[0]; + const double &yc = Xc[1]; + const double invzc = 1.0/Xc[2]; + const double invzc2 = invzc*invzc; + const double &fx = VPose->estimate().fx; + const double &fy = VPose->estimate().fy; + const double &bf = VPose->estimate().bf; + const Eigen::Matrix3d &Rcb = VPose->estimate().Rcb; + + // Jacobian wrt Point + _jacobianOplusXi(0,0) = -fx*invzc*Rcw(0,0)+fx*xc*invzc2*Rcw(2,0); + _jacobianOplusXi(0,1) = -fx*invzc*Rcw(0,1)+fx*xc*invzc2*Rcw(2,1); + _jacobianOplusXi(0,2) = -fx*invzc*Rcw(0,2)+fx*xc*invzc2*Rcw(2,2); + + _jacobianOplusXi(1,0) = -fy*invzc*Rcw(1,0)+fy*yc*invzc2*Rcw(2,0); + _jacobianOplusXi(1,1) = -fy*invzc*Rcw(1,1)+fy*yc*invzc2*Rcw(2,1); + _jacobianOplusXi(1,2) = -fy*invzc*Rcw(1,2)+fy*yc*invzc2*Rcw(2,2); + + _jacobianOplusXi(2,0) = _jacobianOplusXi(0,0)-bf*invzc2*Rcw(2,0); + _jacobianOplusXi(2,1) = _jacobianOplusXi(0,1)-bf*invzc2*Rcw(2,1); + _jacobianOplusXi(2,2) = _jacobianOplusXi(0,2)-bf*invzc2*Rcw(2,2); + + const Eigen::Vector3d Xb = VPose->estimate().Rbc*Xc + VPose->estimate().tbc; + const Eigen::Matrix3d RS = VPose->estimate().Rcb*Skew(Xb); + + // Jacobian wrt Imu Pose + _jacobianOplusXj(0,0) = -fx*invzc*RS(0,0)+fx*xc*invzc2*RS(2,0); + _jacobianOplusXj(0,1) = -fx*invzc*RS(0,1)+fx*xc*invzc2*RS(2,1); + _jacobianOplusXj(0,2) = -fx*invzc*RS(0,2)+fx*xc*invzc2*RS(2,2); + _jacobianOplusXj(0,3) = fx*invzc*Rcb(0,0)-fx*xc*invzc2*Rcb(2,0); + _jacobianOplusXj(0,4) = fx*invzc*Rcb(0,1)-fx*xc*invzc2*Rcb(2,1); + _jacobianOplusXj(0,5) = fx*invzc*Rcb(0,2)-fx*xc*invzc2*Rcb(2,2); + + _jacobianOplusXj(1,0) = -fy*invzc*RS(1,0)+fy*yc*invzc2*RS(2,0); + _jacobianOplusXj(1,1) = -fy*invzc*RS(1,1)+fy*yc*invzc2*RS(2,1); + _jacobianOplusXj(1,2) = -fy*invzc*RS(1,2)+fy*yc*invzc2*RS(2,2); + _jacobianOplusXj(1,3) = fy*invzc*Rcb(1,0)-fy*yc*invzc2*Rcb(2,0); + _jacobianOplusXj(1,4) = fy*invzc*Rcb(1,1)-fy*yc*invzc2*Rcb(2,1); + _jacobianOplusXj(1,5) = fy*invzc*Rcb(1,2)-fy*yc*invzc2*Rcb(2,2); + + _jacobianOplusXj(2,0) = _jacobianOplusXj(0,0) - bf*invzc2*RS(2,0); + _jacobianOplusXj(2,1) = _jacobianOplusXj(0,1) - bf*invzc2*RS(2,1); + _jacobianOplusXj(2,2) = _jacobianOplusXj(0,2) - bf*invzc2*RS(2,2); + _jacobianOplusXj(2,3) = _jacobianOplusXj(0,3) + bf*invzc2*Rcb(2,0); + _jacobianOplusXj(2,4) = _jacobianOplusXj(0,4) + bf*invzc2*Rcb(2,1); + _jacobianOplusXj(2,5) = _jacobianOplusXj(0,5) + bf*invzc2*Rcb(2,2); + */ +} + +void EdgeStereoOnlyPose::linearizeOplus() +{ + const VertexPose* VPose = static_cast(_vertices[0]); + + const Eigen::Matrix3d &Rcw = VPose->estimate().Rcw[cam_idx]; + const Eigen::Vector3d &tcw = VPose->estimate().tcw[cam_idx]; + const Eigen::Vector3d Xc = Rcw*Xw + tcw; + const Eigen::Vector3d Xb = VPose->estimate().Rbc[cam_idx]*Xc+VPose->estimate().tbc[cam_idx]; + const Eigen::Matrix3d &Rcb = VPose->estimate().Rcb[cam_idx]; + const double bf = VPose->estimate().bf; + const double inv_z2 = 1.0/(Xc(2)*Xc(2)); + + Eigen::Matrix proj_jac; + proj_jac.block<2,3>(0,0) = VPose->estimate().pCamera[cam_idx]->projectJac(Xc); + proj_jac.block<1,3>(2,0) = proj_jac.block<1,3>(0,0); + proj_jac(2,2) += bf*inv_z2; + + Eigen::Matrix SE3deriv; + double x = Xb(0); + double y = Xb(1); + double z = Xb(2); + SE3deriv << 0.0, z, -y, 1.0, 0.0, 0.0, + -z , 0.0, x, 0.0, 1.0, 0.0, + y , -x , 0.0, 0.0, 0.0, 1.0; + _jacobianOplusXi = proj_jac * Rcb * SE3deriv; + + /*const VertexPose* VPose = static_cast(_vertices[0]); + const Eigen::Matrix3d &Rcw = VPose->estimate().Rcw; + const Eigen::Vector3d &tcw = VPose->estimate().tcw; + const Eigen::Vector3d Xc = Rcw*Xw + tcw; + const double &xc = Xc[0]; + const double &yc = Xc[1]; + const double invzc = 1.0/Xc[2]; + const double invzc2 = invzc*invzc; + const double &fx = VPose->estimate().fx; + const double &fy = VPose->estimate().fy; + const double &bf = VPose->estimate().bf; + const Eigen::Matrix3d &Rcb = VPose->estimate().Rcb; + + const Eigen::Vector3d Xb = VPose->estimate().Rbc*Xc + VPose->estimate().tbc; + const Eigen::Matrix3d RS = VPose->estimate().Rcb*Skew(Xb); + + // Jacobian wrt Imu Pose + _jacobianOplusXi(0,0) = -fx*invzc*RS(0,0)+fx*xc*invzc2*RS(2,0); + _jacobianOplusXi(0,1) = -fx*invzc*RS(0,1)+fx*xc*invzc2*RS(2,1); + _jacobianOplusXi(0,2) = -fx*invzc*RS(0,2)+fx*xc*invzc2*RS(2,2); + _jacobianOplusXi(0,3) = fx*invzc*Rcb(0,0)-fx*xc*invzc2*Rcb(2,0); + _jacobianOplusXi(0,4) = fx*invzc*Rcb(0,1)-fx*xc*invzc2*Rcb(2,1); + _jacobianOplusXi(0,5) = fx*invzc*Rcb(0,2)-fx*xc*invzc2*Rcb(2,2); + + _jacobianOplusXi(1,0) = -fy*invzc*RS(1,0)+fy*yc*invzc2*RS(2,0); + _jacobianOplusXi(1,1) = -fy*invzc*RS(1,1)+fy*yc*invzc2*RS(2,1); + _jacobianOplusXi(1,2) = -fy*invzc*RS(1,2)+fy*yc*invzc2*RS(2,2); + _jacobianOplusXi(1,3) = fy*invzc*Rcb(1,0)-fy*yc*invzc2*Rcb(2,0); + _jacobianOplusXi(1,4) = fy*invzc*Rcb(1,1)-fy*yc*invzc2*Rcb(2,1); + _jacobianOplusXi(1,5) = fy*invzc*Rcb(1,2)-fy*yc*invzc2*Rcb(2,2); + + _jacobianOplusXi(2,0) = _jacobianOplusXi(0,0) - bf*invzc2*RS(2,0); + _jacobianOplusXi(2,1) = _jacobianOplusXi(0,1) - bf*invzc2*RS(2,1); + _jacobianOplusXi(2,2) = _jacobianOplusXi(0,2) - bf*invzc2*RS(2,2); + _jacobianOplusXi(2,3) = _jacobianOplusXi(0,3) + bf*invzc2*Rcb(2,0); + _jacobianOplusXi(2,4) = _jacobianOplusXi(0,4) + bf*invzc2*Rcb(2,1); + _jacobianOplusXi(2,5) = _jacobianOplusXi(0,5) + bf*invzc2*Rcb(2,2); + */ +} + +/*Eigen::Vector2d EdgeMonoInvdepth::cam_project(const Eigen::Vector3d & trans_xyz) const{ + double invZ = 1./trans_xyz[2]; + Eigen::Vector2d res; + res[0] = invZ*trans_xyz[0]*fx + cx; + res[1] = invZ*trans_xyz[1]*fy + cy; + return res; +} + +Eigen::Vector3d EdgeMonoInvdepth::cam_unproject(const double u, const double v, const double invDepth) const{ + Eigen::Vector3d res; + res[2] = 1./invDepth; + double z_x=res[2]/fx; + double z_y=res[2]/fy; + res[0] = (u-cx)*z_x; + res[1] = (v-cy)*z_y; + + return res; +} + +void EdgeMonoInvdepth::linearizeOplus() +{ + VertexInvDepth *vPt = static_cast(_vertices[0]); + g2o::VertexSE3Expmap *vHost = static_cast(_vertices[1]); + g2o::VertexSE3Expmap *vObs = static_cast(_vertices[2]); + + // + g2o::SE3Quat Tiw(vObs->estimate()); + g2o::SE3Quat T0w(vHost->estimate()); + g2o::SE3Quat Ti0 = Tiw*T0w.inverse(); + double o_rho_j = vPt->estimate().rho; + Eigen::Vector3d o_X_j = cam_unproject(vPt->estimate().u,vPt->estimate().v,o_rho_j); + Eigen::Vector3d i_X_j = Ti0.map(o_X_j); + double i_rho_j = 1./i_X_j[2]; + Eigen::Vector2d i_proj_j = cam_project(i_X_j); + + // i_rho_j*C_ij matrix + Eigen::Matrix rhoC_ij; + rhoC_ij(0,0) = i_rho_j*fx; + rhoC_ij(0,1) = 0.0; + rhoC_ij(0,2) = i_rho_j*(cx-i_proj_j[0]); + rhoC_ij(1,0) = 0.0; + rhoC_ij(1,1) = i_rho_j*fy; + rhoC_ij(1,2) = i_rho_j*(cy-i_proj_j[1]); + + // o_rho_j^{-2}*K^{-1}*0_proj_j vector + Eigen::Matrix3d Ri0 = Ti0.rotation().toRotationMatrix(); + Eigen::Matrix tmp; + tmp = rhoC_ij*Ri0; + + // Skew matrices + Eigen::Matrix3d skew_0_X_j; + Eigen::Matrix3d skew_i_X_j; + + skew_0_X_j=Eigen::MatrixXd::Zero(3,3); + skew_i_X_j=Eigen::MatrixXd::Zero(3,3); + + skew_0_X_j(0,1) = -o_X_j[2]; + skew_0_X_j(1,0) = -skew_0_X_j(0,1); + skew_0_X_j(0,2) = o_X_j[1]; + skew_0_X_j(2,0) = -skew_0_X_j(0,2); + skew_0_X_j(1,2) = -o_X_j[0]; + skew_0_X_j(2,1) = -skew_0_X_j(1,2); + + skew_i_X_j(0,1) = -i_X_j[2]; + skew_i_X_j(1,0) = -skew_i_X_j(0,1); + skew_i_X_j(0,2) = i_X_j[1]; + skew_i_X_j(2,0) = -skew_i_X_j(0,2); + skew_i_X_j(1,2) = -i_X_j[0]; + skew_i_X_j(2,1) = -skew_i_X_j(1,2); + + // Jacobians w.r.t inverse depth in the host frame + _jacobianOplus[0].setZero(); + _jacobianOplus[0] = (1./o_rho_j)*rhoC_ij*Ri0*o_X_j; + + // Jacobians w.r.t pose host frame + _jacobianOplus[1].setZero(); + // Rotation + _jacobianOplus[1].block<2,3>(0,0) = -tmp*skew_0_X_j; + // translation + _jacobianOplus[1].block<2,3>(0,3) = tmp; + + // Jacobians w.r.t pose observer frame + _jacobianOplus[2].setZero(); + // Rotation + _jacobianOplus[2].block<2,3>(0,0) = rhoC_ij*skew_i_X_j; + // translation + _jacobianOplus[2].block<2,3>(0,3) = -rhoC_ij; +} + + +Eigen::Vector2d EdgeMonoInvdepthBody::cam_project(const Eigen::Vector3d & trans_xyz) const{ + double invZ = 1./trans_xyz[2]; + Eigen::Vector2d res; + res[0] = invZ*trans_xyz[0]*fx + cx; + res[1] = invZ*trans_xyz[1]*fy + cy; + return res; +} + +Eigen::Vector3d EdgeMonoInvdepthBody::cam_unproject(const double u, const double v, const double invDepth) const{ + Eigen::Vector3d res; + res[2] = 1./invDepth; + double z_x=res[2]/fx; + double z_y=res[2]/fy; + res[0] = (u-cx)*z_x; + res[1] = (v-cy)*z_y; + + return res; +}*/ + +VertexVelocity::VertexVelocity(KeyFrame* pKF) +{ + setEstimate(Converter::toVector3d(pKF->GetVelocity())); +} + +VertexVelocity::VertexVelocity(Frame* pF) +{ + setEstimate(Converter::toVector3d(pF->mVw)); +} + +VertexGyroBias::VertexGyroBias(KeyFrame *pKF) +{ + setEstimate(Converter::toVector3d(pKF->GetGyroBias())); +} + +VertexGyroBias::VertexGyroBias(Frame *pF) +{ + Eigen::Vector3d bg; + bg << pF->mImuBias.bwx, pF->mImuBias.bwy,pF->mImuBias.bwz; + setEstimate(bg); +} + +VertexAccBias::VertexAccBias(KeyFrame *pKF) +{ + setEstimate(Converter::toVector3d(pKF->GetAccBias())); +} + +VertexAccBias::VertexAccBias(Frame *pF) +{ + Eigen::Vector3d ba; + ba << pF->mImuBias.bax, pF->mImuBias.bay,pF->mImuBias.baz; + setEstimate(ba); +} + + + +EdgeInertial::EdgeInertial(IMU::Preintegrated *pInt):JRg(Converter::toMatrix3d(pInt->JRg)), + JVg(Converter::toMatrix3d(pInt->JVg)), JPg(Converter::toMatrix3d(pInt->JPg)), JVa(Converter::toMatrix3d(pInt->JVa)), + JPa(Converter::toMatrix3d(pInt->JPa)), mpInt(pInt), dt(pInt->dT) +{ + // This edge links 6 vertices + resize(6); + g << 0, 0, -IMU::GRAVITY_VALUE; + cv::Mat cvInfo = pInt->C.rowRange(0,9).colRange(0,9).inv(cv::DECOMP_SVD); + Matrix9d Info; + for(int r=0;r<9;r++) + for(int c=0;c<9;c++) + Info(r,c)=cvInfo.at(r,c); + Info = (Info+Info.transpose())/2; + Eigen::SelfAdjointEigenSolver > es(Info); + Eigen::Matrix eigs = es.eigenvalues(); + for(int i=0;i<9;i++) + if(eigs[i]<1e-12) + eigs[i]=0; + Info = es.eigenvectors()*eigs.asDiagonal()*es.eigenvectors().transpose(); + setInformation(Info); +} + + + + +void EdgeInertial::computeError() +{ + // TODO Maybe Reintegrate inertial measurments when difference between linearization point and current estimate is too big + const VertexPose* VP1 = static_cast(_vertices[0]); + const VertexVelocity* VV1= static_cast(_vertices[1]); + const VertexGyroBias* VG1= static_cast(_vertices[2]); + const VertexAccBias* VA1= static_cast(_vertices[3]); + const VertexPose* VP2 = static_cast(_vertices[4]); + const VertexVelocity* VV2 = static_cast(_vertices[5]); + const IMU::Bias b1(VA1->estimate()[0],VA1->estimate()[1],VA1->estimate()[2],VG1->estimate()[0],VG1->estimate()[1],VG1->estimate()[2]); + const Eigen::Matrix3d dR = Converter::toMatrix3d(mpInt->GetDeltaRotation(b1)); + const Eigen::Vector3d dV = Converter::toVector3d(mpInt->GetDeltaVelocity(b1)); + const Eigen::Vector3d dP = Converter::toVector3d(mpInt->GetDeltaPosition(b1)); + + const Eigen::Vector3d er = LogSO3(dR.transpose()*VP1->estimate().Rwb.transpose()*VP2->estimate().Rwb); + const Eigen::Vector3d ev = VP1->estimate().Rwb.transpose()*(VV2->estimate() - VV1->estimate() - g*dt) - dV; + const Eigen::Vector3d ep = VP1->estimate().Rwb.transpose()*(VP2->estimate().twb - VP1->estimate().twb + - VV1->estimate()*dt - g*dt*dt/2) - dP; + + _error << er, ev, ep; +} + +void EdgeInertial::linearizeOplus() +{ + const VertexPose* VP1 = static_cast(_vertices[0]); + const VertexVelocity* VV1= static_cast(_vertices[1]); + const VertexGyroBias* VG1= static_cast(_vertices[2]); + const VertexAccBias* VA1= static_cast(_vertices[3]); + const VertexPose* VP2 = static_cast(_vertices[4]); + const VertexVelocity* VV2= static_cast(_vertices[5]); + const IMU::Bias b1(VA1->estimate()[0],VA1->estimate()[1],VA1->estimate()[2],VG1->estimate()[0],VG1->estimate()[1],VG1->estimate()[2]); + const IMU::Bias db = mpInt->GetDeltaBias(b1); + Eigen::Vector3d dbg; + dbg << db.bwx, db.bwy, db.bwz; + + const Eigen::Matrix3d Rwb1 = VP1->estimate().Rwb; + const Eigen::Matrix3d Rbw1 = Rwb1.transpose(); + const Eigen::Matrix3d Rwb2 = VP2->estimate().Rwb; + + const Eigen::Matrix3d dR = Converter::toMatrix3d(mpInt->GetDeltaRotation(b1)); + const Eigen::Matrix3d eR = dR.transpose()*Rbw1*Rwb2; + const Eigen::Vector3d er = LogSO3(eR); + const Eigen::Matrix3d invJr = InverseRightJacobianSO3(er); + + // Jacobians wrt Pose 1 + _jacobianOplus[0].setZero(); + // rotation + _jacobianOplus[0].block<3,3>(0,0) = -invJr*Rwb2.transpose()*Rwb1; // OK + _jacobianOplus[0].block<3,3>(3,0) = Skew(Rbw1*(VV2->estimate() - VV1->estimate() - g*dt)); // OK + _jacobianOplus[0].block<3,3>(6,0) = Skew(Rbw1*(VP2->estimate().twb - VP1->estimate().twb + - VV1->estimate()*dt - 0.5*g*dt*dt)); // OK + // translation + _jacobianOplus[0].block<3,3>(6,3) = -Eigen::Matrix3d::Identity(); // OK + + // Jacobians wrt Velocity 1 + _jacobianOplus[1].setZero(); + _jacobianOplus[1].block<3,3>(3,0) = -Rbw1; // OK + _jacobianOplus[1].block<3,3>(6,0) = -Rbw1*dt; // OK + + // Jacobians wrt Gyro 1 + _jacobianOplus[2].setZero(); + _jacobianOplus[2].block<3,3>(0,0) = -invJr*eR.transpose()*RightJacobianSO3(JRg*dbg)*JRg; // OK + _jacobianOplus[2].block<3,3>(3,0) = -JVg; // OK + _jacobianOplus[2].block<3,3>(6,0) = -JPg; // OK + + // Jacobians wrt Accelerometer 1 + _jacobianOplus[3].setZero(); + _jacobianOplus[3].block<3,3>(3,0) = -JVa; // OK + _jacobianOplus[3].block<3,3>(6,0) = -JPa; // OK + + // Jacobians wrt Pose 2 + _jacobianOplus[4].setZero(); + // rotation + _jacobianOplus[4].block<3,3>(0,0) = invJr; // OK + // translation + _jacobianOplus[4].block<3,3>(6,3) = Rbw1*Rwb2; // OK + + // Jacobians wrt Velocity 2 + _jacobianOplus[5].setZero(); + _jacobianOplus[5].block<3,3>(3,0) = Rbw1; // OK +} + +EdgeInertialGS::EdgeInertialGS(IMU::Preintegrated *pInt):JRg(Converter::toMatrix3d(pInt->JRg)), + JVg(Converter::toMatrix3d(pInt->JVg)), JPg(Converter::toMatrix3d(pInt->JPg)), JVa(Converter::toMatrix3d(pInt->JVa)), + JPa(Converter::toMatrix3d(pInt->JPa)), mpInt(pInt), dt(pInt->dT) +{ + // This edge links 8 vertices + resize(8); + gI << 0, 0, -IMU::GRAVITY_VALUE; + cv::Mat cvInfo = pInt->C.rowRange(0,9).colRange(0,9).inv(cv::DECOMP_SVD); + Matrix9d Info; + for(int r=0;r<9;r++) + for(int c=0;c<9;c++) + Info(r,c)=cvInfo.at(r,c); + Info = (Info+Info.transpose())/2; + Eigen::SelfAdjointEigenSolver > es(Info); + Eigen::Matrix eigs = es.eigenvalues(); + for(int i=0;i<9;i++) + if(eigs[i]<1e-12) + eigs[i]=0; + Info = es.eigenvectors()*eigs.asDiagonal()*es.eigenvectors().transpose(); + setInformation(Info); +} + + + +void EdgeInertialGS::computeError() +{ + // TODO Maybe Reintegrate inertial measurments when difference between linearization point and current estimate is too big + const VertexPose* VP1 = static_cast(_vertices[0]); + const VertexVelocity* VV1= static_cast(_vertices[1]); + const VertexGyroBias* VG= static_cast(_vertices[2]); + const VertexAccBias* VA= static_cast(_vertices[3]); + const VertexPose* VP2 = static_cast(_vertices[4]); + const VertexVelocity* VV2 = static_cast(_vertices[5]); + const VertexGDir* VGDir = static_cast(_vertices[6]); + const VertexScale* VS = static_cast(_vertices[7]); + const IMU::Bias b(VA->estimate()[0],VA->estimate()[1],VA->estimate()[2],VG->estimate()[0],VG->estimate()[1],VG->estimate()[2]); + g = VGDir->estimate().Rwg*gI; + const double s = VS->estimate(); + const Eigen::Matrix3d dR = Converter::toMatrix3d(mpInt->GetDeltaRotation(b)); + const Eigen::Vector3d dV = Converter::toVector3d(mpInt->GetDeltaVelocity(b)); + const Eigen::Vector3d dP = Converter::toVector3d(mpInt->GetDeltaPosition(b)); + + const Eigen::Vector3d er = LogSO3(dR.transpose()*VP1->estimate().Rwb.transpose()*VP2->estimate().Rwb); + const Eigen::Vector3d ev = VP1->estimate().Rwb.transpose()*(s*(VV2->estimate() - VV1->estimate()) - g*dt) - dV; + const Eigen::Vector3d ep = VP1->estimate().Rwb.transpose()*(s*(VP2->estimate().twb - VP1->estimate().twb - VV1->estimate()*dt) - g*dt*dt/2) - dP; + + _error << er, ev, ep; +} + +void EdgeInertialGS::linearizeOplus() +{ + const VertexPose* VP1 = static_cast(_vertices[0]); + const VertexVelocity* VV1= static_cast(_vertices[1]); + const VertexGyroBias* VG= static_cast(_vertices[2]); + const VertexAccBias* VA= static_cast(_vertices[3]); + const VertexPose* VP2 = static_cast(_vertices[4]); + const VertexVelocity* VV2 = static_cast(_vertices[5]); + const VertexGDir* VGDir = static_cast(_vertices[6]); + const VertexScale* VS = static_cast(_vertices[7]); + const IMU::Bias b(VA->estimate()[0],VA->estimate()[1],VA->estimate()[2],VG->estimate()[0],VG->estimate()[1],VG->estimate()[2]); + const IMU::Bias db = mpInt->GetDeltaBias(b); + + Eigen::Vector3d dbg; + dbg << db.bwx, db.bwy, db.bwz; + + const Eigen::Matrix3d Rwb1 = VP1->estimate().Rwb; + const Eigen::Matrix3d Rbw1 = Rwb1.transpose(); + const Eigen::Matrix3d Rwb2 = VP2->estimate().Rwb; + const Eigen::Matrix3d Rwg = VGDir->estimate().Rwg; + Eigen::MatrixXd Gm = Eigen::MatrixXd::Zero(3,2); + Gm(0,1) = -IMU::GRAVITY_VALUE; + Gm(1,0) = IMU::GRAVITY_VALUE; + const double s = VS->estimate(); + const Eigen::MatrixXd dGdTheta = Rwg*Gm; + const Eigen::Matrix3d dR = Converter::toMatrix3d(mpInt->GetDeltaRotation(b)); + const Eigen::Matrix3d eR = dR.transpose()*Rbw1*Rwb2; + const Eigen::Vector3d er = LogSO3(eR); + const Eigen::Matrix3d invJr = InverseRightJacobianSO3(er); + + // Jacobians wrt Pose 1 + _jacobianOplus[0].setZero(); + // rotation + _jacobianOplus[0].block<3,3>(0,0) = -invJr*Rwb2.transpose()*Rwb1; + _jacobianOplus[0].block<3,3>(3,0) = Skew(Rbw1*(s*(VV2->estimate() - VV1->estimate()) - g*dt)); + _jacobianOplus[0].block<3,3>(6,0) = Skew(Rbw1*(s*(VP2->estimate().twb - VP1->estimate().twb + - VV1->estimate()*dt) - 0.5*g*dt*dt)); + // translation + _jacobianOplus[0].block<3,3>(6,3) = -s*Eigen::Matrix3d::Identity(); + + // Jacobians wrt Velocity 1 + _jacobianOplus[1].setZero(); + _jacobianOplus[1].block<3,3>(3,0) = -s*Rbw1; + _jacobianOplus[1].block<3,3>(6,0) = -s*Rbw1*dt; + + // Jacobians wrt Gyro bias + _jacobianOplus[2].setZero(); + _jacobianOplus[2].block<3,3>(0,0) = -invJr*eR.transpose()*RightJacobianSO3(JRg*dbg)*JRg; + _jacobianOplus[2].block<3,3>(3,0) = -JVg; + _jacobianOplus[2].block<3,3>(6,0) = -JPg; + + // Jacobians wrt Accelerometer bias + _jacobianOplus[3].setZero(); + _jacobianOplus[3].block<3,3>(3,0) = -JVa; + _jacobianOplus[3].block<3,3>(6,0) = -JPa; + + // Jacobians wrt Pose 2 + _jacobianOplus[4].setZero(); + // rotation + _jacobianOplus[4].block<3,3>(0,0) = invJr; + // translation + _jacobianOplus[4].block<3,3>(6,3) = s*Rbw1*Rwb2; + + // Jacobians wrt Velocity 2 + _jacobianOplus[5].setZero(); + _jacobianOplus[5].block<3,3>(3,0) = s*Rbw1; + + // Jacobians wrt Gravity direction + _jacobianOplus[6].setZero(); + _jacobianOplus[6].block<3,2>(3,0) = -Rbw1*dGdTheta*dt; + _jacobianOplus[6].block<3,2>(6,0) = -0.5*Rbw1*dGdTheta*dt*dt; + + // Jacobians wrt scale factor + _jacobianOplus[7].setZero(); + _jacobianOplus[7].block<3,1>(3,0) = Rbw1*(VV2->estimate()-VV1->estimate()); + _jacobianOplus[7].block<3,1>(6,0) = Rbw1*(VP2->estimate().twb-VP1->estimate().twb-VV1->estimate()*dt); +} + +EdgePriorPoseImu::EdgePriorPoseImu(ConstraintPoseImu *c) +{ + resize(4); + Rwb = c->Rwb; + twb = c->twb; + vwb = c->vwb; + bg = c->bg; + ba = c->ba; + setInformation(c->H); +} + +void EdgePriorPoseImu::computeError() +{ + const VertexPose* VP = static_cast(_vertices[0]); + const VertexVelocity* VV = static_cast(_vertices[1]); + const VertexGyroBias* VG = static_cast(_vertices[2]); + const VertexAccBias* VA = static_cast(_vertices[3]); + + const Eigen::Vector3d er = LogSO3(Rwb.transpose()*VP->estimate().Rwb); + const Eigen::Vector3d et = Rwb.transpose()*(VP->estimate().twb-twb); + const Eigen::Vector3d ev = VV->estimate() - vwb; + const Eigen::Vector3d ebg = VG->estimate() - bg; + const Eigen::Vector3d eba = VA->estimate() - ba; + + _error << er, et, ev, ebg, eba; +} + +void EdgePriorPoseImu::linearizeOplus() +{ + const VertexPose* VP = static_cast(_vertices[0]); + const Eigen::Vector3d er = LogSO3(Rwb.transpose()*VP->estimate().Rwb); + _jacobianOplus[0].setZero(); + _jacobianOplus[0].block<3,3>(0,0) = InverseRightJacobianSO3(er); + _jacobianOplus[0].block<3,3>(3,3) = Rwb.transpose()*VP->estimate().Rwb; + _jacobianOplus[1].setZero(); + _jacobianOplus[1].block<3,3>(6,0) = Eigen::Matrix3d::Identity(); + _jacobianOplus[2].setZero(); + _jacobianOplus[2].block<3,3>(9,0) = Eigen::Matrix3d::Identity(); + _jacobianOplus[3].setZero(); + _jacobianOplus[3].block<3,3>(12,0) = Eigen::Matrix3d::Identity(); +} + +void EdgePriorAcc::linearizeOplus() +{ + // Jacobian wrt bias + _jacobianOplusXi.block<3,3>(0,0) = Eigen::Matrix3d::Identity(); + +} + +void EdgePriorGyro::linearizeOplus() +{ + // Jacobian wrt bias + _jacobianOplusXi.block<3,3>(0,0) = Eigen::Matrix3d::Identity(); + +} + +// SO3 FUNCTIONS +Eigen::Matrix3d ExpSO3(const Eigen::Vector3d &w) +{ + return ExpSO3(w[0],w[1],w[2]); +} + +Eigen::Matrix3d ExpSO3(const double x, const double y, const double z) +{ + const double d2 = x*x+y*y+z*z; + const double d = sqrt(d2); + Eigen::Matrix3d W; + W << 0.0, -z, y,z, 0.0, -x,-y, x, 0.0; + if(d<1e-5) + { + Eigen::Matrix3d res = Eigen::Matrix3d::Identity() + W +0.5*W*W; + return Converter::toMatrix3d(IMU::NormalizeRotation(Converter::toCvMat(res))); + } + else + { + Eigen::Matrix3d res =Eigen::Matrix3d::Identity() + W*sin(d)/d + W*W*(1.0-cos(d))/d2; + return Converter::toMatrix3d(IMU::NormalizeRotation(Converter::toCvMat(res))); + } +} + +Eigen::Vector3d LogSO3(const Eigen::Matrix3d &R) +{ + const double tr = R(0,0)+R(1,1)+R(2,2); + Eigen::Vector3d w; + w << (R(2,1)-R(1,2))/2, (R(0,2)-R(2,0))/2, (R(1,0)-R(0,1))/2; + const double costheta = (tr-1.0)*0.5f; + if(costheta>1 || costheta<-1) + return w; + const double theta = acos(costheta); + const double s = sin(theta); + if(fabs(s)<1e-5) + return w; + else + return theta*w/s; +} + +Eigen::Matrix3d InverseRightJacobianSO3(const Eigen::Vector3d &v) +{ + return InverseRightJacobianSO3(v[0],v[1],v[2]); +} + +Eigen::Matrix3d InverseRightJacobianSO3(const double x, const double y, const double z) +{ + const double d2 = x*x+y*y+z*z; + const double d = sqrt(d2); + + Eigen::Matrix3d W; + W << 0.0, -z, y,z, 0.0, -x,-y, x, 0.0; + if(d<1e-5) + return Eigen::Matrix3d::Identity(); + else + return Eigen::Matrix3d::Identity() + W/2 + W*W*(1.0/d2 - (1.0+cos(d))/(2.0*d*sin(d))); +} + +Eigen::Matrix3d RightJacobianSO3(const Eigen::Vector3d &v) +{ + return RightJacobianSO3(v[0],v[1],v[2]); +} + +Eigen::Matrix3d RightJacobianSO3(const double x, const double y, const double z) +{ + const double d2 = x*x+y*y+z*z; + const double d = sqrt(d2); + + Eigen::Matrix3d W; + W << 0.0, -z, y,z, 0.0, -x,-y, x, 0.0; + if(d<1e-5) + { + return Eigen::Matrix3d::Identity(); + } + else + { + return Eigen::Matrix3d::Identity() - W*(1.0-cos(d))/d2 + W*W*(d-sin(d))/(d2*d); + } +} + +Eigen::Matrix3d Skew(const Eigen::Vector3d &w) +{ + Eigen::Matrix3d W; + W << 0.0, -w[2], w[1],w[2], 0.0, -w[0],-w[1], w[0], 0.0; + return W; +} + +Eigen::Matrix3d NormalizeRotation(const Eigen::Matrix3d &R) +{ + Eigen::JacobiSVD svd(R,Eigen::ComputeFullU | Eigen::ComputeFullV); + return svd.matrixU()*svd.matrixV(); +} +} diff --git a/third_party/ORB_SLAM3/src/ImuTypes.cc b/third_party/ORB_SLAM3/src/ImuTypes.cc new file mode 100644 index 0000000..9e7bf16 --- /dev/null +++ b/third_party/ORB_SLAM3/src/ImuTypes.cc @@ -0,0 +1,522 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + +#include "ImuTypes.h" +#include + +namespace ORB_SLAM3 +{ + +namespace IMU +{ + +const float eps = 1e-4; + +cv::Mat NormalizeRotation(const cv::Mat &R) +{ + cv::Mat U,w,Vt; + cv::SVDecomp(R,w,U,Vt,cv::SVD::FULL_UV); + // assert(cv::determinant(U*Vt)>0); + return U*Vt; +} + +cv::Mat Skew(const cv::Mat &v) +{ + const float x = v.at(0); + const float y = v.at(1); + const float z = v.at(2); + return (cv::Mat_(3,3) << 0, -z, y, + z, 0, -x, + -y, x, 0); +} + +cv::Mat ExpSO3(const float &x, const float &y, const float &z) +{ + cv::Mat I = cv::Mat::eye(3,3,CV_32F); + const float d2 = x*x+y*y+z*z; + const float d = sqrt(d2); + cv::Mat W = (cv::Mat_(3,3) << 0, -z, y, + z, 0, -x, + -y, x, 0); + if(d ExpSO3(const double &x, const double &y, const double &z) +{ + Eigen::Matrix I = Eigen::MatrixXd::Identity(3,3); + const double d2 = x*x+y*y+z*z; + const double d = sqrt(d2); + Eigen::Matrix W; + W(0,0) = 0; + W(0,1) = -z; + W(0,2) = y; + W(1,0) = z; + W(1,1) = 0; + W(1,2) = -x; + W(2,0) = -y; + W(2,1) = x; + W(2,2) = 0; + + if(d(0),v.at(1),v.at(2)); +} + +cv::Mat LogSO3(const cv::Mat &R) +{ + const float tr = R.at(0,0)+R.at(1,1)+R.at(2,2); + cv::Mat w = (cv::Mat_(3,1) <<(R.at(2,1)-R.at(1,2))/2, + (R.at(0,2)-R.at(2,0))/2, + (R.at(1,0)-R.at(0,1))/2); + const float costheta = (tr-1.0f)*0.5f; + if(costheta>1 || costheta<-1) + return w; + const float theta = acos(costheta); + const float s = sin(theta); + if(fabs(s)(3,3) << 0, -z, y, + z, 0, -x, + -y, x, 0); + if(d(0),v.at(1),v.at(2)); +} + +cv::Mat InverseRightJacobianSO3(const float &x, const float &y, const float &z) +{ + cv::Mat I = cv::Mat::eye(3,3,CV_32F); + const float d2 = x*x+y*y+z*z; + const float d = sqrt(d2); + cv::Mat W = (cv::Mat_(3,3) << 0, -z, y, + z, 0, -x, + -y, x, 0); + if(d(0),v.at(1),v.at(2)); +} + + +IntegratedRotation::IntegratedRotation(const cv::Point3f &angVel, const Bias &imuBias, const float &time): + deltaT(time) +{ + const float x = (angVel.x-imuBias.bwx)*time; + const float y = (angVel.y-imuBias.bwy)*time; + const float z = (angVel.z-imuBias.bwz)*time; + + cv::Mat I = cv::Mat::eye(3,3,CV_32F); + + const float d2 = x*x+y*y+z*z; + const float d = sqrt(d2); + + cv::Mat W = (cv::Mat_(3,3) << 0, -z, y, + z, 0, -x, + -y, x, 0); + if(ddT), C(pImuPre->C.clone()), Info(pImuPre->Info.clone()), + Nga(pImuPre->Nga.clone()), NgaWalk(pImuPre->NgaWalk.clone()), b(pImuPre->b), dR(pImuPre->dR.clone()), dV(pImuPre->dV.clone()), + dP(pImuPre->dP.clone()), JRg(pImuPre->JRg.clone()), JVg(pImuPre->JVg.clone()), JVa(pImuPre->JVa.clone()), JPg(pImuPre->JPg.clone()), + JPa(pImuPre->JPa.clone()), avgA(pImuPre->avgA.clone()), avgW(pImuPre->avgW.clone()), bu(pImuPre->bu), db(pImuPre->db.clone()), mvMeasurements(pImuPre->mvMeasurements) +{ + +} + +void Preintegrated::CopyFrom(Preintegrated* pImuPre) +{ + std::cout << "Preintegrated: start clone" << std::endl; + dT = pImuPre->dT; + C = pImuPre->C.clone(); + Info = pImuPre->Info.clone(); + Nga = pImuPre->Nga.clone(); + NgaWalk = pImuPre->NgaWalk.clone(); + std::cout << "Preintegrated: first clone" << std::endl; + b.CopyFrom(pImuPre->b); + dR = pImuPre->dR.clone(); + dV = pImuPre->dV.clone(); + dP = pImuPre->dP.clone(); + JRg = pImuPre->JRg.clone(); + JVg = pImuPre->JVg.clone(); + JVa = pImuPre->JVa.clone(); + JPg = pImuPre->JPg.clone(); + JPa = pImuPre->JPa.clone(); + avgA = pImuPre->avgA.clone(); + avgW = pImuPre->avgW.clone(); + std::cout << "Preintegrated: second clone" << std::endl; + bu.CopyFrom(pImuPre->bu); + db = pImuPre->db.clone(); + std::cout << "Preintegrated: third clone" << std::endl; + mvMeasurements = pImuPre->mvMeasurements; + std::cout << "Preintegrated: end clone" << std::endl; +} + + +void Preintegrated::Initialize(const Bias &b_) +{ + dR = cv::Mat::eye(3,3,CV_32F); + dV = cv::Mat::zeros(3,1,CV_32F); + dP = cv::Mat::zeros(3,1,CV_32F); + JRg = cv::Mat::zeros(3,3,CV_32F); + JVg = cv::Mat::zeros(3,3,CV_32F); + JVa = cv::Mat::zeros(3,3,CV_32F); + JPg = cv::Mat::zeros(3,3,CV_32F); + JPa = cv::Mat::zeros(3,3,CV_32F); + C = cv::Mat::zeros(15,15,CV_32F); + Info=cv::Mat(); + db = cv::Mat::zeros(6,1,CV_32F); + b=b_; + bu=b_; + avgA = cv::Mat::zeros(3,1,CV_32F); + avgW = cv::Mat::zeros(3,1,CV_32F); + dT=0.0f; + mvMeasurements.clear(); +} + +void Preintegrated::Reintegrate() +{ + std::unique_lock lock(mMutex); + const std::vector aux = mvMeasurements; + Initialize(bu); + for(size_t i=0;i(3,1) << acceleration.x-b.bax,acceleration.y-b.bay, acceleration.z-b.baz); + cv::Mat accW = (cv::Mat_(3,1) << angVel.x-b.bwx, angVel.y-b.bwy, angVel.z-b.bwz); + + avgA = (dT*avgA + dR*acc*dt)/(dT+dt); + avgW = (dT*avgW + accW*dt)/(dT+dt); + + // Update delta position dP and velocity dV (rely on no-updated delta rotation) + dP = dP + dV*dt + 0.5f*dR*acc*dt*dt; + dV = dV + dR*acc*dt; + + // Compute velocity and position parts of matrices A and B (rely on non-updated delta rotation) + cv::Mat Wacc = (cv::Mat_(3,3) << 0, -acc.at(2), acc.at(1), + acc.at(2), 0, -acc.at(0), + -acc.at(1), acc.at(0), 0); + A.rowRange(3,6).colRange(0,3) = -dR*dt*Wacc; + A.rowRange(6,9).colRange(0,3) = -0.5f*dR*dt*dt*Wacc; + A.rowRange(6,9).colRange(3,6) = cv::Mat::eye(3,3,CV_32F)*dt; + B.rowRange(3,6).colRange(3,6) = dR*dt; + B.rowRange(6,9).colRange(3,6) = 0.5f*dR*dt*dt; + + // Update position and velocity jacobians wrt bias correction + JPa = JPa + JVa*dt -0.5f*dR*dt*dt; + JPg = JPg + JVg*dt -0.5f*dR*dt*dt*Wacc*JRg; + JVa = JVa - dR*dt; + JVg = JVg - dR*dt*Wacc*JRg; + + // Update delta rotation + IntegratedRotation dRi(angVel,b,dt); + dR = NormalizeRotation(dR*dRi.deltaR); + + // Compute rotation parts of matrices A and B + A.rowRange(0,3).colRange(0,3) = dRi.deltaR.t(); + B.rowRange(0,3).colRange(0,3) = dRi.rightJ*dt; + + // Update covariance + C.rowRange(0,9).colRange(0,9) = A*C.rowRange(0,9).colRange(0,9)*A.t() + B*Nga*B.t(); + C.rowRange(9,15).colRange(9,15) = C.rowRange(9,15).colRange(9,15) + NgaWalk; + + // Update rotation jacobian wrt bias correction + JRg = dRi.deltaR.t()*JRg - dRi.rightJ*dt; + + // Total integrated time + dT += dt; +} + +void Preintegrated::MergePrevious(Preintegrated* pPrev) +{ + if (pPrev==this) + return; + + std::unique_lock lock1(mMutex); + std::unique_lock lock2(pPrev->mMutex); + Bias bav; + bav.bwx = bu.bwx; + bav.bwy = bu.bwy; + bav.bwz = bu.bwz; + bav.bax = bu.bax; + bav.bay = bu.bay; + bav.baz = bu.baz; + + const std::vector aux1 = pPrev->mvMeasurements; + const std::vector aux2 = mvMeasurements; + + Initialize(bav); + for(size_t i=0;i lock(mMutex); + bu = bu_; + + db.at(0) = bu_.bwx-b.bwx; + db.at(1) = bu_.bwy-b.bwy; + db.at(2) = bu_.bwz-b.bwz; + db.at(3) = bu_.bax-b.bax; + db.at(4) = bu_.bay-b.bay; + db.at(5) = bu_.baz-b.baz; +} + +IMU::Bias Preintegrated::GetDeltaBias(const Bias &b_) +{ + std::unique_lock lock(mMutex); + return IMU::Bias(b_.bax-b.bax,b_.bay-b.bay,b_.baz-b.baz,b_.bwx-b.bwx,b_.bwy-b.bwy,b_.bwz-b.bwz); +} + +cv::Mat Preintegrated::GetDeltaRotation(const Bias &b_) +{ + std::unique_lock lock(mMutex); + cv::Mat dbg = (cv::Mat_(3,1) << b_.bwx-b.bwx,b_.bwy-b.bwy,b_.bwz-b.bwz); + return NormalizeRotation(dR*ExpSO3(JRg*dbg)); +} + +cv::Mat Preintegrated::GetDeltaVelocity(const Bias &b_) +{ + std::unique_lock lock(mMutex); + cv::Mat dbg = (cv::Mat_(3,1) << b_.bwx-b.bwx,b_.bwy-b.bwy,b_.bwz-b.bwz); + cv::Mat dba = (cv::Mat_(3,1) << b_.bax-b.bax,b_.bay-b.bay,b_.baz-b.baz); + return dV + JVg*dbg + JVa*dba; +} + +cv::Mat Preintegrated::GetDeltaPosition(const Bias &b_) +{ + std::unique_lock lock(mMutex); + cv::Mat dbg = (cv::Mat_(3,1) << b_.bwx-b.bwx,b_.bwy-b.bwy,b_.bwz-b.bwz); + cv::Mat dba = (cv::Mat_(3,1) << b_.bax-b.bax,b_.bay-b.bay,b_.baz-b.baz); + return dP + JPg*dbg + JPa*dba; +} + +cv::Mat Preintegrated::GetUpdatedDeltaRotation() +{ + std::unique_lock lock(mMutex); + return NormalizeRotation(dR*ExpSO3(JRg*db.rowRange(0,3))); +} + +cv::Mat Preintegrated::GetUpdatedDeltaVelocity() +{ + std::unique_lock lock(mMutex); + return dV + JVg*db.rowRange(0,3) + JVa*db.rowRange(3,6); +} + +cv::Mat Preintegrated::GetUpdatedDeltaPosition() +{ + std::unique_lock lock(mMutex); + return dP + JPg*db.rowRange(0,3) + JPa*db.rowRange(3,6); +} + +cv::Mat Preintegrated::GetOriginalDeltaRotation() +{ + std::unique_lock lock(mMutex); + return dR.clone(); +} + +cv::Mat Preintegrated::GetOriginalDeltaVelocity() +{ + std::unique_lock lock(mMutex); + return dV.clone(); +} + +cv::Mat Preintegrated::GetOriginalDeltaPosition() +{ + std::unique_lock lock(mMutex); + return dP.clone(); +} + +Bias Preintegrated::GetOriginalBias() +{ + std::unique_lock lock(mMutex); + return b; +} + +Bias Preintegrated::GetUpdatedBias() +{ + std::unique_lock lock(mMutex); + return bu; +} + +cv::Mat Preintegrated::GetDeltaBias() +{ + std::unique_lock lock(mMutex); + return db.clone(); +} + +Eigen::Matrix Preintegrated::GetInformationMatrix() +{ + std::unique_lock lock(mMutex); + if(Info.empty()) + { + Info = cv::Mat::zeros(15,15,CV_32F); + Info.rowRange(0,9).colRange(0,9)=C.rowRange(0,9).colRange(0,9).inv(cv::DECOMP_SVD); + for(int i=9;i<15;i++) + Info.at(i,i)=1.0f/C.at(i,i); + } + + Eigen::Matrix EI; + for(int i=0;i<15;i++) + for(int j=0;j<15;j++) + EI(i,j)=Info.at(i,j); + return EI; +} + +void Bias::CopyFrom(Bias &b) +{ + bax = b.bax; + bay = b.bay; + baz = b.baz; + bwx = b.bwx; + bwy = b.bwy; + bwz = b.bwz; +} + +std::ostream& operator<< (std::ostream &out, const Bias &b) +{ + if(b.bwx>0) + out << " "; + out << b.bwx << ","; + if(b.bwy>0) + out << " "; + out << b.bwy << ","; + if(b.bwz>0) + out << " "; + out << b.bwz << ","; + if(b.bax>0) + out << " "; + out << b.bax << ","; + if(b.bay>0) + out << " "; + out << b.bay << ","; + if(b.baz>0) + out << " "; + out << b.baz; + + return out; +} + +void Calib::Set(const cv::Mat &Tbc_, const float &ng, const float &na, const float &ngw, const float &naw) +{ + Tbc = Tbc_.clone(); + Tcb = cv::Mat::eye(4,4,CV_32F); + Tcb.rowRange(0,3).colRange(0,3) = Tbc.rowRange(0,3).colRange(0,3).t(); + Tcb.rowRange(0,3).col(3) = -Tbc.rowRange(0,3).colRange(0,3).t()*Tbc.rowRange(0,3).col(3); + Cov = cv::Mat::eye(6,6,CV_32F); + const float ng2 = ng*ng; + const float na2 = na*na; + Cov.at(0,0) = ng2; + Cov.at(1,1) = ng2; + Cov.at(2,2) = ng2; + Cov.at(3,3) = na2; + Cov.at(4,4) = na2; + Cov.at(5,5) = na2; + CovWalk = cv::Mat::eye(6,6,CV_32F); + const float ngw2 = ngw*ngw; + const float naw2 = naw*naw; + CovWalk.at(0,0) = ngw2; + CovWalk.at(1,1) = ngw2; + CovWalk.at(2,2) = ngw2; + CovWalk.at(3,3) = naw2; + CovWalk.at(4,4) = naw2; + CovWalk.at(5,5) = naw2; +} + +Calib::Calib(const Calib &calib) +{ + Tbc = calib.Tbc.clone(); + Tcb = calib.Tcb.clone(); + Cov = calib.Cov.clone(); + CovWalk = calib.CovWalk.clone(); +} + +} //namespace IMU + +} //namespace ORB_SLAM2 diff --git a/third_party/ORB_SLAM3/src/Initializer.cc b/third_party/ORB_SLAM3/src/Initializer.cc new file mode 100644 index 0000000..f5e4536 --- /dev/null +++ b/third_party/ORB_SLAM3/src/Initializer.cc @@ -0,0 +1,928 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + +#include "Initializer.h" + +#include "Thirdparty/DBoW2/DUtils/Random.h" + +#include "Optimizer.h" +#include "ORBmatcher.h" + +#include +#include + +namespace ORB_SLAM3 +{ + +Initializer::Initializer(const Frame &ReferenceFrame, float sigma, int iterations) +{ + mpCamera = ReferenceFrame.mpCamera; + mK = ReferenceFrame.mK.clone(); + + mvKeys1 = ReferenceFrame.mvKeysUn; + + mSigma = sigma; + mSigma2 = sigma*sigma; + mMaxIterations = iterations; +} + +bool Initializer::Initialize(const Frame &CurrentFrame, const vector &vMatches12, cv::Mat &R21, cv::Mat &t21, + vector &vP3D, vector &vbTriangulated) +{ + + mvKeys2 = CurrentFrame.mvKeysUn; + + mvMatches12.clear(); + mvMatches12.reserve(mvKeys2.size()); + mvbMatched1.resize(mvKeys1.size()); + for(size_t i=0, iend=vMatches12.size();i=0) + { + mvMatches12.push_back(make_pair(i,vMatches12[i])); + mvbMatched1[i]=true; + } + else + mvbMatched1[i]=false; + } + + + + const int N = mvMatches12.size(); + + vector vAllIndices; + vAllIndices.reserve(N); + vector vAvailableIndices; + + for(int i=0; i >(mMaxIterations,vector(8,0)); + + DUtils::Random::SeedRandOnce(0); + + for(int it=0; it vbMatchesInliersH, vbMatchesInliersF; + float SH, SF; + cv::Mat H, F; + + thread threadH(&Initializer::FindHomography,this,ref(vbMatchesInliersH), ref(SH), ref(H)); + thread threadF(&Initializer::FindFundamental,this,ref(vbMatchesInliersF), ref(SF), ref(F)); + + //cout << "5" << endl; + + // Wait until both threads have finished + threadH.join(); + threadF.join(); + + // Compute ratio of scores + float RH = SH/(SH+SF); + + //cout << "6" << endl; + + float minParallax = 1.0; // 1.0 originally + + cv::Mat K = static_cast(mpCamera)->toK(); + // Try to reconstruct from homography or fundamental depending on the ratio (0.40-0.45) + if(RH>0.40) // if(RH>0.40) + { + //cout << "Initialization from Homography" << endl; + return ReconstructH(vbMatchesInliersH,H, K,R21,t21,vP3D,vbTriangulated,minParallax,50); + } + else //if(pF_HF>0.6) + { + //cout << "Initialization from Fundamental" << endl; + return ReconstructF(vbMatchesInliersF,F,K,R21,t21,vP3D,vbTriangulated,minParallax,50); + } + + return false; +} + + +void Initializer::FindHomography(vector &vbMatchesInliers, float &score, cv::Mat &H21) +{ + // Number of putative matches + const int N = mvMatches12.size(); + + // Normalize coordinates + vector vPn1, vPn2; + cv::Mat T1, T2; + Normalize(mvKeys1,vPn1, T1); + Normalize(mvKeys2,vPn2, T2); + cv::Mat T2inv = T2.inv(); + + // Best Results variables + score = 0.0; + vbMatchesInliers = vector(N,false); + + // Iteration variables + vector vPn1i(8); + vector vPn2i(8); + cv::Mat H21i, H12i; + vector vbCurrentInliers(N,false); + float currentScore; + + // Perform all RANSAC iterations and save the solution with highest score + for(int it=0; itscore) + { + H21 = H21i.clone(); + vbMatchesInliers = vbCurrentInliers; + score = currentScore; + } + } +} + + +void Initializer::FindFundamental(vector &vbMatchesInliers, float &score, cv::Mat &F21) +{ + // Number of putative matches + const int N = vbMatchesInliers.size(); + + // Normalize coordinates + vector vPn1, vPn2; + cv::Mat T1, T2; + Normalize(mvKeys1,vPn1, T1); + Normalize(mvKeys2,vPn2, T2); + cv::Mat T2t = T2.t(); + + // Best Results variables + score = 0.0; + vbMatchesInliers = vector(N,false); + + // Iteration variables + vector vPn1i(8); + vector vPn2i(8); + cv::Mat F21i; + vector vbCurrentInliers(N,false); + float currentScore; + + // Perform all RANSAC iterations and save the solution with highest score + for(int it=0; itscore) + { + F21 = F21i.clone(); + vbMatchesInliers = vbCurrentInliers; + score = currentScore; + } + } +} + + +cv::Mat Initializer::ComputeH21(const vector &vP1, const vector &vP2) +{ + const int N = vP1.size(); + + cv::Mat A(2*N,9,CV_32F); + + for(int i=0; i(2*i,0) = 0.0; + A.at(2*i,1) = 0.0; + A.at(2*i,2) = 0.0; + A.at(2*i,3) = -u1; + A.at(2*i,4) = -v1; + A.at(2*i,5) = -1; + A.at(2*i,6) = v2*u1; + A.at(2*i,7) = v2*v1; + A.at(2*i,8) = v2; + + A.at(2*i+1,0) = u1; + A.at(2*i+1,1) = v1; + A.at(2*i+1,2) = 1; + A.at(2*i+1,3) = 0.0; + A.at(2*i+1,4) = 0.0; + A.at(2*i+1,5) = 0.0; + A.at(2*i+1,6) = -u2*u1; + A.at(2*i+1,7) = -u2*v1; + A.at(2*i+1,8) = -u2; + + } + + cv::Mat u,w,vt; + + cv::SVDecomp(A,w,u,vt,cv::SVD::MODIFY_A | cv::SVD::FULL_UV); + + return vt.row(8).reshape(0, 3); +} + +cv::Mat Initializer::ComputeF21(const vector &vP1,const vector &vP2) +{ + const int N = vP1.size(); + + cv::Mat A(N,9,CV_32F); + + for(int i=0; i(i,0) = u2*u1; + A.at(i,1) = u2*v1; + A.at(i,2) = u2; + A.at(i,3) = v2*u1; + A.at(i,4) = v2*v1; + A.at(i,5) = v2; + A.at(i,6) = u1; + A.at(i,7) = v1; + A.at(i,8) = 1; + } + + cv::Mat u,w,vt; + + cv::SVDecomp(A,w,u,vt,cv::SVD::MODIFY_A | cv::SVD::FULL_UV); + + cv::Mat Fpre = vt.row(8).reshape(0, 3); + + cv::SVDecomp(Fpre,w,u,vt,cv::SVD::MODIFY_A | cv::SVD::FULL_UV); + + w.at(2)=0; + + return u*cv::Mat::diag(w)*vt; +} + +float Initializer::CheckHomography(const cv::Mat &H21, const cv::Mat &H12, vector &vbMatchesInliers, float sigma) +{ + const int N = mvMatches12.size(); + + const float h11 = H21.at(0,0); + const float h12 = H21.at(0,1); + const float h13 = H21.at(0,2); + const float h21 = H21.at(1,0); + const float h22 = H21.at(1,1); + const float h23 = H21.at(1,2); + const float h31 = H21.at(2,0); + const float h32 = H21.at(2,1); + const float h33 = H21.at(2,2); + + const float h11inv = H12.at(0,0); + const float h12inv = H12.at(0,1); + const float h13inv = H12.at(0,2); + const float h21inv = H12.at(1,0); + const float h22inv = H12.at(1,1); + const float h23inv = H12.at(1,2); + const float h31inv = H12.at(2,0); + const float h32inv = H12.at(2,1); + const float h33inv = H12.at(2,2); + + vbMatchesInliers.resize(N); + + float score = 0; + + const float th = 5.991; + + const float invSigmaSquare = 1.0/(sigma*sigma); + + for(int i=0; ith) + bIn = false; + else + score += th - chiSquare1; + + // Reprojection error in second image + // x1in2 = H21*x1 + + const float w1in2inv = 1.0/(h31*u1+h32*v1+h33); + const float u1in2 = (h11*u1+h12*v1+h13)*w1in2inv; + const float v1in2 = (h21*u1+h22*v1+h23)*w1in2inv; + + const float squareDist2 = (u2-u1in2)*(u2-u1in2)+(v2-v1in2)*(v2-v1in2); + + const float chiSquare2 = squareDist2*invSigmaSquare; + + if(chiSquare2>th) + bIn = false; + else + score += th - chiSquare2; + + if(bIn) + vbMatchesInliers[i]=true; + else + vbMatchesInliers[i]=false; + } + + return score; +} + +float Initializer::CheckFundamental(const cv::Mat &F21, vector &vbMatchesInliers, float sigma) +{ + const int N = mvMatches12.size(); + + const float f11 = F21.at(0,0); + const float f12 = F21.at(0,1); + const float f13 = F21.at(0,2); + const float f21 = F21.at(1,0); + const float f22 = F21.at(1,1); + const float f23 = F21.at(1,2); + const float f31 = F21.at(2,0); + const float f32 = F21.at(2,1); + const float f33 = F21.at(2,2); + + vbMatchesInliers.resize(N); + + float score = 0; + + const float th = 3.841; + const float thScore = 5.991; + + const float invSigmaSquare = 1.0/(sigma*sigma); + + for(int i=0; ith) + bIn = false; + else + score += thScore - chiSquare1; + + // Reprojection error in second image + // l1 =x2tF21=(a1,b1,c1) + + const float a1 = f11*u2+f21*v2+f31; + const float b1 = f12*u2+f22*v2+f32; + const float c1 = f13*u2+f23*v2+f33; + + const float num1 = a1*u1+b1*v1+c1; + + const float squareDist2 = num1*num1/(a1*a1+b1*b1); + + const float chiSquare2 = squareDist2*invSigmaSquare; + + if(chiSquare2>th) + bIn = false; + else + score += thScore - chiSquare2; + + if(bIn) + vbMatchesInliers[i]=true; + else + vbMatchesInliers[i]=false; + } + + return score; +} + +bool Initializer::ReconstructF(vector &vbMatchesInliers, cv::Mat &F21, cv::Mat &K, + cv::Mat &R21, cv::Mat &t21, vector &vP3D, vector &vbTriangulated, float minParallax, int minTriangulated) +{ + int N=0; + for(size_t i=0, iend = vbMatchesInliers.size() ; i vP3D1, vP3D2, vP3D3, vP3D4; + vector vbTriangulated1,vbTriangulated2,vbTriangulated3, vbTriangulated4; + float parallax1,parallax2, parallax3, parallax4; + + int nGood1 = CheckRT(R1,t1,mvKeys1,mvKeys2,mvMatches12,vbMatchesInliers,K, vP3D1, 4.0*mSigma2, vbTriangulated1, parallax1); + int nGood2 = CheckRT(R2,t1,mvKeys1,mvKeys2,mvMatches12,vbMatchesInliers,K, vP3D2, 4.0*mSigma2, vbTriangulated2, parallax2); + int nGood3 = CheckRT(R1,t2,mvKeys1,mvKeys2,mvMatches12,vbMatchesInliers,K, vP3D3, 4.0*mSigma2, vbTriangulated3, parallax3); + int nGood4 = CheckRT(R2,t2,mvKeys1,mvKeys2,mvMatches12,vbMatchesInliers,K, vP3D4, 4.0*mSigma2, vbTriangulated4, parallax4); + + int maxGood = max(nGood1,max(nGood2,max(nGood3,nGood4))); + + R21 = cv::Mat(); + t21 = cv::Mat(); + + int nMinGood = max(static_cast(0.9*N),minTriangulated); + + int nsimilar = 0; + if(nGood1>0.7*maxGood) + nsimilar++; + if(nGood2>0.7*maxGood) + nsimilar++; + if(nGood3>0.7*maxGood) + nsimilar++; + if(nGood4>0.7*maxGood) + nsimilar++; + + // If there is not a clear winner or not enough triangulated points reject initialization + if(maxGood1) + { + return false; + } + + // If best reconstruction has enough parallax initialize + if(maxGood==nGood1) + { + if(parallax1>minParallax) + { + vP3D = vP3D1; + vbTriangulated = vbTriangulated1; + + R1.copyTo(R21); + t1.copyTo(t21); + return true; + } + }else if(maxGood==nGood2) + { + if(parallax2>minParallax) + { + vP3D = vP3D2; + vbTriangulated = vbTriangulated2; + + R2.copyTo(R21); + t1.copyTo(t21); + return true; + } + }else if(maxGood==nGood3) + { + if(parallax3>minParallax) + { + vP3D = vP3D3; + vbTriangulated = vbTriangulated3; + + R1.copyTo(R21); + t2.copyTo(t21); + return true; + } + }else if(maxGood==nGood4) + { + if(parallax4>minParallax) + { + vP3D = vP3D4; + vbTriangulated = vbTriangulated4; + + R2.copyTo(R21); + t2.copyTo(t21); + return true; + } + } + + return false; +} + +bool Initializer::ReconstructH(vector &vbMatchesInliers, cv::Mat &H21, cv::Mat &K, + cv::Mat &R21, cv::Mat &t21, vector &vP3D, vector &vbTriangulated, float minParallax, int minTriangulated) +{ + int N=0; + for(size_t i=0, iend = vbMatchesInliers.size() ; i(0); + float d2 = w.at(1); + float d3 = w.at(2); + + if(d1/d2<1.00001 || d2/d3<1.00001) + { + return false; + } + + vector vR, vt, vn; + vR.reserve(8); + vt.reserve(8); + vn.reserve(8); + + //n'=[x1 0 x3] 4 posibilities e1=e3=1, e1=1 e3=-1, e1=-1 e3=1, e1=e3=-1 + float aux1 = sqrt((d1*d1-d2*d2)/(d1*d1-d3*d3)); + float aux3 = sqrt((d2*d2-d3*d3)/(d1*d1-d3*d3)); + float x1[] = {aux1,aux1,-aux1,-aux1}; + float x3[] = {aux3,-aux3,aux3,-aux3}; + + //case d'=d2 + float aux_stheta = sqrt((d1*d1-d2*d2)*(d2*d2-d3*d3))/((d1+d3)*d2); + + float ctheta = (d2*d2+d1*d3)/((d1+d3)*d2); + float stheta[] = {aux_stheta, -aux_stheta, -aux_stheta, aux_stheta}; + + for(int i=0; i<4; i++) + { + cv::Mat Rp=cv::Mat::eye(3,3,CV_32F); + Rp.at(0,0)=ctheta; + Rp.at(0,2)=-stheta[i]; + Rp.at(2,0)=stheta[i]; + Rp.at(2,2)=ctheta; + + cv::Mat R = s*U*Rp*Vt; + vR.push_back(R); + + cv::Mat tp(3,1,CV_32F); + tp.at(0)=x1[i]; + tp.at(1)=0; + tp.at(2)=-x3[i]; + tp*=d1-d3; + + cv::Mat t = U*tp; + vt.push_back(t/cv::norm(t)); + + cv::Mat np(3,1,CV_32F); + np.at(0)=x1[i]; + np.at(1)=0; + np.at(2)=x3[i]; + + cv::Mat n = V*np; + if(n.at(2)<0) + n=-n; + vn.push_back(n); + } + + //case d'=-d2 + float aux_sphi = sqrt((d1*d1-d2*d2)*(d2*d2-d3*d3))/((d1-d3)*d2); + + float cphi = (d1*d3-d2*d2)/((d1-d3)*d2); + float sphi[] = {aux_sphi, -aux_sphi, -aux_sphi, aux_sphi}; + + for(int i=0; i<4; i++) + { + cv::Mat Rp=cv::Mat::eye(3,3,CV_32F); + Rp.at(0,0)=cphi; + Rp.at(0,2)=sphi[i]; + Rp.at(1,1)=-1; + Rp.at(2,0)=sphi[i]; + Rp.at(2,2)=-cphi; + + cv::Mat R = s*U*Rp*Vt; + vR.push_back(R); + + cv::Mat tp(3,1,CV_32F); + tp.at(0)=x1[i]; + tp.at(1)=0; + tp.at(2)=x3[i]; + tp*=d1+d3; + + cv::Mat t = U*tp; + vt.push_back(t/cv::norm(t)); + + cv::Mat np(3,1,CV_32F); + np.at(0)=x1[i]; + np.at(1)=0; + np.at(2)=x3[i]; + + cv::Mat n = V*np; + if(n.at(2)<0) + n=-n; + vn.push_back(n); + } + + + int bestGood = 0; + int secondBestGood = 0; + int bestSolutionIdx = -1; + float bestParallax = -1; + vector bestP3D; + vector bestTriangulated; + + // Instead of applying the visibility constraints proposed in the Faugeras' paper (which could fail for points seen with low parallax) + // We reconstruct all hypotheses and check in terms of triangulated points and parallax + for(size_t i=0; i<8; i++) + { + float parallaxi; + vector vP3Di; + vector vbTriangulatedi; + int nGood = CheckRT(vR[i],vt[i],mvKeys1,mvKeys2,mvMatches12,vbMatchesInliers,K,vP3Di, 4.0*mSigma2, vbTriangulatedi, parallaxi); + + if(nGood>bestGood) + { + secondBestGood = bestGood; + bestGood = nGood; + bestSolutionIdx = i; + bestParallax = parallaxi; + bestP3D = vP3Di; + bestTriangulated = vbTriangulatedi; + } + else if(nGood>secondBestGood) + { + secondBestGood = nGood; + } + } + + + if(secondBestGood<0.75*bestGood && bestParallax>=minParallax && bestGood>minTriangulated && bestGood>0.9*N) + { + vR[bestSolutionIdx].copyTo(R21); + vt[bestSolutionIdx].copyTo(t21); + vP3D = bestP3D; + vbTriangulated = bestTriangulated; + + return true; + } + + return false; +} + +void Initializer::Triangulate(const cv::KeyPoint &kp1, const cv::KeyPoint &kp2, const cv::Mat &P1, const cv::Mat &P2, cv::Mat &x3D) +{ + cv::Mat A(4,4,CV_32F); + + A.row(0) = kp1.pt.x*P1.row(2)-P1.row(0); + A.row(1) = kp1.pt.y*P1.row(2)-P1.row(1); + A.row(2) = kp2.pt.x*P2.row(2)-P2.row(0); + A.row(3) = kp2.pt.y*P2.row(2)-P2.row(1); + + cv::Mat u,w,vt; + cv::SVD::compute(A,w,u,vt,cv::SVD::MODIFY_A| cv::SVD::FULL_UV); + x3D = vt.row(3).t(); + x3D = x3D.rowRange(0,3)/x3D.at(3); +} + +void Initializer::Normalize(const vector &vKeys, vector &vNormalizedPoints, cv::Mat &T) +{ + float meanX = 0; + float meanY = 0; + const int N = vKeys.size(); + + vNormalizedPoints.resize(N); + + for(int i=0; i(0,0) = sX; + T.at(1,1) = sY; + T.at(0,2) = -meanX*sX; + T.at(1,2) = -meanY*sY; +} + + +int Initializer::CheckRT(const cv::Mat &R, const cv::Mat &t, const vector &vKeys1, const vector &vKeys2, + const vector &vMatches12, vector &vbMatchesInliers, + const cv::Mat &K, vector &vP3D, float th2, vector &vbGood, float ¶llax) +{ + vbGood = vector(vKeys1.size(),false); + vP3D.resize(vKeys1.size()); + + vector vCosParallax; + vCosParallax.reserve(vKeys1.size()); + + // Camera 1 Projection Matrix K[I|0] + cv::Mat P1(3,4,CV_32F,cv::Scalar(0)); + K.copyTo(P1.rowRange(0,3).colRange(0,3)); + + cv::Mat O1 = cv::Mat::zeros(3,1,CV_32F); + + // Camera 2 Projection Matrix K[R|t] + cv::Mat P2(3,4,CV_32F); + R.copyTo(P2.rowRange(0,3).colRange(0,3)); + t.copyTo(P2.rowRange(0,3).col(3)); + P2 = K*P2; + + cv::Mat O2 = -R.t()*t; + + int nGood=0; + + for(size_t i=0, iend=vMatches12.size();i(0)) || !isfinite(p3dC1.at(1)) || !isfinite(p3dC1.at(2))) + { + vbGood[vMatches12[i].first]=false; + continue; + } + + // Check parallax + cv::Mat normal1 = p3dC1 - O1; + float dist1 = cv::norm(normal1); + + cv::Mat normal2 = p3dC1 - O2; + float dist2 = cv::norm(normal2); + + float cosParallax = normal1.dot(normal2)/(dist1*dist2); + + // Check depth in front of first camera (only if enough parallax, as "infinite" points can easily go to negative depth) + if(p3dC1.at(2)<=0 && cosParallax<0.99998) + continue; + + // Check depth in front of second camera (only if enough parallax, as "infinite" points can easily go to negative depth) + cv::Mat p3dC2 = R*p3dC1+t; + + if(p3dC2.at(2)<=0 && cosParallax<0.99998) + continue; + + // Check reprojection error in first image + cv::Point2f uv1 = mpCamera->project(p3dC1); + float squareError1 = (uv1.x-kp1.pt.x)*(uv1.x-kp1.pt.x)+(uv1.y-kp1.pt.y)*(uv1.y-kp1.pt.y); + + if(squareError1>th2) + continue; + + // Check reprojection error in second image + cv::Point2f uv2 = mpCamera->project(p3dC2); + float squareError2 = (uv2.x-kp2.pt.x)*(uv2.x-kp2.pt.x)+(uv2.y-kp2.pt.y)*(uv2.y-kp2.pt.y); + + if(squareError2>th2) + continue; + + vCosParallax.push_back(cosParallax); + vP3D[vMatches12[i].first] = cv::Point3f(p3dC1.at(0),p3dC1.at(1),p3dC1.at(2)); + nGood++; + + if(cosParallax<0.99998) + vbGood[vMatches12[i].first]=true; + } + + if(nGood>0) + { + sort(vCosParallax.begin(),vCosParallax.end()); + + size_t idx = min(50,int(vCosParallax.size()-1)); + parallax = acos(vCosParallax[idx])*180/CV_PI; + } + else + parallax=0; + + return nGood; +} + +void Initializer::DecomposeE(const cv::Mat &E, cv::Mat &R1, cv::Mat &R2, cv::Mat &t) +{ + cv::Mat u,w,vt; + cv::SVD::compute(E,w,u,vt); + + u.col(2).copyTo(t); + t=t/cv::norm(t); + + cv::Mat W(3,3,CV_32F,cv::Scalar(0)); + W.at(0,1)=-1; + W.at(1,0)=1; + W.at(2,2)=1; + + R1 = u*W*vt; + if(cv::determinant(R1)<0) + R1=-R1; + + R2 = u*W.t()*vt; + if(cv::determinant(R2)<0) + R2=-R2; +} + +} //namespace ORB_SLAM diff --git a/third_party/ORB_SLAM3/src/KeyFrame.cc b/third_party/ORB_SLAM3/src/KeyFrame.cc new file mode 100644 index 0000000..40c5bdd --- /dev/null +++ b/third_party/ORB_SLAM3/src/KeyFrame.cc @@ -0,0 +1,1274 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + +#include "KeyFrame.h" +#include "Converter.h" +#include "ORBmatcher.h" +#include "ImuTypes.h" +#include + +namespace ORB_SLAM3 +{ + +long unsigned int KeyFrame::nNextId=0; + +KeyFrame::KeyFrame(): + mnFrameId(0), mTimeStamp(0), mnGridCols(FRAME_GRID_COLS), mnGridRows(FRAME_GRID_ROWS), + mfGridElementWidthInv(0), mfGridElementHeightInv(0), + mnTrackReferenceForFrame(0), mnFuseTargetForKF(0), mnBALocalForKF(0), mnBAFixedForKF(0), mnBALocalForMerge(0), + mnLoopQuery(0), mnLoopWords(0), mnRelocQuery(0), mnRelocWords(0), mnMergeQuery(0), mnMergeWords(0), mnBAGlobalForKF(0), + fx(0), fy(0), cx(0), cy(0), invfx(0), invfy(0), mnPlaceRecognitionQuery(0), mnPlaceRecognitionWords(0), mPlaceRecognitionScore(0), + mbf(0), mb(0), mThDepth(0), N(0), mvKeys(static_cast >(NULL)), mvKeysUn(static_cast >(NULL)), + mvuRight(static_cast >(NULL)), mvDepth(static_cast >(NULL)), /*mDescriptors(NULL),*/ + /*mBowVec(NULL), mFeatVec(NULL),*/ mnScaleLevels(0), mfScaleFactor(0), + mfLogScaleFactor(0), mvScaleFactors(0), mvLevelSigma2(0), + mvInvLevelSigma2(0), mnMinX(0), mnMinY(0), mnMaxX(0), + mnMaxY(0), /*mK(NULL),*/ mPrevKF(static_cast(NULL)), mNextKF(static_cast(NULL)), mbFirstConnection(true), mpParent(NULL), mbNotErase(false), + mbToBeErased(false), mbBad(false), mHalfBaseline(0), mbCurrentPlaceRecognition(false), mbHasHessian(false), mnMergeCorrectedForKF(0), + NLeft(0),NRight(0), mnNumberOfOpt(0) +{ + +} + +KeyFrame::KeyFrame(Frame &F, Map *pMap, KeyFrameDatabase *pKFDB): + bImu(pMap->isImuInitialized()), mnFrameId(F.mnId), mTimeStamp(F.mTimeStamp), mnGridCols(FRAME_GRID_COLS), mnGridRows(FRAME_GRID_ROWS), + mfGridElementWidthInv(F.mfGridElementWidthInv), mfGridElementHeightInv(F.mfGridElementHeightInv), + mnTrackReferenceForFrame(0), mnFuseTargetForKF(0), mnBALocalForKF(0), mnBAFixedForKF(0), mnBALocalForMerge(0), + mnLoopQuery(0), mnLoopWords(0), mnRelocQuery(0), mnRelocWords(0), mnBAGlobalForKF(0), mnPlaceRecognitionQuery(0), mnPlaceRecognitionWords(0), mPlaceRecognitionScore(0), + fx(F.fx), fy(F.fy), cx(F.cx), cy(F.cy), invfx(F.invfx), invfy(F.invfy), + mbf(F.mbf), mb(F.mb), mThDepth(F.mThDepth), N(F.N), mvKeys(F.mvKeys), mvKeysUn(F.mvKeysUn), + mvuRight(F.mvuRight), mvDepth(F.mvDepth), mDescriptors(F.mDescriptors.clone()), + mBowVec(F.mBowVec), mFeatVec(F.mFeatVec), mnScaleLevels(F.mnScaleLevels), mfScaleFactor(F.mfScaleFactor), + mfLogScaleFactor(F.mfLogScaleFactor), mvScaleFactors(F.mvScaleFactors), mvLevelSigma2(F.mvLevelSigma2), + mvInvLevelSigma2(F.mvInvLevelSigma2), mnMinX(F.mnMinX), mnMinY(F.mnMinY), mnMaxX(F.mnMaxX), + mnMaxY(F.mnMaxY), mK(F.mK), mPrevKF(NULL), mNextKF(NULL), mpImuPreintegrated(F.mpImuPreintegrated), + mImuCalib(F.mImuCalib), mvpMapPoints(F.mvpMapPoints), mpKeyFrameDB(pKFDB), + mpORBvocabulary(F.mpORBvocabulary), mbFirstConnection(true), mpParent(NULL), mDistCoef(F.mDistCoef), mbNotErase(false), mnDataset(F.mnDataset), + mbToBeErased(false), mbBad(false), mHalfBaseline(F.mb/2), mpMap(pMap), mbCurrentPlaceRecognition(false), mNameFile(F.mNameFile), mbHasHessian(false), mnMergeCorrectedForKF(0), + mpCamera(F.mpCamera), mpCamera2(F.mpCamera2), + mvLeftToRightMatch(F.mvLeftToRightMatch),mvRightToLeftMatch(F.mvRightToLeftMatch),mTlr(F.mTlr.clone()), + mvKeysRight(F.mvKeysRight), NLeft(F.Nleft), NRight(F.Nright), mTrl(F.mTrl), mnNumberOfOpt(0) +{ + + imgLeft = F.imgLeft.clone(); + imgRight = F.imgRight.clone(); + + mnId=nNextId++; + + mGrid.resize(mnGridCols); + if(F.Nleft != -1) mGridRight.resize(mnGridCols); + for(int i=0; iGetId(); +} + +void KeyFrame::ComputeBoW() +{ + if(mBowVec.empty() || mFeatVec.empty()) + { + vector vCurrentDesc = Converter::toDescriptorVector(mDescriptors); + // Feature vector associate features with nodes in the 4th level (from leaves up) + // We assume the vocabulary tree has 6 levels, change the 4 otherwise + mpORBvocabulary->transform(vCurrentDesc,mBowVec,mFeatVec,4); + } +} + +void KeyFrame::SetPose(const cv::Mat &Tcw_) +{ + unique_lock lock(mMutexPose); + Tcw_.copyTo(Tcw); + cv::Mat Rcw = Tcw.rowRange(0,3).colRange(0,3); + cv::Mat tcw = Tcw.rowRange(0,3).col(3); + cv::Mat Rwc = Rcw.t(); + Ow = -Rwc*tcw; + if (!mImuCalib.Tcb.empty()) + Owb = Rwc*mImuCalib.Tcb.rowRange(0,3).col(3)+Ow; + + + Twc = cv::Mat::eye(4,4,Tcw.type()); + Rwc.copyTo(Twc.rowRange(0,3).colRange(0,3)); + Ow.copyTo(Twc.rowRange(0,3).col(3)); + cv::Mat center = (cv::Mat_(4,1) << mHalfBaseline, 0 , 0, 1); + Cw = Twc*center; +} + +void KeyFrame::SetVelocity(const cv::Mat &Vw_) +{ + unique_lock lock(mMutexPose); + Vw_.copyTo(Vw); +} + + +cv::Mat KeyFrame::GetPose() +{ + unique_lock lock(mMutexPose); + return Tcw.clone(); +} + +cv::Mat KeyFrame::GetPoseInverse() +{ + unique_lock lock(mMutexPose); + return Twc.clone(); +} + +cv::Mat KeyFrame::GetCameraCenter() +{ + unique_lock lock(mMutexPose); + return Ow.clone(); +} + +cv::Mat KeyFrame::GetStereoCenter() +{ + unique_lock lock(mMutexPose); + return Cw.clone(); +} + +cv::Mat KeyFrame::GetImuPosition() +{ + unique_lock lock(mMutexPose); + return Owb.clone(); +} + +cv::Mat KeyFrame::GetImuRotation() +{ + unique_lock lock(mMutexPose); + return Twc.rowRange(0,3).colRange(0,3)*mImuCalib.Tcb.rowRange(0,3).colRange(0,3); +} + +cv::Mat KeyFrame::GetImuPose() +{ + unique_lock lock(mMutexPose); + return Twc*mImuCalib.Tcb; +} + +cv::Mat KeyFrame::GetRotation() +{ + unique_lock lock(mMutexPose); + return Tcw.rowRange(0,3).colRange(0,3).clone(); +} + +cv::Mat KeyFrame::GetTranslation() +{ + unique_lock lock(mMutexPose); + return Tcw.rowRange(0,3).col(3).clone(); +} + +cv::Mat KeyFrame::GetVelocity() +{ + unique_lock lock(mMutexPose); + return Vw.clone(); +} + +void KeyFrame::AddConnection(KeyFrame *pKF, const int &weight) +{ + { + unique_lock lock(mMutexConnections); + if(!mConnectedKeyFrameWeights.count(pKF)) + mConnectedKeyFrameWeights[pKF]=weight; + else if(mConnectedKeyFrameWeights[pKF]!=weight) + mConnectedKeyFrameWeights[pKF]=weight; + else + return; + } + + UpdateBestCovisibles(); +} + +void KeyFrame::UpdateBestCovisibles() +{ + unique_lock lock(mMutexConnections); + vector > vPairs; + vPairs.reserve(mConnectedKeyFrameWeights.size()); + for(map::iterator mit=mConnectedKeyFrameWeights.begin(), mend=mConnectedKeyFrameWeights.end(); mit!=mend; mit++) + vPairs.push_back(make_pair(mit->second,mit->first)); + + sort(vPairs.begin(),vPairs.end()); + list lKFs; + list lWs; + for(size_t i=0, iend=vPairs.size(); iisBad()) + { + lKFs.push_front(vPairs[i].second); + lWs.push_front(vPairs[i].first); + } + } + + mvpOrderedConnectedKeyFrames = vector(lKFs.begin(),lKFs.end()); + mvOrderedWeights = vector(lWs.begin(), lWs.end()); +} + +set KeyFrame::GetConnectedKeyFrames() +{ + unique_lock lock(mMutexConnections); + set s; + for(map::iterator mit=mConnectedKeyFrameWeights.begin();mit!=mConnectedKeyFrameWeights.end();mit++) + s.insert(mit->first); + return s; +} + +vector KeyFrame::GetVectorCovisibleKeyFrames() +{ + unique_lock lock(mMutexConnections); + return mvpOrderedConnectedKeyFrames; +} + +vector KeyFrame::GetBestCovisibilityKeyFrames(const int &N) +{ + unique_lock lock(mMutexConnections); + if((int)mvpOrderedConnectedKeyFrames.size()(mvpOrderedConnectedKeyFrames.begin(),mvpOrderedConnectedKeyFrames.begin()+N); + +} + +vector KeyFrame::GetCovisiblesByWeight(const int &w) +{ + unique_lock lock(mMutexConnections); + + if(mvpOrderedConnectedKeyFrames.empty()) + { + return vector(); + } + + vector::iterator it = upper_bound(mvOrderedWeights.begin(),mvOrderedWeights.end(),w,KeyFrame::weightComp); + + if(it==mvOrderedWeights.end() && mvOrderedWeights.back() < w) + { + return vector(); + } + else + { + int n = it-mvOrderedWeights.begin(); + //cout << "n = " << n << endl; + return vector(mvpOrderedConnectedKeyFrames.begin(), mvpOrderedConnectedKeyFrames.begin()+n); + } +} + +int KeyFrame::GetWeight(KeyFrame *pKF) +{ + unique_lock lock(mMutexConnections); + if(mConnectedKeyFrameWeights.count(pKF)) + return mConnectedKeyFrameWeights[pKF]; + else + return 0; +} + +int KeyFrame::GetNumberMPs() +{ + unique_lock lock(mMutexFeatures); + int numberMPs = 0; + for(size_t i=0, iend=mvpMapPoints.size(); i lock(mMutexFeatures); + mvpMapPoints[idx]=pMP; +} + +void KeyFrame::EraseMapPointMatch(const int &idx) +{ + unique_lock lock(mMutexFeatures); + mvpMapPoints[idx]=static_cast(NULL); +} + +void KeyFrame::EraseMapPointMatch(MapPoint* pMP) +{ + tuple indexes = pMP->GetIndexInKeyFrame(this); + size_t leftIndex = get<0>(indexes), rightIndex = get<1>(indexes); + if(leftIndex != -1) + mvpMapPoints[leftIndex]=static_cast(NULL); + if(rightIndex != -1) + mvpMapPoints[rightIndex]=static_cast(NULL); +} + + +void KeyFrame::ReplaceMapPointMatch(const int &idx, MapPoint* pMP) +{ + mvpMapPoints[idx]=pMP; +} + +set KeyFrame::GetMapPoints() +{ + unique_lock lock(mMutexFeatures); + set s; + for(size_t i=0, iend=mvpMapPoints.size(); iisBad()) + s.insert(pMP); + } + return s; +} + +int KeyFrame::TrackedMapPoints(const int &minObs) +{ + unique_lock lock(mMutexFeatures); + + int nPoints=0; + const bool bCheckObs = minObs>0; + for(int i=0; iisBad()) + { + if(bCheckObs) + { + if(mvpMapPoints[i]->Observations()>=minObs) + nPoints++; + } + else + nPoints++; + } + } + } + + return nPoints; +} + +vector KeyFrame::GetMapPointMatches() +{ + unique_lock lock(mMutexFeatures); + return mvpMapPoints; +} + +MapPoint* KeyFrame::GetMapPoint(const size_t &idx) +{ + unique_lock lock(mMutexFeatures); + return mvpMapPoints[idx]; +} + +void KeyFrame::UpdateConnections(bool upParent) +{ + map KFcounter; + + vector vpMP; + + { + unique_lock lockMPs(mMutexFeatures); + vpMP = mvpMapPoints; + } + + //For all map points in keyframe check in which other keyframes are they seen + //Increase counter for those keyframes + for(vector::iterator vit=vpMP.begin(), vend=vpMP.end(); vit!=vend; vit++) + { + MapPoint* pMP = *vit; + + if(!pMP) + continue; + + if(pMP->isBad()) + continue; + + map> observations = pMP->GetObservations(); + + for(map>::iterator mit=observations.begin(), mend=observations.end(); mit!=mend; mit++) + { + if(mit->first->mnId==mnId || mit->first->isBad() || mit->first->GetMap() != mpMap) + continue; + KFcounter[mit->first]++; + + } + } + + // This should not happen + if(KFcounter.empty()) + return; + + //If the counter is greater than threshold add connection + //In case no keyframe counter is over threshold add the one with maximum counter + int nmax=0; + KeyFrame* pKFmax=NULL; + int th = 15; + + vector > vPairs; + vPairs.reserve(KFcounter.size()); + if(!upParent) + cout << "UPDATE_CONN: current KF " << mnId << endl; + for(map::iterator mit=KFcounter.begin(), mend=KFcounter.end(); mit!=mend; mit++) + { + if(!upParent) + cout << " UPDATE_CONN: KF " << mit->first->mnId << " ; num matches: " << mit->second << endl; + if(mit->second>nmax) + { + nmax=mit->second; + pKFmax=mit->first; + } + if(mit->second>=th) + { + vPairs.push_back(make_pair(mit->second,mit->first)); + (mit->first)->AddConnection(this,mit->second); + } + } + + if(vPairs.empty()) + { + vPairs.push_back(make_pair(nmax,pKFmax)); + pKFmax->AddConnection(this,nmax); + } + + sort(vPairs.begin(),vPairs.end()); + list lKFs; + list lWs; + for(size_t i=0; i lockCon(mMutexConnections); + + // mspConnectedKeyFrames = spConnectedKeyFrames; + mConnectedKeyFrameWeights = KFcounter; + mvpOrderedConnectedKeyFrames = vector(lKFs.begin(),lKFs.end()); + mvOrderedWeights = vector(lWs.begin(), lWs.end()); + +// if(mbFirstConnection && mnId!=mpMap->GetInitKFid()) +// { +// mpParent = mvpOrderedConnectedKeyFrames.front(); +// mpParent->AddChild(this); +// mbFirstConnection = false; +// } + + if(mbFirstConnection && mnId!=mpMap->GetInitKFid()) + { + /*if(!mpParent || mpParent->GetParent() != this) + { + KeyFrame* pBestParent = static_cast(NULL); + for(KeyFrame* pKFi : mvpOrderedConnectedKeyFrames) + { + if(pKFi->GetParent() || pKFi->mnId == mpMap->GetInitKFid()) + { + pBestParent = pKFi; + break; + } + } + if(!pBestParent) + { + cout << "It can't be a covisible KF without Parent" << endl << endl; + return; + } + mpParent = pBestParent; + mpParent->AddChild(this); + mbFirstConnection = false; + }*/ + // cout << "udt.conn.id: " << mnId << endl; + mpParent = mvpOrderedConnectedKeyFrames.front(); + mpParent->AddChild(this); + mbFirstConnection = false; + } + + } +} + +void KeyFrame::AddChild(KeyFrame *pKF) +{ + unique_lock lockCon(mMutexConnections); + mspChildrens.insert(pKF); +} + +void KeyFrame::EraseChild(KeyFrame *pKF) +{ + unique_lock lockCon(mMutexConnections); + mspChildrens.erase(pKF); +} + +void KeyFrame::ChangeParent(KeyFrame *pKF) +{ + unique_lock lockCon(mMutexConnections); +// if(!mpParent && mpParent != this) +// mpParent->EraseChild(this); + if(pKF == this) + { + cout << "ERROR: Change parent KF, the parent and child are the same KF" << endl; + throw std::invalid_argument("The parent and child can not be the same"); + } + + mpParent = pKF; + pKF->AddChild(this); +} + +set KeyFrame::GetChilds() +{ + unique_lock lockCon(mMutexConnections); + return mspChildrens; +} + +KeyFrame* KeyFrame::GetParent() +{ + unique_lock lockCon(mMutexConnections); + return mpParent; +} + +bool KeyFrame::hasChild(KeyFrame *pKF) +{ + unique_lock lockCon(mMutexConnections); + return mspChildrens.count(pKF); +} + +void KeyFrame::SetFirstConnection(bool bFirst) +{ + unique_lock lockCon(mMutexConnections); + mbFirstConnection=bFirst; +} + +void KeyFrame::AddLoopEdge(KeyFrame *pKF) +{ + unique_lock lockCon(mMutexConnections); + mbNotErase = true; + mspLoopEdges.insert(pKF); +} + +set KeyFrame::GetLoopEdges() +{ + unique_lock lockCon(mMutexConnections); + return mspLoopEdges; +} + +void KeyFrame::AddMergeEdge(KeyFrame* pKF) +{ + unique_lock lockCon(mMutexConnections); + mbNotErase = true; + mspMergeEdges.insert(pKF); +} + +set KeyFrame::GetMergeEdges() +{ + unique_lock lockCon(mMutexConnections); + return mspMergeEdges; +} + +void KeyFrame::SetNotErase() +{ + unique_lock lock(mMutexConnections); + mbNotErase = true; +} + +void KeyFrame::SetErase() +{ + { + unique_lock lock(mMutexConnections); + if(mspLoopEdges.empty()) + { + mbNotErase = false; + } + } + + if(mbToBeErased) + { + SetBadFlag(); + } +} + +void KeyFrame::SetBadFlag() +{ + // std::cout << "Erasing KF..." << std::endl; + { + unique_lock lock(mMutexConnections); + if(mnId==mpMap->GetInitKFid()) + { + //std::cout << "KF.BADFLAG-> KF 0!!" << std::endl; + return; + } + else if(mbNotErase) + { + //std::cout << "KF.BADFLAG-> mbNotErase!!" << std::endl; + mbToBeErased = true; + return; + } + if(!mpParent) + { + //cout << "KF.BADFLAG-> There is not parent, but it is not the first KF in the map" << endl; + //cout << "KF.BADFLAG-> KF: " << mnId << "; first KF: " << mpMap->GetInitKFid() << endl; + } + } + //std::cout << "KF.BADFLAG-> Erasing KF..." << std::endl; + + for(map::iterator mit = mConnectedKeyFrameWeights.begin(), mend=mConnectedKeyFrameWeights.end(); mit!=mend; mit++) + { + mit->first->EraseConnection(this); + } + //std::cout << "KF.BADFLAG-> Connection erased..." << std::endl; + + for(size_t i=0; iEraseObservation(this); + // nDeletedPoints++; + } + } + // cout << "nDeletedPoints: " << nDeletedPoints << endl; + //std::cout << "KF.BADFLAG-> Observations deleted..." << std::endl; + + { + unique_lock lock(mMutexConnections); + unique_lock lock1(mMutexFeatures); + + mConnectedKeyFrameWeights.clear(); + mvpOrderedConnectedKeyFrames.clear(); + + // Update Spanning Tree + set sParentCandidates; + if(mpParent) + sParentCandidates.insert(mpParent); + //std::cout << "KF.BADFLAG-> Initially there are " << sParentCandidates.size() << " candidates" << std::endl; + + // Assign at each iteration one children with a parent (the pair with highest covisibility weight) + // Include that children as new parent candidate for the rest + while(!mspChildrens.empty()) + { + bool bContinue = false; + + int max = -1; + KeyFrame* pC; + KeyFrame* pP; + + for(set::iterator sit=mspChildrens.begin(), send=mspChildrens.end(); sit!=send; sit++) + { + KeyFrame* pKF = *sit; + if(pKF->isBad()) + continue; + + // Check if a parent candidate is connected to the keyframe + vector vpConnected = pKF->GetVectorCovisibleKeyFrames(); + for(size_t i=0, iend=vpConnected.size(); i::iterator spcit=sParentCandidates.begin(), spcend=sParentCandidates.end(); spcit!=spcend; spcit++) + { + if(vpConnected[i]->mnId == (*spcit)->mnId) + { + int w = pKF->GetWeight(vpConnected[i]); + if(w>max) + { + pC = pKF; + pP = vpConnected[i]; + max = w; + bContinue = true; + } + } + } + } + } + //std::cout << "KF.BADFLAG-> Find most similar children" << std::endl; + + if(bContinue) + { + if(pC->mnId == pP->mnId) + { + /*cout << "ERROR: The parent and son can't be the same KF. ID: " << pC->mnId << endl; + cout << "Current KF: " << mnId << endl; + cout << "Parent of the map: " << endl;*/ + } + pC->ChangeParent(pP); + sParentCandidates.insert(pC); + mspChildrens.erase(pC); + } + else + break; + } + //std::cout << "KF.BADFLAG-> Apply change of parent to children" << std::endl; + + // If a children has no covisibility links with any parent candidate, assign to the original parent of this KF + if(!mspChildrens.empty()) + { + for(set::iterator sit=mspChildrens.begin(); sit!=mspChildrens.end(); sit++) + { + (*sit)->ChangeParent(mpParent); + } + } + //std::cout << "KF.BADFLAG-> Apply change to its parent" << std::endl; + + if(mpParent){ + mpParent->EraseChild(this); + mTcp = Tcw*mpParent->GetPoseInverse(); + } + else + { + //cout << "Error: KF haven't got a parent, it is imposible reach this code point without him" << endl; + } + mbBad = true; + } + + + mpMap->EraseKeyFrame(this); + mpKeyFrameDB->erase(this); +} + +bool KeyFrame::isBad() +{ + unique_lock lock(mMutexConnections); + return mbBad; +} + +void KeyFrame::EraseConnection(KeyFrame* pKF) +{ + bool bUpdate = false; + { + unique_lock lock(mMutexConnections); + if(mConnectedKeyFrameWeights.count(pKF)) + { + mConnectedKeyFrameWeights.erase(pKF); + bUpdate=true; + } + } + + if(bUpdate) + UpdateBestCovisibles(); +} + + +vector KeyFrame::GetFeaturesInArea(const float &x, const float &y, const float &r, const bool bRight) const +{ + vector vIndices; + vIndices.reserve(N); + + float factorX = r; + float factorY = r; + + const int nMinCellX = max(0,(int)floor((x-mnMinX-factorX)*mfGridElementWidthInv)); + if(nMinCellX>=mnGridCols) + return vIndices; + + const int nMaxCellX = min((int)mnGridCols-1,(int)ceil((x-mnMinX+factorX)*mfGridElementWidthInv)); + if(nMaxCellX<0) + return vIndices; + + const int nMinCellY = max(0,(int)floor((y-mnMinY-factorY)*mfGridElementHeightInv)); + if(nMinCellY>=mnGridRows) + return vIndices; + + const int nMaxCellY = min((int)mnGridRows-1,(int)ceil((y-mnMinY+factorY)*mfGridElementHeightInv)); + if(nMaxCellY<0) + return vIndices; + + for(int ix = nMinCellX; ix<=nMaxCellX; ix++) + { + for(int iy = nMinCellY; iy<=nMaxCellY; iy++) + { + const vector vCell = (!bRight) ? mGrid[ix][iy] : mGridRight[ix][iy]; + for(size_t j=0, jend=vCell.size(); j=mnMinX && x=mnMinY && y0) + { + const float u = mvKeys[i].pt.x; + const float v = mvKeys[i].pt.y; + const float x = (u-cx)*z*invfx; + const float y = (v-cy)*z*invfy; + cv::Mat x3Dc = (cv::Mat_(3,1) << x, y, z); + + unique_lock lock(mMutexPose); + return Twc.rowRange(0,3).colRange(0,3)*x3Dc+Twc.rowRange(0,3).col(3); + } + else + return cv::Mat(); +} + +float KeyFrame::ComputeSceneMedianDepth(const int q) +{ + vector vpMapPoints; + cv::Mat Tcw_; + { + unique_lock lock(mMutexFeatures); + unique_lock lock2(mMutexPose); + vpMapPoints = mvpMapPoints; + Tcw_ = Tcw.clone(); + } + + vector vDepths; + vDepths.reserve(N); + cv::Mat Rcw2 = Tcw_.row(2).colRange(0,3); + Rcw2 = Rcw2.t(); + float zcw = Tcw_.at(2,3); + for(int i=0; iGetWorldPos(); + float z = Rcw2.dot(x3Dw)+zcw; + vDepths.push_back(z); + } + } + + sort(vDepths.begin(),vDepths.end()); + + return vDepths[(vDepths.size()-1)/q]; +} + +void KeyFrame::SetNewBias(const IMU::Bias &b) +{ + unique_lock lock(mMutexPose); + mImuBias = b; + if(mpImuPreintegrated) + mpImuPreintegrated->SetNewBias(b); +} + +cv::Mat KeyFrame::GetGyroBias() +{ + unique_lock lock(mMutexPose); + return (cv::Mat_(3,1) << mImuBias.bwx, mImuBias.bwy, mImuBias.bwz); +} + +cv::Mat KeyFrame::GetAccBias() +{ + unique_lock lock(mMutexPose); + return (cv::Mat_(3,1) << mImuBias.bax, mImuBias.bay, mImuBias.baz); +} + +IMU::Bias KeyFrame::GetImuBias() +{ + unique_lock lock(mMutexPose); + return mImuBias; +} + +Map* KeyFrame::GetMap() +{ + unique_lock lock(mMutexMap); + return mpMap; +} + +void KeyFrame::UpdateMap(Map* pMap) +{ + unique_lock lock(mMutexMap); + mpMap = pMap; +} + +void KeyFrame::PreSave(set& spKF,set& spMP, set& spCam) +{ + // Save the id of each MapPoint in this KF, there can be null pointer in the vector + mvBackupMapPointsId.clear(); + mvBackupMapPointsId.reserve(N); + for(int i = 0; i < N; ++i) + { + + if(mvpMapPoints[i] && spMP.find(mvpMapPoints[i]) != spMP.end()) // Checks if the element is not null + mvBackupMapPointsId.push_back(mvpMapPoints[i]->mnId); + else // If the element is null his value is -1 because all the id are positives + mvBackupMapPointsId.push_back(-1); + } + //cout << "KeyFrame: ID from MapPoints stored" << endl; + // Save the id of each connected KF with it weight + mBackupConnectedKeyFrameIdWeights.clear(); + for(std::map::const_iterator it = mConnectedKeyFrameWeights.begin(), end = mConnectedKeyFrameWeights.end(); it != end; ++it) + { + if(spKF.find(it->first) != spKF.end()) + mBackupConnectedKeyFrameIdWeights[it->first->mnId] = it->second; + } + //cout << "KeyFrame: ID from connected KFs stored" << endl; + // Save the parent id + mBackupParentId = -1; + if(mpParent && spKF.find(mpParent) != spKF.end()) + mBackupParentId = mpParent->mnId; + //cout << "KeyFrame: ID from Parent KF stored" << endl; + // Save the id of the childrens KF + mvBackupChildrensId.clear(); + mvBackupChildrensId.reserve(mspChildrens.size()); + for(KeyFrame* pKFi : mspChildrens) + { + if(spKF.find(pKFi) != spKF.end()) + mvBackupChildrensId.push_back(pKFi->mnId); + } + //cout << "KeyFrame: ID from Children KFs stored" << endl; + // Save the id of the loop edge KF + mvBackupLoopEdgesId.clear(); + mvBackupLoopEdgesId.reserve(mspLoopEdges.size()); + for(KeyFrame* pKFi : mspLoopEdges) + { + if(spKF.find(pKFi) != spKF.end()) + mvBackupLoopEdgesId.push_back(pKFi->mnId); + } + //cout << "KeyFrame: ID from Loop KFs stored" << endl; + // Save the id of the merge edge KF + mvBackupMergeEdgesId.clear(); + mvBackupMergeEdgesId.reserve(mspMergeEdges.size()); + for(KeyFrame* pKFi : mspMergeEdges) + { + if(spKF.find(pKFi) != spKF.end()) + mvBackupMergeEdgesId.push_back(pKFi->mnId); + } + //cout << "KeyFrame: ID from Merge KFs stored" << endl; + + //Camera data + mnBackupIdCamera = -1; + if(mpCamera && spCam.find(mpCamera) != spCam.end()) + mnBackupIdCamera = mpCamera->GetId(); + //cout << "KeyFrame: ID from Camera1 stored; " << mnBackupIdCamera << endl; + + mnBackupIdCamera2 = -1; + if(mpCamera2 && spCam.find(mpCamera2) != spCam.end()) + mnBackupIdCamera2 = mpCamera2->GetId(); + //cout << "KeyFrame: ID from Camera2 stored; " << mnBackupIdCamera2 << endl; + + //Inertial data + mBackupPrevKFId = -1; + if(mPrevKF && spKF.find(mPrevKF) != spKF.end()) + mBackupPrevKFId = mPrevKF->mnId; + //cout << "KeyFrame: ID from Prev KF stored" << endl; + mBackupNextKFId = -1; + if(mNextKF && spKF.find(mNextKF) != spKF.end()) + mBackupNextKFId = mNextKF->mnId; + //cout << "KeyFrame: ID from NextKF stored" << endl; + if(mpImuPreintegrated) + mBackupImuPreintegrated.CopyFrom(mpImuPreintegrated); + //cout << "KeyFrame: Imu Preintegrated stored" << endl; +} + +void KeyFrame::PostLoad(map& mpKFid, map& mpMPid, map& mpCamId){ + // Rebuild the empty variables + + // Pose + SetPose(Tcw); + + // Reference reconstruction + // Each MapPoint sight from this KeyFrame + mvpMapPoints.clear(); + mvpMapPoints.resize(N); + for(int i=0; i(NULL); + } + + // Conected KeyFrames with him weight + mConnectedKeyFrameWeights.clear(); + for(map::const_iterator it = mBackupConnectedKeyFrameIdWeights.begin(), end = mBackupConnectedKeyFrameIdWeights.end(); + it != end; ++it) + { + KeyFrame* pKFi = mpKFid[it->first]; + mConnectedKeyFrameWeights[pKFi] = it->second; + } + + // Restore parent KeyFrame + if(mBackupParentId>=0) + mpParent = mpKFid[mBackupParentId]; + + // KeyFrame childrens + mspChildrens.clear(); + for(vector::const_iterator it = mvBackupChildrensId.begin(), end = mvBackupChildrensId.end(); it!=end; ++it) + { + mspChildrens.insert(mpKFid[*it]); + } + + // Loop edge KeyFrame + mspLoopEdges.clear(); + for(vector::const_iterator it = mvBackupLoopEdgesId.begin(), end = mvBackupLoopEdgesId.end(); it != end; ++it) + { + mspLoopEdges.insert(mpKFid[*it]); + } + + // Merge edge KeyFrame + mspMergeEdges.clear(); + for(vector::const_iterator it = mvBackupMergeEdgesId.begin(), end = mvBackupMergeEdgesId.end(); it != end; ++it) + { + mspMergeEdges.insert(mpKFid[*it]); + } + + //Camera data + if(mnBackupIdCamera >= 0) + { + mpCamera = mpCamId[mnBackupIdCamera]; + } + if(mnBackupIdCamera2 >= 0) + { + mpCamera2 = mpCamId[mnBackupIdCamera2]; + } + + //Inertial data + if(mBackupPrevKFId != -1) + { + mPrevKF = mpKFid[mBackupPrevKFId]; + } + if(mBackupNextKFId != -1) + { + mNextKF = mpKFid[mBackupNextKFId]; + } + mpImuPreintegrated = &mBackupImuPreintegrated; + + + // Remove all backup container + mvBackupMapPointsId.clear(); + mBackupConnectedKeyFrameIdWeights.clear(); + mvBackupChildrensId.clear(); + mvBackupLoopEdgesId.clear(); + + UpdateBestCovisibles(); + + //ComputeSceneMedianDepth(); +} + +bool KeyFrame::ProjectPointDistort(MapPoint* pMP, cv::Point2f &kp, float &u, float &v) +{ + + // 3D in absolute coordinates + cv::Mat P = pMP->GetWorldPos(); + cv::Mat Rcw = Tcw.rowRange(0, 3).colRange(0, 3); + cv::Mat tcw = Tcw.rowRange(0, 3).col(3); + + // 3D in camera coordinates + cv::Mat Pc = Rcw*P+tcw; + float &PcX = Pc.at(0); + float &PcY= Pc.at(1); + float &PcZ = Pc.at(2); + + // Check positive depth + if(PcZ<0.0f) + { + cout << "Negative depth: " << PcZ << endl; + return false; + } + + // Project in image and check it is not outside + float invz = 1.0f/PcZ; + u=fx*PcX*invz+cx; + v=fy*PcY*invz+cy; + + // cout << "c"; + + if(umnMaxX) + return false; + if(vmnMaxY) + return false; + + float x = (u - cx) * invfx; + float y = (v - cy) * invfy; + float r2 = x * x + y * y; + float k1 = mDistCoef.at(0); + float k2 = mDistCoef.at(1); + float p1 = mDistCoef.at(2); + float p2 = mDistCoef.at(3); + float k3 = 0; + if(mDistCoef.total() == 5) + { + k3 = mDistCoef.at(4); + } + + // Radial distorsion + float x_distort = x * (1 + k1 * r2 + k2 * r2 * r2 + k3 * r2 * r2 * r2); + float y_distort = y * (1 + k1 * r2 + k2 * r2 * r2 + k3 * r2 * r2 * r2); + + // Tangential distorsion + x_distort = x_distort + (2 * p1 * x * y + p2 * (r2 + 2 * x * x)); + y_distort = y_distort + (p1 * (r2 + 2 * y * y) + 2 * p2 * x * y); + + float u_distort = x_distort * fx + cx; + float v_distort = y_distort * fy + cy; + + u = u_distort; + v = v_distort; + + kp = cv::Point2f(u, v); + + return true; +} + +bool KeyFrame::ProjectPointUnDistort(MapPoint* pMP, cv::Point2f &kp, float &u, float &v) +{ + + // 3D in absolute coordinates + cv::Mat P = pMP->GetWorldPos(); + cv::Mat Rcw = Tcw.rowRange(0, 3).colRange(0, 3); + cv::Mat tcw = Tcw.rowRange(0, 3).col(3); + // 3D in camera coordinates + cv::Mat Pc = Rcw*P+tcw; + float &PcX = Pc.at(0); + float &PcY= Pc.at(1); + float &PcZ = Pc.at(2); + + // Check positive depth + if(PcZ<0.0f) + { + cout << "Negative depth: " << PcZ << endl; + return false; + } + + // Project in image and check it is not outside + const float invz = 1.0f/PcZ; + u=fx*PcX*invz+cx; + v=fy*PcY*invz+cy; + + // cout << "c"; + + if(umnMaxX) + return false; + if(vmnMaxY) + return false; + + kp = cv::Point2f(u, v); + + return true; +} + +cv::Mat KeyFrame::GetRightPose() { + unique_lock lock(mMutexPose); + + cv::Mat Rrl = mTlr.rowRange(0,3).colRange(0,3).t(); + cv::Mat Rlw = Tcw.rowRange(0,3).colRange(0,3).clone(); + cv::Mat Rrw = Rrl * Rlw; + + cv::Mat tlw = Tcw.rowRange(0,3).col(3).clone(); + cv::Mat trl = - Rrl * mTlr.rowRange(0,3).col(3); + + cv::Mat trw = Rrl * tlw + trl; + + cv::Mat Trw; + cv::hconcat(Rrw,trw,Trw); + + return Trw.clone(); +} + +cv::Mat KeyFrame::GetRightPoseInverse() { + unique_lock lock(mMutexPose); + cv::Mat Rrl = mTlr.rowRange(0,3).colRange(0,3).t(); + cv::Mat Rlw = Tcw.rowRange(0,3).colRange(0,3).clone(); + cv::Mat Rwr = (Rrl * Rlw).t(); + + cv::Mat Rwl = Tcw.rowRange(0,3).colRange(0,3).t(); + cv::Mat tlr = mTlr.rowRange(0,3).col(3); + cv::Mat twl = GetCameraCenter(); + + cv::Mat twr = Rwl * tlr + twl; + + cv::Mat Twr; + cv::hconcat(Rwr,twr,Twr); + + return Twr.clone(); +} + +cv::Mat KeyFrame::GetRightPoseInverseH() { + unique_lock lock(mMutexPose); + cv::Mat Rrl = mTlr.rowRange(0,3).colRange(0,3).t(); + cv::Mat Rlw = Tcw.rowRange(0,3).colRange(0,3).clone(); + cv::Mat Rwr = (Rrl * Rlw).t(); + + cv::Mat Rwl = Tcw.rowRange(0,3).colRange(0,3).t(); + cv::Mat tlr = mTlr.rowRange(0,3).col(3); + cv::Mat twl = Ow.clone(); + + cv::Mat twr = Rwl * tlr + twl; + + cv::Mat Twr; + cv::hconcat(Rwr,twr,Twr); + cv::Mat h(1,4,CV_32F,cv::Scalar(0.0f)); h.at(3) = 1.0f; + cv::vconcat(Twr,h,Twr); + + return Twr.clone(); +} + +cv::Mat KeyFrame::GetRightCameraCenter() { + unique_lock lock(mMutexPose); + cv::Mat Rwl = Tcw.rowRange(0,3).colRange(0,3).t(); + cv::Mat tlr = mTlr.rowRange(0,3).col(3); + cv::Mat twl = Ow.clone(); + + cv::Mat twr = Rwl * tlr + twl; + + return twr.clone(); +} + +cv::Mat KeyFrame::GetRightRotation() { + unique_lock lock(mMutexPose); + cv::Mat Rrl = mTlr.rowRange(0,3).colRange(0,3).t(); + cv::Mat Rlw = Tcw.rowRange(0,3).colRange(0,3).clone(); + cv::Mat Rrw = Rrl * Rlw; + + return Rrw.clone(); + +} + +cv::Mat KeyFrame::GetRightTranslation() { + unique_lock lock(mMutexPose); + cv::Mat Rrl = mTlr.rowRange(0,3).colRange(0,3).t(); + cv::Mat tlw = Tcw.rowRange(0,3).col(3).clone(); + cv::Mat trl = - Rrl * mTlr.rowRange(0,3).col(3); + + cv::Mat trw = Rrl * tlw + trl; + + return trw.clone(); +} + +void KeyFrame::SetORBVocabulary(ORBVocabulary* pORBVoc) +{ + mpORBvocabulary = pORBVoc; +} + +void KeyFrame::SetKeyFrameDatabase(KeyFrameDatabase* pKFDB) +{ + mpKeyFrameDB = pKFDB; +} + +} //namespace ORB_SLAM diff --git a/third_party/ORB_SLAM3/src/KeyFrameDatabase.cc b/third_party/ORB_SLAM3/src/KeyFrameDatabase.cc new file mode 100644 index 0000000..c8f730f --- /dev/null +++ b/third_party/ORB_SLAM3/src/KeyFrameDatabase.cc @@ -0,0 +1,937 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + + +#include "KeyFrameDatabase.h" + +#include "KeyFrame.h" +#include "Thirdparty/DBoW2/DBoW2/BowVector.h" + +#include + +using namespace std; + +namespace ORB_SLAM3 +{ + +KeyFrameDatabase::KeyFrameDatabase (const ORBVocabulary &voc): + mpVoc(&voc) +{ + mvInvertedFile.resize(voc.size()); +} + + +void KeyFrameDatabase::add(KeyFrame *pKF) +{ + unique_lock lock(mMutex); + + for(DBoW2::BowVector::const_iterator vit= pKF->mBowVec.begin(), vend=pKF->mBowVec.end(); vit!=vend; vit++) + mvInvertedFile[vit->first].push_back(pKF); +} + +void KeyFrameDatabase::erase(KeyFrame* pKF) +{ + unique_lock lock(mMutex); + + // Erase elements in the Inverse File for the entry + for(DBoW2::BowVector::const_iterator vit=pKF->mBowVec.begin(), vend=pKF->mBowVec.end(); vit!=vend; vit++) + { + // List of keyframes that share the word + list &lKFs = mvInvertedFile[vit->first]; + + for(list::iterator lit=lKFs.begin(), lend= lKFs.end(); lit!=lend; lit++) + { + if(pKF==*lit) + { + lKFs.erase(lit); + break; + } + } + } +} + +void KeyFrameDatabase::clear() +{ + mvInvertedFile.clear(); + mvInvertedFile.resize(mpVoc->size()); +} + +void KeyFrameDatabase::clearMap(Map* pMap) +{ + unique_lock lock(mMutex); + + // Erase elements in the Inverse File for the entry + for(std::vector >::iterator vit=mvInvertedFile.begin(), vend=mvInvertedFile.end(); vit!=vend; vit++) + { + // List of keyframes that share the word + list &lKFs = *vit; + + for(list::iterator lit=lKFs.begin(), lend= lKFs.end(); lit!=lend;) + { + KeyFrame* pKFi = *lit; + if(pMap == pKFi->GetMap()) + { + lit = lKFs.erase(lit); + // Dont delete the KF because the class Map clean all the KF when it is destroyed + } + else + { + ++lit; + } + } + } +} + +vector KeyFrameDatabase::DetectLoopCandidates(KeyFrame* pKF, float minScore) +{ + set spConnectedKeyFrames = pKF->GetConnectedKeyFrames(); + list lKFsSharingWords; + + // Search all keyframes that share a word with current keyframes + // Discard keyframes connected to the query keyframe + { + unique_lock lock(mMutex); + + for(DBoW2::BowVector::const_iterator vit=pKF->mBowVec.begin(), vend=pKF->mBowVec.end(); vit != vend; vit++) + { + list &lKFs = mvInvertedFile[vit->first]; + + for(list::iterator lit=lKFs.begin(), lend= lKFs.end(); lit!=lend; lit++) + { + KeyFrame* pKFi=*lit; + if(pKFi->GetMap()==pKF->GetMap()) // For consider a loop candidate it a candidate it must be in the same map + { + if(pKFi->mnLoopQuery!=pKF->mnId) + { + pKFi->mnLoopWords=0; + if(!spConnectedKeyFrames.count(pKFi)) + { + pKFi->mnLoopQuery=pKF->mnId; + lKFsSharingWords.push_back(pKFi); + } + } + pKFi->mnLoopWords++; + } + + + } + } + } + + if(lKFsSharingWords.empty()) + return vector(); + + list > lScoreAndMatch; + + // Only compare against those keyframes that share enough words + int maxCommonWords=0; + for(list::iterator lit=lKFsSharingWords.begin(), lend= lKFsSharingWords.end(); lit!=lend; lit++) + { + if((*lit)->mnLoopWords>maxCommonWords) + maxCommonWords=(*lit)->mnLoopWords; + } + + int minCommonWords = maxCommonWords*0.8f; + + int nscores=0; + + // Compute similarity score. Retain the matches whose score is higher than minScore + for(list::iterator lit=lKFsSharingWords.begin(), lend= lKFsSharingWords.end(); lit!=lend; lit++) + { + KeyFrame* pKFi = *lit; + + if(pKFi->mnLoopWords>minCommonWords) + { + nscores++; + + float si = mpVoc->score(pKF->mBowVec,pKFi->mBowVec); + + pKFi->mLoopScore = si; + if(si>=minScore) + lScoreAndMatch.push_back(make_pair(si,pKFi)); + } + } + + if(lScoreAndMatch.empty()) + return vector(); + + list > lAccScoreAndMatch; + float bestAccScore = minScore; + + // Lets now accumulate score by covisibility + for(list >::iterator it=lScoreAndMatch.begin(), itend=lScoreAndMatch.end(); it!=itend; it++) + { + KeyFrame* pKFi = it->second; + vector vpNeighs = pKFi->GetBestCovisibilityKeyFrames(10); + + float bestScore = it->first; + float accScore = it->first; + KeyFrame* pBestKF = pKFi; + for(vector::iterator vit=vpNeighs.begin(), vend=vpNeighs.end(); vit!=vend; vit++) + { + KeyFrame* pKF2 = *vit; + if(pKF2->mnLoopQuery==pKF->mnId && pKF2->mnLoopWords>minCommonWords) + { + accScore+=pKF2->mLoopScore; + if(pKF2->mLoopScore>bestScore) + { + pBestKF=pKF2; + bestScore = pKF2->mLoopScore; + } + } + } + + lAccScoreAndMatch.push_back(make_pair(accScore,pBestKF)); + if(accScore>bestAccScore) + bestAccScore=accScore; + } + + // Return all those keyframes with a score higher than 0.75*bestScore + float minScoreToRetain = 0.75f*bestAccScore; + + set spAlreadyAddedKF; + vector vpLoopCandidates; + vpLoopCandidates.reserve(lAccScoreAndMatch.size()); + + for(list >::iterator it=lAccScoreAndMatch.begin(), itend=lAccScoreAndMatch.end(); it!=itend; it++) + { + if(it->first>minScoreToRetain) + { + KeyFrame* pKFi = it->second; + if(!spAlreadyAddedKF.count(pKFi)) + { + vpLoopCandidates.push_back(pKFi); + spAlreadyAddedKF.insert(pKFi); + } + } + } + + + return vpLoopCandidates; +} + +void KeyFrameDatabase::DetectCandidates(KeyFrame* pKF, float minScore,vector& vpLoopCand, vector& vpMergeCand) +{ + set spConnectedKeyFrames = pKF->GetConnectedKeyFrames(); + list lKFsSharingWordsLoop,lKFsSharingWordsMerge; + + // Search all keyframes that share a word with current keyframes + // Discard keyframes connected to the query keyframe + { + unique_lock lock(mMutex); + + for(DBoW2::BowVector::const_iterator vit=pKF->mBowVec.begin(), vend=pKF->mBowVec.end(); vit != vend; vit++) + { + list &lKFs = mvInvertedFile[vit->first]; + + for(list::iterator lit=lKFs.begin(), lend= lKFs.end(); lit!=lend; lit++) + { + KeyFrame* pKFi=*lit; + if(pKFi->GetMap()==pKF->GetMap()) // For consider a loop candidate it a candidate it must be in the same map + { + if(pKFi->mnLoopQuery!=pKF->mnId) + { + pKFi->mnLoopWords=0; + if(!spConnectedKeyFrames.count(pKFi)) + { + pKFi->mnLoopQuery=pKF->mnId; + lKFsSharingWordsLoop.push_back(pKFi); + } + } + pKFi->mnLoopWords++; + } + else if(!pKFi->GetMap()->IsBad()) + { + if(pKFi->mnMergeQuery!=pKF->mnId) + { + pKFi->mnMergeWords=0; + if(!spConnectedKeyFrames.count(pKFi)) + { + pKFi->mnMergeQuery=pKF->mnId; + lKFsSharingWordsMerge.push_back(pKFi); + } + } + pKFi->mnMergeWords++; + } + } + } + } + + if(lKFsSharingWordsLoop.empty() && lKFsSharingWordsMerge.empty()) + return; + + if(!lKFsSharingWordsLoop.empty()) + { + list > lScoreAndMatch; + + // Only compare against those keyframes that share enough words + int maxCommonWords=0; + for(list::iterator lit=lKFsSharingWordsLoop.begin(), lend= lKFsSharingWordsLoop.end(); lit!=lend; lit++) + { + if((*lit)->mnLoopWords>maxCommonWords) + maxCommonWords=(*lit)->mnLoopWords; + } + + int minCommonWords = maxCommonWords*0.8f; + + int nscores=0; + + // Compute similarity score. Retain the matches whose score is higher than minScore + for(list::iterator lit=lKFsSharingWordsLoop.begin(), lend= lKFsSharingWordsLoop.end(); lit!=lend; lit++) + { + KeyFrame* pKFi = *lit; + + if(pKFi->mnLoopWords>minCommonWords) + { + nscores++; + + float si = mpVoc->score(pKF->mBowVec,pKFi->mBowVec); + + pKFi->mLoopScore = si; + if(si>=minScore) + lScoreAndMatch.push_back(make_pair(si,pKFi)); + } + } + + if(!lScoreAndMatch.empty()) + { + list > lAccScoreAndMatch; + float bestAccScore = minScore; + + // Lets now accumulate score by covisibility + for(list >::iterator it=lScoreAndMatch.begin(), itend=lScoreAndMatch.end(); it!=itend; it++) + { + KeyFrame* pKFi = it->second; + vector vpNeighs = pKFi->GetBestCovisibilityKeyFrames(10); + + float bestScore = it->first; + float accScore = it->first; + KeyFrame* pBestKF = pKFi; + for(vector::iterator vit=vpNeighs.begin(), vend=vpNeighs.end(); vit!=vend; vit++) + { + KeyFrame* pKF2 = *vit; + if(pKF2->mnLoopQuery==pKF->mnId && pKF2->mnLoopWords>minCommonWords) + { + accScore+=pKF2->mLoopScore; + if(pKF2->mLoopScore>bestScore) + { + pBestKF=pKF2; + bestScore = pKF2->mLoopScore; + } + } + } + + lAccScoreAndMatch.push_back(make_pair(accScore,pBestKF)); + if(accScore>bestAccScore) + bestAccScore=accScore; + } + + // Return all those keyframes with a score higher than 0.75*bestScore + float minScoreToRetain = 0.75f*bestAccScore; + + set spAlreadyAddedKF; + vpLoopCand.reserve(lAccScoreAndMatch.size()); + + for(list >::iterator it=lAccScoreAndMatch.begin(), itend=lAccScoreAndMatch.end(); it!=itend; it++) + { + if(it->first>minScoreToRetain) + { + KeyFrame* pKFi = it->second; + if(!spAlreadyAddedKF.count(pKFi)) + { + vpLoopCand.push_back(pKFi); + spAlreadyAddedKF.insert(pKFi); + } + } + } + } + + } + + if(!lKFsSharingWordsMerge.empty()) + { + //cout << "BoW candidates: " << lKFsSharingWordsMerge.size() << endl; + list > lScoreAndMatch; + + // Only compare against those keyframes that share enough words + int maxCommonWords=0; + for(list::iterator lit=lKFsSharingWordsMerge.begin(), lend=lKFsSharingWordsMerge.end(); lit!=lend; lit++) + { + if((*lit)->mnMergeWords>maxCommonWords) + maxCommonWords=(*lit)->mnMergeWords; + } + //cout << "Max common words: " << maxCommonWords << endl; + + int minCommonWords = maxCommonWords*0.8f; + + int nscores=0; + + // Compute similarity score. Retain the matches whose score is higher than minScore + for(list::iterator lit=lKFsSharingWordsMerge.begin(), lend=lKFsSharingWordsMerge.end(); lit!=lend; lit++) + { + KeyFrame* pKFi = *lit; + + if(pKFi->mnMergeWords>minCommonWords) + { + nscores++; + + float si = mpVoc->score(pKF->mBowVec,pKFi->mBowVec); + //cout << "KF score: " << si << endl; + + pKFi->mMergeScore = si; + if(si>=minScore) + lScoreAndMatch.push_back(make_pair(si,pKFi)); + } + } + //cout << "BoW candidates2: " << lScoreAndMatch.size() << endl; + + if(!lScoreAndMatch.empty()) + { + list > lAccScoreAndMatch; + float bestAccScore = minScore; + + // Lets now accumulate score by covisibility + for(list >::iterator it=lScoreAndMatch.begin(), itend=lScoreAndMatch.end(); it!=itend; it++) + { + KeyFrame* pKFi = it->second; + vector vpNeighs = pKFi->GetBestCovisibilityKeyFrames(10); + + float bestScore = it->first; + float accScore = it->first; + KeyFrame* pBestKF = pKFi; + for(vector::iterator vit=vpNeighs.begin(), vend=vpNeighs.end(); vit!=vend; vit++) + { + KeyFrame* pKF2 = *vit; + if(pKF2->mnMergeQuery==pKF->mnId && pKF2->mnMergeWords>minCommonWords) + { + accScore+=pKF2->mMergeScore; + if(pKF2->mMergeScore>bestScore) + { + pBestKF=pKF2; + bestScore = pKF2->mMergeScore; + } + } + } + + lAccScoreAndMatch.push_back(make_pair(accScore,pBestKF)); + if(accScore>bestAccScore) + bestAccScore=accScore; + } + + // Return all those keyframes with a score higher than 0.75*bestScore + float minScoreToRetain = 0.75f*bestAccScore; + + //cout << "Min score to retain: " << minScoreToRetain << endl; + + set spAlreadyAddedKF; + vpMergeCand.reserve(lAccScoreAndMatch.size()); + + for(list >::iterator it=lAccScoreAndMatch.begin(), itend=lAccScoreAndMatch.end(); it!=itend; it++) + { + if(it->first>minScoreToRetain) + { + KeyFrame* pKFi = it->second; + if(!spAlreadyAddedKF.count(pKFi)) + { + vpMergeCand.push_back(pKFi); + spAlreadyAddedKF.insert(pKFi); + } + } + } + //cout << "Candidates: " << vpMergeCand.size() << endl; + } + + } + + //---- + for(DBoW2::BowVector::const_iterator vit=pKF->mBowVec.begin(), vend=pKF->mBowVec.end(); vit != vend; vit++) + { + list &lKFs = mvInvertedFile[vit->first]; + + for(list::iterator lit=lKFs.begin(), lend= lKFs.end(); lit!=lend; lit++) + { + KeyFrame* pKFi=*lit; + pKFi->mnLoopQuery=-1; + pKFi->mnMergeQuery=-1; + } + } + +} + +void KeyFrameDatabase::DetectBestCandidates(KeyFrame *pKF, vector &vpLoopCand, vector &vpMergeCand, int nMinWords) +{ + list lKFsSharingWords; + set spConnectedKF; + + // Search all keyframes that share a word with current frame + { + unique_lock lock(mMutex); + + spConnectedKF = pKF->GetConnectedKeyFrames(); + + for(DBoW2::BowVector::const_iterator vit=pKF->mBowVec.begin(), vend=pKF->mBowVec.end(); vit != vend; vit++) + { + list &lKFs = mvInvertedFile[vit->first]; + + for(list::iterator lit=lKFs.begin(), lend= lKFs.end(); lit!=lend; lit++) + { + KeyFrame* pKFi=*lit; + if(spConnectedKF.find(pKFi) != spConnectedKF.end()) + { + continue; + } + if(pKFi->mnPlaceRecognitionQuery!=pKF->mnId) + { + pKFi->mnPlaceRecognitionWords=0; + pKFi->mnPlaceRecognitionQuery=pKF->mnId; + lKFsSharingWords.push_back(pKFi); + } + pKFi->mnPlaceRecognitionWords++; + + } + } + } + if(lKFsSharingWords.empty()) + return; + + // Only compare against those keyframes that share enough words + int maxCommonWords=0; + for(list::iterator lit=lKFsSharingWords.begin(), lend= lKFsSharingWords.end(); lit!=lend; lit++) + { + if((*lit)->mnPlaceRecognitionWords>maxCommonWords) + maxCommonWords=(*lit)->mnPlaceRecognitionWords; + } + + int minCommonWords = maxCommonWords*0.8f; + + if(minCommonWords < nMinWords) + { + minCommonWords = nMinWords; + } + + list > lScoreAndMatch; + + int nscores=0; + + // Compute similarity score. + for(list::iterator lit=lKFsSharingWords.begin(), lend= lKFsSharingWords.end(); lit!=lend; lit++) + { + KeyFrame* pKFi = *lit; + + if(pKFi->mnPlaceRecognitionWords>minCommonWords) + { + nscores++; + float si = mpVoc->score(pKF->mBowVec,pKFi->mBowVec); + pKFi->mPlaceRecognitionScore=si; + lScoreAndMatch.push_back(make_pair(si,pKFi)); + } + } + + if(lScoreAndMatch.empty()) + return; + + list > lAccScoreAndMatch; + float bestAccScore = 0; + + // Lets now accumulate score by covisibility + for(list >::iterator it=lScoreAndMatch.begin(), itend=lScoreAndMatch.end(); it!=itend; it++) + { + KeyFrame* pKFi = it->second; + vector vpNeighs = pKFi->GetBestCovisibilityKeyFrames(10); + + float bestScore = it->first; + float accScore = bestScore; + KeyFrame* pBestKF = pKFi; + for(vector::iterator vit=vpNeighs.begin(), vend=vpNeighs.end(); vit!=vend; vit++) + { + KeyFrame* pKF2 = *vit; + if(pKF2->mnPlaceRecognitionQuery!=pKF->mnId) + continue; + + accScore+=pKF2->mPlaceRecognitionScore; + if(pKF2->mPlaceRecognitionScore>bestScore) + { + pBestKF=pKF2; + bestScore = pKF2->mPlaceRecognitionScore; + } + + } + lAccScoreAndMatch.push_back(make_pair(accScore,pBestKF)); + if(accScore>bestAccScore) + bestAccScore=accScore; + } + + // Return all those keyframes with a score higher than 0.75*bestScore + float minScoreToRetain = 0.75f*bestAccScore; + set spAlreadyAddedKF; + vpLoopCand.reserve(lAccScoreAndMatch.size()); + vpMergeCand.reserve(lAccScoreAndMatch.size()); + for(list >::iterator it=lAccScoreAndMatch.begin(), itend=lAccScoreAndMatch.end(); it!=itend; it++) + { + const float &si = it->first; + if(si>minScoreToRetain) + { + KeyFrame* pKFi = it->second; + if(!spAlreadyAddedKF.count(pKFi)) + { + if(pKF->GetMap() == pKFi->GetMap()) + { + vpLoopCand.push_back(pKFi); + } + else + { + vpMergeCand.push_back(pKFi); + } + spAlreadyAddedKF.insert(pKFi); + } + } + } +} + +bool compFirst(const pair & a, const pair & b) +{ + return a.first > b.first; +} + + +void KeyFrameDatabase::DetectNBestCandidates(KeyFrame *pKF, vector &vpLoopCand, vector &vpMergeCand, int nNumCandidates) +{ + list lKFsSharingWords; + //set spInsertedKFsSharing; + set spConnectedKF; + + // Search all keyframes that share a word with current frame + { + unique_lock lock(mMutex); + + spConnectedKF = pKF->GetConnectedKeyFrames(); + + for(DBoW2::BowVector::const_iterator vit=pKF->mBowVec.begin(), vend=pKF->mBowVec.end(); vit != vend; vit++) + { + list &lKFs = mvInvertedFile[vit->first]; + + for(list::iterator lit=lKFs.begin(), lend= lKFs.end(); lit!=lend; lit++) + { + KeyFrame* pKFi=*lit; + /*if(spConnectedKF.find(pKFi) != spConnectedKF.end()) + { + continue; + }*/ + if(pKFi->mnPlaceRecognitionQuery!=pKF->mnId) + { + pKFi->mnPlaceRecognitionWords=0; + if(!spConnectedKF.count(pKFi)) + { + + pKFi->mnPlaceRecognitionQuery=pKF->mnId; + lKFsSharingWords.push_back(pKFi); + } + } + pKFi->mnPlaceRecognitionWords++; + /*if(spInsertedKFsSharing.find(pKFi) == spInsertedKFsSharing.end()) + { + lKFsSharingWords.push_back(pKFi); + spInsertedKFsSharing.insert(pKFi); + }*/ + + } + } + } + if(lKFsSharingWords.empty()) + return; + + // Only compare against those keyframes that share enough words + int maxCommonWords=0; + for(list::iterator lit=lKFsSharingWords.begin(), lend= lKFsSharingWords.end(); lit!=lend; lit++) + { + if((*lit)->mnPlaceRecognitionWords>maxCommonWords) + maxCommonWords=(*lit)->mnPlaceRecognitionWords; + } + + int minCommonWords = maxCommonWords*0.8f; + + list > lScoreAndMatch; + + int nscores=0; + + // Compute similarity score. + for(list::iterator lit=lKFsSharingWords.begin(), lend= lKFsSharingWords.end(); lit!=lend; lit++) + { + KeyFrame* pKFi = *lit; + + if(pKFi->mnPlaceRecognitionWords>minCommonWords) + { + nscores++; + float si = mpVoc->score(pKF->mBowVec,pKFi->mBowVec); + pKFi->mPlaceRecognitionScore=si; + lScoreAndMatch.push_back(make_pair(si,pKFi)); + } + } + + if(lScoreAndMatch.empty()) + return; + + list > lAccScoreAndMatch; + float bestAccScore = 0; + + // Lets now accumulate score by covisibility + for(list >::iterator it=lScoreAndMatch.begin(), itend=lScoreAndMatch.end(); it!=itend; it++) + { + KeyFrame* pKFi = it->second; + vector vpNeighs = pKFi->GetBestCovisibilityKeyFrames(10); + + float bestScore = it->first; + float accScore = bestScore; + KeyFrame* pBestKF = pKFi; + for(vector::iterator vit=vpNeighs.begin(), vend=vpNeighs.end(); vit!=vend; vit++) + { + KeyFrame* pKF2 = *vit; + if(pKF2->mnPlaceRecognitionQuery!=pKF->mnId) + continue; + + accScore+=pKF2->mPlaceRecognitionScore; + if(pKF2->mPlaceRecognitionScore>bestScore) + { + pBestKF=pKF2; + bestScore = pKF2->mPlaceRecognitionScore; + } + + } + lAccScoreAndMatch.push_back(make_pair(accScore,pBestKF)); + if(accScore>bestAccScore) + bestAccScore=accScore; + } + + //cout << "Amount of candidates: " << lAccScoreAndMatch.size() << endl; + + lAccScoreAndMatch.sort(compFirst); + + vpLoopCand.reserve(nNumCandidates); + vpMergeCand.reserve(nNumCandidates); + set spAlreadyAddedKF; + //cout << "Candidates in score order " << endl; + //for(list >::iterator it=lAccScoreAndMatch.begin(), itend=lAccScoreAndMatch.end(); it!=itend; it++) + int i = 0; + list >::iterator it=lAccScoreAndMatch.begin(); + while(i < lAccScoreAndMatch.size() && (vpLoopCand.size() < nNumCandidates || vpMergeCand.size() < nNumCandidates)) + { + //cout << "Accum score: " << it->first << endl; + KeyFrame* pKFi = it->second; + if(pKFi->isBad()) + continue; + + if(!spAlreadyAddedKF.count(pKFi)) + { + if(pKF->GetMap() == pKFi->GetMap() && vpLoopCand.size() < nNumCandidates) + { + vpLoopCand.push_back(pKFi); + } + else if(pKF->GetMap() != pKFi->GetMap() && vpMergeCand.size() < nNumCandidates && !pKFi->GetMap()->IsBad()) + { + vpMergeCand.push_back(pKFi); + } + spAlreadyAddedKF.insert(pKFi); + } + i++; + it++; + } + //------- + + // Return all those keyframes with a score higher than 0.75*bestScore + /*float minScoreToRetain = 0.75f*bestAccScore; + set spAlreadyAddedKF; + vpLoopCand.reserve(lAccScoreAndMatch.size()); + vpMergeCand.reserve(lAccScoreAndMatch.size()); + for(list >::iterator it=lAccScoreAndMatch.begin(), itend=lAccScoreAndMatch.end(); it!=itend; it++) + { + const float &si = it->first; + if(si>minScoreToRetain) + { + KeyFrame* pKFi = it->second; + if(!spAlreadyAddedKF.count(pKFi)) + { + if(pKF->GetMap() == pKFi->GetMap()) + { + vpLoopCand.push_back(pKFi); + } + else + { + vpMergeCand.push_back(pKFi); + } + spAlreadyAddedKF.insert(pKFi); + } + } + }*/ +} + + +vector KeyFrameDatabase::DetectRelocalizationCandidates(Frame *F, Map* pMap) +{ + list lKFsSharingWords; + + // Search all keyframes that share a word with current frame + { + unique_lock lock(mMutex); + + for(DBoW2::BowVector::const_iterator vit=F->mBowVec.begin(), vend=F->mBowVec.end(); vit != vend; vit++) + { + list &lKFs = mvInvertedFile[vit->first]; + + for(list::iterator lit=lKFs.begin(), lend= lKFs.end(); lit!=lend; lit++) + { + KeyFrame* pKFi=*lit; + if(pKFi->mnRelocQuery!=F->mnId) + { + pKFi->mnRelocWords=0; + pKFi->mnRelocQuery=F->mnId; + lKFsSharingWords.push_back(pKFi); + } + pKFi->mnRelocWords++; + } + } + } + if(lKFsSharingWords.empty()) + return vector(); + + // Only compare against those keyframes that share enough words + int maxCommonWords=0; + for(list::iterator lit=lKFsSharingWords.begin(), lend= lKFsSharingWords.end(); lit!=lend; lit++) + { + if((*lit)->mnRelocWords>maxCommonWords) + maxCommonWords=(*lit)->mnRelocWords; + } + + int minCommonWords = maxCommonWords*0.8f; + + list > lScoreAndMatch; + + int nscores=0; + + // Compute similarity score. + for(list::iterator lit=lKFsSharingWords.begin(), lend= lKFsSharingWords.end(); lit!=lend; lit++) + { + KeyFrame* pKFi = *lit; + + if(pKFi->mnRelocWords>minCommonWords) + { + nscores++; + float si = mpVoc->score(F->mBowVec,pKFi->mBowVec); + pKFi->mRelocScore=si; + lScoreAndMatch.push_back(make_pair(si,pKFi)); + } + } + + if(lScoreAndMatch.empty()) + return vector(); + + list > lAccScoreAndMatch; + float bestAccScore = 0; + + // Lets now accumulate score by covisibility + for(list >::iterator it=lScoreAndMatch.begin(), itend=lScoreAndMatch.end(); it!=itend; it++) + { + KeyFrame* pKFi = it->second; + vector vpNeighs = pKFi->GetBestCovisibilityKeyFrames(10); + + float bestScore = it->first; + float accScore = bestScore; + KeyFrame* pBestKF = pKFi; + for(vector::iterator vit=vpNeighs.begin(), vend=vpNeighs.end(); vit!=vend; vit++) + { + KeyFrame* pKF2 = *vit; + if(pKF2->mnRelocQuery!=F->mnId) + continue; + + accScore+=pKF2->mRelocScore; + if(pKF2->mRelocScore>bestScore) + { + pBestKF=pKF2; + bestScore = pKF2->mRelocScore; + } + + } + lAccScoreAndMatch.push_back(make_pair(accScore,pBestKF)); + if(accScore>bestAccScore) + bestAccScore=accScore; + } + + // Return all those keyframes with a score higher than 0.75*bestScore + float minScoreToRetain = 0.75f*bestAccScore; + set spAlreadyAddedKF; + vector vpRelocCandidates; + vpRelocCandidates.reserve(lAccScoreAndMatch.size()); + for(list >::iterator it=lAccScoreAndMatch.begin(), itend=lAccScoreAndMatch.end(); it!=itend; it++) + { + const float &si = it->first; + if(si>minScoreToRetain) + { + KeyFrame* pKFi = it->second; + if (pKFi->GetMap() != pMap) + continue; + if(!spAlreadyAddedKF.count(pKFi)) + { + vpRelocCandidates.push_back(pKFi); + spAlreadyAddedKF.insert(pKFi); + } + } + } + + return vpRelocCandidates; +} + +void KeyFrameDatabase::PreSave() +{ + //Save the information about the inverted index of KF to node + mvBackupInvertedFileId.resize(mvInvertedFile.size()); + for(int i = 0, numEl = mvInvertedFile.size(); i < numEl; ++i) + { + for(std::list::const_iterator it = mvInvertedFile[i].begin(), end = mvInvertedFile[i].end(); it != end; ++it) + { + mvBackupInvertedFileId[i].push_back((*it)->mnId); + } + } +} + +void KeyFrameDatabase::PostLoad(map mpKFid) +{ + mvInvertedFile.clear(); + mvInvertedFile.resize(mpVoc->size()); + for(unsigned int i = 0; i < mvBackupInvertedFileId.size(); ++i) + { + for(long unsigned int KFid : mvBackupInvertedFileId[i]) + { + if(mpKFid.find(KFid) != mpKFid.end()) + { + mvInvertedFile[i].push_back(mpKFid[KFid]); + } + } + } + +} + +void KeyFrameDatabase::SetORBVocabulary(ORBVocabulary* pORBVoc) +{ + ORBVocabulary** ptr; + ptr = (ORBVocabulary**)( &mpVoc ); + *ptr = pORBVoc; + + mvInvertedFile.clear(); + mvInvertedFile.resize(mpVoc->size()); +} + +} //namespace ORB_SLAM diff --git a/third_party/ORB_SLAM3/src/LocalMapping.cc b/third_party/ORB_SLAM3/src/LocalMapping.cc new file mode 100644 index 0000000..472f634 --- /dev/null +++ b/third_party/ORB_SLAM3/src/LocalMapping.cc @@ -0,0 +1,1487 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + + +#include "LocalMapping.h" +#include "LoopClosing.h" +#include "ORBmatcher.h" +#include "Optimizer.h" +#include "Converter.h" + +#include +#include + +namespace ORB_SLAM3 +{ + +LocalMapping::LocalMapping(System* pSys, Atlas *pAtlas, const float bMonocular, bool bInertial, const string &_strSeqName): + mpSystem(pSys), mbMonocular(bMonocular), mbInertial(bInertial), mbResetRequested(false), mbResetRequestedActiveMap(false), mbFinishRequested(false), mbFinished(true), mpAtlas(pAtlas), bInitializing(false), + mbAbortBA(false), mbStopped(false), mbStopRequested(false), mbNotStop(false), mbAcceptKeyFrames(true), + mbNewInit(false), mIdxInit(0), mScale(1.0), mInitSect(0), mbNotBA1(true), mbNotBA2(true), mIdxIteration(0), infoInertial(Eigen::MatrixXd::Zero(9,9)) +{ + mnMatchesInliers = 0; + + mbBadImu = false; + + mTinit = 0.f; + + mNumLM = 0; + mNumKFCulling=0; + + //DEBUG: times and data from LocalMapping in each frame + + strSequence = "";//_strSeqName; + + //f_lm.open("localMapping_times" + strSequence + ".txt"); + /*f_lm.open("localMapping_times.txt"); + + f_lm << "# Timestamp KF, Num CovKFs, Num KFs, Num RecentMPs, Num MPs, processKF, MPCulling, CreateMP, SearchNeigh, BA, KFCulling, [numFixKF_LBA]" << endl; + f_lm << fixed;*/ +} + +void LocalMapping::SetLoopCloser(LoopClosing* pLoopCloser) +{ + mpLoopCloser = pLoopCloser; +} + +void LocalMapping::SetTracker(Tracking *pTracker) +{ + mpTracker=pTracker; +} + +void LocalMapping::Run() +{ + + mbFinished = false; + + while(1) + { + // Tracking will see that Local Mapping is busy + SetAcceptKeyFrames(false); + + // Check if there are keyframes in the queue + if(CheckNewKeyFrames() && !mbBadImu) + { + // std::cout << "LM" << std::endl; + std::chrono::steady_clock::time_point t0 = std::chrono::steady_clock::now(); + + // BoW conversion and insertion in Map + ProcessNewKeyFrame(); + std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now(); + + // Check recent MapPoints + MapPointCulling(); + std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now(); + + // Triangulate new MapPoints + CreateNewMapPoints(); + std::chrono::steady_clock::time_point t3 = std::chrono::steady_clock::now(); + + // Save here: + // # Cov KFs + // # tot Kfs + // # recent added MPs + // # tot MPs + // # localMPs in LBA + // # fixedKFs in LBA + + mbAbortBA = false; + + if(!CheckNewKeyFrames()) + { + // Find more matches in neighbor keyframes and fuse point duplications + SearchInNeighbors(); + } + + std::chrono::steady_clock::time_point t4 = std::chrono::steady_clock::now(); + std::chrono::steady_clock::time_point t5 = t4, t6 = t4; + // mbAbortBA = false; + + //DEBUG-- + /*f_lm << setprecision(0); + f_lm << mpCurrentKeyFrame->mTimeStamp*1e9 << ","; + f_lm << mpCurrentKeyFrame->GetVectorCovisibleKeyFrames().size() << ","; + f_lm << mpCurrentKeyFrame->GetMap()->GetAllKeyFrames().size() << ","; + f_lm << mlpRecentAddedMapPoints.size() << ","; + f_lm << mpCurrentKeyFrame->GetMap()->GetAllMapPoints().size() << ",";*/ + //-- + int num_FixedKF_BA = 0; + + if(!CheckNewKeyFrames() && !stopRequested()) + { + if(mpAtlas->KeyFramesInMap()>2) + { + if(mbInertial && mpCurrentKeyFrame->GetMap()->isImuInitialized()) + { + float dist = cv::norm(mpCurrentKeyFrame->mPrevKF->GetCameraCenter() - mpCurrentKeyFrame->GetCameraCenter()) + + cv::norm(mpCurrentKeyFrame->mPrevKF->mPrevKF->GetCameraCenter() - mpCurrentKeyFrame->mPrevKF->GetCameraCenter()); + + if(dist>0.05) + mTinit += mpCurrentKeyFrame->mTimeStamp - mpCurrentKeyFrame->mPrevKF->mTimeStamp; + if(!mpCurrentKeyFrame->GetMap()->GetIniertialBA2()) + { + if((mTinit<10.f) && (dist<0.02)) + { + cout << "Not enough motion for initializing. Reseting..." << endl; + unique_lock lock(mMutexReset); + mbResetRequestedActiveMap = true; + mpMapToReset = mpCurrentKeyFrame->GetMap(); + mbBadImu = true; + } + } + + bool bLarge = ((mpTracker->GetMatchesInliers()>75)&&mbMonocular)||((mpTracker->GetMatchesInliers()>100)&&!mbMonocular); + Optimizer::LocalInertialBA(mpCurrentKeyFrame, &mbAbortBA, mpCurrentKeyFrame->GetMap(), bLarge, !mpCurrentKeyFrame->GetMap()->GetIniertialBA2()); + } + else + { + std::chrono::steady_clock::time_point begin = std::chrono::steady_clock::now(); + Optimizer::LocalBundleAdjustment(mpCurrentKeyFrame,&mbAbortBA, mpCurrentKeyFrame->GetMap(),num_FixedKF_BA); + std::chrono::steady_clock::time_point end = std::chrono::steady_clock::now(); + } + } + + t5 = std::chrono::steady_clock::now(); + + // Initialize IMU here + if(!mpCurrentKeyFrame->GetMap()->isImuInitialized() && mbInertial) + { + if (mbMonocular) + InitializeIMU(1e2, 1e10, true); + else + InitializeIMU(1e2, 1e5, true); + } + + + // Check redundant local Keyframes + KeyFrameCulling(); + + t6 = std::chrono::steady_clock::now(); + + if ((mTinit<100.0f) && mbInertial) + { + if(mpCurrentKeyFrame->GetMap()->isImuInitialized() && mpTracker->mState==Tracking::OK) // Enter here everytime local-mapping is called + { + if(!mpCurrentKeyFrame->GetMap()->GetIniertialBA1()){ + if (mTinit>5.0f) + { + cout << "start VIBA 1" << endl; + mpCurrentKeyFrame->GetMap()->SetIniertialBA1(); + if (mbMonocular) + InitializeIMU(1.f, 1e5, true); // 1.f, 1e5 + else + InitializeIMU(1.f, 1e5, true); // 1.f, 1e5 + + cout << "end VIBA 1" << endl; + } + } + //else if (mbNotBA2){ + else if(!mpCurrentKeyFrame->GetMap()->GetIniertialBA2()){ + if (mTinit>15.0f){ // 15.0f + cout << "start VIBA 2" << endl; + mpCurrentKeyFrame->GetMap()->SetIniertialBA2(); + if (mbMonocular) + InitializeIMU(0.f, 0.f, true); // 0.f, 0.f + else + InitializeIMU(0.f, 0.f, true); + + cout << "end VIBA 2" << endl; + } + } + + // scale refinement + if (((mpAtlas->KeyFramesInMap())<=100) && + ((mTinit>25.0f && mTinit<25.5f)|| + (mTinit>35.0f && mTinit<35.5f)|| + (mTinit>45.0f && mTinit<45.5f)|| + (mTinit>55.0f && mTinit<55.5f)|| + (mTinit>65.0f && mTinit<65.5f)|| + (mTinit>75.0f && mTinit<75.5f))){ + cout << "start scale ref" << endl; + if (mbMonocular) + ScaleRefinement(); + cout << "end scale ref" << endl; + } + } + } + } + + std::chrono::steady_clock::time_point t7 = std::chrono::steady_clock::now(); + + mpLoopCloser->InsertKeyFrame(mpCurrentKeyFrame); + std::chrono::steady_clock::time_point t8 = std::chrono::steady_clock::now(); + + double t_procKF = std::chrono::duration_cast >(t1 - t0).count(); + double t_MPcull = std::chrono::duration_cast >(t2 - t1).count(); + double t_CheckMP = std::chrono::duration_cast >(t3 - t2).count(); + double t_searchNeigh = std::chrono::duration_cast >(t4 - t3).count(); + double t_Opt = std::chrono::duration_cast >(t5 - t4).count(); + double t_KF_cull = std::chrono::duration_cast >(t6 - t5).count(); + double t_Insert = std::chrono::duration_cast >(t8 - t7).count(); + + //DEBUG-- + /*f_lm << setprecision(6); + f_lm << t_procKF << ","; + f_lm << t_MPcull << ","; + f_lm << t_CheckMP << ","; + f_lm << t_searchNeigh << ","; + f_lm << t_Opt << ","; + f_lm << t_KF_cull << ","; + f_lm << setprecision(0) << num_FixedKF_BA << "\n";*/ + //-- + + } + else if(Stop() && !mbBadImu) + { + // Safe area to stop + while(isStopped() && !CheckFinish()) + { + // cout << "LM: usleep if is stopped" << endl; + usleep(3000); + } + if(CheckFinish()) + break; + } + + ResetIfRequested(); + + // Tracking will see that Local Mapping is busy + SetAcceptKeyFrames(true); + + if(CheckFinish()) + break; + + // cout << "LM: normal usleep" << endl; + usleep(3000); + } + + //f_lm.close(); + + SetFinish(); +} + +void LocalMapping::InsertKeyFrame(KeyFrame *pKF) +{ + unique_lock lock(mMutexNewKFs); + mlNewKeyFrames.push_back(pKF); + mbAbortBA=true; +} + + +bool LocalMapping::CheckNewKeyFrames() +{ + unique_lock lock(mMutexNewKFs); + return(!mlNewKeyFrames.empty()); +} + +void LocalMapping::ProcessNewKeyFrame() +{ + //cout << "ProcessNewKeyFrame: " << mlNewKeyFrames.size() << endl; + { + unique_lock lock(mMutexNewKFs); + mpCurrentKeyFrame = mlNewKeyFrames.front(); + mlNewKeyFrames.pop_front(); + } + + // Compute Bags of Words structures + mpCurrentKeyFrame->ComputeBoW(); + + // Associate MapPoints to the new keyframe and update normal and descriptor + const vector vpMapPointMatches = mpCurrentKeyFrame->GetMapPointMatches(); + + for(size_t i=0; iisBad()) + { + if(!pMP->IsInKeyFrame(mpCurrentKeyFrame)) + { + pMP->AddObservation(mpCurrentKeyFrame, i); + pMP->UpdateNormalAndDepth(); + pMP->ComputeDistinctiveDescriptors(); + } + else // this can only happen for new stereo points inserted by the Tracking + { + mlpRecentAddedMapPoints.push_back(pMP); + } + } + } + } + + // Update links in the Covisibility Graph + mpCurrentKeyFrame->UpdateConnections(); + + // Insert Keyframe in Map + mpAtlas->AddKeyFrame(mpCurrentKeyFrame); +} + +void LocalMapping::EmptyQueue() +{ + while(CheckNewKeyFrames()) + ProcessNewKeyFrame(); +} + +void LocalMapping::MapPointCulling() +{ + // Check Recent Added MapPoints + list::iterator lit = mlpRecentAddedMapPoints.begin(); + const unsigned long int nCurrentKFid = mpCurrentKeyFrame->mnId; + + int nThObs; + if(mbMonocular) + nThObs = 2; + else + nThObs = 3; // MODIFICATION_STEREO_IMU here 3 + const int cnThObs = nThObs; + + int borrar = mlpRecentAddedMapPoints.size(); + + while(lit!=mlpRecentAddedMapPoints.end()) + { + MapPoint* pMP = *lit; + + if(pMP->isBad()) + lit = mlpRecentAddedMapPoints.erase(lit); + else if(pMP->GetFoundRatio()<0.25f) + { + pMP->SetBadFlag(); + lit = mlpRecentAddedMapPoints.erase(lit); + } + else if(((int)nCurrentKFid-(int)pMP->mnFirstKFid)>=2 && pMP->Observations()<=cnThObs) + { + pMP->SetBadFlag(); + lit = mlpRecentAddedMapPoints.erase(lit); + } + else if(((int)nCurrentKFid-(int)pMP->mnFirstKFid)>=3) + lit = mlpRecentAddedMapPoints.erase(lit); + else + { + lit++; + borrar--; + } + } + //cout << "erase MP: " << borrar << endl; +} + +void LocalMapping::CreateNewMapPoints() +{ + // Retrieve neighbor keyframes in covisibility graph + int nn = 10; + // For stereo inertial case + if(mbMonocular) + nn=20; + vector vpNeighKFs = mpCurrentKeyFrame->GetBestCovisibilityKeyFrames(nn); + + if (mbInertial) + { + KeyFrame* pKF = mpCurrentKeyFrame; + int count=0; + while((vpNeighKFs.size()<=nn)&&(pKF->mPrevKF)&&(count++::iterator it = std::find(vpNeighKFs.begin(), vpNeighKFs.end(), pKF->mPrevKF); + if(it==vpNeighKFs.end()) + vpNeighKFs.push_back(pKF->mPrevKF); + pKF = pKF->mPrevKF; + } + } + + float th = 0.6f; + + ORBmatcher matcher(th,false); + + cv::Mat Rcw1 = mpCurrentKeyFrame->GetRotation(); + cv::Mat Rwc1 = Rcw1.t(); + cv::Mat tcw1 = mpCurrentKeyFrame->GetTranslation(); + cv::Mat Tcw1(3,4,CV_32F); + Rcw1.copyTo(Tcw1.colRange(0,3)); + tcw1.copyTo(Tcw1.col(3)); + cv::Mat Ow1 = mpCurrentKeyFrame->GetCameraCenter(); + + const float &fx1 = mpCurrentKeyFrame->fx; + const float &fy1 = mpCurrentKeyFrame->fy; + const float &cx1 = mpCurrentKeyFrame->cx; + const float &cy1 = mpCurrentKeyFrame->cy; + const float &invfx1 = mpCurrentKeyFrame->invfx; + const float &invfy1 = mpCurrentKeyFrame->invfy; + + const float ratioFactor = 1.5f*mpCurrentKeyFrame->mfScaleFactor; + + // Search matches with epipolar restriction and triangulate + for(size_t i=0; i0 && CheckNewKeyFrames())// && (mnMatchesInliers>50)) + return; + + KeyFrame* pKF2 = vpNeighKFs[i]; + + GeometricCamera* pCamera1 = mpCurrentKeyFrame->mpCamera, *pCamera2 = pKF2->mpCamera; + + // Check first that baseline is not too short + cv::Mat Ow2 = pKF2->GetCameraCenter(); + cv::Mat vBaseline = Ow2-Ow1; + const float baseline = cv::norm(vBaseline); + + if(!mbMonocular) + { + if(baselinemb) + continue; + } + else + { + const float medianDepthKF2 = pKF2->ComputeSceneMedianDepth(2); + const float ratioBaselineDepth = baseline/medianDepthKF2; + + if(ratioBaselineDepth<0.01) + continue; + } + + // Compute Fundamental Matrix + cv::Mat F12 = ComputeF12(mpCurrentKeyFrame,pKF2); + + // Search matches that fullfil epipolar constraint + vector > vMatchedIndices; + bool bCoarse = mbInertial && + ((!mpCurrentKeyFrame->GetMap()->GetIniertialBA2() && mpCurrentKeyFrame->GetMap()->GetIniertialBA1())|| + mpTracker->mState==Tracking::RECENTLY_LOST); + matcher.SearchForTriangulation(mpCurrentKeyFrame,pKF2,F12,vMatchedIndices,false,bCoarse); + + cv::Mat Rcw2 = pKF2->GetRotation(); + cv::Mat Rwc2 = Rcw2.t(); + cv::Mat tcw2 = pKF2->GetTranslation(); + cv::Mat Tcw2(3,4,CV_32F); + Rcw2.copyTo(Tcw2.colRange(0,3)); + tcw2.copyTo(Tcw2.col(3)); + + const float &fx2 = pKF2->fx; + const float &fy2 = pKF2->fy; + const float &cx2 = pKF2->cx; + const float &cy2 = pKF2->cy; + const float &invfx2 = pKF2->invfx; + const float &invfy2 = pKF2->invfy; + + // Triangulate each match + const int nmatches = vMatchedIndices.size(); + for(int ikp=0; ikp NLeft == -1) ? mpCurrentKeyFrame->mvKeysUn[idx1] + : (idx1 < mpCurrentKeyFrame -> NLeft) ? mpCurrentKeyFrame -> mvKeys[idx1] + : mpCurrentKeyFrame -> mvKeysRight[idx1 - mpCurrentKeyFrame -> NLeft]; + const float kp1_ur=mpCurrentKeyFrame->mvuRight[idx1]; + bool bStereo1 = (!mpCurrentKeyFrame->mpCamera2 && kp1_ur>=0); + const bool bRight1 = (mpCurrentKeyFrame -> NLeft == -1 || idx1 < mpCurrentKeyFrame -> NLeft) ? false + : true; + + const cv::KeyPoint &kp2 = (pKF2 -> NLeft == -1) ? pKF2->mvKeysUn[idx2] + : (idx2 < pKF2 -> NLeft) ? pKF2 -> mvKeys[idx2] + : pKF2 -> mvKeysRight[idx2 - pKF2 -> NLeft]; + + const float kp2_ur = pKF2->mvuRight[idx2]; + bool bStereo2 = (!pKF2->mpCamera2 && kp2_ur>=0); + const bool bRight2 = (pKF2 -> NLeft == -1 || idx2 < pKF2 -> NLeft) ? false + : true; + + if(mpCurrentKeyFrame->mpCamera2 && pKF2->mpCamera2){ + if(bRight1 && bRight2){ + Rcw1 = mpCurrentKeyFrame->GetRightRotation(); + Rwc1 = Rcw1.t(); + tcw1 = mpCurrentKeyFrame->GetRightTranslation(); + Tcw1 = mpCurrentKeyFrame->GetRightPose(); + Ow1 = mpCurrentKeyFrame->GetRightCameraCenter(); + + Rcw2 = pKF2->GetRightRotation(); + Rwc2 = Rcw2.t(); + tcw2 = pKF2->GetRightTranslation(); + Tcw2 = pKF2->GetRightPose(); + Ow2 = pKF2->GetRightCameraCenter(); + + pCamera1 = mpCurrentKeyFrame->mpCamera2; + pCamera2 = pKF2->mpCamera2; + } + else if(bRight1 && !bRight2){ + Rcw1 = mpCurrentKeyFrame->GetRightRotation(); + Rwc1 = Rcw1.t(); + tcw1 = mpCurrentKeyFrame->GetRightTranslation(); + Tcw1 = mpCurrentKeyFrame->GetRightPose(); + Ow1 = mpCurrentKeyFrame->GetRightCameraCenter(); + + Rcw2 = pKF2->GetRotation(); + Rwc2 = Rcw2.t(); + tcw2 = pKF2->GetTranslation(); + Tcw2 = pKF2->GetPose(); + Ow2 = pKF2->GetCameraCenter(); + + pCamera1 = mpCurrentKeyFrame->mpCamera2; + pCamera2 = pKF2->mpCamera; + } + else if(!bRight1 && bRight2){ + Rcw1 = mpCurrentKeyFrame->GetRotation(); + Rwc1 = Rcw1.t(); + tcw1 = mpCurrentKeyFrame->GetTranslation(); + Tcw1 = mpCurrentKeyFrame->GetPose(); + Ow1 = mpCurrentKeyFrame->GetCameraCenter(); + + Rcw2 = pKF2->GetRightRotation(); + Rwc2 = Rcw2.t(); + tcw2 = pKF2->GetRightTranslation(); + Tcw2 = pKF2->GetRightPose(); + Ow2 = pKF2->GetRightCameraCenter(); + + pCamera1 = mpCurrentKeyFrame->mpCamera; + pCamera2 = pKF2->mpCamera2; + } + else{ + Rcw1 = mpCurrentKeyFrame->GetRotation(); + Rwc1 = Rcw1.t(); + tcw1 = mpCurrentKeyFrame->GetTranslation(); + Tcw1 = mpCurrentKeyFrame->GetPose(); + Ow1 = mpCurrentKeyFrame->GetCameraCenter(); + + Rcw2 = pKF2->GetRotation(); + Rwc2 = Rcw2.t(); + tcw2 = pKF2->GetTranslation(); + Tcw2 = pKF2->GetPose(); + Ow2 = pKF2->GetCameraCenter(); + + pCamera1 = mpCurrentKeyFrame->mpCamera; + pCamera2 = pKF2->mpCamera; + } + } + + // Check parallax between rays + cv::Mat xn1 = pCamera1->unprojectMat(kp1.pt); + cv::Mat xn2 = pCamera2->unprojectMat(kp2.pt); + + cv::Mat ray1 = Rwc1*xn1; + cv::Mat ray2 = Rwc2*xn2; + const float cosParallaxRays = ray1.dot(ray2)/(cv::norm(ray1)*cv::norm(ray2)); + + float cosParallaxStereo = cosParallaxRays+1; + float cosParallaxStereo1 = cosParallaxStereo; + float cosParallaxStereo2 = cosParallaxStereo; + + if(bStereo1) + cosParallaxStereo1 = cos(2*atan2(mpCurrentKeyFrame->mb/2,mpCurrentKeyFrame->mvDepth[idx1])); + else if(bStereo2) + cosParallaxStereo2 = cos(2*atan2(pKF2->mb/2,pKF2->mvDepth[idx2])); + + cosParallaxStereo = min(cosParallaxStereo1,cosParallaxStereo2); + + cv::Mat x3D; + if(cosParallaxRays0 && (bStereo1 || bStereo2 || + (cosParallaxRays<0.9998 && mbInertial) || (cosParallaxRays<0.9998 && !mbInertial))) + { + // Linear Triangulation Method + cv::Mat A(4,4,CV_32F); + A.row(0) = xn1.at(0)*Tcw1.row(2)-Tcw1.row(0); + A.row(1) = xn1.at(1)*Tcw1.row(2)-Tcw1.row(1); + A.row(2) = xn2.at(0)*Tcw2.row(2)-Tcw2.row(0); + A.row(3) = xn2.at(1)*Tcw2.row(2)-Tcw2.row(1); + + cv::Mat w,u,vt; + cv::SVD::compute(A,w,u,vt,cv::SVD::MODIFY_A| cv::SVD::FULL_UV); + + x3D = vt.row(3).t(); + + if(x3D.at(3)==0) + continue; + + // Euclidean coordinates + x3D = x3D.rowRange(0,3)/x3D.at(3); + + } + else if(bStereo1 && cosParallaxStereo1UnprojectStereo(idx1); + } + else if(bStereo2 && cosParallaxStereo2UnprojectStereo(idx2); + } + else + { + continue; //No stereo and very low parallax + } + + cv::Mat x3Dt = x3D.t(); + + if(x3Dt.empty()) continue; + //Check triangulation in front of cameras + float z1 = Rcw1.row(2).dot(x3Dt)+tcw1.at(2); + if(z1<=0) + continue; + + float z2 = Rcw2.row(2).dot(x3Dt)+tcw2.at(2); + if(z2<=0) + continue; + + //Check reprojection error in first keyframe + const float &sigmaSquare1 = mpCurrentKeyFrame->mvLevelSigma2[kp1.octave]; + const float x1 = Rcw1.row(0).dot(x3Dt)+tcw1.at(0); + const float y1 = Rcw1.row(1).dot(x3Dt)+tcw1.at(1); + const float invz1 = 1.0/z1; + + if(!bStereo1) + { + cv::Point2f uv1 = pCamera1->project(cv::Point3f(x1,y1,z1)); + float errX1 = uv1.x - kp1.pt.x; + float errY1 = uv1.y - kp1.pt.y; + + if((errX1*errX1+errY1*errY1)>5.991*sigmaSquare1) + continue; + + } + else + { + float u1 = fx1*x1*invz1+cx1; + float u1_r = u1 - mpCurrentKeyFrame->mbf*invz1; + float v1 = fy1*y1*invz1+cy1; + float errX1 = u1 - kp1.pt.x; + float errY1 = v1 - kp1.pt.y; + float errX1_r = u1_r - kp1_ur; + if((errX1*errX1+errY1*errY1+errX1_r*errX1_r)>7.8*sigmaSquare1) + continue; + } + + //Check reprojection error in second keyframe + const float sigmaSquare2 = pKF2->mvLevelSigma2[kp2.octave]; + const float x2 = Rcw2.row(0).dot(x3Dt)+tcw2.at(0); + const float y2 = Rcw2.row(1).dot(x3Dt)+tcw2.at(1); + const float invz2 = 1.0/z2; + if(!bStereo2) + { + cv::Point2f uv2 = pCamera2->project(cv::Point3f(x2,y2,z2)); + float errX2 = uv2.x - kp2.pt.x; + float errY2 = uv2.y - kp2.pt.y; + if((errX2*errX2+errY2*errY2)>5.991*sigmaSquare2) + continue; + } + else + { + float u2 = fx2*x2*invz2+cx2; + float u2_r = u2 - mpCurrentKeyFrame->mbf*invz2; + float v2 = fy2*y2*invz2+cy2; + float errX2 = u2 - kp2.pt.x; + float errY2 = v2 - kp2.pt.y; + float errX2_r = u2_r - kp2_ur; + if((errX2*errX2+errY2*errY2+errX2_r*errX2_r)>7.8*sigmaSquare2) + continue; + } + + //Check scale consistency + cv::Mat normal1 = x3D-Ow1; + float dist1 = cv::norm(normal1); + + cv::Mat normal2 = x3D-Ow2; + float dist2 = cv::norm(normal2); + + if(dist1==0 || dist2==0) + continue; + + if(mbFarPoints && (dist1>=mThFarPoints||dist2>=mThFarPoints)) // MODIFICATION + continue; + + const float ratioDist = dist2/dist1; + const float ratioOctave = mpCurrentKeyFrame->mvScaleFactors[kp1.octave]/pKF2->mvScaleFactors[kp2.octave]; + + if(ratioDist*ratioFactorratioOctave*ratioFactor) + continue; + + // Triangulation is succesfull + MapPoint* pMP = new MapPoint(x3D,mpCurrentKeyFrame,mpAtlas->GetCurrentMap()); + + pMP->AddObservation(mpCurrentKeyFrame,idx1); + pMP->AddObservation(pKF2,idx2); + + mpCurrentKeyFrame->AddMapPoint(pMP,idx1); + pKF2->AddMapPoint(pMP,idx2); + + pMP->ComputeDistinctiveDescriptors(); + + pMP->UpdateNormalAndDepth(); + + mpAtlas->AddMapPoint(pMP); + mlpRecentAddedMapPoints.push_back(pMP); + } + } +} + + +void LocalMapping::SearchInNeighbors() +{ + // Retrieve neighbor keyframes + int nn = 10; + if(mbMonocular) + nn=20; + const vector vpNeighKFs = mpCurrentKeyFrame->GetBestCovisibilityKeyFrames(nn); + vector vpTargetKFs; + for(vector::const_iterator vit=vpNeighKFs.begin(), vend=vpNeighKFs.end(); vit!=vend; vit++) + { + KeyFrame* pKFi = *vit; + if(pKFi->isBad() || pKFi->mnFuseTargetForKF == mpCurrentKeyFrame->mnId) + continue; + vpTargetKFs.push_back(pKFi); + pKFi->mnFuseTargetForKF = mpCurrentKeyFrame->mnId; + } + + // Add some covisible of covisible + // Extend to some second neighbors if abort is not requested + for(int i=0, imax=vpTargetKFs.size(); i vpSecondNeighKFs = vpTargetKFs[i]->GetBestCovisibilityKeyFrames(20); + for(vector::const_iterator vit2=vpSecondNeighKFs.begin(), vend2=vpSecondNeighKFs.end(); vit2!=vend2; vit2++) + { + KeyFrame* pKFi2 = *vit2; + if(pKFi2->isBad() || pKFi2->mnFuseTargetForKF==mpCurrentKeyFrame->mnId || pKFi2->mnId==mpCurrentKeyFrame->mnId) + continue; + vpTargetKFs.push_back(pKFi2); + pKFi2->mnFuseTargetForKF=mpCurrentKeyFrame->mnId; + } + if (mbAbortBA) + break; + } + + // Extend to temporal neighbors + if(mbInertial) + { + KeyFrame* pKFi = mpCurrentKeyFrame->mPrevKF; + while(vpTargetKFs.size()<20 && pKFi) + { + if(pKFi->isBad() || pKFi->mnFuseTargetForKF==mpCurrentKeyFrame->mnId) + { + pKFi = pKFi->mPrevKF; + continue; + } + vpTargetKFs.push_back(pKFi); + pKFi->mnFuseTargetForKF=mpCurrentKeyFrame->mnId; + pKFi = pKFi->mPrevKF; + } + } + + // Search matches by projection from current KF in target KFs + ORBmatcher matcher; + vector vpMapPointMatches = mpCurrentKeyFrame->GetMapPointMatches(); + for(vector::iterator vit=vpTargetKFs.begin(), vend=vpTargetKFs.end(); vit!=vend; vit++) + { + KeyFrame* pKFi = *vit; + + matcher.Fuse(pKFi,vpMapPointMatches); + if(pKFi->NLeft != -1) matcher.Fuse(pKFi,vpMapPointMatches,true); + } + + if (mbAbortBA) + return; + + // Search matches by projection from target KFs in current KF + vector vpFuseCandidates; + vpFuseCandidates.reserve(vpTargetKFs.size()*vpMapPointMatches.size()); + + for(vector::iterator vitKF=vpTargetKFs.begin(), vendKF=vpTargetKFs.end(); vitKF!=vendKF; vitKF++) + { + KeyFrame* pKFi = *vitKF; + + vector vpMapPointsKFi = pKFi->GetMapPointMatches(); + + for(vector::iterator vitMP=vpMapPointsKFi.begin(), vendMP=vpMapPointsKFi.end(); vitMP!=vendMP; vitMP++) + { + MapPoint* pMP = *vitMP; + if(!pMP) + continue; + if(pMP->isBad() || pMP->mnFuseCandidateForKF == mpCurrentKeyFrame->mnId) + continue; + pMP->mnFuseCandidateForKF = mpCurrentKeyFrame->mnId; + vpFuseCandidates.push_back(pMP); + } + } + + matcher.Fuse(mpCurrentKeyFrame,vpFuseCandidates); + if(mpCurrentKeyFrame->NLeft != -1) matcher.Fuse(mpCurrentKeyFrame,vpFuseCandidates,true); + + + // Update points + vpMapPointMatches = mpCurrentKeyFrame->GetMapPointMatches(); + for(size_t i=0, iend=vpMapPointMatches.size(); iisBad()) + { + pMP->ComputeDistinctiveDescriptors(); + pMP->UpdateNormalAndDepth(); + } + } + } + + // Update connections in covisibility graph + mpCurrentKeyFrame->UpdateConnections(); +} + +cv::Mat LocalMapping::ComputeF12(KeyFrame *&pKF1, KeyFrame *&pKF2) +{ + cv::Mat R1w = pKF1->GetRotation(); + cv::Mat t1w = pKF1->GetTranslation(); + cv::Mat R2w = pKF2->GetRotation(); + cv::Mat t2w = pKF2->GetTranslation(); + + cv::Mat R12 = R1w*R2w.t(); + cv::Mat t12 = -R1w*R2w.t()*t2w+t1w; + + cv::Mat t12x = SkewSymmetricMatrix(t12); + + const cv::Mat &K1 = pKF1->mpCamera->toK(); + const cv::Mat &K2 = pKF2->mpCamera->toK(); + + + return K1.t().inv()*t12x*R12*K2.inv(); +} + +void LocalMapping::RequestStop() +{ + unique_lock lock(mMutexStop); + mbStopRequested = true; + unique_lock lock2(mMutexNewKFs); + mbAbortBA = true; +} + +bool LocalMapping::Stop() +{ + unique_lock lock(mMutexStop); + if(mbStopRequested && !mbNotStop) + { + mbStopped = true; + cout << "Local Mapping STOP" << endl; + return true; + } + + return false; +} + +bool LocalMapping::isStopped() +{ + unique_lock lock(mMutexStop); + return mbStopped; +} + +bool LocalMapping::stopRequested() +{ + unique_lock lock(mMutexStop); + return mbStopRequested; +} + +void LocalMapping::Release() +{ + unique_lock lock(mMutexStop); + unique_lock lock2(mMutexFinish); + if(mbFinished) + return; + mbStopped = false; + mbStopRequested = false; + for(list::iterator lit = mlNewKeyFrames.begin(), lend=mlNewKeyFrames.end(); lit!=lend; lit++) + delete *lit; + mlNewKeyFrames.clear(); + + cout << "Local Mapping RELEASE" << endl; +} + +bool LocalMapping::AcceptKeyFrames() +{ + unique_lock lock(mMutexAccept); + return mbAcceptKeyFrames; +} + +void LocalMapping::SetAcceptKeyFrames(bool flag) +{ + unique_lock lock(mMutexAccept); + mbAcceptKeyFrames=flag; +} + +bool LocalMapping::SetNotStop(bool flag) +{ + unique_lock lock(mMutexStop); + + if(flag && mbStopped) + return false; + + mbNotStop = flag; + + return true; +} + +void LocalMapping::InterruptBA() +{ + mbAbortBA = true; +} + +void LocalMapping::KeyFrameCulling() +{ + // Check redundant keyframes (only local keyframes) + // A keyframe is considered redundant if the 90% of the MapPoints it sees, are seen + // in at least other 3 keyframes (in the same or finer scale) + // We only consider close stereo points + const int Nd = 21; // MODIFICATION_STEREO_IMU 20 This should be the same than that one from LIBA + mpCurrentKeyFrame->UpdateBestCovisibles(); + vector vpLocalKeyFrames = mpCurrentKeyFrame->GetVectorCovisibleKeyFrames(); + + float redundant_th; + if(!mbInertial) + redundant_th = 0.9; + else if (mbMonocular) + redundant_th = 0.9; + else + redundant_th = 0.5; + + const bool bInitImu = mpAtlas->isImuInitialized(); + int count=0; + + // Compoute last KF from optimizable window: + unsigned int last_ID; + if (mbInertial) + { + int count = 0; + KeyFrame* aux_KF = mpCurrentKeyFrame; + while(countmPrevKF) + { + aux_KF = aux_KF->mPrevKF; + count++; + } + last_ID = aux_KF->mnId; + } + + + + for(vector::iterator vit=vpLocalKeyFrames.begin(), vend=vpLocalKeyFrames.end(); vit!=vend; vit++) + { + count++; + KeyFrame* pKF = *vit; + + if((pKF->mnId==pKF->GetMap()->GetInitKFid()) || pKF->isBad()) + continue; + const vector vpMapPoints = pKF->GetMapPointMatches(); + + int nObs = 3; + const int thObs=nObs; + int nRedundantObservations=0; + int nMPs=0; + for(size_t i=0, iend=vpMapPoints.size(); iisBad()) + { + if(!mbMonocular) + { + if(pKF->mvDepth[i]>pKF->mThDepth || pKF->mvDepth[i]<0) + continue; + } + + nMPs++; + if(pMP->Observations()>thObs) + { + const int &scaleLevel = (pKF -> NLeft == -1) ? pKF->mvKeysUn[i].octave + : (i < pKF -> NLeft) ? pKF -> mvKeys[i].octave + : pKF -> mvKeysRight[i].octave; + const map> observations = pMP->GetObservations(); + int nObs=0; + for(map>::const_iterator mit=observations.begin(), mend=observations.end(); mit!=mend; mit++) + { + KeyFrame* pKFi = mit->first; + if(pKFi==pKF) + continue; + tuple indexes = mit->second; + int leftIndex = get<0>(indexes), rightIndex = get<1>(indexes); + int scaleLeveli = -1; + if(pKFi -> NLeft == -1) + scaleLeveli = pKFi->mvKeysUn[leftIndex].octave; + else { + if (leftIndex != -1) { + scaleLeveli = pKFi->mvKeys[leftIndex].octave; + } + if (rightIndex != -1) { + int rightLevel = pKFi->mvKeysRight[rightIndex - pKFi->NLeft].octave; + scaleLeveli = (scaleLeveli == -1 || scaleLeveli > rightLevel) ? rightLevel + : scaleLeveli; + } + } + + if(scaleLeveli<=scaleLevel+1) + { + nObs++; + if(nObs>thObs) + break; + } + } + if(nObs>thObs) + { + nRedundantObservations++; + } + } + } + } + } + + if(nRedundantObservations>redundant_th*nMPs) + { + if (mbInertial) + { + if (mpAtlas->KeyFramesInMap()<=Nd) + continue; + + if(pKF->mnId>(mpCurrentKeyFrame->mnId-2)) + continue; + + if(pKF->mPrevKF && pKF->mNextKF) + { + const float t = pKF->mNextKF->mTimeStamp-pKF->mPrevKF->mTimeStamp; + + if((bInitImu && (pKF->mnIdmNextKF->mpImuPreintegrated->MergePrevious(pKF->mpImuPreintegrated); + pKF->mNextKF->mPrevKF = pKF->mPrevKF; + pKF->mPrevKF->mNextKF = pKF->mNextKF; + pKF->mNextKF = NULL; + pKF->mPrevKF = NULL; + pKF->SetBadFlag(); + } + else if(!mpCurrentKeyFrame->GetMap()->GetIniertialBA2() && (cv::norm(pKF->GetImuPosition()-pKF->mPrevKF->GetImuPosition())<0.02) && (t<3)) + { + pKF->mNextKF->mpImuPreintegrated->MergePrevious(pKF->mpImuPreintegrated); + pKF->mNextKF->mPrevKF = pKF->mPrevKF; + pKF->mPrevKF->mNextKF = pKF->mNextKF; + pKF->mNextKF = NULL; + pKF->mPrevKF = NULL; + pKF->SetBadFlag(); + } + } + } + else + { + pKF->SetBadFlag(); + } + } + if((count > 20 && mbAbortBA) || count>100) // MODIFICATION originally 20 for mbabortBA check just 10 keyframes + { + break; + } + } +} + + +cv::Mat LocalMapping::SkewSymmetricMatrix(const cv::Mat &v) +{ + return (cv::Mat_(3,3) << 0, -v.at(2), v.at(1), + v.at(2), 0,-v.at(0), + -v.at(1), v.at(0), 0); +} + +void LocalMapping::RequestReset() +{ + { + unique_lock lock(mMutexReset); + cout << "LM: Map reset recieved" << endl; + mbResetRequested = true; + } + cout << "LM: Map reset, waiting..." << endl; + + while(1) + { + { + unique_lock lock2(mMutexReset); + if(!mbResetRequested) + break; + } + usleep(3000); + } + cout << "LM: Map reset, Done!!!" << endl; +} + +void LocalMapping::RequestResetActiveMap(Map* pMap) +{ + { + unique_lock lock(mMutexReset); + cout << "LM: Active map reset recieved" << endl; + mbResetRequestedActiveMap = true; + mpMapToReset = pMap; + } + cout << "LM: Active map reset, waiting..." << endl; + + while(1) + { + { + unique_lock lock2(mMutexReset); + if(!mbResetRequestedActiveMap) + break; + } + usleep(3000); + } + cout << "LM: Active map reset, Done!!!" << endl; +} + +void LocalMapping::ResetIfRequested() +{ + bool executed_reset = false; + { + unique_lock lock(mMutexReset); + if(mbResetRequested) + { + executed_reset = true; + + cout << "LM: Reseting Atlas in Local Mapping..." << endl; + mlNewKeyFrames.clear(); + mlpRecentAddedMapPoints.clear(); + mbResetRequested=false; + mbResetRequestedActiveMap = false; + + // Inertial parameters + mTinit = 0.f; + mbNotBA2 = true; + mbNotBA1 = true; + mbBadImu=false; + + mIdxInit=0; + + cout << "LM: End reseting Local Mapping..." << endl; + } + + if(mbResetRequestedActiveMap) { + executed_reset = true; + cout << "LM: Reseting current map in Local Mapping..." << endl; + mlNewKeyFrames.clear(); + mlpRecentAddedMapPoints.clear(); + + // Inertial parameters + mTinit = 0.f; + mbNotBA2 = true; + mbNotBA1 = true; + mbBadImu=false; + + mbResetRequestedActiveMap = false; + cout << "LM: End reseting Local Mapping..." << endl; + } + } + if(executed_reset) + cout << "LM: Reset free the mutex" << endl; + +} + +void LocalMapping::RequestFinish() +{ + unique_lock lock(mMutexFinish); + mbFinishRequested = true; +} + +bool LocalMapping::CheckFinish() +{ + unique_lock lock(mMutexFinish); + return mbFinishRequested; +} + +void LocalMapping::SetFinish() +{ + unique_lock lock(mMutexFinish); + mbFinished = true; + unique_lock lock2(mMutexStop); + mbStopped = true; +} + +bool LocalMapping::isFinished() +{ + unique_lock lock(mMutexFinish); + return mbFinished; +} + +void LocalMapping::InitializeIMU(float priorG, float priorA, bool bFIBA) +{ + if (mbResetRequested) + return; + + float minTime; + int nMinKF; + if (mbMonocular) + { + minTime = 2.0; + nMinKF = 10; + } + else + { + minTime = 1.0; + nMinKF = 10; + } + + + if(mpAtlas->KeyFramesInMap() lpKF; + KeyFrame* pKF = mpCurrentKeyFrame; + while(pKF->mPrevKF) + { + lpKF.push_front(pKF); + pKF = pKF->mPrevKF; + } + lpKF.push_front(pKF); + vector vpKF(lpKF.begin(),lpKF.end()); + + if(vpKF.size()mTimeStamp; + if(mpCurrentKeyFrame->mTimeStamp-mFirstTsGetMap()->isImuInitialized()) + { + cv::Mat cvRwg; + cv::Mat dirG = cv::Mat::zeros(3,1,CV_32F); + for(vector::iterator itKF = vpKF.begin(); itKF!=vpKF.end(); itKF++) + { + if (!(*itKF)->mpImuPreintegrated) + continue; + if (!(*itKF)->mPrevKF) + continue; + + dirG -= (*itKF)->mPrevKF->GetImuRotation()*(*itKF)->mpImuPreintegrated->GetUpdatedDeltaVelocity(); + cv::Mat _vel = ((*itKF)->GetImuPosition() - (*itKF)->mPrevKF->GetImuPosition())/(*itKF)->mpImuPreintegrated->dT; + (*itKF)->SetVelocity(_vel); + (*itKF)->mPrevKF->SetVelocity(_vel); + } + + dirG = dirG/cv::norm(dirG); + cv::Mat gI = (cv::Mat_(3,1) << 0.0f, 0.0f, -1.0f); + cv::Mat v = gI.cross(dirG); + const float nv = cv::norm(v); + const float cosg = gI.dot(dirG); + const float ang = acos(cosg); + cv::Mat vzg = v*ang/nv; + cvRwg = IMU::ExpSO3(vzg); + mRwg = Converter::toMatrix3d(cvRwg); + mTinit = mpCurrentKeyFrame->mTimeStamp-mFirstTs; + } + else + { + mRwg = Eigen::Matrix3d::Identity(); + mbg = Converter::toVector3d(mpCurrentKeyFrame->GetGyroBias()); + mba = Converter::toVector3d(mpCurrentKeyFrame->GetAccBias()); + } + + mScale=1.0; + + mInitTime = mpTracker->mLastFrame.mTimeStamp-vpKF.front()->mTimeStamp; + + std::chrono::steady_clock::time_point t0 = std::chrono::steady_clock::now(); + Optimizer::InertialOptimization(mpAtlas->GetCurrentMap(), mRwg, mScale, mbg, mba, mbMonocular, infoInertial, false, false, priorG, priorA); + std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now(); + + /*cout << "scale after inertial-only optimization: " << mScale << endl; + cout << "bg after inertial-only optimization: " << mbg << endl; + cout << "ba after inertial-only optimization: " << mba << endl;*/ + + + if (mScale<1e-1) + { + cout << "scale too small" << endl; + bInitializing=false; + return; + } + + + + // Before this line we are not changing the map + + unique_lock lock(mpAtlas->GetCurrentMap()->mMutexMapUpdate); + std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now(); + if ((fabs(mScale-1.f)>0.00001)||!mbMonocular) + { + mpAtlas->GetCurrentMap()->ApplyScaledRotation(Converter::toCvMat(mRwg).t(),mScale,true); + mpTracker->UpdateFrameIMU(mScale,vpKF[0]->GetImuBias(),mpCurrentKeyFrame); + } + std::chrono::steady_clock::time_point t3 = std::chrono::steady_clock::now(); + + // Check if initialization OK + if (!mpAtlas->isImuInitialized()) + for(int i=0;ibImu = true; + } + + /*cout << "Before GIBA: " << endl; + cout << "ba: " << mpCurrentKeyFrame->GetAccBias() << endl; + cout << "bg: " << mpCurrentKeyFrame->GetGyroBias() << endl;*/ + + std::chrono::steady_clock::time_point t4 = std::chrono::steady_clock::now(); + if (bFIBA) + { + if (priorA!=0.f) + Optimizer::FullInertialBA(mpAtlas->GetCurrentMap(), 100, false, 0, NULL, true, priorG, priorA); + else + Optimizer::FullInertialBA(mpAtlas->GetCurrentMap(), 100, false, 0, NULL, false); + } + + std::chrono::steady_clock::time_point t5 = std::chrono::steady_clock::now(); + + // If initialization is OK + mpTracker->UpdateFrameIMU(1.0,vpKF[0]->GetImuBias(),mpCurrentKeyFrame); + if (!mpAtlas->isImuInitialized()) + { + cout << "IMU in Map " << mpAtlas->GetCurrentMap()->GetId() << " is initialized" << endl; + mpAtlas->SetImuInitialized(); + mpTracker->t0IMU = mpTracker->mCurrentFrame.mTimeStamp; + mpCurrentKeyFrame->bImu = true; + } + + + mbNewInit=true; + mnKFs=vpKF.size(); + mIdxInit++; + + for(list::iterator lit = mlNewKeyFrames.begin(), lend=mlNewKeyFrames.end(); lit!=lend; lit++) + { + (*lit)->SetBadFlag(); + delete *lit; + } + mlNewKeyFrames.clear(); + + mpTracker->mState=Tracking::OK; + bInitializing = false; + + + /*cout << "After GIBA: " << endl; + cout << "ba: " << mpCurrentKeyFrame->GetAccBias() << endl; + cout << "bg: " << mpCurrentKeyFrame->GetGyroBias() << endl; + double t_inertial_only = std::chrono::duration_cast >(t1 - t0).count(); + double t_update = std::chrono::duration_cast >(t3 - t2).count(); + double t_viba = std::chrono::duration_cast >(t5 - t4).count(); + cout << t_inertial_only << ", " << t_update << ", " << t_viba << endl;*/ + + mpCurrentKeyFrame->GetMap()->IncreaseChangeIndex(); + + return; +} + +void LocalMapping::ScaleRefinement() +{ + // Minimum number of keyframes to compute a solution + // Minimum time (seconds) between first and last keyframe to compute a solution. Make the difference between monocular and stereo + // unique_lock lock0(mMutexImuInit); + if (mbResetRequested) + return; + + // Retrieve all keyframes in temporal order + list lpKF; + KeyFrame* pKF = mpCurrentKeyFrame; + while(pKF->mPrevKF) + { + lpKF.push_front(pKF); + pKF = pKF->mPrevKF; + } + lpKF.push_front(pKF); + vector vpKF(lpKF.begin(),lpKF.end()); + + while(CheckNewKeyFrames()) + { + ProcessNewKeyFrame(); + vpKF.push_back(mpCurrentKeyFrame); + lpKF.push_back(mpCurrentKeyFrame); + } + + const int N = vpKF.size(); + + mRwg = Eigen::Matrix3d::Identity(); + mScale=1.0; + + std::chrono::steady_clock::time_point t0 = std::chrono::steady_clock::now(); + Optimizer::InertialOptimization(mpAtlas->GetCurrentMap(), mRwg, mScale); + std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now(); + + if (mScale<1e-1) // 1e-1 + { + cout << "scale too small" << endl; + bInitializing=false; + return; + } + + // Before this line we are not changing the map + unique_lock lock(mpAtlas->GetCurrentMap()->mMutexMapUpdate); + std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now(); + if ((fabs(mScale-1.f)>0.00001)||!mbMonocular) + { + mpAtlas->GetCurrentMap()->ApplyScaledRotation(Converter::toCvMat(mRwg).t(),mScale,true); + mpTracker->UpdateFrameIMU(mScale,mpCurrentKeyFrame->GetImuBias(),mpCurrentKeyFrame); + } + std::chrono::steady_clock::time_point t3 = std::chrono::steady_clock::now(); + + for(list::iterator lit = mlNewKeyFrames.begin(), lend=mlNewKeyFrames.end(); lit!=lend; lit++) + { + (*lit)->SetBadFlag(); + delete *lit; + } + mlNewKeyFrames.clear(); + + double t_inertial_only = std::chrono::duration_cast >(t1 - t0).count(); + + // To perform pose-inertial opt w.r.t. last keyframe + mpCurrentKeyFrame->GetMap()->IncreaseChangeIndex(); + + return; +} + + + +bool LocalMapping::IsInitializing() +{ + return bInitializing; +} + + +double LocalMapping::GetCurrKFTime() +{ + + if (mpCurrentKeyFrame) + { + return mpCurrentKeyFrame->mTimeStamp; + } + else + return 0.0; +} + +KeyFrame* LocalMapping::GetCurrKF() +{ + return mpCurrentKeyFrame; +} + +} //namespace ORB_SLAM diff --git a/third_party/ORB_SLAM3/src/LoopClosing.cc b/third_party/ORB_SLAM3/src/LoopClosing.cc new file mode 100644 index 0000000..e0b54fb --- /dev/null +++ b/third_party/ORB_SLAM3/src/LoopClosing.cc @@ -0,0 +1,2680 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + + +#include "LoopClosing.h" + +#include "Sim3Solver.h" +#include "Converter.h" +#include "Optimizer.h" +#include "ORBmatcher.h" +#include "G2oTypes.h" + +#include +#include + +#include +#include + + +namespace ORB_SLAM3 +{ + +LoopClosing::LoopClosing(Atlas *pAtlas, KeyFrameDatabase *pDB, ORBVocabulary *pVoc, const bool bFixScale): + mbResetRequested(false), mbResetActiveMapRequested(false), mbFinishRequested(false), mbFinished(true), mpAtlas(pAtlas), + mpKeyFrameDB(pDB), mpORBVocabulary(pVoc), mpMatchedKF(NULL), mLastLoopKFid(0), mbRunningGBA(false), mbFinishedGBA(true), + mbStopGBA(false), mpThreadGBA(NULL), mbFixScale(bFixScale), mnFullBAIdx(0), mnLoopNumCoincidences(0), mnMergeNumCoincidences(0), + mbLoopDetected(false), mbMergeDetected(false), mnLoopNumNotFound(0), mnMergeNumNotFound(0) +{ + mnCovisibilityConsistencyTh = 3; + mpLastCurrentKF = static_cast(NULL); +} + +void LoopClosing::SetTracker(Tracking *pTracker) +{ + mpTracker=pTracker; +} + +void LoopClosing::SetLocalMapper(LocalMapping *pLocalMapper) +{ + mpLocalMapper=pLocalMapper; +} + + +void LoopClosing::Run() +{ + mbFinished =false; + + while(1) + { + //NEW LOOP AND MERGE DETECTION ALGORITHM + //---------------------------- + if(CheckNewKeyFrames()) + { + if(mpLastCurrentKF) + { + mpLastCurrentKF->mvpLoopCandKFs.clear(); + mpLastCurrentKF->mvpMergeCandKFs.clear(); + } + if(NewDetectCommonRegions()) + { + if(mbMergeDetected) + { + if ((mpTracker->mSensor==System::IMU_MONOCULAR ||mpTracker->mSensor==System::IMU_STEREO) && + (!mpCurrentKF->GetMap()->isImuInitialized())) + { + cout << "IMU is not initilized, merge is aborted" << endl; + } + else + { + Verbose::PrintMess("*Merged detected", Verbose::VERBOSITY_QUIET); + Verbose::PrintMess("Number of KFs in the current map: " + to_string(mpCurrentKF->GetMap()->KeyFramesInMap()), Verbose::VERBOSITY_DEBUG); + cv::Mat mTmw = mpMergeMatchedKF->GetPose(); + g2o::Sim3 gSmw2(Converter::toMatrix3d(mTmw.rowRange(0, 3).colRange(0, 3)),Converter::toVector3d(mTmw.rowRange(0, 3).col(3)),1.0); + cv::Mat mTcw = mpCurrentKF->GetPose(); + g2o::Sim3 gScw1(Converter::toMatrix3d(mTcw.rowRange(0, 3).colRange(0, 3)),Converter::toVector3d(mTcw.rowRange(0, 3).col(3)),1.0); + g2o::Sim3 gSw2c = mg2oMergeSlw.inverse(); + g2o::Sim3 gSw1m = mg2oMergeSlw; + + mSold_new = (gSw2c * gScw1); + + if(mpCurrentKF->GetMap()->IsInertial() && mpMergeMatchedKF->GetMap()->IsInertial()) + { + if(mSold_new.scale()<0.90||mSold_new.scale()>1.1){ + mpMergeLastCurrentKF->SetErase(); + mpMergeMatchedKF->SetErase(); + mnMergeNumCoincidences = 0; + mvpMergeMatchedMPs.clear(); + mvpMergeMPs.clear(); + mnMergeNumNotFound = 0; + mbMergeDetected = false; + Verbose::PrintMess("scale bad estimated. Abort merging", Verbose::VERBOSITY_NORMAL); + continue; + } + // If inertial, force only yaw + if ((mpTracker->mSensor==System::IMU_MONOCULAR ||mpTracker->mSensor==System::IMU_STEREO) && + mpCurrentKF->GetMap()->GetIniertialBA1()) // TODO, maybe with GetIniertialBA1 + { + Eigen::Vector3d phi = LogSO3(mSold_new.rotation().toRotationMatrix()); + phi(0)=0; + phi(1)=0; + mSold_new = g2o::Sim3(ExpSO3(phi),mSold_new.translation(),1.0); + } + } + + +// cout << "tw2w1: " << mSold_new.translation() << endl; +// cout << "Rw2w1: " << mSold_new.rotation().toRotationMatrix() << endl; +// cout << "Angle Rw2w1: " << 180*LogSO3(mSold_new.rotation().toRotationMatrix())/3.14 << endl; +// cout << "scale w2w1: " << mSold_new.scale() << endl; + + mg2oMergeSmw = gSmw2 * gSw2c * gScw1; + + mg2oMergeScw = mg2oMergeSlw; + + // TODO UNCOMMENT + if (mpTracker->mSensor==System::IMU_MONOCULAR ||mpTracker->mSensor==System::IMU_STEREO) + MergeLocal2(); + else + MergeLocal(); + } + + vdPR_CurrentTime.push_back(mpCurrentKF->mTimeStamp); + vdPR_MatchedTime.push_back(mpMergeMatchedKF->mTimeStamp); + vnPR_TypeRecogn.push_back(1); + + // Reset all variables + mpMergeLastCurrentKF->SetErase(); + mpMergeMatchedKF->SetErase(); + mnMergeNumCoincidences = 0; + mvpMergeMatchedMPs.clear(); + mvpMergeMPs.clear(); + mnMergeNumNotFound = 0; + mbMergeDetected = false; + + if(mbLoopDetected) + { + // Reset Loop variables + mpLoopLastCurrentKF->SetErase(); + mpLoopMatchedKF->SetErase(); + mnLoopNumCoincidences = 0; + mvpLoopMatchedMPs.clear(); + mvpLoopMPs.clear(); + mnLoopNumNotFound = 0; + mbLoopDetected = false; + } + + } + + if(mbLoopDetected) + { + vdPR_CurrentTime.push_back(mpCurrentKF->mTimeStamp); + vdPR_MatchedTime.push_back(mpLoopMatchedKF->mTimeStamp); + vnPR_TypeRecogn.push_back(0); + + + Verbose::PrintMess("*Loop detected", Verbose::VERBOSITY_QUIET); + + mg2oLoopScw = mg2oLoopSlw; //*mvg2oSim3LoopTcw[nCurrentIndex]; + if(mpCurrentKF->GetMap()->IsInertial()) + { + cv::Mat Twc = mpCurrentKF->GetPoseInverse(); + g2o::Sim3 g2oTwc(Converter::toMatrix3d(Twc.rowRange(0, 3).colRange(0, 3)),Converter::toVector3d(Twc.rowRange(0, 3).col(3)),1.0); + g2o::Sim3 g2oSww_new = g2oTwc*mg2oLoopScw; + + Eigen::Vector3d phi = LogSO3(g2oSww_new.rotation().toRotationMatrix()); + //cout << "tw2w1: " << g2oSww_new.translation() << endl; + //cout << "Rw2w1: " << g2oSww_new.rotation().toRotationMatrix() << endl; + //cout << "Angle Rw2w1: " << 180*phi/3.14 << endl; + //cout << "scale w2w1: " << g2oSww_new.scale() << endl; + + if (fabs(phi(0))<0.008f && fabs(phi(1))<0.008f && fabs(phi(2))<0.349f) + { + if(mpCurrentKF->GetMap()->IsInertial()) + { + // If inertial, force only yaw + if ((mpTracker->mSensor==System::IMU_MONOCULAR ||mpTracker->mSensor==System::IMU_STEREO) && + mpCurrentKF->GetMap()->GetIniertialBA2()) // TODO, maybe with GetIniertialBA1 + { + phi(0)=0; + phi(1)=0; + g2oSww_new = g2o::Sim3(ExpSO3(phi),g2oSww_new.translation(),1.0); + mg2oLoopScw = g2oTwc.inverse()*g2oSww_new; + } + } + + mvpLoopMapPoints = mvpLoopMPs;//*mvvpLoopMapPoints[nCurrentIndex]; + CorrectLoop(); + } + else + { + cout << "BAD LOOP!!!" << endl; + } + } + else + { + mvpLoopMapPoints = mvpLoopMPs; + CorrectLoop(); + } + + // Reset all variables + mpLoopLastCurrentKF->SetErase(); + mpLoopMatchedKF->SetErase(); + mnLoopNumCoincidences = 0; + mvpLoopMatchedMPs.clear(); + mvpLoopMPs.clear(); + mnLoopNumNotFound = 0; + mbLoopDetected = false; + } + + } + mpLastCurrentKF = mpCurrentKF; + } + + ResetIfRequested(); + + if(CheckFinish()){ + // cout << "LC: Finish requested" << endl; + break; + } + + usleep(5000); + } + + //ofstream f_stats; + //f_stats.open("PlaceRecognition_stats" + mpLocalMapper->strSequence + ".txt"); + //f_stats << "# current_timestamp, matched_timestamp, [0:Loop, 1:Merge]" << endl; + //f_stats << fixed; + //for(int i=0; i< vdPR_CurrentTime.size(); ++i) + //{ + // f_stats << 1e9*vdPR_CurrentTime[i] << "," << 1e9*vdPR_MatchedTime[i] << "," << vnPR_TypeRecogn[i] << endl; + //} + + //f_stats.close(); + + SetFinish(); +} + +void LoopClosing::InsertKeyFrame(KeyFrame *pKF) +{ + unique_lock lock(mMutexLoopQueue); + if(pKF->mnId!=0) + mlpLoopKeyFrameQueue.push_back(pKF); +} + +bool LoopClosing::CheckNewKeyFrames() +{ + unique_lock lock(mMutexLoopQueue); + return(!mlpLoopKeyFrameQueue.empty()); +} + +bool LoopClosing::NewDetectCommonRegions() +{ + { + unique_lock lock(mMutexLoopQueue); + mpCurrentKF = mlpLoopKeyFrameQueue.front(); + mlpLoopKeyFrameQueue.pop_front(); + // Avoid that a keyframe can be erased while it is being process by this thread + mpCurrentKF->SetNotErase(); + mpCurrentKF->mbCurrentPlaceRecognition = true; + + mpLastMap = mpCurrentKF->GetMap(); + } + + if(mpLastMap->IsInertial() && !mpLastMap->GetIniertialBA1()) + { + mpKeyFrameDB->add(mpCurrentKF); + mpCurrentKF->SetErase(); + return false; + } + + if(mpTracker->mSensor == System::STEREO && mpLastMap->GetAllKeyFrames().size() < 5) //12 + { + mpKeyFrameDB->add(mpCurrentKF); + mpCurrentKF->SetErase(); + return false; + } + + if(mpLastMap->GetAllKeyFrames().size() < 12) + { + mpKeyFrameDB->add(mpCurrentKF); + mpCurrentKF->SetErase(); + return false; + } + + //Check the last candidates with geometric validation + // Loop candidates + bool bLoopDetectedInKF = false; + bool bCheckSpatial = false; + + if(mnLoopNumCoincidences > 0) + { + bCheckSpatial = true; + // Find from the last KF candidates + cv::Mat mTcl = mpCurrentKF->GetPose() * mpLoopLastCurrentKF->GetPoseInverse(); + g2o::Sim3 gScl(Converter::toMatrix3d(mTcl.rowRange(0, 3).colRange(0, 3)),Converter::toVector3d(mTcl.rowRange(0, 3).col(3)),1.0); + g2o::Sim3 gScw = gScl * mg2oLoopSlw; + int numProjMatches = 0; + vector vpMatchedMPs; + bool bCommonRegion = DetectAndReffineSim3FromLastKF(mpCurrentKF, mpLoopMatchedKF, gScw, numProjMatches, mvpLoopMPs, vpMatchedMPs); + if(bCommonRegion) + { + + bLoopDetectedInKF = true; + + mnLoopNumCoincidences++; + mpLoopLastCurrentKF->SetErase(); + mpLoopLastCurrentKF = mpCurrentKF; + mg2oLoopSlw = gScw; + mvpLoopMatchedMPs = vpMatchedMPs; + + + mbLoopDetected = mnLoopNumCoincidences >= 3; + mnLoopNumNotFound = 0; + + if(!mbLoopDetected) + { + //f_succes_pr << mpCurrentKF->mNameFile << " " << "8"<< endl; + //f_succes_pr << "% Number of spatial consensous: " << std::to_string(mnLoopNumCoincidences) << endl; + cout << "PR: Loop detected with Reffine Sim3" << endl; + } + } + else + { + bLoopDetectedInKF = false; + /*f_succes_pr << mpCurrentKF->mNameFile << " " << "8"<< endl; + f_succes_pr << "% Number of spatial consensous: " << std::to_string(mnLoopNumCoincidences) << endl;*/ + + mnLoopNumNotFound++; + if(mnLoopNumNotFound >= 2) + { + /*for(int i=0; iSetErase(); + mvpLoopCandidateKF[i]->SetErase(); + mvpLoopLastKF[i]->mbCurrentPlaceRecognition = true; + } + + mvpLoopCandidateKF.clear(); + mvpLoopLastKF.clear(); + mvg2oSim3LoopTcw.clear(); + mvnLoopNumMatches.clear(); + mvvpLoopMapPoints.clear(); + mvvpLoopMatchedMapPoints.clear();*/ + + mpLoopLastCurrentKF->SetErase(); + mpLoopMatchedKF->SetErase(); + //mg2oLoopScw; + mnLoopNumCoincidences = 0; + mvpLoopMatchedMPs.clear(); + mvpLoopMPs.clear(); + mnLoopNumNotFound = 0; + } + + } + } + + //Merge candidates + bool bMergeDetectedInKF = false; + if(mnMergeNumCoincidences > 0) + { + // Find from the last KF candidates + + cv::Mat mTcl = mpCurrentKF->GetPose() * mpMergeLastCurrentKF->GetPoseInverse(); + g2o::Sim3 gScl(Converter::toMatrix3d(mTcl.rowRange(0, 3).colRange(0, 3)),Converter::toVector3d(mTcl.rowRange(0, 3).col(3)),1.0); + g2o::Sim3 gScw = gScl * mg2oMergeSlw; + int numProjMatches = 0; + vector vpMatchedMPs; + bool bCommonRegion = DetectAndReffineSim3FromLastKF(mpCurrentKF, mpMergeMatchedKF, gScw, numProjMatches, mvpMergeMPs, vpMatchedMPs); + if(bCommonRegion) + { + //cout << "BoW: Merge reffined Sim3 transformation suscelful" << endl; + bMergeDetectedInKF = true; + + mnMergeNumCoincidences++; + mpMergeLastCurrentKF->SetErase(); + mpMergeLastCurrentKF = mpCurrentKF; + mg2oMergeSlw = gScw; + mvpMergeMatchedMPs = vpMatchedMPs; + + mbMergeDetected = mnMergeNumCoincidences >= 3; + } + else + { + //cout << "BoW: Merge reffined Sim3 transformation failed" << endl; + mbMergeDetected = false; + bMergeDetectedInKF = false; + + mnMergeNumNotFound++; + if(mnMergeNumNotFound >= 2) + { + /*cout << "+++++++Merge detected failed in KF" << endl; + + for(int i=0; iSetErase(); + mvpMergeCandidateKF[i]->SetErase(); + mvpMergeLastKF[i]->mbCurrentPlaceRecognition = true; + } + + mvpMergeCandidateKF.clear(); + mvpMergeLastKF.clear(); + mvg2oSim3MergeTcw.clear(); + mvnMergeNumMatches.clear(); + mvvpMergeMapPoints.clear(); + mvvpMergeMatchedMapPoints.clear();*/ + + mpMergeLastCurrentKF->SetErase(); + mpMergeMatchedKF->SetErase(); + mnMergeNumCoincidences = 0; + mvpMergeMatchedMPs.clear(); + mvpMergeMPs.clear(); + mnMergeNumNotFound = 0; + } + + + } + } + + if(mbMergeDetected || mbLoopDetected) + { + //f_time_pr << "Geo" << " " << timeGeoKF_ms.count() << endl; + mpKeyFrameDB->add(mpCurrentKF); + return true; + } + + //------------- + //TODO: This is only necessary if we use a minimun score for pick the best candidates + const vector vpConnectedKeyFrames = mpCurrentKF->GetVectorCovisibleKeyFrames(); + const DBoW2::BowVector &CurrentBowVec = mpCurrentKF->mBowVec; + /*float minScore = 1; + for(size_t i=0; iisBad()) + continue; + const DBoW2::BowVector &BowVec = pKF->mBowVec; + + float score = mpORBVocabulary->score(CurrentBowVec, BowVec); + + if(score vpMergeBowCand, vpLoopBowCand; + //cout << "LC: bMergeDetectedInKF: " << bMergeDetectedInKF << " bLoopDetectedInKF: " << bLoopDetectedInKF << endl; + if(!bMergeDetectedInKF || !bLoopDetectedInKF) + { + // Search in BoW + mpKeyFrameDB->DetectNBestCandidates(mpCurrentKF, vpLoopBowCand, vpMergeBowCand,3); + } + + // Check the BoW candidates if the geometric candidate list is empty + //Loop candidates +/*#ifdef COMPILEDWITHC11 + std::chrono::steady_clock::time_point timeStartGeoBoW = std::chrono::steady_clock::now(); +#else + std::chrono::monotonic_clock::time_point timeStartGeoBoW = std::chrono::monotonic_clock::now(); +#endif*/ + + if(!bLoopDetectedInKF && !vpLoopBowCand.empty()) + { + mbLoopDetected = DetectCommonRegionsFromBoW(vpLoopBowCand, mpLoopMatchedKF, mpLoopLastCurrentKF, mg2oLoopSlw, mnLoopNumCoincidences, mvpLoopMPs, mvpLoopMatchedMPs); + } + // Merge candidates + + //cout << "LC: Find BoW candidates" << endl; + + if(!bMergeDetectedInKF && !vpMergeBowCand.empty()) + { + mbMergeDetected = DetectCommonRegionsFromBoW(vpMergeBowCand, mpMergeMatchedKF, mpMergeLastCurrentKF, mg2oMergeSlw, mnMergeNumCoincidences, mvpMergeMPs, mvpMergeMatchedMPs); + } + + //cout << "LC: add to KFDB" << endl; + mpKeyFrameDB->add(mpCurrentKF); + + if(mbMergeDetected || mbLoopDetected) + { + return true; + } + + //cout << "LC: erase KF" << endl; + mpCurrentKF->SetErase(); + mpCurrentKF->mbCurrentPlaceRecognition = false; + + return false; +} + +bool LoopClosing::DetectAndReffineSim3FromLastKF(KeyFrame* pCurrentKF, KeyFrame* pMatchedKF, g2o::Sim3 &gScw, int &nNumProjMatches, + std::vector &vpMPs, std::vector &vpMatchedMPs) +{ + set spAlreadyMatchedMPs; + nNumProjMatches = FindMatchesByProjection(pCurrentKF, pMatchedKF, gScw, spAlreadyMatchedMPs, vpMPs, vpMatchedMPs); + cout << "REFFINE-SIM3: Projection from last KF with " << nNumProjMatches << " matches" << endl; + + + int nProjMatches = 30; + int nProjOptMatches = 50; + int nProjMatchesRep = 100; + + /*if(mpTracker->mSensor==System::IMU_MONOCULAR ||mpTracker->mSensor==System::IMU_STEREO) + { + nProjMatches = 50; + nProjOptMatches = 50; + nProjMatchesRep = 80; + }*/ + + if(nNumProjMatches >= nProjMatches) + { + cv::Mat mScw = Converter::toCvMat(gScw); + cv::Mat mTwm = pMatchedKF->GetPoseInverse(); + g2o::Sim3 gSwm(Converter::toMatrix3d(mTwm.rowRange(0, 3).colRange(0, 3)),Converter::toVector3d(mTwm.rowRange(0, 3).col(3)),1.0); + g2o::Sim3 gScm = gScw * gSwm; + Eigen::Matrix mHessian7x7; + + bool bFixedScale = mbFixScale; // TODO CHECK; Solo para el monocular inertial + if(mpTracker->mSensor==System::IMU_MONOCULAR && !pCurrentKF->GetMap()->GetIniertialBA2()) + bFixedScale=false; + int numOptMatches = Optimizer::OptimizeSim3(mpCurrentKF, pMatchedKF, vpMatchedMPs, gScm, 10, bFixedScale, mHessian7x7, true); + cout << "REFFINE-SIM3: Optimize Sim3 from last KF with " << numOptMatches << " inliers" << endl; + + + + if(numOptMatches > nProjOptMatches) + { + g2o::Sim3 gScw_estimation(Converter::toMatrix3d(mScw.rowRange(0, 3).colRange(0, 3)), + Converter::toVector3d(mScw.rowRange(0, 3).col(3)),1.0); + + vector vpMatchedMP; + vpMatchedMP.resize(mpCurrentKF->GetMapPointMatches().size(), static_cast(NULL)); + + nNumProjMatches = FindMatchesByProjection(pCurrentKF, pMatchedKF, gScw_estimation, spAlreadyMatchedMPs, vpMPs, vpMatchedMPs); + //cout << "REFFINE-SIM3: Projection with optimize Sim3 from last KF with " << nNumProjMatches << " matches" << endl; + if(nNumProjMatches >= nProjMatchesRep) + { + gScw = gScw_estimation; + return true; + } + } + } + return false; +} + +bool LoopClosing::DetectCommonRegionsFromBoW(std::vector &vpBowCand, KeyFrame* &pMatchedKF2, KeyFrame* &pLastCurrentKF, g2o::Sim3 &g2oScw, + int &nNumCoincidences, std::vector &vpMPs, std::vector &vpMatchedMPs) +{ + int nBoWMatches = 20; + int nBoWInliers = 15; + int nSim3Inliers = 20; + int nProjMatches = 50; + int nProjOptMatches = 80; + /*if(mpTracker->mSensor==System::IMU_MONOCULAR ||mpTracker->mSensor==System::IMU_STEREO) + { + nBoWMatches = 20; + nBoWInliers = 15; + nSim3Inliers = 20; + nProjMatches = 35; + nProjOptMatches = 50; + }*/ + + set spConnectedKeyFrames = mpCurrentKF->GetConnectedKeyFrames(); + + int nNumCovisibles = 5; + + ORBmatcher matcherBoW(0.9, true); + ORBmatcher matcher(0.75, true); + int nNumGuidedMatching = 0; + + // Varibles to select the best numbe + KeyFrame* pBestMatchedKF; + int nBestMatchesReproj = 0; + int nBestNumCoindicendes = 0; + g2o::Sim3 g2oBestScw; + std::vector vpBestMapPoints; + std::vector vpBestMatchedMapPoints; + + int numCandidates = vpBowCand.size(); + vector vnStage(numCandidates, 0); + vector vnMatchesStage(numCandidates, 0); + + int index = 0; + for(KeyFrame* pKFi : vpBowCand) + { + //cout << endl << "-------------------------------" << endl; + if(!pKFi || pKFi->isBad()) + continue; + + + // Current KF against KF with covisibles version + std::vector vpCovKFi = pKFi->GetBestCovisibilityKeyFrames(nNumCovisibles); + vpCovKFi.push_back(vpCovKFi[0]); + vpCovKFi[0] = pKFi; + + std::vector > vvpMatchedMPs; + vvpMatchedMPs.resize(vpCovKFi.size()); + std::set spMatchedMPi; + int numBoWMatches = 0; + + KeyFrame* pMostBoWMatchesKF = pKFi; + int nMostBoWNumMatches = 0; + + std::vector vpMatchedPoints = std::vector(mpCurrentKF->GetMapPointMatches().size(), static_cast(NULL)); + std::vector vpKeyFrameMatchedMP = std::vector(mpCurrentKF->GetMapPointMatches().size(), static_cast(NULL)); + + int nIndexMostBoWMatchesKF=0; + for(int j=0; jisBad()) + continue; + + int num = matcherBoW.SearchByBoW(mpCurrentKF, vpCovKFi[j], vvpMatchedMPs[j]); + //cout << "BoW: " << num << " putative matches with KF " << vpCovKFi[j]->mnId << endl; + if (num > nMostBoWNumMatches) + { + nMostBoWNumMatches = num; + nIndexMostBoWMatchesKF = j; + } + } + + bool bAbortByNearKF = false; + for(int j=0; jisBad()) + continue; + + if(spMatchedMPi.find(pMPi_j) == spMatchedMPi.end()) + { + spMatchedMPi.insert(pMPi_j); + numBoWMatches++; + + vpMatchedPoints[k]= pMPi_j; + vpKeyFrameMatchedMP[k] = vpCovKFi[j]; + } + } + } + + //cout <<"BoW: " << numBoWMatches << " independent putative matches" << endl; + if(!bAbortByNearKF && numBoWMatches >= nBoWMatches) // TODO pick a good threshold + { + /*cout << "-------------------------------" << endl; + cout << "Geometric validation with " << numBoWMatches << endl; + cout << "KFc: " << mpCurrentKF->mnId << "; KFm: " << pMostBoWMatchesKF->mnId << endl;*/ + // Geometric validation + + bool bFixedScale = mbFixScale; + if(mpTracker->mSensor==System::IMU_MONOCULAR && !mpCurrentKF->GetMap()->GetIniertialBA2()) + bFixedScale=false; + + Sim3Solver solver = Sim3Solver(mpCurrentKF, pMostBoWMatchesKF, vpMatchedPoints, bFixedScale, vpKeyFrameMatchedMP); + solver.SetRansacParameters(0.99, nBoWInliers, 300); // at least 15 inliers + + bool bNoMore = false; + vector vbInliers; + int nInliers; + bool bConverge = false; + cv::Mat mTcm; + while(!bConverge && !bNoMore) + { + mTcm = solver.iterate(20,bNoMore, vbInliers, nInliers, bConverge); + } + + //cout << "Num inliers: " << nInliers << endl; + if(bConverge) + { + //cout <<"BoW: " << nInliers << " inliers in Sim3Solver" << endl; + + // Match by reprojection + //int nNumCovisibles = 5; + vpCovKFi.clear(); + vpCovKFi = pMostBoWMatchesKF->GetBestCovisibilityKeyFrames(nNumCovisibles); + int nInitialCov = vpCovKFi.size(); + vpCovKFi.push_back(pMostBoWMatchesKF); + set spCheckKFs(vpCovKFi.begin(), vpCovKFi.end()); + + set spMapPoints; + vector vpMapPoints; + vector vpKeyFrames; + for(KeyFrame* pCovKFi : vpCovKFi) + { + for(MapPoint* pCovMPij : pCovKFi->GetMapPointMatches()) + { + if(!pCovMPij || pCovMPij->isBad()) + continue; + + if(spMapPoints.find(pCovMPij) == spMapPoints.end()) + { + spMapPoints.insert(pCovMPij); + vpMapPoints.push_back(pCovMPij); + vpKeyFrames.push_back(pCovKFi); + } + } + } + //cout << "Point cloud: " << vpMapPoints.size() << endl; + + + g2o::Sim3 gScm(Converter::toMatrix3d(solver.GetEstimatedRotation()),Converter::toVector3d(solver.GetEstimatedTranslation()),solver.GetEstimatedScale()); + g2o::Sim3 gSmw(Converter::toMatrix3d(pMostBoWMatchesKF->GetRotation()),Converter::toVector3d(pMostBoWMatchesKF->GetTranslation()),1.0); + g2o::Sim3 gScw = gScm*gSmw; // Similarity matrix of current from the world position + cv::Mat mScw = Converter::toCvMat(gScw); + + + vector vpMatchedMP; + vpMatchedMP.resize(mpCurrentKF->GetMapPointMatches().size(), static_cast(NULL)); + vector vpMatchedKF; + vpMatchedKF.resize(mpCurrentKF->GetMapPointMatches().size(), static_cast(NULL)); + int numProjMatches = matcher.SearchByProjection(mpCurrentKF, mScw, vpMapPoints, vpKeyFrames, vpMatchedMP, vpMatchedKF, 8, 1.5); + cout <<"BoW: " << numProjMatches << " matches between " << vpMapPoints.size() << " points with coarse Sim3" << endl; + + if(numProjMatches >= nProjMatches) + { + // Optimize Sim3 transformation with every matches + Eigen::Matrix mHessian7x7; + + bool bFixedScale = mbFixScale; + if(mpTracker->mSensor==System::IMU_MONOCULAR && !mpCurrentKF->GetMap()->GetIniertialBA2()) + bFixedScale=false; + + int numOptMatches = Optimizer::OptimizeSim3(mpCurrentKF, pKFi, vpMatchedMP, gScm, 10, mbFixScale, mHessian7x7, true); + //cout <<"BoW: " << numOptMatches << " inliers in the Sim3 optimization" << endl; + //cout << "Inliers in Sim3 optimization: " << numOptMatches << endl; + + if(numOptMatches >= nSim3Inliers) + { + //cout <<"BoW: " << numOptMatches << " inliers in Sim3 optimization" << endl; + g2o::Sim3 gSmw(Converter::toMatrix3d(pMostBoWMatchesKF->GetRotation()),Converter::toVector3d(pMostBoWMatchesKF->GetTranslation()),1.0); + g2o::Sim3 gScw = gScm*gSmw; // Similarity matrix of current from the world position + cv::Mat mScw = Converter::toCvMat(gScw); + + vector vpMatchedMP; + vpMatchedMP.resize(mpCurrentKF->GetMapPointMatches().size(), static_cast(NULL)); + int numProjOptMatches = matcher.SearchByProjection(mpCurrentKF, mScw, vpMapPoints, vpMatchedMP, 5, 1.0); + //cout <<"BoW: " << numProjOptMatches << " matches after of the Sim3 optimization" << endl; + + if(numProjOptMatches >= nProjOptMatches) + { + cout << "BoW: Current KF " << mpCurrentKF->mnId << "; candidate KF " << pKFi->mnId << endl; + cout << "BoW: There are " << numProjOptMatches << " matches between them with the optimized Sim3" << endl; + int max_x = -1, min_x = 1000000; + int max_y = -1, min_y = 1000000; + for(MapPoint* pMPi : vpMatchedMP) + { + if(!pMPi || pMPi->isBad()) + { + continue; + } + + tuple indexes = pMPi->GetIndexInKeyFrame(pKFi); + int index = get<0>(indexes); + if(index >= 0) + { + int coord_x = pKFi->mvKeysUn[index].pt.x; + if(coord_x < min_x) + { + min_x = coord_x; + } + if(coord_x > max_x) + { + max_x = coord_x; + } + int coord_y = pKFi->mvKeysUn[index].pt.y; + if(coord_y < min_y) + { + min_y = coord_y; + } + if(coord_y > max_y) + { + max_y = coord_y; + } + } + } + //cout << "BoW: Coord in X -> " << min_x << ", " << max_x << "; and Y -> " << min_y << ", " << max_y << endl; + //cout << "BoW: features area in X -> " << (max_x - min_x) << " and Y -> " << (max_y - min_y) << endl; + + int nNumKFs = 0; + //vpMatchedMPs = vpMatchedMP; + //vpMPs = vpMapPoints; + // Check the Sim3 transformation with the current KeyFrame covisibles + vector vpCurrentCovKFs = mpCurrentKF->GetBestCovisibilityKeyFrames(nNumCovisibles); + //cout << "---" << endl; + //cout << "BoW: Geometrical validation" << endl; + int j = 0; + while(nNumKFs < 3 && jGetPose() * mpCurrentKF->GetPoseInverse(); + g2o::Sim3 gSjc(Converter::toMatrix3d(mTjc.rowRange(0, 3).colRange(0, 3)),Converter::toVector3d(mTjc.rowRange(0, 3).col(3)),1.0); + g2o::Sim3 gSjw = gSjc * gScw; + int numProjMatches_j = 0; + vector vpMatchedMPs_j; + bool bValid = DetectCommonRegionsFromLastKF(pKFj,pMostBoWMatchesKF, gSjw,numProjMatches_j, vpMapPoints, vpMatchedMPs_j); + + if(bValid) + { + //cout << "BoW: KF " << pKFj->mnId << " has " << numProjMatches_j << " matches" << endl; + cv::Mat Tc_w = mpCurrentKF->GetPose(); + cv::Mat Tw_cj = pKFj->GetPoseInverse(); + cv::Mat Tc_cj = Tc_w * Tw_cj; + cv::Vec3d vector_dist = Tc_cj.rowRange(0, 3).col(3); + cv::Mat Rc_cj = Tc_cj.rowRange(0, 3).colRange(0, 3); + double dist = cv::norm(vector_dist); + cout << "BoW: KF " << pKFi->mnId << " to KF " << pKFj->mnId << " is separated by " << dist << " meters" << endl; + cout << "BoW: Rotation between KF -> " << Rc_cj << endl; + vector v_euler = Converter::toEuler(Rc_cj); + v_euler[0] *= 180 /3.1415; + v_euler[1] *= 180 /3.1415; + v_euler[2] *= 180 /3.1415; + cout << "BoW: Rotation in angles (x, y, z) -> (" << v_euler[0] << ", " << v_euler[1] << ", " << v_euler[2] << ")" << endl; + nNumKFs++; + /*if(numProjMatches_j > numProjOptMatches) + { + pLastCurrentKF = pKFj; + g2oScw = gSjw; + vpMatchedMPs = vpMatchedMPs_j; + }*/ + } + + j++; + } + + if(nNumKFs < 3) + { + vnStage[index] = 8; + vnMatchesStage[index] = nNumKFs; + } + + if(nBestMatchesReproj < numProjOptMatches) + { + nBestMatchesReproj = numProjOptMatches; + nBestNumCoindicendes = nNumKFs; + pBestMatchedKF = pMostBoWMatchesKF; + g2oBestScw = gScw; + vpBestMapPoints = vpMapPoints; + vpBestMatchedMapPoints = vpMatchedMP; + } + + + } + + } + + } + } + } + index++; + } + + if(nBestMatchesReproj > 0) + { + pLastCurrentKF = mpCurrentKF; + nNumCoincidences = nBestNumCoindicendes; + pMatchedKF2 = pBestMatchedKF; + pMatchedKF2->SetNotErase(); + g2oScw = g2oBestScw; + vpMPs = vpBestMapPoints; + vpMatchedMPs = vpBestMatchedMapPoints; + + return nNumCoincidences >= 3; + } + else + { + int maxStage = -1; + int maxMatched; + for(int i=0; i maxStage) + { + maxStage = vnStage[i]; + maxMatched = vnMatchesStage[i]; + } + } + +// f_succes_pr << mpCurrentKF->mNameFile << " " << std::to_string(maxStage) << endl; +// f_succes_pr << "% NumCand: " << std::to_string(numCandidates) << "; matches: " << std::to_string(maxMatched) << endl; + } + return false; +} + +bool LoopClosing::DetectCommonRegionsFromLastKF(KeyFrame* pCurrentKF, KeyFrame* pMatchedKF, g2o::Sim3 &gScw, int &nNumProjMatches, + std::vector &vpMPs, std::vector &vpMatchedMPs) +{ + set spAlreadyMatchedMPs(vpMatchedMPs.begin(), vpMatchedMPs.end()); + nNumProjMatches = FindMatchesByProjection(pCurrentKF, pMatchedKF, gScw, spAlreadyMatchedMPs, vpMPs, vpMatchedMPs); + //cout << "Projection from last KF with " << nNumProjMatches << " matches" << endl; + + int nProjMatches = 30; + if(nNumProjMatches >= nProjMatches) + { + /*cout << "PR_From_LastKF: KF " << pCurrentKF->mnId << " has " << nNumProjMatches << " with KF " << pMatchedKF->mnId << endl; + + int max_x = -1, min_x = 1000000; + int max_y = -1, min_y = 1000000; + for(MapPoint* pMPi : vpMatchedMPs) + { + if(!pMPi || pMPi->isBad()) + { + continue; + } + + tuple indexes = pMPi->GetIndexInKeyFrame(pMatchedKF); + int index = get<0>(indexes); + if(index >= 0) + { + int coord_x = pCurrentKF->mvKeysUn[index].pt.x; + if(coord_x < min_x) + { + min_x = coord_x; + } + if(coord_x > max_x) + { + max_x = coord_x; + } + int coord_y = pCurrentKF->mvKeysUn[index].pt.y; + if(coord_y < min_y) + { + min_y = coord_y; + } + if(coord_y > max_y) + { + max_y = coord_y; + } + } + }*/ + //cout << "PR_From_LastKF: Coord in X -> " << min_x << ", " << max_x << "; and Y -> " << min_y << ", " << max_y << endl; + //cout << "PR_From_LastKF: features area in X -> " << (max_x - min_x) << " and Y -> " << (max_y - min_y) << endl; + + + return true; + } + + return false; +} + +int LoopClosing::FindMatchesByProjection(KeyFrame* pCurrentKF, KeyFrame* pMatchedKFw, g2o::Sim3 &g2oScw, + set &spMatchedMPinOrigin, vector &vpMapPoints, + vector &vpMatchedMapPoints) +{ + int nNumCovisibles = 5; + vector vpCovKFm = pMatchedKFw->GetBestCovisibilityKeyFrames(nNumCovisibles); + int nInitialCov = vpCovKFm.size(); + vpCovKFm.push_back(pMatchedKFw); + set spCheckKFs(vpCovKFm.begin(), vpCovKFm.end()); + set spCurrentCovisbles = pCurrentKF->GetConnectedKeyFrames(); + for(int i=0; i vpKFs = vpCovKFm[i]->GetBestCovisibilityKeyFrames(nNumCovisibles); + int nInserted = 0; + int j = 0; + while(j < vpKFs.size() && nInserted < nNumCovisibles) + { + if(spCheckKFs.find(vpKFs[j]) == spCheckKFs.end() && spCurrentCovisbles.find(vpKFs[j]) == spCurrentCovisbles.end()) + { + spCheckKFs.insert(vpKFs[j]); + ++nInserted; + } + ++j; + } + vpCovKFm.insert(vpCovKFm.end(), vpKFs.begin(), vpKFs.end()); + } + set spMapPoints; + vpMapPoints.clear(); + vpMatchedMapPoints.clear(); + for(KeyFrame* pKFi : vpCovKFm) + { + for(MapPoint* pMPij : pKFi->GetMapPointMatches()) + { + if(!pMPij || pMPij->isBad()) + continue; + + if(spMapPoints.find(pMPij) == spMapPoints.end()) + { + spMapPoints.insert(pMPij); + vpMapPoints.push_back(pMPij); + } + } + } + //cout << "Point cloud: " << vpMapPoints.size() << endl; + + cv::Mat mScw = Converter::toCvMat(g2oScw); + + ORBmatcher matcher(0.9, true); + + vpMatchedMapPoints.resize(pCurrentKF->GetMapPointMatches().size(), static_cast(NULL)); + int num_matches = matcher.SearchByProjection(pCurrentKF, mScw, vpMapPoints, vpMatchedMapPoints, 3, 1.5); + + return num_matches; +} + +void LoopClosing::CorrectLoop() +{ + cout << "Loop detected!" << endl; + + // Send a stop signal to Local Mapping + // Avoid new keyframes are inserted while correcting the loop + mpLocalMapper->RequestStop(); + mpLocalMapper->EmptyQueue(); // Proccess keyframes in the queue + + + // If a Global Bundle Adjustment is running, abort it + cout << "Request GBA abort" << endl; + if(isRunningGBA()) + { + unique_lock lock(mMutexGBA); + mbStopGBA = true; + + mnFullBAIdx++; + + if(mpThreadGBA) + { + cout << "GBA running... Abort!" << endl; + mpThreadGBA->detach(); + delete mpThreadGBA; + } + } + + // Wait until Local Mapping has effectively stopped + while(!mpLocalMapper->isStopped()) + { + usleep(1000); + } + + // Ensure current keyframe is updated + cout << "start updating connections" << endl; + assert(mpCurrentKF->GetMap()->CheckEssentialGraph()); + mpCurrentKF->UpdateConnections(); + assert(mpCurrentKF->GetMap()->CheckEssentialGraph()); + + // Retrive keyframes connected to the current keyframe and compute corrected Sim3 pose by propagation + mvpCurrentConnectedKFs = mpCurrentKF->GetVectorCovisibleKeyFrames(); + mvpCurrentConnectedKFs.push_back(mpCurrentKF); + + KeyFrameAndPose CorrectedSim3, NonCorrectedSim3; + CorrectedSim3[mpCurrentKF]=mg2oLoopScw; + cv::Mat Twc = mpCurrentKF->GetPoseInverse(); + + Map* pLoopMap = mpCurrentKF->GetMap(); + + { + // Get Map Mutex + unique_lock lock(pLoopMap->mMutexMapUpdate); + + const bool bImuInit = pLoopMap->isImuInitialized(); + + for(vector::iterator vit=mvpCurrentConnectedKFs.begin(), vend=mvpCurrentConnectedKFs.end(); vit!=vend; vit++) + { + KeyFrame* pKFi = *vit; + + cv::Mat Tiw = pKFi->GetPose(); + + if(pKFi!=mpCurrentKF) + { + cv::Mat Tic = Tiw*Twc; + cv::Mat Ric = Tic.rowRange(0,3).colRange(0,3); + cv::Mat tic = Tic.rowRange(0,3).col(3); + g2o::Sim3 g2oSic(Converter::toMatrix3d(Ric),Converter::toVector3d(tic),1.0); + g2o::Sim3 g2oCorrectedSiw = g2oSic*mg2oLoopScw; + //Pose corrected with the Sim3 of the loop closure + CorrectedSim3[pKFi]=g2oCorrectedSiw; + } + + cv::Mat Riw = Tiw.rowRange(0,3).colRange(0,3); + cv::Mat tiw = Tiw.rowRange(0,3).col(3); + g2o::Sim3 g2oSiw(Converter::toMatrix3d(Riw),Converter::toVector3d(tiw),1.0); + //Pose without correction + NonCorrectedSim3[pKFi]=g2oSiw; + } + + // Correct all MapPoints obsrved by current keyframe and neighbors, so that they align with the other side of the loop + cout << "LC: start correcting KeyFrames" << endl; + cout << "LC: there are " << CorrectedSim3.size() << " KFs in the local window" << endl; + for(KeyFrameAndPose::iterator mit=CorrectedSim3.begin(), mend=CorrectedSim3.end(); mit!=mend; mit++) + { + KeyFrame* pKFi = mit->first; + g2o::Sim3 g2oCorrectedSiw = mit->second; + g2o::Sim3 g2oCorrectedSwi = g2oCorrectedSiw.inverse(); + + g2o::Sim3 g2oSiw =NonCorrectedSim3[pKFi]; + + vector vpMPsi = pKFi->GetMapPointMatches(); + for(size_t iMP=0, endMPi = vpMPsi.size(); iMPisBad()) + continue; + if(pMPi->mnCorrectedByKF==mpCurrentKF->mnId) + continue; + + // Project with non-corrected pose and project back with corrected pose + cv::Mat P3Dw = pMPi->GetWorldPos(); + Eigen::Matrix eigP3Dw = Converter::toVector3d(P3Dw); + Eigen::Matrix eigCorrectedP3Dw = g2oCorrectedSwi.map(g2oSiw.map(eigP3Dw)); + + cv::Mat cvCorrectedP3Dw = Converter::toCvMat(eigCorrectedP3Dw); + pMPi->SetWorldPos(cvCorrectedP3Dw); + pMPi->mnCorrectedByKF = mpCurrentKF->mnId; + pMPi->mnCorrectedReference = pKFi->mnId; + pMPi->UpdateNormalAndDepth(); + } + + // Update keyframe pose with corrected Sim3. First transform Sim3 to SE3 (scale translation) + Eigen::Matrix3d eigR = g2oCorrectedSiw.rotation().toRotationMatrix(); + Eigen::Vector3d eigt = g2oCorrectedSiw.translation(); + double s = g2oCorrectedSiw.scale(); + // cout << "scale for loop-closing: " << s << endl; + + eigt *=(1./s); //[R t/s;0 1] + + cv::Mat correctedTiw = Converter::toCvSE3(eigR,eigt); + + pKFi->SetPose(correctedTiw); + + // Correct velocity according to orientation correction + if(bImuInit) + { + Eigen::Matrix3d Rcor = eigR.transpose()*g2oSiw.rotation().toRotationMatrix(); + pKFi->SetVelocity(Converter::toCvMat(Rcor)*pKFi->GetVelocity()); + } + + // Make sure connections are updated + pKFi->UpdateConnections(); + } + // TODO Check this index increasement + mpAtlas->GetCurrentMap()->IncreaseChangeIndex(); + cout << "LC: end correcting KeyFrames" << endl; + + + // Start Loop Fusion + // Update matched map points and replace if duplicated + cout << "LC: start replacing duplicated" << endl; + for(size_t i=0; iGetMapPoint(i); + if(pCurMP) + pCurMP->Replace(pLoopMP); + else + { + mpCurrentKF->AddMapPoint(pLoopMP,i); + pLoopMP->AddObservation(mpCurrentKF,i); + pLoopMP->ComputeDistinctiveDescriptors(); + } + } + } + cout << "LC: end replacing duplicated" << endl; + } + + // Project MapPoints observed in the neighborhood of the loop keyframe + // into the current keyframe and neighbors using corrected poses. + // Fuse duplications. + //cout << "LC: start SearchAndFuse" << endl; + SearchAndFuse(CorrectedSim3, mvpLoopMapPoints); + //cout << "LC: end SearchAndFuse" << endl; + + + // After the MapPoint fusion, new links in the covisibility graph will appear attaching both sides of the loop + //cout << "LC: start updating covisibility graph" << endl; + map > LoopConnections; + + for(vector::iterator vit=mvpCurrentConnectedKFs.begin(), vend=mvpCurrentConnectedKFs.end(); vit!=vend; vit++) + { + KeyFrame* pKFi = *vit; + vector vpPreviousNeighbors = pKFi->GetVectorCovisibleKeyFrames(); + + // Update connections. Detect new links. + pKFi->UpdateConnections(); + LoopConnections[pKFi]=pKFi->GetConnectedKeyFrames(); + for(vector::iterator vit_prev=vpPreviousNeighbors.begin(), vend_prev=vpPreviousNeighbors.end(); vit_prev!=vend_prev; vit_prev++) + { + LoopConnections[pKFi].erase(*vit_prev); + } + for(vector::iterator vit2=mvpCurrentConnectedKFs.begin(), vend2=mvpCurrentConnectedKFs.end(); vit2!=vend2; vit2++) + { + LoopConnections[pKFi].erase(*vit2); + } + } + //cout << "LC: end updating covisibility graph" << endl; + + // Optimize graph + //cout << "start opt essentialgraph" << endl; + bool bFixedScale = mbFixScale; + // TODO CHECK; Solo para el monocular inertial + if(mpTracker->mSensor==System::IMU_MONOCULAR && !mpCurrentKF->GetMap()->GetIniertialBA2()) + bFixedScale=false; + + + //cout << "Optimize essential graph" << endl; + if(pLoopMap->IsInertial() && pLoopMap->isImuInitialized()) + { + //cout << "With 4DoF" << endl; + Optimizer::OptimizeEssentialGraph4DoF(pLoopMap, mpLoopMatchedKF, mpCurrentKF, NonCorrectedSim3, CorrectedSim3, LoopConnections); + } + else + { + //cout << "With 7DoF" << endl; + Optimizer::OptimizeEssentialGraph(pLoopMap, mpLoopMatchedKF, mpCurrentKF, NonCorrectedSim3, CorrectedSim3, LoopConnections, bFixedScale); + } + + + //cout << "Optimize essential graph finished" << endl; + //usleep(5*1000*1000); + + mpAtlas->InformNewBigChange(); + + // Add loop edge + mpLoopMatchedKF->AddLoopEdge(mpCurrentKF); + mpCurrentKF->AddLoopEdge(mpLoopMatchedKF); + + // Launch a new thread to perform Global Bundle Adjustment (Only if few keyframes, if not it would take too much time) + if(!pLoopMap->isImuInitialized() || (pLoopMap->KeyFramesInMap()<200 && mpAtlas->CountMaps()==1)) + { + mbRunningGBA = true; + mbFinishedGBA = false; + mbStopGBA = false; + + mpThreadGBA = new thread(&LoopClosing::RunGlobalBundleAdjustment, this, pLoopMap, mpCurrentKF->mnId); + } + + // Loop closed. Release Local Mapping. + mpLocalMapper->Release(); + + mLastLoopKFid = mpCurrentKF->mnId; //TODO old varible, it is not use in the new algorithm +} + +void LoopClosing::MergeLocal() +{ + Verbose::PrintMess("MERGE-VISUAL: Merge Visual detected!!!!", Verbose::VERBOSITY_NORMAL); + //mpTracker->SetStepByStep(true); + + int numTemporalKFs = 15; //TODO (set by parameter): Temporal KFs in the local window if the map is inertial. + + //Relationship to rebuild the essential graph, it is used two times, first in the local window and later in the rest of the map + KeyFrame* pNewChild; + KeyFrame* pNewParent; + + vector vpLocalCurrentWindowKFs; + vector vpMergeConnectedKFs; + + // Flag that is true only when we stopped a running BA, in this case we need relaunch at the end of the merge + bool bRelaunchBA = false; + + Verbose::PrintMess("MERGE-VISUAL: Check Full Bundle Adjustment", Verbose::VERBOSITY_DEBUG); + // If a Global Bundle Adjustment is running, abort it + if(isRunningGBA()) + { + unique_lock lock(mMutexGBA); + mbStopGBA = true; + + mnFullBAIdx++; + + if(mpThreadGBA) + { + mpThreadGBA->detach(); + delete mpThreadGBA; + } + bRelaunchBA = true; + } + + Verbose::PrintMess("MERGE-VISUAL: Request Stop Local Mapping", Verbose::VERBOSITY_DEBUG); + mpLocalMapper->RequestStop(); + // Wait until Local Mapping has effectively stopped + while(!mpLocalMapper->isStopped()) + { + usleep(1000); + } + Verbose::PrintMess("MERGE-VISUAL: Local Map stopped", Verbose::VERBOSITY_DEBUG); + + mpLocalMapper->EmptyQueue(); + + // Merge map will become in the new active map with the local window of KFs and MPs from the current map. + // Later, the elements of the current map will be transform to the new active map reference, in order to keep real time tracking + Map* pCurrentMap = mpCurrentKF->GetMap(); + Map* pMergeMap = mpMergeMatchedKF->GetMap(); + + Verbose::PrintMess("MERGE-VISUAL: Initially there are " + to_string(pCurrentMap->KeyFramesInMap()) + " KFs and " + to_string(pCurrentMap->MapPointsInMap()) + " MPs in the active map ", Verbose::VERBOSITY_DEBUG); + Verbose::PrintMess("MERGE-VISUAL: Initially there are " + to_string(pMergeMap->KeyFramesInMap()) + " KFs and " + to_string(pMergeMap->MapPointsInMap()) + " MPs in the matched map ", Verbose::VERBOSITY_DEBUG); + //vector vpMergeKFs = pMergeMap->GetAllKeyFrames(); + + //// + + // Ensure current keyframe is updated + mpCurrentKF->UpdateConnections(); + + //Get the current KF and its neighbors(visual->covisibles; inertial->temporal+covisibles) + set spLocalWindowKFs; + //Get MPs in the welding area from the current map + set spLocalWindowMPs; + if(pCurrentMap->IsInertial() && pMergeMap->IsInertial()) //TODO Check the correct initialization + { + KeyFrame* pKFi = mpCurrentKF; + int nInserted = 0; + while(pKFi && nInserted < numTemporalKFs) + { + spLocalWindowKFs.insert(pKFi); + pKFi = mpCurrentKF->mPrevKF; + nInserted++; + + set spMPi = pKFi->GetMapPoints(); + spLocalWindowMPs.insert(spMPi.begin(), spMPi.end()); + } + + pKFi = mpCurrentKF->mNextKF; + while(pKFi) + { + spLocalWindowKFs.insert(pKFi); + + set spMPi = pKFi->GetMapPoints(); + spLocalWindowMPs.insert(spMPi.begin(), spMPi.end()); + } + } + else + { + spLocalWindowKFs.insert(mpCurrentKF); + } + + vector vpCovisibleKFs = mpCurrentKF->GetBestCovisibilityKeyFrames(numTemporalKFs); + spLocalWindowKFs.insert(vpCovisibleKFs.begin(), vpCovisibleKFs.end()); + Verbose::PrintMess("MERGE-VISUAL: Initial number of KFs in local window from active map: " + to_string(spLocalWindowKFs.size()), Verbose::VERBOSITY_DEBUG); + const int nMaxTries = 3; + int nNumTries = 0; + while(spLocalWindowKFs.size() < numTemporalKFs && nNumTries < nMaxTries) + { + vector vpNewCovKFs; + vpNewCovKFs.empty(); + for(KeyFrame* pKFi : spLocalWindowKFs) + { + vector vpKFiCov = pKFi->GetBestCovisibilityKeyFrames(numTemporalKFs/2); + for(KeyFrame* pKFcov : vpKFiCov) + { + if(pKFcov && !pKFcov->isBad() && spLocalWindowKFs.find(pKFcov) == spLocalWindowKFs.end()) + { + vpNewCovKFs.push_back(pKFcov); + } + + } + } + + spLocalWindowKFs.insert(vpNewCovKFs.begin(), vpNewCovKFs.end()); + nNumTries++; + } + Verbose::PrintMess("MERGE-VISUAL: Last number of KFs in local window from the active map: " + to_string(spLocalWindowKFs.size()), Verbose::VERBOSITY_DEBUG); + + //TODO TEST + //vector vpTestKFs = pCurrentMap->GetAllKeyFrames(); + //spLocalWindowKFs.insert(vpTestKFs.begin(), vpTestKFs.end()); + + for(KeyFrame* pKFi : spLocalWindowKFs) + { + if(!pKFi || pKFi->isBad()) + continue; + + set spMPs = pKFi->GetMapPoints(); + spLocalWindowMPs.insert(spMPs.begin(), spMPs.end()); + } + Verbose::PrintMess("MERGE-VISUAL: Number of MPs in local window from active map: " + to_string(spLocalWindowMPs.size()), Verbose::VERBOSITY_DEBUG); + Verbose::PrintMess("MERGE-VISUAL: Number of MPs in the active map: " + to_string(pCurrentMap->GetAllMapPoints().size()), Verbose::VERBOSITY_DEBUG); + + Verbose::PrintMess("-------", Verbose::VERBOSITY_DEBUG); + set spMergeConnectedKFs; + if(pCurrentMap->IsInertial() && pMergeMap->IsInertial()) //TODO Check the correct initialization + { + KeyFrame* pKFi = mpMergeMatchedKF; + int nInserted = 0; + while(pKFi && nInserted < numTemporalKFs) + { + spMergeConnectedKFs.insert(pKFi); + pKFi = mpCurrentKF->mPrevKF; + nInserted++; + } + + pKFi = mpMergeMatchedKF->mNextKF; + while(pKFi) + { + spMergeConnectedKFs.insert(pKFi); + } + } + else + { + spMergeConnectedKFs.insert(mpMergeMatchedKF); + } + vpCovisibleKFs = mpMergeMatchedKF->GetBestCovisibilityKeyFrames(numTemporalKFs); + spMergeConnectedKFs.insert(vpCovisibleKFs.begin(), vpCovisibleKFs.end()); + Verbose::PrintMess("MERGE-VISUAL: Initial number of KFs in the local window from matched map: " + to_string(spMergeConnectedKFs.size()), Verbose::VERBOSITY_DEBUG); + nNumTries = 0; + while(spMergeConnectedKFs.size() < numTemporalKFs && nNumTries < nMaxTries) + { + vector vpNewCovKFs; + for(KeyFrame* pKFi : spMergeConnectedKFs) + { + vector vpKFiCov = pKFi->GetBestCovisibilityKeyFrames(numTemporalKFs/2); + for(KeyFrame* pKFcov : vpKFiCov) + { + if(pKFcov && !pKFcov->isBad() && spMergeConnectedKFs.find(pKFcov) == spMergeConnectedKFs.end()) + { + vpNewCovKFs.push_back(pKFcov); + } + + } + } + + spMergeConnectedKFs.insert(vpNewCovKFs.begin(), vpNewCovKFs.end()); + nNumTries++; + } + Verbose::PrintMess("MERGE-VISUAL: Last number of KFs in the localwindow from matched map: " + to_string(spMergeConnectedKFs.size()), Verbose::VERBOSITY_DEBUG); + + set spMapPointMerge; + for(KeyFrame* pKFi : spMergeConnectedKFs) + { + set vpMPs = pKFi->GetMapPoints(); + spMapPointMerge.insert(vpMPs.begin(),vpMPs.end()); + } + + vector vpCheckFuseMapPoint; + vpCheckFuseMapPoint.reserve(spMapPointMerge.size()); + std::copy(spMapPointMerge.begin(), spMapPointMerge.end(), std::back_inserter(vpCheckFuseMapPoint)); + + // + cv::Mat Twc = mpCurrentKF->GetPoseInverse(); + + cv::Mat Rwc = Twc.rowRange(0,3).colRange(0,3); + cv::Mat twc = Twc.rowRange(0,3).col(3); + g2o::Sim3 g2oNonCorrectedSwc(Converter::toMatrix3d(Rwc),Converter::toVector3d(twc),1.0); + g2o::Sim3 g2oNonCorrectedScw = g2oNonCorrectedSwc.inverse(); + g2o::Sim3 g2oCorrectedScw = mg2oMergeScw; //TODO Check the transformation + + KeyFrameAndPose vCorrectedSim3, vNonCorrectedSim3; + vCorrectedSim3[mpCurrentKF]=g2oCorrectedScw; + vNonCorrectedSim3[mpCurrentKF]=g2oNonCorrectedScw; + + + //TODO Time test +#ifdef COMPILEDWITHC11 + std::chrono::steady_clock::time_point timeStartTransfMerge = std::chrono::steady_clock::now(); +#else + std::chrono::monotonic_clock::time_point timeStartTransfMerge = std::chrono::monotonic_clock::now(); +#endif + for(KeyFrame* pKFi : spLocalWindowKFs) + { + if(!pKFi || pKFi->isBad()) + { + Verbose::PrintMess("Bad KF in correction", Verbose::VERBOSITY_DEBUG); + continue; + } + + if(pKFi->GetMap() != pCurrentMap) + Verbose::PrintMess("Other map KF, this should't happen", Verbose::VERBOSITY_DEBUG); + + g2o::Sim3 g2oCorrectedSiw; + + if(pKFi!=mpCurrentKF) + { + cv::Mat Tiw = pKFi->GetPose(); + cv::Mat Riw = Tiw.rowRange(0,3).colRange(0,3); + cv::Mat tiw = Tiw.rowRange(0,3).col(3); + g2o::Sim3 g2oSiw(Converter::toMatrix3d(Riw),Converter::toVector3d(tiw),1.0); + //Pose without correction + vNonCorrectedSim3[pKFi]=g2oSiw; + + cv::Mat Tic = Tiw*Twc; + cv::Mat Ric = Tic.rowRange(0,3).colRange(0,3); + cv::Mat tic = Tic.rowRange(0,3).col(3); + g2o::Sim3 g2oSic(Converter::toMatrix3d(Ric),Converter::toVector3d(tic),1.0); + g2oCorrectedSiw = g2oSic*mg2oMergeScw; + vCorrectedSim3[pKFi]=g2oCorrectedSiw; + } + else + { + g2oCorrectedSiw = g2oCorrectedScw; + } + pKFi->mTcwMerge = pKFi->GetPose(); + + // Update keyframe pose with corrected Sim3. First transform Sim3 to SE3 (scale translation) + Eigen::Matrix3d eigR = g2oCorrectedSiw.rotation().toRotationMatrix(); + Eigen::Vector3d eigt = g2oCorrectedSiw.translation(); + double s = g2oCorrectedSiw.scale(); + + pKFi->mfScale = s; + eigt *=(1./s); //[R t/s;0 1] + + //cout << "R: " << mg2oMergeScw.rotation().toRotationMatrix() << endl; + //cout << "angle: " << 180*LogSO3(mg2oMergeScw.rotation().toRotationMatrix())/3.14 << endl; + //cout << "t: " << mg2oMergeScw.translation() << endl; + + cv::Mat correctedTiw = Converter::toCvSE3(eigR,eigt); + + pKFi->mTcwMerge = correctedTiw; + + //pKFi->SetPose(correctedTiw); + + // Make sure connections are updated + //pKFi->UpdateMap(pMergeMap); + //pMergeMap->AddKeyFrame(pKFi); + //pCurrentMap->EraseKeyFrame(pKFi); + + //cout << "After -> Map current: " << pCurrentMap << "; New map: " << pKFi->GetMap() << endl; + + if(pCurrentMap->isImuInitialized()) + { + Eigen::Matrix3d Rcor = eigR.transpose()*vNonCorrectedSim3[pKFi].rotation().toRotationMatrix(); + pKFi->mVwbMerge = Converter::toCvMat(Rcor)*pKFi->GetVelocity(); + //pKFi->SetVelocity(Converter::toCvMat(Rcor)*pKFi->GetVelocity()); // TODO: should add here scale s + } + + //TODO DEBUG to know which are the KFs that had been moved to the other map + //pKFi->mnOriginMapId = 5; + } + + for(MapPoint* pMPi : spLocalWindowMPs) + { + if(!pMPi || pMPi->isBad()) + continue; + + KeyFrame* pKFref = pMPi->GetReferenceKeyFrame(); + g2o::Sim3 g2oCorrectedSwi = vCorrectedSim3[pKFref].inverse(); + g2o::Sim3 g2oNonCorrectedSiw = vNonCorrectedSim3[pKFref]; + + // Project with non-corrected pose and project back with corrected pose + cv::Mat P3Dw = pMPi->GetWorldPos(); + Eigen::Matrix eigP3Dw = Converter::toVector3d(P3Dw); + Eigen::Matrix eigCorrectedP3Dw = g2oCorrectedSwi.map(g2oNonCorrectedSiw.map(eigP3Dw)); + Eigen::Matrix3d eigR = g2oCorrectedSwi.rotation().toRotationMatrix(); + Eigen::Matrix3d Rcor = eigR * g2oNonCorrectedSiw.rotation().toRotationMatrix(); + + cv::Mat cvCorrectedP3Dw = Converter::toCvMat(eigCorrectedP3Dw); + + pMPi->mPosMerge = cvCorrectedP3Dw; + //cout << "Rcor: " << Rcor << endl; + //cout << "Normal: " << pMPi->GetNormal() << endl; + pMPi->mNormalVectorMerge = Converter::toCvMat(Rcor) * pMPi->GetNormal(); + //pMPi->SetWorldPos(cvCorrectedP3Dw); + //pMPi->UpdateMap(pMergeMap); + //pMergeMap->AddMapPoint(pMPi); + //pCurrentMap->EraseMapPoint(pMPi); + //pMPi->UpdateNormalAndDepth(); + } +#ifdef COMPILEDWITHC11 + std::chrono::steady_clock::time_point timeFinishTransfMerge = std::chrono::steady_clock::now(); +#else + std::chrono::monotonic_clock::time_point timeFinishTransfMerge = std::chrono::monotonic_clock::now(); +#endif + std::chrono::duration timeTransfMerge = timeFinishTransfMerge - timeStartTransfMerge; // Time in milliseconds + Verbose::PrintMess("MERGE-VISUAL: TRANSF ms: " + to_string(timeTransfMerge.count()), Verbose::VERBOSITY_DEBUG); + + + //TODO Time test +#ifdef COMPILEDWITHC11 + std::chrono::steady_clock::time_point timeStartCritMerge = std::chrono::steady_clock::now(); +#else + std::chrono::monotonic_clock::time_point timeStartCritMerge = std::chrono::monotonic_clock::now(); +#endif + { + unique_lock currentLock(pCurrentMap->mMutexMapUpdate); // We update the current map with the Merge information + unique_lock mergeLock(pMergeMap->mMutexMapUpdate); // We remove the Kfs and MPs in the merged area from the old map + + for(KeyFrame* pKFi : spLocalWindowKFs) + { + if(!pKFi || pKFi->isBad()) + { + //cout << "Bad KF in correction" << endl; + continue; + } + + pKFi->mTcwBefMerge = pKFi->GetPose(); + pKFi->mTwcBefMerge = pKFi->GetPoseInverse(); + pKFi->SetPose(pKFi->mTcwMerge); + + // Make sure connections are updated + pKFi->UpdateMap(pMergeMap); + pKFi->mnMergeCorrectedForKF = mpCurrentKF->mnId; + pMergeMap->AddKeyFrame(pKFi); + pCurrentMap->EraseKeyFrame(pKFi); + + if(pCurrentMap->isImuInitialized()) + { + pKFi->SetVelocity(pKFi->mVwbMerge); + } + } + + for(MapPoint* pMPi : spLocalWindowMPs) + { + if(!pMPi || pMPi->isBad()) + continue; + + pMPi->SetWorldPos(pMPi->mPosMerge); + pMPi->SetNormalVector(pMPi->mNormalVectorMerge); + pMPi->UpdateMap(pMergeMap); + pMergeMap->AddMapPoint(pMPi); + pCurrentMap->EraseMapPoint(pMPi); + //pMPi->UpdateNormalAndDepth(); + } + + mpAtlas->ChangeMap(pMergeMap); + mpAtlas->SetMapBad(pCurrentMap); + pMergeMap->IncreaseChangeIndex(); + //TODO for debug + pMergeMap->ChangeId(pCurrentMap->GetId()); + } + +#ifdef COMPILEDWITHC11 + std::chrono::steady_clock::time_point timeFinishCritMerge = std::chrono::steady_clock::now(); +#else + std::chrono::monotonic_clock::time_point timeFinishCritMerge = std::chrono::monotonic_clock::now(); +#endif + std::chrono::duration timeCritMerge = timeFinishCritMerge - timeStartCritMerge; // Time in milliseconds + Verbose::PrintMess("MERGE-VISUAL: New current map: " + to_string(pMergeMap->GetId()), Verbose::VERBOSITY_DEBUG); + Verbose::PrintMess("MERGE-VISUAL: CRITICAL ms: " + to_string(timeCritMerge.count()), Verbose::VERBOSITY_DEBUG); + Verbose::PrintMess("MERGE-VISUAL: LOCAL MAPPING number of KFs: " + to_string(mpLocalMapper->KeyframesInQueue()), Verbose::VERBOSITY_DEBUG); + + //Rebuild the essential graph in the local window + pCurrentMap->GetOriginKF()->SetFirstConnection(false); + pNewChild = mpCurrentKF->GetParent(); // Old parent, it will be the new child of this KF + pNewParent = mpCurrentKF; // Old child, now it will be the parent of its own parent(we need eliminate this KF from children list in its old parent) + mpCurrentKF->ChangeParent(mpMergeMatchedKF); + while(pNewChild /*&& spLocalWindowKFs.find(pNewChild) != spLocalWindowKFs.end()*/) + { + pNewChild->EraseChild(pNewParent); // We remove the relation between the old parent and the new for avoid loop + KeyFrame * pOldParent = pNewChild->GetParent(); + + pNewChild->ChangeParent(pNewParent); + //cout << "The new parent of KF " << pNewChild->mnId << " was " << pNewChild->GetParent()->mnId << endl; + + pNewParent = pNewChild; + pNewChild = pOldParent; + + } + + //Update the connections between the local window + mpMergeMatchedKF->UpdateConnections(); + //cout << "MERGE-VISUAL: Essential graph rebuilded" << endl; + + + //std::copy(spMapPointCurrent.begin(), spMapPointCurrent.end(), std::back_inserter(vpCheckFuseMapPoint)); + vpMergeConnectedKFs = mpMergeMatchedKF->GetVectorCovisibleKeyFrames(); + vpMergeConnectedKFs.push_back(mpMergeMatchedKF); + vpCheckFuseMapPoint.reserve(spMapPointMerge.size()); + std::copy(spMapPointMerge.begin(), spMapPointMerge.end(), std::back_inserter(vpCheckFuseMapPoint)); + + + //TODO Time test +#ifdef COMPILEDWITHC11 + std::chrono::steady_clock::time_point timeStartFuseMerge = std::chrono::steady_clock::now(); +#else + std::chrono::monotonic_clock::time_point timeStartFuseMerge = std::chrono::monotonic_clock::now(); +#endif + + // Project MapPoints observed in the neighborhood of the merge keyframe + // into the current keyframe and neighbors using corrected poses. + // Fuse duplications. + SearchAndFuse(vCorrectedSim3, vpCheckFuseMapPoint); + +#ifdef COMPILEDWITHC11 + std::chrono::steady_clock::time_point timeFinishFuseMerge = std::chrono::steady_clock::now(); +#else + std::chrono::monotonic_clock::time_point timeFinishFuseMerge = std::chrono::monotonic_clock::now(); +#endif + std::chrono::duration timeFuseMerge = timeFinishFuseMerge - timeStartFuseMerge; // Time in milliseconds + Verbose::PrintMess("MERGE-VISUAL: FUSE DUPLICATED ms: " + to_string(timeFuseMerge.count()), Verbose::VERBOSITY_DEBUG); + + // Update connectivity + Verbose::PrintMess("MERGE-VISUAL: Init to update connections in the welding area", Verbose::VERBOSITY_DEBUG); + for(KeyFrame* pKFi : spLocalWindowKFs) + { + if(!pKFi || pKFi->isBad()) + continue; + + pKFi->UpdateConnections(); + } + for(KeyFrame* pKFi : spMergeConnectedKFs) + { + if(!pKFi || pKFi->isBad()) + continue; + + pKFi->UpdateConnections(); + } + + //CheckObservations(spLocalWindowKFs, spMergeConnectedKFs); + + Verbose::PrintMess("MERGE-VISUAL: Finish to update connections in the welding area", Verbose::VERBOSITY_DEBUG); + + bool bStop = false; + Verbose::PrintMess("MERGE-VISUAL: Start local BA ", Verbose::VERBOSITY_DEBUG); + vpLocalCurrentWindowKFs.clear(); + vpMergeConnectedKFs.clear(); + std::copy(spLocalWindowKFs.begin(), spLocalWindowKFs.end(), std::back_inserter(vpLocalCurrentWindowKFs)); + std::copy(spMergeConnectedKFs.begin(), spMergeConnectedKFs.end(), std::back_inserter(vpMergeConnectedKFs)); + if (mpTracker->mSensor==System::IMU_MONOCULAR || mpTracker->mSensor==System::IMU_STEREO) + { + Verbose::PrintMess("MERGE-VISUAL: Visual-Inertial", Verbose::VERBOSITY_DEBUG); + Optimizer::MergeInertialBA(mpLocalMapper->GetCurrKF(),mpMergeMatchedKF,&bStop, mpCurrentKF->GetMap(),vCorrectedSim3); + } + else + { + Verbose::PrintMess("MERGE-VISUAL: Visual", Verbose::VERBOSITY_DEBUG); + Verbose::PrintMess("MERGE-VISUAL: Local current window->" + to_string(vpLocalCurrentWindowKFs.size()) + "; Local merge window->" + to_string(vpMergeConnectedKFs.size()), Verbose::VERBOSITY_DEBUG); + Optimizer::LocalBundleAdjustment(mpCurrentKF, vpLocalCurrentWindowKFs, vpMergeConnectedKFs,&bStop); + } + + // Loop closed. Release Local Mapping. + mpLocalMapper->Release(); + + + //return; + Verbose::PrintMess("MERGE-VISUAL: Finish the LBA", Verbose::VERBOSITY_DEBUG); + + + //// + //Update the non critical area from the current map to the merged map + vector vpCurrentMapKFs = pCurrentMap->GetAllKeyFrames(); + vector vpCurrentMapMPs = pCurrentMap->GetAllMapPoints(); + + if(vpCurrentMapKFs.size() == 0) + { + Verbose::PrintMess("MERGE-VISUAL: There are not KFs outside of the welding area", Verbose::VERBOSITY_DEBUG); + } + else + { + Verbose::PrintMess("MERGE-VISUAL: Calculate the new position of the elements outside of the window", Verbose::VERBOSITY_DEBUG); + //Apply the transformation + { + if(mpTracker->mSensor == System::MONOCULAR) + { + unique_lock currentLock(pCurrentMap->mMutexMapUpdate); // We update the current map with the Merge information + + for(KeyFrame* pKFi : vpCurrentMapKFs) + { + if(!pKFi || pKFi->isBad() || pKFi->GetMap() != pCurrentMap) + { + continue; + } + + g2o::Sim3 g2oCorrectedSiw; + + cv::Mat Tiw = pKFi->GetPose(); + cv::Mat Riw = Tiw.rowRange(0,3).colRange(0,3); + cv::Mat tiw = Tiw.rowRange(0,3).col(3); + g2o::Sim3 g2oSiw(Converter::toMatrix3d(Riw),Converter::toVector3d(tiw),1.0); + //Pose without correction + vNonCorrectedSim3[pKFi]=g2oSiw; + + cv::Mat Tic = Tiw*Twc; + cv::Mat Ric = Tic.rowRange(0,3).colRange(0,3); + cv::Mat tic = Tic.rowRange(0,3).col(3); + g2o::Sim3 g2oSim(Converter::toMatrix3d(Ric),Converter::toVector3d(tic),1.0); + g2oCorrectedSiw = g2oSim*mg2oMergeScw; + vCorrectedSim3[pKFi]=g2oCorrectedSiw; + + // Update keyframe pose with corrected Sim3. First transform Sim3 to SE3 (scale translation) + Eigen::Matrix3d eigR = g2oCorrectedSiw.rotation().toRotationMatrix(); + Eigen::Vector3d eigt = g2oCorrectedSiw.translation(); + double s = g2oCorrectedSiw.scale(); + + pKFi->mfScale = s; + eigt *=(1./s); //[R t/s;0 1] + + cv::Mat correctedTiw = Converter::toCvSE3(eigR,eigt); + + pKFi->mTcwBefMerge = pKFi->GetPose(); + pKFi->mTwcBefMerge = pKFi->GetPoseInverse(); + + pKFi->SetPose(correctedTiw); + + if(pCurrentMap->isImuInitialized()) + { + Eigen::Matrix3d Rcor = eigR.transpose()*vNonCorrectedSim3[pKFi].rotation().toRotationMatrix(); + pKFi->SetVelocity(Converter::toCvMat(Rcor)*pKFi->GetVelocity()); // TODO: should add here scale s + } + + } + for(MapPoint* pMPi : vpCurrentMapMPs) + { + if(!pMPi || pMPi->isBad()|| pMPi->GetMap() != pCurrentMap) + continue; + + KeyFrame* pKFref = pMPi->GetReferenceKeyFrame(); + g2o::Sim3 g2oCorrectedSwi = vCorrectedSim3[pKFref].inverse(); + g2o::Sim3 g2oNonCorrectedSiw = vNonCorrectedSim3[pKFref]; + + // Project with non-corrected pose and project back with corrected pose + cv::Mat P3Dw = pMPi->GetWorldPos(); + Eigen::Matrix eigP3Dw = Converter::toVector3d(P3Dw); + Eigen::Matrix eigCorrectedP3Dw = g2oCorrectedSwi.map(g2oNonCorrectedSiw.map(eigP3Dw)); + + cv::Mat cvCorrectedP3Dw = Converter::toCvMat(eigCorrectedP3Dw); + pMPi->SetWorldPos(cvCorrectedP3Dw); + + pMPi->UpdateNormalAndDepth(); + } + } + } + Verbose::PrintMess("MERGE-VISUAL: Apply transformation to all elements of the old map", Verbose::VERBOSITY_DEBUG); + + mpLocalMapper->RequestStop(); + // Wait until Local Mapping has effectively stopped + while(!mpLocalMapper->isStopped()) + { + usleep(1000); + } + Verbose::PrintMess("MERGE-VISUAL: Local Map stopped", Verbose::VERBOSITY_DEBUG); + + // Optimize graph (and update the loop position for each element form the begining to the end) + if(mpTracker->mSensor != System::MONOCULAR) + { + Optimizer::OptimizeEssentialGraph(mpCurrentKF, vpMergeConnectedKFs, vpLocalCurrentWindowKFs, vpCurrentMapKFs, vpCurrentMapMPs); + } + + + { + // Get Merge Map Mutex + unique_lock currentLock(pCurrentMap->mMutexMapUpdate); // We update the current map with the Merge information + unique_lock mergeLock(pMergeMap->mMutexMapUpdate); // We remove the Kfs and MPs in the merged area from the old map + + Verbose::PrintMess("MERGE-VISUAL: There are " + to_string(pMergeMap->KeyFramesInMap()) + " KFs in the map", Verbose::VERBOSITY_DEBUG); + Verbose::PrintMess("MERGE-VISUAL: It will be inserted " + to_string(vpCurrentMapKFs.size()) + " KFs in the map", Verbose::VERBOSITY_DEBUG); + + for(KeyFrame* pKFi : vpCurrentMapKFs) + { + if(!pKFi || pKFi->isBad() || pKFi->GetMap() != pCurrentMap) + { + continue; + } + + // Make sure connections are updated + pKFi->UpdateMap(pMergeMap); + pMergeMap->AddKeyFrame(pKFi); + pCurrentMap->EraseKeyFrame(pKFi); + } + Verbose::PrintMess("MERGE-VISUAL: There are " + to_string(pMergeMap->MapPointsInMap()) + " MPs in the map", Verbose::VERBOSITY_DEBUG); + Verbose::PrintMess("MERGE-VISUAL: It will be inserted " + to_string(vpCurrentMapMPs.size()) + " MPs in the map", Verbose::VERBOSITY_DEBUG); + + for(MapPoint* pMPi : vpCurrentMapMPs) + { + if(!pMPi || pMPi->isBad()) + continue; + + pMPi->UpdateMap(pMergeMap); + pMergeMap->AddMapPoint(pMPi); + pCurrentMap->EraseMapPoint(pMPi); + } + Verbose::PrintMess("MERGE-VISUAL: There are " + to_string(pMergeMap->MapPointsInMap()) + " MPs in the map", Verbose::VERBOSITY_DEBUG); + } + + Verbose::PrintMess("MERGE-VISUAL: Optimaze the essential graph", Verbose::VERBOSITY_DEBUG); + } + + + + mpLocalMapper->Release(); + + + Verbose::PrintMess("MERGE-VISUAL: Finally there are " + to_string(pMergeMap->KeyFramesInMap()) + "KFs and " + to_string(pMergeMap->MapPointsInMap()) + " MPs in the complete map ", Verbose::VERBOSITY_DEBUG); + Verbose::PrintMess("MERGE-VISUAL:Completed!!!!!", Verbose::VERBOSITY_DEBUG); + + if(bRelaunchBA && (!pCurrentMap->isImuInitialized() || (pCurrentMap->KeyFramesInMap()<200 && mpAtlas->CountMaps()==1))) + { + // Launch a new thread to perform Global Bundle Adjustment + Verbose::PrintMess("Relaunch Global BA", Verbose::VERBOSITY_DEBUG); + mbRunningGBA = true; + mbFinishedGBA = false; + mbStopGBA = false; + mpThreadGBA = new thread(&LoopClosing::RunGlobalBundleAdjustment,this, pMergeMap, mpCurrentKF->mnId); + } + + mpMergeMatchedKF->AddMergeEdge(mpCurrentKF); + mpCurrentKF->AddMergeEdge(mpMergeMatchedKF); + + pCurrentMap->IncreaseChangeIndex(); + pMergeMap->IncreaseChangeIndex(); + + mpAtlas->RemoveBadMaps(); + +} + +void LoopClosing::printReprojectionError(set &spLocalWindowKFs, KeyFrame* mpCurrentKF, string &name) +{ + string path_imgs = "./test_Reproj/"; + for(KeyFrame* pKFi : spLocalWindowKFs) + { + //cout << "KF " << pKFi->mnId << endl; + cv::Mat img_i = cv::imread(pKFi->mNameFile, cv::IMREAD_UNCHANGED); + //cout << "Image -> " << img_i.cols << ", " << img_i.rows << endl; + cv::cvtColor(img_i, img_i, CV_GRAY2BGR); + //cout << "Change of color in the image " << endl; + + vector vpMPs = pKFi->GetMapPointMatches(); + int num_points = 0; + for(int j=0; jisBad()) + { + continue; + } + + cv::KeyPoint point_img = pKFi->mvKeysUn[j]; + cv::Point2f reproj_p; + float u, v; + bool bIsInImage = pKFi->ProjectPointUnDistort(pMPij, reproj_p, u, v); + if(bIsInImage){ + //cout << "Reproj in the image" << endl; + cv::circle(img_i, point_img.pt, 1/*point_img.octave*/, cv::Scalar(0, 255, 0)); + cv::line(img_i, point_img.pt, reproj_p, cv::Scalar(0, 0, 255)); + num_points++; + } + else + { + //cout << "Reproj out of the image" << endl; + cv::circle(img_i, point_img.pt, point_img.octave, cv::Scalar(0, 0, 255)); + } + + } + //cout << "Image painted" << endl; + string filename_img = path_imgs + "KF" + to_string(mpCurrentKF->mnId) + "_" + to_string(pKFi->mnId) + name + "points" + to_string(num_points) + ".png"; + cv::imwrite(filename_img, img_i); + } + +} + + +void LoopClosing::MergeLocal2() +{ + cout << "Merge detected!!!!" << endl; + + int numTemporalKFs = 11; //TODO (set by parameter): Temporal KFs in the local window if the map is inertial. + + //Relationship to rebuild the essential graph, it is used two times, first in the local window and later in the rest of the map + KeyFrame* pNewChild; + KeyFrame* pNewParent; + + vector vpLocalCurrentWindowKFs; + vector vpMergeConnectedKFs; + + KeyFrameAndPose CorrectedSim3, NonCorrectedSim3; + // NonCorrectedSim3[mpCurrentKF]=mg2oLoopScw; + + // Flag that is true only when we stopped a running BA, in this case we need relaunch at the end of the merge + bool bRelaunchBA = false; + + cout << "Check Full Bundle Adjustment" << endl; + // If a Global Bundle Adjustment is running, abort it + if(isRunningGBA()) + { + unique_lock lock(mMutexGBA); + mbStopGBA = true; + + mnFullBAIdx++; + + if(mpThreadGBA) + { + mpThreadGBA->detach(); + delete mpThreadGBA; + } + bRelaunchBA = true; + } + + + cout << "Request Stop Local Mapping" << endl; + mpLocalMapper->RequestStop(); + // Wait until Local Mapping has effectively stopped + while(!mpLocalMapper->isStopped()) + { + usleep(1000); + } + cout << "Local Map stopped" << endl; + + Map* pCurrentMap = mpCurrentKF->GetMap(); + Map* pMergeMap = mpMergeMatchedKF->GetMap(); + + { + float s_on = mSold_new.scale(); + cv::Mat R_on = Converter::toCvMat(mSold_new.rotation().toRotationMatrix()); + cv::Mat t_on = Converter::toCvMat(mSold_new.translation()); + + unique_lock lock(mpAtlas->GetCurrentMap()->mMutexMapUpdate); + + cout << "KFs before empty: " << mpAtlas->GetCurrentMap()->KeyFramesInMap() << endl; + mpLocalMapper->EmptyQueue(); + cout << "KFs after empty: " << mpAtlas->GetCurrentMap()->KeyFramesInMap() << endl; + + std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now(); + cout << "updating active map to merge reference" << endl; + cout << "curr merge KF id: " << mpCurrentKF->mnId << endl; + cout << "curr tracking KF id: " << mpTracker->GetLastKeyFrame()->mnId << endl; + bool bScaleVel=false; + if(s_on!=1) + bScaleVel=true; + mpAtlas->GetCurrentMap()->ApplyScaledRotation(R_on,s_on,bScaleVel,t_on); + mpTracker->UpdateFrameIMU(s_on,mpCurrentKF->GetImuBias(),mpTracker->GetLastKeyFrame()); + + std::chrono::steady_clock::time_point t3 = std::chrono::steady_clock::now(); + } + + const int numKFnew=pCurrentMap->KeyFramesInMap(); + + if((mpTracker->mSensor==System::IMU_MONOCULAR || mpTracker->mSensor==System::IMU_STEREO)&& !pCurrentMap->GetIniertialBA2()){ + // Map is not completly initialized + Eigen::Vector3d bg, ba; + bg << 0., 0., 0.; + ba << 0., 0., 0.; + Optimizer::InertialOptimization(pCurrentMap,bg,ba); + IMU::Bias b (ba[0],ba[1],ba[2],bg[0],bg[1],bg[2]); + unique_lock lock(mpAtlas->GetCurrentMap()->mMutexMapUpdate); + mpTracker->UpdateFrameIMU(1.0f,b,mpTracker->GetLastKeyFrame()); + + // Set map initialized + pCurrentMap->SetIniertialBA2(); + pCurrentMap->SetIniertialBA1(); + pCurrentMap->SetImuInitialized(); + + } + + + cout << "MergeMap init ID: " << pMergeMap->GetInitKFid() << " CurrMap init ID: " << pCurrentMap->GetInitKFid() << endl; + + // Load KFs and MPs from merge map + cout << "updating current map" << endl; + { + // Get Merge Map Mutex (This section stops tracking!!) + unique_lock currentLock(pCurrentMap->mMutexMapUpdate); // We update the current map with the Merge information + unique_lock mergeLock(pMergeMap->mMutexMapUpdate); // We remove the Kfs and MPs in the merged area from the old map + + + vector vpMergeMapKFs = pMergeMap->GetAllKeyFrames(); + vector vpMergeMapMPs = pMergeMap->GetAllMapPoints(); + + + for(KeyFrame* pKFi : vpMergeMapKFs) + { + if(!pKFi || pKFi->isBad() || pKFi->GetMap() != pMergeMap) + { + continue; + } + + // Make sure connections are updated + pKFi->UpdateMap(pCurrentMap); + pCurrentMap->AddKeyFrame(pKFi); + pMergeMap->EraseKeyFrame(pKFi); + } + + for(MapPoint* pMPi : vpMergeMapMPs) + { + if(!pMPi || pMPi->isBad() || pMPi->GetMap() != pMergeMap) + continue; + + pMPi->UpdateMap(pCurrentMap); + pCurrentMap->AddMapPoint(pMPi); + pMergeMap->EraseMapPoint(pMPi); + } + + // Save non corrected poses (already merged maps) + vector vpKFs = pCurrentMap->GetAllKeyFrames(); + for(KeyFrame* pKFi : vpKFs) + { + cv::Mat Tiw=pKFi->GetPose(); + cv::Mat Riw = Tiw.rowRange(0,3).colRange(0,3); + cv::Mat tiw = Tiw.rowRange(0,3).col(3); + g2o::Sim3 g2oSiw(Converter::toMatrix3d(Riw),Converter::toVector3d(tiw),1.0); + NonCorrectedSim3[pKFi]=g2oSiw; + } + } + + cout << "MergeMap init ID: " << pMergeMap->GetInitKFid() << " CurrMap init ID: " << pCurrentMap->GetInitKFid() << endl; + + cout << "end updating current map" << endl; + + // Critical zone + bool good = pCurrentMap->CheckEssentialGraph(); + /*if(!good) + cout << "BAD ESSENTIAL GRAPH!!" << endl;*/ + + cout << "Update essential graph" << endl; + // mpCurrentKF->UpdateConnections(); // to put at false mbFirstConnection + pMergeMap->GetOriginKF()->SetFirstConnection(false); + pNewChild = mpMergeMatchedKF->GetParent(); // Old parent, it will be the new child of this KF + pNewParent = mpMergeMatchedKF; // Old child, now it will be the parent of its own parent(we need eliminate this KF from children list in its old parent) + mpMergeMatchedKF->ChangeParent(mpCurrentKF); + while(pNewChild) + { + pNewChild->EraseChild(pNewParent); // We remove the relation between the old parent and the new for avoid loop + KeyFrame * pOldParent = pNewChild->GetParent(); + pNewChild->ChangeParent(pNewParent); + pNewParent = pNewChild; + pNewChild = pOldParent; + + } + + + cout << "MergeMap init ID: " << pMergeMap->GetInitKFid() << " CurrMap init ID: " << pCurrentMap->GetInitKFid() << endl; + + cout << "end update essential graph" << endl; + + good = pCurrentMap->CheckEssentialGraph(); + if(!good) + cout << "BAD ESSENTIAL GRAPH 1!!" << endl; + + cout << "Update relationship between KFs" << endl; + vector vpCheckFuseMapPoint; // MapPoint vector from current map to allow to fuse duplicated points with the old map (merge) + vector vpCurrentConnectedKFs; + + + + mvpMergeConnectedKFs.push_back(mpMergeMatchedKF); + vector aux = mpMergeMatchedKF->GetVectorCovisibleKeyFrames(); + mvpMergeConnectedKFs.insert(mvpMergeConnectedKFs.end(), aux.begin(), aux.end()); + if (mvpMergeConnectedKFs.size()>6) + mvpMergeConnectedKFs.erase(mvpMergeConnectedKFs.begin()+6,mvpMergeConnectedKFs.end()); + /*mvpMergeConnectedKFs = mpMergeMatchedKF->GetVectorCovisibleKeyFrames(); + mvpMergeConnectedKFs.push_back(mpMergeMatchedKF);*/ + + mpCurrentKF->UpdateConnections(); + vpCurrentConnectedKFs.push_back(mpCurrentKF); + /*vpCurrentConnectedKFs = mpCurrentKF->GetVectorCovisibleKeyFrames(); + vpCurrentConnectedKFs.push_back(mpCurrentKF);*/ + aux = mpCurrentKF->GetVectorCovisibleKeyFrames(); + vpCurrentConnectedKFs.insert(vpCurrentConnectedKFs.end(), aux.begin(), aux.end()); + if (vpCurrentConnectedKFs.size()>6) + vpCurrentConnectedKFs.erase(vpCurrentConnectedKFs.begin()+6,vpCurrentConnectedKFs.end()); + + set spMapPointMerge; + for(KeyFrame* pKFi : mvpMergeConnectedKFs) + { + set vpMPs = pKFi->GetMapPoints(); + spMapPointMerge.insert(vpMPs.begin(),vpMPs.end()); + if(spMapPointMerge.size()>1000) + break; + } + + cout << "vpCurrentConnectedKFs.size() " << vpCurrentConnectedKFs.size() << endl; + cout << "mvpMergeConnectedKFs.size() " << mvpMergeConnectedKFs.size() << endl; + cout << "spMapPointMerge.size() " << spMapPointMerge.size() << endl; + + + vpCheckFuseMapPoint.reserve(spMapPointMerge.size()); + std::copy(spMapPointMerge.begin(), spMapPointMerge.end(), std::back_inserter(vpCheckFuseMapPoint)); + cout << "Finished to update relationship between KFs" << endl; + + cout << "MergeMap init ID: " << pMergeMap->GetInitKFid() << " CurrMap init ID: " << pCurrentMap->GetInitKFid() << endl; + + good = pCurrentMap->CheckEssentialGraph(); + if(!good) + cout << "BAD ESSENTIAL GRAPH 2!!" << endl; + + cout << "start SearchAndFuse" << endl; + SearchAndFuse(vpCurrentConnectedKFs, vpCheckFuseMapPoint); + cout << "end SearchAndFuse" << endl; + + cout << "MergeMap init ID: " << pMergeMap->GetInitKFid() << " CurrMap init ID: " << pCurrentMap->GetInitKFid() << endl; + + good = pCurrentMap->CheckEssentialGraph(); + if(!good) + cout << "BAD ESSENTIAL GRAPH 3!!" << endl; + + cout << "Init to update connections" << endl; + + + for(KeyFrame* pKFi : vpCurrentConnectedKFs) + { + if(!pKFi || pKFi->isBad()) + continue; + + pKFi->UpdateConnections(); + } + for(KeyFrame* pKFi : mvpMergeConnectedKFs) + { + if(!pKFi || pKFi->isBad()) + continue; + + pKFi->UpdateConnections(); + } + cout << "end update connections" << endl; + + cout << "MergeMap init ID: " << pMergeMap->GetInitKFid() << " CurrMap init ID: " << pCurrentMap->GetInitKFid() << endl; + + good = pCurrentMap->CheckEssentialGraph(); + if(!good) + cout << "BAD ESSENTIAL GRAPH 4!!" << endl; + + // TODO Check: If new map is too small, we suppose that not informaiton can be propagated from new to old map + if (numKFnew<10){ + mpLocalMapper->Release(); + return; + } + + good = pCurrentMap->CheckEssentialGraph(); + if(!good) + cout << "BAD ESSENTIAL GRAPH 5!!" << endl; + + // Perform BA + bool bStopFlag=false; + KeyFrame* pCurrKF = mpTracker->GetLastKeyFrame(); + cout << "start MergeInertialBA" << endl; + Optimizer::MergeInertialBA(pCurrKF, mpMergeMatchedKF, &bStopFlag, pCurrentMap,CorrectedSim3); + cout << "end MergeInertialBA" << endl; + + good = pCurrentMap->CheckEssentialGraph(); + if(!good) + cout << "BAD ESSENTIAL GRAPH 6!!" << endl; + + // Release Local Mapping. + mpLocalMapper->Release(); + + + return; +} + +void LoopClosing::CheckObservations(set &spKFsMap1, set &spKFsMap2) +{ + cout << "----------------------" << endl; + for(KeyFrame* pKFi1 : spKFsMap1) + { + map mMatchedMP; + set spMPs = pKFi1->GetMapPoints(); + + for(MapPoint* pMPij : spMPs) + { + if(!pMPij || pMPij->isBad()) + { + continue; + } + + map> mMPijObs = pMPij->GetObservations(); + for(KeyFrame* pKFi2 : spKFsMap2) + { + if(mMPijObs.find(pKFi2) != mMPijObs.end()) + { + if(mMatchedMP.find(pKFi2) != mMatchedMP.end()) + { + mMatchedMP[pKFi2] = mMatchedMP[pKFi2] + 1; + } + else + { + mMatchedMP[pKFi2] = 1; + } + } + } + + } + + if(mMatchedMP.size() == 0) + { + cout << "CHECK-OBS: KF " << pKFi1->mnId << " has not any matched MP with the other map" << endl; + } + else + { + cout << "CHECK-OBS: KF " << pKFi1->mnId << " has matched MP with " << mMatchedMP.size() << " KF from the other map" << endl; + for(pair matchedKF : mMatchedMP) + { + cout << " -KF: " << matchedKF.first->mnId << ", Number of matches: " << matchedKF.second << endl; + } + } + } + cout << "----------------------" << endl; +} + + +void LoopClosing::SearchAndFuse(const KeyFrameAndPose &CorrectedPosesMap, vector &vpMapPoints) +{ + ORBmatcher matcher(0.8); + + int total_replaces = 0; + + cout << "FUSE: Initially there are " << vpMapPoints.size() << " MPs" << endl; + cout << "FUSE: Intially there are " << CorrectedPosesMap.size() << " KFs" << endl; + for(KeyFrameAndPose::const_iterator mit=CorrectedPosesMap.begin(), mend=CorrectedPosesMap.end(); mit!=mend;mit++) + { + int num_replaces = 0; + KeyFrame* pKFi = mit->first; + Map* pMap = pKFi->GetMap(); + + g2o::Sim3 g2oScw = mit->second; + cv::Mat cvScw = Converter::toCvMat(g2oScw); + + vector vpReplacePoints(vpMapPoints.size(),static_cast(NULL)); + int numFused = matcher.Fuse(pKFi,cvScw,vpMapPoints,4,vpReplacePoints); + + // Get Map Mutex + unique_lock lock(pMap->mMutexMapUpdate); + const int nLP = vpMapPoints.size(); + for(int i=0; iReplace(vpMapPoints[i]); + + } + } + + total_replaces += num_replaces; + } + cout << "FUSE: " << total_replaces << " MPs had been fused" << endl; +} + + +void LoopClosing::SearchAndFuse(const vector &vConectedKFs, vector &vpMapPoints) +{ + ORBmatcher matcher(0.8); + + int total_replaces = 0; + + cout << "FUSE-POSE: Initially there are " << vpMapPoints.size() << " MPs" << endl; + cout << "FUSE-POSE: Intially there are " << vConectedKFs.size() << " KFs" << endl; + for(auto mit=vConectedKFs.begin(), mend=vConectedKFs.end(); mit!=mend;mit++) + { + int num_replaces = 0; + KeyFrame* pKF = (*mit); + Map* pMap = pKF->GetMap(); + cv::Mat cvScw = pKF->GetPose(); + + vector vpReplacePoints(vpMapPoints.size(),static_cast(NULL)); + matcher.Fuse(pKF,cvScw,vpMapPoints,4,vpReplacePoints); + + // Get Map Mutex + unique_lock lock(pMap->mMutexMapUpdate); + const int nLP = vpMapPoints.size(); + for(int i=0; iReplace(vpMapPoints[i]); + } + } + cout << "FUSE-POSE: KF " << pKF->mnId << " ->" << num_replaces << " MPs fused" << endl; + total_replaces += num_replaces; + } + cout << "FUSE-POSE: " << total_replaces << " MPs had been fused" << endl; +} + + + +void LoopClosing::RequestReset() +{ + { + unique_lock lock(mMutexReset); + mbResetRequested = true; + } + + while(1) + { + { + unique_lock lock2(mMutexReset); + if(!mbResetRequested) + break; + } + usleep(5000); + } +} + +void LoopClosing::RequestResetActiveMap(Map *pMap) +{ + { + unique_lock lock(mMutexReset); + mbResetActiveMapRequested = true; + mpMapToReset = pMap; + } + + while(1) + { + { + unique_lock lock2(mMutexReset); + if(!mbResetActiveMapRequested) + break; + } + usleep(3000); + } +} + +void LoopClosing::ResetIfRequested() +{ + unique_lock lock(mMutexReset); + if(mbResetRequested) + { + cout << "Loop closer reset requested..." << endl; + mlpLoopKeyFrameQueue.clear(); + mLastLoopKFid=0; //TODO old variable, it is not use in the new algorithm + mbResetRequested=false; + mbResetActiveMapRequested = false; + } + else if(mbResetActiveMapRequested) + { + + for (list::const_iterator it=mlpLoopKeyFrameQueue.begin(); it != mlpLoopKeyFrameQueue.end();) + { + KeyFrame* pKFi = *it; + if(pKFi->GetMap() == mpMapToReset) + { + it = mlpLoopKeyFrameQueue.erase(it); + } + else + ++it; + } + + mLastLoopKFid=mpAtlas->GetLastInitKFid(); //TODO old variable, it is not use in the new algorithm + mbResetActiveMapRequested=false; + + } +} + +void LoopClosing::RunGlobalBundleAdjustment(Map* pActiveMap, unsigned long nLoopKF) +{ + Verbose::PrintMess("Starting Global Bundle Adjustment", Verbose::VERBOSITY_NORMAL); + + const bool bImuInit = pActiveMap->isImuInitialized(); + + if(!bImuInit) + Optimizer::GlobalBundleAdjustemnt(pActiveMap,10,&mbStopGBA,nLoopKF,false); + else + Optimizer::FullInertialBA(pActiveMap,7,false,nLoopKF,&mbStopGBA); + + + int idx = mnFullBAIdx; + // Optimizer::GlobalBundleAdjustemnt(mpMap,10,&mbStopGBA,nLoopKF,false); + + // Update all MapPoints and KeyFrames + // Local Mapping was active during BA, that means that there might be new keyframes + // not included in the Global BA and they are not consistent with the updated map. + // We need to propagate the correction through the spanning tree + { + unique_lock lock(mMutexGBA); + if(idx!=mnFullBAIdx) + return; + + if(!bImuInit && pActiveMap->isImuInitialized()) + return; + + if(!mbStopGBA) + { + Verbose::PrintMess("Global Bundle Adjustment finished", Verbose::VERBOSITY_NORMAL); + Verbose::PrintMess("Updating map ...", Verbose::VERBOSITY_NORMAL); + + mpLocalMapper->RequestStop(); + // Wait until Local Mapping has effectively stopped + + while(!mpLocalMapper->isStopped() && !mpLocalMapper->isFinished()) + { + usleep(1000); + } + + // Get Map Mutex + unique_lock lock(pActiveMap->mMutexMapUpdate); + // cout << "LC: Update Map Mutex adquired" << endl; + + //pActiveMap->PrintEssentialGraph(); + // Correct keyframes starting at map first keyframe + list lpKFtoCheck(pActiveMap->mvpKeyFrameOrigins.begin(),pActiveMap->mvpKeyFrameOrigins.end()); + + while(!lpKFtoCheck.empty()) + { + KeyFrame* pKF = lpKFtoCheck.front(); + const set sChilds = pKF->GetChilds(); + //cout << "---Updating KF " << pKF->mnId << " with " << sChilds.size() << " childs" << endl; + //cout << " KF mnBAGlobalForKF: " << pKF->mnBAGlobalForKF << endl; + cv::Mat Twc = pKF->GetPoseInverse(); + //cout << "Twc: " << Twc << endl; + //cout << "GBA: Correct KeyFrames" << endl; + for(set::const_iterator sit=sChilds.begin();sit!=sChilds.end();sit++) + { + KeyFrame* pChild = *sit; + if(!pChild || pChild->isBad()) + continue; + + if(pChild->mnBAGlobalForKF!=nLoopKF) + { + //cout << "++++New child with flag " << pChild->mnBAGlobalForKF << "; LoopKF: " << nLoopKF << endl; + //cout << " child id: " << pChild->mnId << endl; + cv::Mat Tchildc = pChild->GetPose()*Twc; + //cout << "Child pose: " << Tchildc << endl; + //cout << "pKF->mTcwGBA: " << pKF->mTcwGBA << endl; + pChild->mTcwGBA = Tchildc*pKF->mTcwGBA;//*Tcorc*pKF->mTcwGBA; + + cv::Mat Rcor = pChild->mTcwGBA.rowRange(0,3).colRange(0,3).t()*pChild->GetRotation(); + if(!pChild->GetVelocity().empty()){ + //cout << "Child velocity: " << pChild->GetVelocity() << endl; + pChild->mVwbGBA = Rcor*pChild->GetVelocity(); + } + else + Verbose::PrintMess("Child velocity empty!! ", Verbose::VERBOSITY_NORMAL); + + + //cout << "Child bias: " << pChild->GetImuBias() << endl; + pChild->mBiasGBA = pChild->GetImuBias(); + + + pChild->mnBAGlobalForKF=nLoopKF; + + } + lpKFtoCheck.push_back(pChild); + } + + //cout << "-------Update pose" << endl; + pKF->mTcwBefGBA = pKF->GetPose(); + //cout << "pKF->mTcwBefGBA: " << pKF->mTcwBefGBA << endl; + pKF->SetPose(pKF->mTcwGBA); + /*cv::Mat Tco_cn = pKF->mTcwBefGBA * pKF->mTcwGBA.inv(); + cv::Vec3d trasl = Tco_cn.rowRange(0,3).col(3); + double dist = cv::norm(trasl); + cout << "GBA: KF " << pKF->mnId << " had been moved " << dist << " meters" << endl; + double desvX = 0; + double desvY = 0; + double desvZ = 0; + if(pKF->mbHasHessian) + { + cv::Mat hessianInv = pKF->mHessianPose.inv(); + + double covX = hessianInv.at(3,3); + desvX = std::sqrt(covX); + double covY = hessianInv.at(4,4); + desvY = std::sqrt(covY); + double covZ = hessianInv.at(5,5); + desvZ = std::sqrt(covZ); + pKF->mbHasHessian = false; + } + if(dist > 1) + { + cout << "--To much distance correction: It has " << pKF->GetConnectedKeyFrames().size() << " connected KFs" << endl; + cout << "--It has " << pKF->GetCovisiblesByWeight(80).size() << " connected KF with 80 common matches or more" << endl; + cout << "--It has " << pKF->GetCovisiblesByWeight(50).size() << " connected KF with 50 common matches or more" << endl; + cout << "--It has " << pKF->GetCovisiblesByWeight(20).size() << " connected KF with 20 common matches or more" << endl; + + cout << "--STD in meters(x, y, z): " << desvX << ", " << desvY << ", " << desvZ << endl; + + + string strNameFile = pKF->mNameFile; + cv::Mat imLeft = cv::imread(strNameFile, CV_LOAD_IMAGE_UNCHANGED); + + cv::cvtColor(imLeft, imLeft, CV_GRAY2BGR); + + vector vpMapPointsKF = pKF->GetMapPointMatches(); + int num_MPs = 0; + for(int i=0; iisBad()) + { + continue; + } + num_MPs += 1; + string strNumOBs = to_string(vpMapPointsKF[i]->Observations()); + cv::circle(imLeft, pKF->mvKeys[i].pt, 2, cv::Scalar(0, 255, 0)); + cv::putText(imLeft, strNumOBs, pKF->mvKeys[i].pt, CV_FONT_HERSHEY_DUPLEX, 1, cv::Scalar(255, 0, 0)); + } + cout << "--It has " << num_MPs << " MPs matched in the map" << endl; + + string namefile = "./test_GBA/GBA_" + to_string(nLoopKF) + "_KF" + to_string(pKF->mnId) +"_D" + to_string(dist) +".png"; + cv::imwrite(namefile, imLeft); + }*/ + + + if(pKF->bImu) + { + //cout << "-------Update inertial values" << endl; + pKF->mVwbBefGBA = pKF->GetVelocity(); + if (pKF->mVwbGBA.empty()) + Verbose::PrintMess("pKF->mVwbGBA is empty", Verbose::VERBOSITY_NORMAL); + + assert(!pKF->mVwbGBA.empty()); + pKF->SetVelocity(pKF->mVwbGBA); + pKF->SetNewBias(pKF->mBiasGBA); + } + + lpKFtoCheck.pop_front(); + } + + //cout << "GBA: Correct MapPoints" << endl; + // Correct MapPoints + const vector vpMPs = pActiveMap->GetAllMapPoints(); + + for(size_t i=0; iisBad()) + continue; + + if(pMP->mnBAGlobalForKF==nLoopKF) + { + // If optimized by Global BA, just update + pMP->SetWorldPos(pMP->mPosGBA); + } + else + { + // Update according to the correction of its reference keyframe + KeyFrame* pRefKF = pMP->GetReferenceKeyFrame(); + + if(pRefKF->mnBAGlobalForKF!=nLoopKF) + continue; + + if(pRefKF->mTcwBefGBA.empty()) + continue; + + // Map to non-corrected camera + cv::Mat Rcw = pRefKF->mTcwBefGBA.rowRange(0,3).colRange(0,3); + cv::Mat tcw = pRefKF->mTcwBefGBA.rowRange(0,3).col(3); + cv::Mat Xc = Rcw*pMP->GetWorldPos()+tcw; + + // Backproject using corrected camera + cv::Mat Twc = pRefKF->GetPoseInverse(); + cv::Mat Rwc = Twc.rowRange(0,3).colRange(0,3); + cv::Mat twc = Twc.rowRange(0,3).col(3); + + pMP->SetWorldPos(Rwc*Xc+twc); + } + } + + pActiveMap->InformNewBigChange(); + pActiveMap->IncreaseChangeIndex(); + + // TODO Check this update + // mpTracker->UpdateFrameIMU(1.0f, mpTracker->GetLastKeyFrame()->GetImuBias(), mpTracker->GetLastKeyFrame()); + + mpLocalMapper->Release(); + + Verbose::PrintMess("Map updated!", Verbose::VERBOSITY_NORMAL); + } + + mbFinishedGBA = true; + mbRunningGBA = false; + } +} + +void LoopClosing::RequestFinish() +{ + unique_lock lock(mMutexFinish); + // cout << "LC: Finish requested" << endl; + mbFinishRequested = true; +} + +bool LoopClosing::CheckFinish() +{ + unique_lock lock(mMutexFinish); + return mbFinishRequested; +} + +void LoopClosing::SetFinish() +{ + unique_lock lock(mMutexFinish); + mbFinished = true; +} + +bool LoopClosing::isFinished() +{ + unique_lock lock(mMutexFinish); + return mbFinished; +} + + +} //namespace ORB_SLAM diff --git a/third_party/ORB_SLAM3/src/MLPnPsolver.cpp b/third_party/ORB_SLAM3/src/MLPnPsolver.cpp new file mode 100644 index 0000000..02f1545 --- /dev/null +++ b/third_party/ORB_SLAM3/src/MLPnPsolver.cpp @@ -0,0 +1,1051 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ +/****************************************************************************** +* Author: Steffen Urban * +* Contact: urbste@gmail.com * +* License: Copyright (c) 2016 Steffen Urban, ANU. All rights reserved. * +* * +* Redistribution and use in source and binary forms, with or without * +* modification, are permitted provided that the following conditions * +* are met: * +* * Redistributions of source code must retain the above copyright * +* notice, this list of conditions and the following disclaimer. * +* * Redistributions in binary form must reproduce the above copyright * +* notice, this list of conditions and the following disclaimer in the * +* documentation and/or other materials provided with the distribution. * +* * Neither the name of ANU nor the names of its contributors may be * +* used to endorse or promote products derived from this software without * +* specific prior written permission. * +* * +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * +* ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * +* OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * +* SUCH DAMAGE. * +******************************************************************************/ + +#include "MLPnPsolver.h" + +#include + + +namespace ORB_SLAM3 { + MLPnPsolver::MLPnPsolver(const Frame &F, const vector &vpMapPointMatches): + mnInliersi(0), mnIterations(0), mnBestInliers(0), N(0), mpCamera(F.mpCamera){ + mvpMapPointMatches = vpMapPointMatches; + mvBearingVecs.reserve(F.mvpMapPoints.size()); + mvP2D.reserve(F.mvpMapPoints.size()); + mvSigma2.reserve(F.mvpMapPoints.size()); + mvP3Dw.reserve(F.mvpMapPoints.size()); + mvKeyPointIndices.reserve(F.mvpMapPoints.size()); + mvAllIndices.reserve(F.mvpMapPoints.size()); + + int idx = 0; + for(size_t i = 0, iend = mvpMapPointMatches.size(); i < iend; i++){ + MapPoint* pMP = vpMapPointMatches[i]; + + if(pMP){ + if(!pMP -> isBad()){ + if(i >= F.mvKeysUn.size()) continue; + const cv::KeyPoint &kp = F.mvKeysUn[i]; + + mvP2D.push_back(kp.pt); + mvSigma2.push_back(F.mvLevelSigma2[kp.octave]); + + //Bearing vector should be normalized + cv::Point3f cv_br = mpCamera->unproject(kp.pt); + cv_br /= cv_br.z; + bearingVector_t br(cv_br.x,cv_br.y,cv_br.z); + mvBearingVecs.push_back(br); + + //3D coordinates + cv::Mat cv_pos = pMP -> GetWorldPos(); + point_t pos(cv_pos.at(0),cv_pos.at(1),cv_pos.at(2)); + mvP3Dw.push_back(pos); + + mvKeyPointIndices.push_back(i); + mvAllIndices.push_back(idx); + + idx++; + } + } + } + + SetRansacParameters(); + } + + //RANSAC methods + cv::Mat MLPnPsolver::iterate(int nIterations, bool &bNoMore, vector &vbInliers, int &nInliers){ + bNoMore = false; + vbInliers.clear(); + nInliers=0; + + if(N vAvailableIndices; + + int nCurrentIterations = 0; + while(mnIterations indexes(mRansacMinSet); + + // Get min set of points + for(short i = 0; i < mRansacMinSet; ++i) + { + int randi = DUtils::Random::RandomInt(0, vAvailableIndices.size()-1); + + int idx = vAvailableIndices[randi]; + + bearingVecs[i] = mvBearingVecs[idx]; + p3DS[i] = mvP3Dw[idx]; + indexes[i] = i; + + vAvailableIndices[randi] = vAvailableIndices.back(); + vAvailableIndices.pop_back(); + } + + //By the moment, we are using MLPnP without covariance info + cov3_mats_t covs(1); + + //Result + transformation_t result; + + // Compute camera pose + computePose(bearingVecs,p3DS,covs,indexes,result); + + //Save result + mRi[0][0] = result(0,0); + mRi[0][1] = result(0,1); + mRi[0][2] = result(0,2); + + mRi[1][0] = result(1,0); + mRi[1][1] = result(1,1); + mRi[1][2] = result(1,2); + + mRi[2][0] = result(2,0); + mRi[2][1] = result(2,1); + mRi[2][2] = result(2,2); + + mti[0] = result(0,3);mti[1] = result(1,3);mti[2] = result(2,3); + + // Check inliers + CheckInliers(); + + if(mnInliersi>=mRansacMinInliers) + { + // If it is the best solution so far, save it + if(mnInliersi>mnBestInliers) + { + mvbBestInliers = mvbInliersi; + mnBestInliers = mnInliersi; + + cv::Mat Rcw(3,3,CV_64F,mRi); + cv::Mat tcw(3,1,CV_64F,mti); + Rcw.convertTo(Rcw,CV_32F); + tcw.convertTo(tcw,CV_32F); + mBestTcw = cv::Mat::eye(4,4,CV_32F); + Rcw.copyTo(mBestTcw.rowRange(0,3).colRange(0,3)); + tcw.copyTo(mBestTcw.rowRange(0,3).col(3)); + } + + if(Refine()) + { + nInliers = mnRefinedInliers; + vbInliers = vector(mvpMapPointMatches.size(),false); + for(int i=0; i=mRansacMaxIts) + { + bNoMore=true; + if(mnBestInliers>=mRansacMinInliers) + { + nInliers=mnBestInliers; + vbInliers = vector(mvpMapPointMatches.size(),false); + for(int i=0; iproject(P3Dc); + + float distX = P2D.x-uv.x; + float distY = P2D.y-uv.y; + + float error2 = distX*distX+distY*distY; + + if(error2 vIndices; + vIndices.reserve(mvbBestInliers.size()); + + for(size_t i=0; i indexes; + + for(size_t i=0; imRansacMinInliers) + { + cv::Mat Rcw(3,3,CV_64F,mRi); + cv::Mat tcw(3,1,CV_64F,mti); + Rcw.convertTo(Rcw,CV_32F); + tcw.convertTo(tcw,CV_32F); + mRefinedTcw = cv::Mat::eye(4,4,CV_32F); + Rcw.copyTo(mRefinedTcw.rowRange(0,3).colRange(0,3)); + tcw.copyTo(mRefinedTcw.rowRange(0,3).col(3)); + return true; + } + + return false; + } + + //MLPnP methods + void MLPnPsolver::computePose(const bearingVectors_t &f, const points_t &p, const cov3_mats_t &covMats, + const std::vector &indices, transformation_t &result) { + size_t numberCorrespondences = indices.size(); + assert(numberCorrespondences > 5); + + bool planar = false; + // compute the nullspace of all vectors + std::vector nullspaces(numberCorrespondences); + Eigen::MatrixXd points3(3, numberCorrespondences); + points_t points3v(numberCorrespondences); + points4_t points4v(numberCorrespondences); + for (size_t i = 0; i < numberCorrespondences; i++) { + bearingVector_t f_current = f[indices[i]]; + points3.col(i) = p[indices[i]]; + // nullspace of right vector + Eigen::JacobiSVD + svd_f(f_current.transpose(), Eigen::ComputeFullV); + nullspaces[i] = svd_f.matrixV().block(0, 1, 3, 2); + points3v[i] = p[indices[i]]; + } + + ////////////////////////////////////// + // 1. test if we have a planar scene + ////////////////////////////////////// + + Eigen::Matrix3d planarTest = points3 * points3.transpose(); + Eigen::FullPivHouseholderQR rankTest(planarTest); + //int r, c; + //double minEigenVal = abs(eigen_solver.eigenvalues().real().minCoeff(&r, &c)); + Eigen::Matrix3d eigenRot; + eigenRot.setIdentity(); + + // if yes -> transform points to new eigen frame + //if (minEigenVal < 1e-3 || minEigenVal == 0.0) + //rankTest.setThreshold(1e-10); + if (rankTest.rank() == 2) { + planar = true; + // self adjoint is faster and more accurate than general eigen solvers + // also has closed form solution for 3x3 self-adjoint matrices + // in addition this solver sorts the eigenvalues in increasing order + Eigen::SelfAdjointEigenSolver eigen_solver(planarTest); + eigenRot = eigen_solver.eigenvectors().real(); + eigenRot.transposeInPlace(); + for (size_t i = 0; i < numberCorrespondences; i++) + points3.col(i) = eigenRot * points3.col(i); + } + ////////////////////////////////////// + // 2. stochastic model + ////////////////////////////////////// + Eigen::SparseMatrix P(2 * numberCorrespondences, + 2 * numberCorrespondences); + bool use_cov = false; + P.setIdentity(); // standard + + // if we do have covariance information + // -> fill covariance matrix + if (covMats.size() == numberCorrespondences) { + use_cov = true; + int l = 0; + for (size_t i = 0; i < numberCorrespondences; ++i) { + // invert matrix + cov2_mat_t temp = nullspaces[i].transpose() * covMats[i] * nullspaces[i]; + temp = temp.inverse().eval(); + P.coeffRef(l, l) = temp(0, 0); + P.coeffRef(l, l + 1) = temp(0, 1); + P.coeffRef(l + 1, l) = temp(1, 0); + P.coeffRef(l + 1, l + 1) = temp(1, 1); + l += 2; + } + } + + ////////////////////////////////////// + // 3. fill the design matrix A + ////////////////////////////////////// + const int rowsA = 2 * numberCorrespondences; + int colsA = 12; + Eigen::MatrixXd A; + if (planar) { + colsA = 9; + A = Eigen::MatrixXd(rowsA, 9); + } else + A = Eigen::MatrixXd(rowsA, 12); + A.setZero(); + + // fill design matrix + if (planar) { + for (size_t i = 0; i < numberCorrespondences; ++i) { + point_t pt3_current = points3.col(i); + + // r12 + A(2 * i, 0) = nullspaces[i](0, 0) * pt3_current[1]; + A(2 * i + 1, 0) = nullspaces[i](0, 1) * pt3_current[1]; + // r13 + A(2 * i, 1) = nullspaces[i](0, 0) * pt3_current[2]; + A(2 * i + 1, 1) = nullspaces[i](0, 1) * pt3_current[2]; + // r22 + A(2 * i, 2) = nullspaces[i](1, 0) * pt3_current[1]; + A(2 * i + 1, 2) = nullspaces[i](1, 1) * pt3_current[1]; + // r23 + A(2 * i, 3) = nullspaces[i](1, 0) * pt3_current[2]; + A(2 * i + 1, 3) = nullspaces[i](1, 1) * pt3_current[2]; + // r32 + A(2 * i, 4) = nullspaces[i](2, 0) * pt3_current[1]; + A(2 * i + 1, 4) = nullspaces[i](2, 1) * pt3_current[1]; + // r33 + A(2 * i, 5) = nullspaces[i](2, 0) * pt3_current[2]; + A(2 * i + 1, 5) = nullspaces[i](2, 1) * pt3_current[2]; + // t1 + A(2 * i, 6) = nullspaces[i](0, 0); + A(2 * i + 1, 6) = nullspaces[i](0, 1); + // t2 + A(2 * i, 7) = nullspaces[i](1, 0); + A(2 * i + 1, 7) = nullspaces[i](1, 1); + // t3 + A(2 * i, 8) = nullspaces[i](2, 0); + A(2 * i + 1, 8) = nullspaces[i](2, 1); + } + } else { + for (size_t i = 0; i < numberCorrespondences; ++i) { + point_t pt3_current = points3.col(i); + + // r11 + A(2 * i, 0) = nullspaces[i](0, 0) * pt3_current[0]; + A(2 * i + 1, 0) = nullspaces[i](0, 1) * pt3_current[0]; + // r12 + A(2 * i, 1) = nullspaces[i](0, 0) * pt3_current[1]; + A(2 * i + 1, 1) = nullspaces[i](0, 1) * pt3_current[1]; + // r13 + A(2 * i, 2) = nullspaces[i](0, 0) * pt3_current[2]; + A(2 * i + 1, 2) = nullspaces[i](0, 1) * pt3_current[2]; + // r21 + A(2 * i, 3) = nullspaces[i](1, 0) * pt3_current[0]; + A(2 * i + 1, 3) = nullspaces[i](1, 1) * pt3_current[0]; + // r22 + A(2 * i, 4) = nullspaces[i](1, 0) * pt3_current[1]; + A(2 * i + 1, 4) = nullspaces[i](1, 1) * pt3_current[1]; + // r23 + A(2 * i, 5) = nullspaces[i](1, 0) * pt3_current[2]; + A(2 * i + 1, 5) = nullspaces[i](1, 1) * pt3_current[2]; + // r31 + A(2 * i, 6) = nullspaces[i](2, 0) * pt3_current[0]; + A(2 * i + 1, 6) = nullspaces[i](2, 1) * pt3_current[0]; + // r32 + A(2 * i, 7) = nullspaces[i](2, 0) * pt3_current[1]; + A(2 * i + 1, 7) = nullspaces[i](2, 1) * pt3_current[1]; + // r33 + A(2 * i, 8) = nullspaces[i](2, 0) * pt3_current[2]; + A(2 * i + 1, 8) = nullspaces[i](2, 1) * pt3_current[2]; + // t1 + A(2 * i, 9) = nullspaces[i](0, 0); + A(2 * i + 1, 9) = nullspaces[i](0, 1); + // t2 + A(2 * i, 10) = nullspaces[i](1, 0); + A(2 * i + 1, 10) = nullspaces[i](1, 1); + // t3 + A(2 * i, 11) = nullspaces[i](2, 0); + A(2 * i + 1, 11) = nullspaces[i](2, 1); + } + } + + ////////////////////////////////////// + // 4. solve least squares + ////////////////////////////////////// + Eigen::MatrixXd AtPA; + if (use_cov) + AtPA = A.transpose() * P * A; // setting up the full normal equations seems to be unstable + else + AtPA = A.transpose() * A; + + Eigen::JacobiSVD svd_A(AtPA, Eigen::ComputeFullV); + Eigen::MatrixXd result1 = svd_A.matrixV().col(colsA - 1); + + //////////////////////////////// + // now we treat the results differently, + // depending on the scene (planar or not) + //////////////////////////////// + //transformation_t T_final; + rotation_t Rout; + translation_t tout; + if (planar) // planar case + { + rotation_t tmp; + // until now, we only estimated + // row one and two of the transposed rotation matrix + tmp << 0.0, result1(0, 0), result1(1, 0), + 0.0, result1(2, 0), result1(3, 0), + 0.0, result1(4, 0), result1(5, 0); + //double scale = 1 / sqrt(tmp.col(1).norm() * tmp.col(2).norm()); + // row 3 + tmp.col(0) = tmp.col(1).cross(tmp.col(2)); + tmp.transposeInPlace(); + + double scale = 1.0 / std::sqrt(std::abs(tmp.col(1).norm() * tmp.col(2).norm())); + // find best rotation matrix in frobenius sense + Eigen::JacobiSVD svd_R_frob(tmp, Eigen::ComputeFullU | Eigen::ComputeFullV); + rotation_t Rout1 = svd_R_frob.matrixU() * svd_R_frob.matrixV().transpose(); + // test if we found a good rotation matrix + if (Rout1.determinant() < 0) + Rout1 *= -1.0; + // rotate this matrix back using the eigen frame + Rout1 = eigenRot.transpose() * Rout1; + + translation_t t = scale * translation_t(result1(6, 0), result1(7, 0), result1(8, 0)); + Rout1.transposeInPlace(); + Rout1 *= -1; + if (Rout1.determinant() < 0.0) + Rout1.col(2) *= -1; + // now we have to find the best out of 4 combinations + rotation_t R1, R2; + R1.col(0) = Rout1.col(0); + R1.col(1) = Rout1.col(1); + R1.col(2) = Rout1.col(2); + R2.col(0) = -Rout1.col(0); + R2.col(1) = -Rout1.col(1); + R2.col(2) = Rout1.col(2); + + vector> Ts(4); + Ts[0].block<3, 3>(0, 0) = R1; + Ts[0].block<3, 1>(0, 3) = t; + Ts[1].block<3, 3>(0, 0) = R1; + Ts[1].block<3, 1>(0, 3) = -t; + Ts[2].block<3, 3>(0, 0) = R2; + Ts[2].block<3, 1>(0, 3) = t; + Ts[3].block<3, 3>(0, 0) = R2; + Ts[3].block<3, 1>(0, 3) = -t; + + vector normVal(4); + for (int i = 0; i < 4; ++i) { + point_t reproPt; + double norms = 0.0; + for (int p = 0; p < 6; ++p) { + reproPt = Ts[i].block<3, 3>(0, 0) * points3v[p] + Ts[i].block<3, 1>(0, 3); + reproPt = reproPt / reproPt.norm(); + norms += (1.0 - reproPt.transpose() * f[indices[p]]); + } + normVal[i] = norms; + } + std::vector::iterator + findMinRepro = std::min_element(std::begin(normVal), std::end(normVal)); + int idx = std::distance(std::begin(normVal), findMinRepro); + Rout = Ts[idx].block<3, 3>(0, 0); + tout = Ts[idx].block<3, 1>(0, 3); + } else // non-planar + { + rotation_t tmp; + tmp << result1(0, 0), result1(3, 0), result1(6, 0), + result1(1, 0), result1(4, 0), result1(7, 0), + result1(2, 0), result1(5, 0), result1(8, 0); + // get the scale + double scale = 1.0 / + std::pow(std::abs(tmp.col(0).norm() * tmp.col(1).norm() * tmp.col(2).norm()), 1.0 / 3.0); + //double scale = 1.0 / std::sqrt(std::abs(tmp.col(0).norm() * tmp.col(1).norm())); + // find best rotation matrix in frobenius sense + Eigen::JacobiSVD svd_R_frob(tmp, Eigen::ComputeFullU | Eigen::ComputeFullV); + Rout = svd_R_frob.matrixU() * svd_R_frob.matrixV().transpose(); + // test if we found a good rotation matrix + if (Rout.determinant() < 0) + Rout *= -1.0; + // scale translation + tout = Rout * (scale * translation_t(result1(9, 0), result1(10, 0), result1(11, 0))); + + // find correct direction in terms of reprojection error, just take the first 6 correspondences + vector error(2); + vector> Ts(2); + for (int s = 0; s < 2; ++s) { + error[s] = 0.0; + Ts[s] = Eigen::Matrix4d::Identity(); + Ts[s].block<3, 3>(0, 0) = Rout; + if (s == 0) + Ts[s].block<3, 1>(0, 3) = tout; + else + Ts[s].block<3, 1>(0, 3) = -tout; + Ts[s] = Ts[s].inverse().eval(); + for (int p = 0; p < 6; ++p) { + bearingVector_t v = Ts[s].block<3, 3>(0, 0) * points3v[p] + Ts[s].block<3, 1>(0, 3); + v = v / v.norm(); + error[s] += (1.0 - v.transpose() * f[indices[p]]); + } + } + if (error[0] < error[1]) + tout = Ts[0].block<3, 1>(0, 3); + else + tout = Ts[1].block<3, 1>(0, 3); + Rout = Ts[0].block<3, 3>(0, 0); + + } + + ////////////////////////////////////// + // 5. gauss newton + ////////////////////////////////////// + rodrigues_t omega = rot2rodrigues(Rout); + Eigen::VectorXd minx(6); + minx[0] = omega[0]; + minx[1] = omega[1]; + minx[2] = omega[2]; + minx[3] = tout[0]; + minx[4] = tout[1]; + minx[5] = tout[2]; + + mlpnp_gn(minx, points3v, nullspaces, P, use_cov); + + Rout = rodrigues2rot(rodrigues_t(minx[0], minx[1], minx[2])); + tout = translation_t(minx[3], minx[4], minx[5]); + // result inverse as opengv uses this convention + result.block<3, 3>(0, 0) = Rout;//Rout.transpose(); + result.block<3, 1>(0, 3) = tout;//-result.block<3, 3>(0, 0) * tout; + } + + Eigen::Matrix3d MLPnPsolver::rodrigues2rot(const Eigen::Vector3d &omega) { + rotation_t R = Eigen::Matrix3d::Identity(); + + Eigen::Matrix3d skewW; + skewW << 0.0, -omega(2), omega(1), + omega(2), 0.0, -omega(0), + -omega(1), omega(0), 0.0; + + double omega_norm = omega.norm(); + + if (omega_norm > std::numeric_limits::epsilon()) + R = R + sin(omega_norm) / omega_norm * skewW + + (1 - cos(omega_norm)) / (omega_norm * omega_norm) * (skewW * skewW); + + return R; + } + + Eigen::Vector3d MLPnPsolver::rot2rodrigues(const Eigen::Matrix3d &R) { + rodrigues_t omega; + omega << 0.0, 0.0, 0.0; + + double trace = R.trace() - 1.0; + double wnorm = acos(trace / 2.0); + if (wnorm > std::numeric_limits::epsilon()) + { + omega[0] = (R(2, 1) - R(1, 2)); + omega[1] = (R(0, 2) - R(2, 0)); + omega[2] = (R(1, 0) - R(0, 1)); + double sc = wnorm / (2.0*sin(wnorm)); + omega *= sc; + } + return omega; + } + + void MLPnPsolver::mlpnp_gn(Eigen::VectorXd &x, const points_t &pts, const std::vector &nullspaces, + const Eigen::SparseMatrix Kll, bool use_cov) { + const int numObservations = pts.size(); + const int numUnknowns = 6; + // check redundancy + assert((2 * numObservations - numUnknowns) > 0); + + // ============= + // set all matrices up + // ============= + + Eigen::VectorXd r(2 * numObservations); + Eigen::VectorXd rd(2 * numObservations); + Eigen::MatrixXd Jac(2 * numObservations, numUnknowns); + Eigen::VectorXd g(numUnknowns, 1); + Eigen::VectorXd dx(numUnknowns, 1); // result vector + + Jac.setZero(); + r.setZero(); + dx.setZero(); + g.setZero(); + + int it_cnt = 0; + bool stop = false; + const int maxIt = 5; + double epsP = 1e-5; + + Eigen::MatrixXd JacTSKll; + Eigen::MatrixXd A; + // solve simple gradient descent + while (it_cnt < maxIt && !stop) { + mlpnp_residuals_and_jacs(x, pts, + nullspaces, + r, Jac, true); + + if (use_cov) + JacTSKll = Jac.transpose() * Kll; + else + JacTSKll = Jac.transpose(); + + A = JacTSKll * Jac; + + // get system matrix + g = JacTSKll * r; + + // solve + Eigen::LDLT chol(A); + dx = chol.solve(g); + //dx = A.jacobiSvd(Eigen::ComputeThinU | Eigen::ComputeThinV).solve(g); + // this is to prevent the solution from falling into a wrong minimum + // if the linear estimate is spurious + if (dx.array().abs().maxCoeff() > 5.0 || dx.array().abs().minCoeff() > 1.0) + break; + // observation update + Eigen::MatrixXd dl = Jac * dx; + if (dl.array().abs().maxCoeff() < epsP) { + stop = true; + x = x - dx; + break; + } else + x = x - dx; + + ++it_cnt; + }//while + // result + } + + void MLPnPsolver::mlpnp_residuals_and_jacs(const Eigen::VectorXd &x, const points_t &pts, + const std::vector &nullspaces, Eigen::VectorXd &r, + Eigen::MatrixXd &fjac, bool getJacs) { + rodrigues_t w(x[0], x[1], x[2]); + translation_t T(x[3], x[4], x[5]); + + //rotation_t R = math::cayley2rot(c); + rotation_t R = rodrigues2rot(w); + int ii = 0; + + Eigen::MatrixXd jacs(2, 6); + + for (int i = 0; i < pts.size(); ++i) + { + Eigen::Vector3d ptCam = R*pts[i] + T; + ptCam /= ptCam.norm(); + + r[ii] = nullspaces[i].col(0).transpose()*ptCam; + r[ii + 1] = nullspaces[i].col(1).transpose()*ptCam; + if (getJacs) + { + // jacs + mlpnpJacs(pts[i], + nullspaces[i].col(0), nullspaces[i].col(1), + w, T, + jacs); + + // r + fjac(ii, 0) = jacs(0, 0); + fjac(ii, 1) = jacs(0, 1); + fjac(ii, 2) = jacs(0, 2); + + fjac(ii, 3) = jacs(0, 3); + fjac(ii, 4) = jacs(0, 4); + fjac(ii, 5) = jacs(0, 5); + // s + fjac(ii + 1, 0) = jacs(1, 0); + fjac(ii + 1, 1) = jacs(1, 1); + fjac(ii + 1, 2) = jacs(1, 2); + + fjac(ii + 1, 3) = jacs(1, 3); + fjac(ii + 1, 4) = jacs(1, 4); + fjac(ii + 1, 5) = jacs(1, 5); + + } + ii += 2; + } + } + + void MLPnPsolver::mlpnpJacs(const point_t& pt, const Eigen::Vector3d& nullspace_r, + const Eigen::Vector3d& nullspace_s, const rodrigues_t& w, + const translation_t& t, Eigen::MatrixXd& jacs){ + double r1 = nullspace_r[0]; + double r2 = nullspace_r[1]; + double r3 = nullspace_r[2]; + + double s1 = nullspace_s[0]; + double s2 = nullspace_s[1]; + double s3 = nullspace_s[2]; + + double X1 = pt[0]; + double Y1 = pt[1]; + double Z1 = pt[2]; + + double w1 = w[0]; + double w2 = w[1]; + double w3 = w[2]; + + double t1 = t[0]; + double t2 = t[1]; + double t3 = t[2]; + + double t5 = w1*w1; + double t6 = w2*w2; + double t7 = w3*w3; + double t8 = t5+t6+t7; + double t9 = sqrt(t8); + double t10 = sin(t9); + double t11 = 1.0/sqrt(t8); + double t12 = cos(t9); + double t13 = t12-1.0; + double t14 = 1.0/t8; + double t16 = t10*t11*w3; + double t17 = t13*t14*w1*w2; + double t19 = t10*t11*w2; + double t20 = t13*t14*w1*w3; + double t24 = t6+t7; + double t27 = t16+t17; + double t28 = Y1*t27; + double t29 = t19-t20; + double t30 = Z1*t29; + double t31 = t13*t14*t24; + double t32 = t31+1.0; + double t33 = X1*t32; + double t15 = t1-t28+t30+t33; + double t21 = t10*t11*w1; + double t22 = t13*t14*w2*w3; + double t45 = t5+t7; + double t53 = t16-t17; + double t54 = X1*t53; + double t55 = t21+t22; + double t56 = Z1*t55; + double t57 = t13*t14*t45; + double t58 = t57+1.0; + double t59 = Y1*t58; + double t18 = t2+t54-t56+t59; + double t34 = t5+t6; + double t38 = t19+t20; + double t39 = X1*t38; + double t40 = t21-t22; + double t41 = Y1*t40; + double t42 = t13*t14*t34; + double t43 = t42+1.0; + double t44 = Z1*t43; + double t23 = t3-t39+t41+t44; + double t25 = 1.0/pow(t8,3.0/2.0); + double t26 = 1.0/(t8*t8); + double t35 = t12*t14*w1*w2; + double t36 = t5*t10*t25*w3; + double t37 = t5*t13*t26*w3*2.0; + double t46 = t10*t25*w1*w3; + double t47 = t5*t10*t25*w2; + double t48 = t5*t13*t26*w2*2.0; + double t49 = t10*t11; + double t50 = t5*t12*t14; + double t51 = t13*t26*w1*w2*w3*2.0; + double t52 = t10*t25*w1*w2*w3; + double t60 = t15*t15; + double t61 = t18*t18; + double t62 = t23*t23; + double t63 = t60+t61+t62; + double t64 = t5*t10*t25; + double t65 = 1.0/sqrt(t63); + double t66 = Y1*r2*t6; + double t67 = Z1*r3*t7; + double t68 = r1*t1*t5; + double t69 = r1*t1*t6; + double t70 = r1*t1*t7; + double t71 = r2*t2*t5; + double t72 = r2*t2*t6; + double t73 = r2*t2*t7; + double t74 = r3*t3*t5; + double t75 = r3*t3*t6; + double t76 = r3*t3*t7; + double t77 = X1*r1*t5; + double t78 = X1*r2*w1*w2; + double t79 = X1*r3*w1*w3; + double t80 = Y1*r1*w1*w2; + double t81 = Y1*r3*w2*w3; + double t82 = Z1*r1*w1*w3; + double t83 = Z1*r2*w2*w3; + double t84 = X1*r1*t6*t12; + double t85 = X1*r1*t7*t12; + double t86 = Y1*r2*t5*t12; + double t87 = Y1*r2*t7*t12; + double t88 = Z1*r3*t5*t12; + double t89 = Z1*r3*t6*t12; + double t90 = X1*r2*t9*t10*w3; + double t91 = Y1*r3*t9*t10*w1; + double t92 = Z1*r1*t9*t10*w2; + double t102 = X1*r3*t9*t10*w2; + double t103 = Y1*r1*t9*t10*w3; + double t104 = Z1*r2*t9*t10*w1; + double t105 = X1*r2*t12*w1*w2; + double t106 = X1*r3*t12*w1*w3; + double t107 = Y1*r1*t12*w1*w2; + double t108 = Y1*r3*t12*w2*w3; + double t109 = Z1*r1*t12*w1*w3; + double t110 = Z1*r2*t12*w2*w3; + double t93 = t66+t67+t68+t69+t70+t71+t72+t73+t74+t75+t76+t77+t78+t79+t80+t81+t82+t83+t84+t85+t86+t87+t88+t89+t90+t91+t92-t102-t103-t104-t105-t106-t107-t108-t109-t110; + double t94 = t10*t25*w1*w2; + double t95 = t6*t10*t25*w3; + double t96 = t6*t13*t26*w3*2.0; + double t97 = t12*t14*w2*w3; + double t98 = t6*t10*t25*w1; + double t99 = t6*t13*t26*w1*2.0; + double t100 = t6*t10*t25; + double t101 = 1.0/pow(t63,3.0/2.0); + double t111 = t6*t12*t14; + double t112 = t10*t25*w2*w3; + double t113 = t12*t14*w1*w3; + double t114 = t7*t10*t25*w2; + double t115 = t7*t13*t26*w2*2.0; + double t116 = t7*t10*t25*w1; + double t117 = t7*t13*t26*w1*2.0; + double t118 = t7*t12*t14; + double t119 = t13*t24*t26*w1*2.0; + double t120 = t10*t24*t25*w1; + double t121 = t119+t120; + double t122 = t13*t26*t34*w1*2.0; + double t123 = t10*t25*t34*w1; + double t131 = t13*t14*w1*2.0; + double t124 = t122+t123-t131; + double t139 = t13*t14*w3; + double t125 = -t35+t36+t37+t94-t139; + double t126 = X1*t125; + double t127 = t49+t50+t51+t52-t64; + double t128 = Y1*t127; + double t129 = t126+t128-Z1*t124; + double t130 = t23*t129*2.0; + double t132 = t13*t26*t45*w1*2.0; + double t133 = t10*t25*t45*w1; + double t138 = t13*t14*w2; + double t134 = -t46+t47+t48+t113-t138; + double t135 = X1*t134; + double t136 = -t49-t50+t51+t52+t64; + double t137 = Z1*t136; + double t140 = X1*s1*t5; + double t141 = Y1*s2*t6; + double t142 = Z1*s3*t7; + double t143 = s1*t1*t5; + double t144 = s1*t1*t6; + double t145 = s1*t1*t7; + double t146 = s2*t2*t5; + double t147 = s2*t2*t6; + double t148 = s2*t2*t7; + double t149 = s3*t3*t5; + double t150 = s3*t3*t6; + double t151 = s3*t3*t7; + double t152 = X1*s2*w1*w2; + double t153 = X1*s3*w1*w3; + double t154 = Y1*s1*w1*w2; + double t155 = Y1*s3*w2*w3; + double t156 = Z1*s1*w1*w3; + double t157 = Z1*s2*w2*w3; + double t158 = X1*s1*t6*t12; + double t159 = X1*s1*t7*t12; + double t160 = Y1*s2*t5*t12; + double t161 = Y1*s2*t7*t12; + double t162 = Z1*s3*t5*t12; + double t163 = Z1*s3*t6*t12; + double t164 = X1*s2*t9*t10*w3; + double t165 = Y1*s3*t9*t10*w1; + double t166 = Z1*s1*t9*t10*w2; + double t183 = X1*s3*t9*t10*w2; + double t184 = Y1*s1*t9*t10*w3; + double t185 = Z1*s2*t9*t10*w1; + double t186 = X1*s2*t12*w1*w2; + double t187 = X1*s3*t12*w1*w3; + double t188 = Y1*s1*t12*w1*w2; + double t189 = Y1*s3*t12*w2*w3; + double t190 = Z1*s1*t12*w1*w3; + double t191 = Z1*s2*t12*w2*w3; + double t167 = t140+t141+t142+t143+t144+t145+t146+t147+t148+t149+t150+t151+t152+t153+t154+t155+t156+t157+t158+t159+t160+t161+t162+t163+t164+t165+t166-t183-t184-t185-t186-t187-t188-t189-t190-t191; + double t168 = t13*t26*t45*w2*2.0; + double t169 = t10*t25*t45*w2; + double t170 = t168+t169; + double t171 = t13*t26*t34*w2*2.0; + double t172 = t10*t25*t34*w2; + double t176 = t13*t14*w2*2.0; + double t173 = t171+t172-t176; + double t174 = -t49+t51+t52+t100-t111; + double t175 = X1*t174; + double t177 = t13*t24*t26*w2*2.0; + double t178 = t10*t24*t25*w2; + double t192 = t13*t14*w1; + double t179 = -t97+t98+t99+t112-t192; + double t180 = Y1*t179; + double t181 = t49+t51+t52-t100+t111; + double t182 = Z1*t181; + double t193 = t13*t26*t34*w3*2.0; + double t194 = t10*t25*t34*w3; + double t195 = t193+t194; + double t196 = t13*t26*t45*w3*2.0; + double t197 = t10*t25*t45*w3; + double t200 = t13*t14*w3*2.0; + double t198 = t196+t197-t200; + double t199 = t7*t10*t25; + double t201 = t13*t24*t26*w3*2.0; + double t202 = t10*t24*t25*w3; + double t203 = -t49+t51+t52-t118+t199; + double t204 = Y1*t203; + double t205 = t1*2.0; + double t206 = Z1*t29*2.0; + double t207 = X1*t32*2.0; + double t208 = t205+t206+t207-Y1*t27*2.0; + double t209 = t2*2.0; + double t210 = X1*t53*2.0; + double t211 = Y1*t58*2.0; + double t212 = t209+t210+t211-Z1*t55*2.0; + double t213 = t3*2.0; + double t214 = Y1*t40*2.0; + double t215 = Z1*t43*2.0; + double t216 = t213+t214+t215-X1*t38*2.0; + jacs(0, 0) = t14*t65*(X1*r1*w1*2.0+X1*r2*w2+X1*r3*w3+Y1*r1*w2+Z1*r1*w3+r1*t1*w1*2.0+r2*t2*w1*2.0+r3*t3*w1*2.0+Y1*r3*t5*t12+Y1*r3*t9*t10-Z1*r2*t5*t12-Z1*r2*t9*t10-X1*r2*t12*w2-X1*r3*t12*w3-Y1*r1*t12*w2+Y1*r2*t12*w1*2.0-Z1*r1*t12*w3+Z1*r3*t12*w1*2.0+Y1*r3*t5*t10*t11-Z1*r2*t5*t10*t11+X1*r2*t12*w1*w3-X1*r3*t12*w1*w2-Y1*r1*t12*w1*w3+Z1*r1*t12*w1*w2-Y1*r1*t10*t11*w1*w3+Z1*r1*t10*t11*w1*w2-X1*r1*t6*t10*t11*w1-X1*r1*t7*t10*t11*w1+X1*r2*t5*t10*t11*w2+X1*r3*t5*t10*t11*w3+Y1*r1*t5*t10*t11*w2-Y1*r2*t5*t10*t11*w1-Y1*r2*t7*t10*t11*w1+Z1*r1*t5*t10*t11*w3-Z1*r3*t5*t10*t11*w1-Z1*r3*t6*t10*t11*w1+X1*r2*t10*t11*w1*w3-X1*r3*t10*t11*w1*w2+Y1*r3*t10*t11*w1*w2*w3+Z1*r2*t10*t11*w1*w2*w3)-t26*t65*t93*w1*2.0-t14*t93*t101*(t130+t15*(-X1*t121+Y1*(t46+t47+t48-t13*t14*w2-t12*t14*w1*w3)+Z1*(t35+t36+t37-t13*t14*w3-t10*t25*w1*w2))*2.0+t18*(t135+t137-Y1*(t132+t133-t13*t14*w1*2.0))*2.0)*(1.0/2.0); + jacs(0, 1) = t14*t65*(X1*r2*w1+Y1*r1*w1+Y1*r2*w2*2.0+Y1*r3*w3+Z1*r2*w3+r1*t1*w2*2.0+r2*t2*w2*2.0+r3*t3*w2*2.0-X1*r3*t6*t12-X1*r3*t9*t10+Z1*r1*t6*t12+Z1*r1*t9*t10+X1*r1*t12*w2*2.0-X1*r2*t12*w1-Y1*r1*t12*w1-Y1*r3*t12*w3-Z1*r2*t12*w3+Z1*r3*t12*w2*2.0-X1*r3*t6*t10*t11+Z1*r1*t6*t10*t11+X1*r2*t12*w2*w3-Y1*r1*t12*w2*w3+Y1*r3*t12*w1*w2-Z1*r2*t12*w1*w2-Y1*r1*t10*t11*w2*w3+Y1*r3*t10*t11*w1*w2-Z1*r2*t10*t11*w1*w2-X1*r1*t6*t10*t11*w2+X1*r2*t6*t10*t11*w1-X1*r1*t7*t10*t11*w2+Y1*r1*t6*t10*t11*w1-Y1*r2*t5*t10*t11*w2-Y1*r2*t7*t10*t11*w2+Y1*r3*t6*t10*t11*w3-Z1*r3*t5*t10*t11*w2+Z1*r2*t6*t10*t11*w3-Z1*r3*t6*t10*t11*w2+X1*r2*t10*t11*w2*w3+X1*r3*t10*t11*w1*w2*w3+Z1*r1*t10*t11*w1*w2*w3)-t26*t65*t93*w2*2.0-t14*t93*t101*(t18*(Z1*(-t35+t94+t95+t96-t13*t14*w3)-Y1*t170+X1*(t97+t98+t99-t13*t14*w1-t10*t25*w2*w3))*2.0+t15*(t180+t182-X1*(t177+t178-t13*t14*w2*2.0))*2.0+t23*(t175+Y1*(t35-t94+t95+t96-t13*t14*w3)-Z1*t173)*2.0)*(1.0/2.0); + jacs(0, 2) = t14*t65*(X1*r3*w1+Y1*r3*w2+Z1*r1*w1+Z1*r2*w2+Z1*r3*w3*2.0+r1*t1*w3*2.0+r2*t2*w3*2.0+r3*t3*w3*2.0+X1*r2*t7*t12+X1*r2*t9*t10-Y1*r1*t7*t12-Y1*r1*t9*t10+X1*r1*t12*w3*2.0-X1*r3*t12*w1+Y1*r2*t12*w3*2.0-Y1*r3*t12*w2-Z1*r1*t12*w1-Z1*r2*t12*w2+X1*r2*t7*t10*t11-Y1*r1*t7*t10*t11-X1*r3*t12*w2*w3+Y1*r3*t12*w1*w3+Z1*r1*t12*w2*w3-Z1*r2*t12*w1*w3+Y1*r3*t10*t11*w1*w3+Z1*r1*t10*t11*w2*w3-Z1*r2*t10*t11*w1*w3-X1*r1*t6*t10*t11*w3-X1*r1*t7*t10*t11*w3+X1*r3*t7*t10*t11*w1-Y1*r2*t5*t10*t11*w3-Y1*r2*t7*t10*t11*w3+Y1*r3*t7*t10*t11*w2+Z1*r1*t7*t10*t11*w1+Z1*r2*t7*t10*t11*w2-Z1*r3*t5*t10*t11*w3-Z1*r3*t6*t10*t11*w3-X1*r3*t10*t11*w2*w3+X1*r2*t10*t11*w1*w2*w3+Y1*r1*t10*t11*w1*w2*w3)-t26*t65*t93*w3*2.0-t14*t93*t101*(t18*(Z1*(t46-t113+t114+t115-t13*t14*w2)-Y1*t198+X1*(t49+t51+t52+t118-t7*t10*t25))*2.0+t23*(X1*(-t97+t112+t116+t117-t13*t14*w1)+Y1*(-t46+t113+t114+t115-t13*t14*w2)-Z1*t195)*2.0+t15*(t204+Z1*(t97-t112+t116+t117-t13*t14*w1)-X1*(t201+t202-t13*t14*w3*2.0))*2.0)*(1.0/2.0); + jacs(0, 3) = r1*t65-t14*t93*t101*t208*(1.0/2.0); + jacs(0, 4) = r2*t65-t14*t93*t101*t212*(1.0/2.0); + jacs(0, 5) = r3*t65-t14*t93*t101*t216*(1.0/2.0); + jacs(1, 0) = t14*t65*(X1*s1*w1*2.0+X1*s2*w2+X1*s3*w3+Y1*s1*w2+Z1*s1*w3+s1*t1*w1*2.0+s2*t2*w1*2.0+s3*t3*w1*2.0+Y1*s3*t5*t12+Y1*s3*t9*t10-Z1*s2*t5*t12-Z1*s2*t9*t10-X1*s2*t12*w2-X1*s3*t12*w3-Y1*s1*t12*w2+Y1*s2*t12*w1*2.0-Z1*s1*t12*w3+Z1*s3*t12*w1*2.0+Y1*s3*t5*t10*t11-Z1*s2*t5*t10*t11+X1*s2*t12*w1*w3-X1*s3*t12*w1*w2-Y1*s1*t12*w1*w3+Z1*s1*t12*w1*w2+X1*s2*t10*t11*w1*w3-X1*s3*t10*t11*w1*w2-Y1*s1*t10*t11*w1*w3+Z1*s1*t10*t11*w1*w2-X1*s1*t6*t10*t11*w1-X1*s1*t7*t10*t11*w1+X1*s2*t5*t10*t11*w2+X1*s3*t5*t10*t11*w3+Y1*s1*t5*t10*t11*w2-Y1*s2*t5*t10*t11*w1-Y1*s2*t7*t10*t11*w1+Z1*s1*t5*t10*t11*w3-Z1*s3*t5*t10*t11*w1-Z1*s3*t6*t10*t11*w1+Y1*s3*t10*t11*w1*w2*w3+Z1*s2*t10*t11*w1*w2*w3)-t14*t101*t167*(t130+t15*(Y1*(t46+t47+t48-t113-t138)+Z1*(t35+t36+t37-t94-t139)-X1*t121)*2.0+t18*(t135+t137-Y1*(-t131+t132+t133))*2.0)*(1.0/2.0)-t26*t65*t167*w1*2.0; + jacs(1, 1) = t14*t65*(X1*s2*w1+Y1*s1*w1+Y1*s2*w2*2.0+Y1*s3*w3+Z1*s2*w3+s1*t1*w2*2.0+s2*t2*w2*2.0+s3*t3*w2*2.0-X1*s3*t6*t12-X1*s3*t9*t10+Z1*s1*t6*t12+Z1*s1*t9*t10+X1*s1*t12*w2*2.0-X1*s2*t12*w1-Y1*s1*t12*w1-Y1*s3*t12*w3-Z1*s2*t12*w3+Z1*s3*t12*w2*2.0-X1*s3*t6*t10*t11+Z1*s1*t6*t10*t11+X1*s2*t12*w2*w3-Y1*s1*t12*w2*w3+Y1*s3*t12*w1*w2-Z1*s2*t12*w1*w2+X1*s2*t10*t11*w2*w3-Y1*s1*t10*t11*w2*w3+Y1*s3*t10*t11*w1*w2-Z1*s2*t10*t11*w1*w2-X1*s1*t6*t10*t11*w2+X1*s2*t6*t10*t11*w1-X1*s1*t7*t10*t11*w2+Y1*s1*t6*t10*t11*w1-Y1*s2*t5*t10*t11*w2-Y1*s2*t7*t10*t11*w2+Y1*s3*t6*t10*t11*w3-Z1*s3*t5*t10*t11*w2+Z1*s2*t6*t10*t11*w3-Z1*s3*t6*t10*t11*w2+X1*s3*t10*t11*w1*w2*w3+Z1*s1*t10*t11*w1*w2*w3)-t26*t65*t167*w2*2.0-t14*t101*t167*(t18*(X1*(t97+t98+t99-t112-t192)+Z1*(-t35+t94+t95+t96-t139)-Y1*t170)*2.0+t15*(t180+t182-X1*(-t176+t177+t178))*2.0+t23*(t175+Y1*(t35-t94+t95+t96-t139)-Z1*t173)*2.0)*(1.0/2.0); + jacs(1, 2) = t14*t65*(X1*s3*w1+Y1*s3*w2+Z1*s1*w1+Z1*s2*w2+Z1*s3*w3*2.0+s1*t1*w3*2.0+s2*t2*w3*2.0+s3*t3*w3*2.0+X1*s2*t7*t12+X1*s2*t9*t10-Y1*s1*t7*t12-Y1*s1*t9*t10+X1*s1*t12*w3*2.0-X1*s3*t12*w1+Y1*s2*t12*w3*2.0-Y1*s3*t12*w2-Z1*s1*t12*w1-Z1*s2*t12*w2+X1*s2*t7*t10*t11-Y1*s1*t7*t10*t11-X1*s3*t12*w2*w3+Y1*s3*t12*w1*w3+Z1*s1*t12*w2*w3-Z1*s2*t12*w1*w3-X1*s3*t10*t11*w2*w3+Y1*s3*t10*t11*w1*w3+Z1*s1*t10*t11*w2*w3-Z1*s2*t10*t11*w1*w3-X1*s1*t6*t10*t11*w3-X1*s1*t7*t10*t11*w3+X1*s3*t7*t10*t11*w1-Y1*s2*t5*t10*t11*w3-Y1*s2*t7*t10*t11*w3+Y1*s3*t7*t10*t11*w2+Z1*s1*t7*t10*t11*w1+Z1*s2*t7*t10*t11*w2-Z1*s3*t5*t10*t11*w3-Z1*s3*t6*t10*t11*w3+X1*s2*t10*t11*w1*w2*w3+Y1*s1*t10*t11*w1*w2*w3)-t26*t65*t167*w3*2.0-t14*t101*t167*(t18*(Z1*(t46-t113+t114+t115-t138)-Y1*t198+X1*(t49+t51+t52+t118-t199))*2.0+t23*(X1*(-t97+t112+t116+t117-t192)+Y1*(-t46+t113+t114+t115-t138)-Z1*t195)*2.0+t15*(t204+Z1*(t97-t112+t116+t117-t192)-X1*(-t200+t201+t202))*2.0)*(1.0/2.0); + jacs(1, 3) = s1*t65-t14*t101*t167*t208*(1.0/2.0); + jacs(1, 4) = s2*t65-t14*t101*t167*t212*(1.0/2.0); + jacs(1, 5) = s3*t65-t14*t101*t167*t216*(1.0/2.0); + } +}//End namespace ORB_SLAM2 diff --git a/third_party/ORB_SLAM3/src/Map.cc b/third_party/ORB_SLAM3/src/Map.cc new file mode 100644 index 0000000..8db0af0 --- /dev/null +++ b/third_party/ORB_SLAM3/src/Map.cc @@ -0,0 +1,645 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + + +#include "Map.h" + +#include + +#include +#include + +namespace ORB_SLAM3 +{ + +long unsigned int Map::nNextId=0; + +Map::Map():mnMaxKFid(0),mnBigChangeIdx(0), mbImuInitialized(false), mnMapChange(0), mpFirstRegionKF(static_cast(NULL)), +mbFail(false), mIsInUse(false), mHasTumbnail(false), mbBad(false), mnMapChangeNotified(0), mbIsInertial(false), mbIMU_BA1(false), mbIMU_BA2(false) +{ + mnId=nNextId++; + mThumbnail = static_cast(NULL); +} + +Map::Map(int initKFid):mnInitKFid(initKFid), mnMaxKFid(initKFid),mnLastLoopKFid(initKFid), mnBigChangeIdx(0), mIsInUse(false), + mHasTumbnail(false), mbBad(false), mbImuInitialized(false), mpFirstRegionKF(static_cast(NULL)), + mnMapChange(0), mbFail(false), mnMapChangeNotified(0), mbIsInertial(false), mbIMU_BA1(false), mbIMU_BA2(false) +{ + mnId=nNextId++; + mThumbnail = static_cast(NULL); +} + +Map::~Map() +{ + //TODO: erase all points from memory + mspMapPoints.clear(); + + //TODO: erase all keyframes from memory + mspKeyFrames.clear(); + + if(mThumbnail) + delete mThumbnail; + mThumbnail = static_cast(NULL); + + mvpReferenceMapPoints.clear(); + mvpKeyFrameOrigins.clear(); +} + +void Map::AddKeyFrame(KeyFrame *pKF) +{ + unique_lock lock(mMutexMap); + if(mspKeyFrames.empty()){ + cout << "First KF:" << pKF->mnId << "; Map init KF:" << mnInitKFid << endl; + mnInitKFid = pKF->mnId; + mpKFinitial = pKF; + mpKFlowerID = pKF; + } + mspKeyFrames.insert(pKF); + if(pKF->mnId>mnMaxKFid) + { + mnMaxKFid=pKF->mnId; + } + if(pKF->mnIdmnId) + { + mpKFlowerID = pKF; + } +} + +void Map::AddMapPoint(MapPoint *pMP) +{ + unique_lock lock(mMutexMap); + mspMapPoints.insert(pMP); +} + +void Map::SetImuInitialized() +{ + unique_lock lock(mMutexMap); + mbImuInitialized = true; +} + +bool Map::isImuInitialized() +{ + unique_lock lock(mMutexMap); + return mbImuInitialized; +} + +void Map::EraseMapPoint(MapPoint *pMP) +{ + unique_lock lock(mMutexMap); + mspMapPoints.erase(pMP); + + // TODO: This only erase the pointer. + // Delete the MapPoint +} + +void Map::EraseKeyFrame(KeyFrame *pKF) +{ + unique_lock lock(mMutexMap); + mspKeyFrames.erase(pKF); + if(mspKeyFrames.size()>0) + { + if(pKF->mnId == mpKFlowerID->mnId) + { + vector vpKFs = vector(mspKeyFrames.begin(),mspKeyFrames.end()); + sort(vpKFs.begin(),vpKFs.end(),KeyFrame::lId); + mpKFlowerID = vpKFs[0]; + } + } + else + { + mpKFlowerID = 0; + } + + // TODO: This only erase the pointer. + // Delete the MapPoint +} + +void Map::SetReferenceMapPoints(const vector &vpMPs) +{ + unique_lock lock(mMutexMap); + mvpReferenceMapPoints = vpMPs; +} + +void Map::InformNewBigChange() +{ + unique_lock lock(mMutexMap); + mnBigChangeIdx++; +} + +int Map::GetLastBigChangeIdx() +{ + unique_lock lock(mMutexMap); + return mnBigChangeIdx; +} + +vector Map::GetAllKeyFrames() +{ + unique_lock lock(mMutexMap); + return vector(mspKeyFrames.begin(),mspKeyFrames.end()); +} + +vector Map::GetAllMapPoints() +{ + unique_lock lock(mMutexMap); + return vector(mspMapPoints.begin(),mspMapPoints.end()); +} + +long unsigned int Map::MapPointsInMap() +{ + unique_lock lock(mMutexMap); + return mspMapPoints.size(); +} + +long unsigned int Map::KeyFramesInMap() +{ + unique_lock lock(mMutexMap); + return mspKeyFrames.size(); +} + +vector Map::GetReferenceMapPoints() +{ + unique_lock lock(mMutexMap); + return mvpReferenceMapPoints; +} + +long unsigned int Map::GetId() +{ + return mnId; +} +long unsigned int Map::GetInitKFid() +{ + unique_lock lock(mMutexMap); + return mnInitKFid; +} + +void Map::SetInitKFid(long unsigned int initKFif) +{ + unique_lock lock(mMutexMap); + mnInitKFid = initKFif; +} + +long unsigned int Map::GetMaxKFid() +{ + unique_lock lock(mMutexMap); + return mnMaxKFid; +} + +KeyFrame* Map::GetOriginKF() +{ + return mpKFinitial; +} + +void Map::SetCurrentMap() +{ + mIsInUse = true; +} + +void Map::SetStoredMap() +{ + mIsInUse = false; +} + +void Map::clear() +{ +// for(set::iterator sit=mspMapPoints.begin(), send=mspMapPoints.end(); sit!=send; sit++) +// delete *sit; + + for(set::iterator sit=mspKeyFrames.begin(), send=mspKeyFrames.end(); sit!=send; sit++) + { + KeyFrame* pKF = *sit; + pKF->UpdateMap(static_cast(NULL)); +// delete *sit; + } + + mspMapPoints.clear(); + mspKeyFrames.clear(); + mnMaxKFid = mnInitKFid; + mnLastLoopKFid = 0; + mbImuInitialized = false; + mvpReferenceMapPoints.clear(); + mvpKeyFrameOrigins.clear(); + mbIMU_BA1 = false; + mbIMU_BA2 = false; +} + +bool Map::IsInUse() +{ + return mIsInUse; +} + +void Map::SetBad() +{ + mbBad = true; +} + +bool Map::IsBad() +{ + return mbBad; +} + +void Map::RotateMap(const cv::Mat &R) +{ + unique_lock lock(mMutexMap); + + cv::Mat Txw = cv::Mat::eye(4,4,CV_32F); + R.copyTo(Txw.rowRange(0,3).colRange(0,3)); + + KeyFrame* pKFini = mvpKeyFrameOrigins[0]; + cv::Mat Twc_0 = pKFini->GetPoseInverse(); + cv::Mat Txc_0 = Txw*Twc_0; + cv::Mat Txb_0 = Txc_0*pKFini->mImuCalib.Tcb; + cv::Mat Tyx = cv::Mat::eye(4,4,CV_32F); + Tyx.rowRange(0,3).col(3) = -Txb_0.rowRange(0,3).col(3); + cv::Mat Tyw = Tyx*Txw; + cv::Mat Ryw = Tyw.rowRange(0,3).colRange(0,3); + cv::Mat tyw = Tyw.rowRange(0,3).col(3); + + for(set::iterator sit=mspKeyFrames.begin(); sit!=mspKeyFrames.end(); sit++) + { + KeyFrame* pKF = *sit; + cv::Mat Twc = pKF->GetPoseInverse(); + cv::Mat Tyc = Tyw*Twc; + cv::Mat Tcy = cv::Mat::eye(4,4,CV_32F); + Tcy.rowRange(0,3).colRange(0,3) = Tyc.rowRange(0,3).colRange(0,3).t(); + Tcy.rowRange(0,3).col(3) = -Tcy.rowRange(0,3).colRange(0,3)*Tyc.rowRange(0,3).col(3); + pKF->SetPose(Tcy); + cv::Mat Vw = pKF->GetVelocity(); + pKF->SetVelocity(Ryw*Vw); + } + for(set::iterator sit=mspMapPoints.begin(); sit!=mspMapPoints.end(); sit++) + { + MapPoint* pMP = *sit; + pMP->SetWorldPos(Ryw*pMP->GetWorldPos()+tyw); + pMP->UpdateNormalAndDepth(); + } +} + +void Map::ApplyScaledRotation(const cv::Mat &R, const float s, const bool bScaledVel, const cv::Mat t) +{ + unique_lock lock(mMutexMap); + + // Body position (IMU) of first keyframe is fixed to (0,0,0) + cv::Mat Txw = cv::Mat::eye(4,4,CV_32F); + R.copyTo(Txw.rowRange(0,3).colRange(0,3)); + + cv::Mat Tyx = cv::Mat::eye(4,4,CV_32F); + + cv::Mat Tyw = Tyx*Txw; + Tyw.rowRange(0,3).col(3) = Tyw.rowRange(0,3).col(3)+t; + cv::Mat Ryw = Tyw.rowRange(0,3).colRange(0,3); + cv::Mat tyw = Tyw.rowRange(0,3).col(3); + + for(set::iterator sit=mspKeyFrames.begin(); sit!=mspKeyFrames.end(); sit++) + { + KeyFrame* pKF = *sit; + cv::Mat Twc = pKF->GetPoseInverse(); + Twc.rowRange(0,3).col(3)*=s; + cv::Mat Tyc = Tyw*Twc; + cv::Mat Tcy = cv::Mat::eye(4,4,CV_32F); + Tcy.rowRange(0,3).colRange(0,3) = Tyc.rowRange(0,3).colRange(0,3).t(); + Tcy.rowRange(0,3).col(3) = -Tcy.rowRange(0,3).colRange(0,3)*Tyc.rowRange(0,3).col(3); + pKF->SetPose(Tcy); + cv::Mat Vw = pKF->GetVelocity(); + if(!bScaledVel) + pKF->SetVelocity(Ryw*Vw); + else + pKF->SetVelocity(Ryw*Vw*s); + + } + for(set::iterator sit=mspMapPoints.begin(); sit!=mspMapPoints.end(); sit++) + { + MapPoint* pMP = *sit; + pMP->SetWorldPos(s*Ryw*pMP->GetWorldPos()+tyw); + pMP->UpdateNormalAndDepth(); + } + mnMapChange++; +} + +void Map::SetInertialSensor() +{ + unique_lock lock(mMutexMap); + mbIsInertial = true; +} + +bool Map::IsInertial() +{ + unique_lock lock(mMutexMap); + return mbIsInertial; +} + +void Map::SetIniertialBA1() +{ + unique_lock lock(mMutexMap); + mbIMU_BA1 = true; +} + +void Map::SetIniertialBA2() +{ + unique_lock lock(mMutexMap); + mbIMU_BA2 = true; +} + +bool Map::GetIniertialBA1() +{ + unique_lock lock(mMutexMap); + return mbIMU_BA1; +} + +bool Map::GetIniertialBA2() +{ + unique_lock lock(mMutexMap); + return mbIMU_BA2; +} + +void Map::PrintEssentialGraph() +{ + //Print the essential graph + vector vpOriginKFs = mvpKeyFrameOrigins; + int count=0; + cout << "Number of origin KFs: " << vpOriginKFs.size() << endl; + KeyFrame* pFirstKF; + for(KeyFrame* pKFi : vpOriginKFs) + { + if(!pFirstKF) + pFirstKF = pKFi; + else if(!pKFi->GetParent()) + pFirstKF = pKFi; + } + if(pFirstKF->GetParent()) + { + cout << "First KF in the essential graph has a parent, which is not possible" << endl; + } + + cout << "KF: " << pFirstKF->mnId << endl; + set spChilds = pFirstKF->GetChilds(); + vector vpChilds; + vector vstrHeader; + for(KeyFrame* pKFi : spChilds){ + vstrHeader.push_back("--"); + vpChilds.push_back(pKFi); + } + for(int i=0; imnId << endl; + + set spKFiChilds = pKFi->GetChilds(); + for(KeyFrame* pKFj : spKFiChilds) + { + vpChilds.push_back(pKFj); + vstrHeader.push_back(strHeader+"--"); + } + } + if (count == (mspKeyFrames.size()+10)) + cout << "CYCLE!!" << endl; + + cout << "------------------" << endl << "End of the essential graph" << endl; +} + +bool Map::CheckEssentialGraph(){ + vector vpOriginKFs = mvpKeyFrameOrigins; + int count=0; + cout << "Number of origin KFs: " << vpOriginKFs.size() << endl; + KeyFrame* pFirstKF; + for(KeyFrame* pKFi : vpOriginKFs) + { + if(!pFirstKF) + pFirstKF = pKFi; + else if(!pKFi->GetParent()) + pFirstKF = pKFi; + } + cout << "Checking if the first KF has parent" << endl; + if(pFirstKF->GetParent()) + { + cout << "First KF in the essential graph has a parent, which is not possible" << endl; + } + + set spChilds = pFirstKF->GetChilds(); + vector vpChilds; + vpChilds.reserve(mspKeyFrames.size()); + for(KeyFrame* pKFi : spChilds) + vpChilds.push_back(pKFi); + + for(int i=0; i spKFiChilds = pKFi->GetChilds(); + for(KeyFrame* pKFj : spKFiChilds) + vpChilds.push_back(pKFj); + } + + cout << "count/tot" << count << "/" << mspKeyFrames.size() << endl; + if (count != (mspKeyFrames.size()-1)) + return false; + else + return true; +} + +void Map::ChangeId(long unsigned int nId) +{ + mnId = nId; +} + +unsigned int Map::GetLowerKFID() +{ + unique_lock lock(mMutexMap); + if (mpKFlowerID) { + return mpKFlowerID->mnId; + } + return 0; +} + +int Map::GetMapChangeIndex() +{ + unique_lock lock(mMutexMap); + return mnMapChange; +} + +void Map::IncreaseChangeIndex() +{ + unique_lock lock(mMutexMap); + mnMapChange++; +} + +int Map::GetLastMapChange() +{ + unique_lock lock(mMutexMap); + return mnMapChangeNotified; +} + +void Map::SetLastMapChange(int currentChangeId) +{ + unique_lock lock(mMutexMap); + mnMapChangeNotified = currentChangeId; +} + +void Map::printReprojectionError(list &lpLocalWindowKFs, KeyFrame* mpCurrentKF, string &name, string &name_folder) +{ + string path_imgs = "./" + name_folder + "/"; + for(KeyFrame* pKFi : lpLocalWindowKFs) + { + //cout << "KF " << pKFi->mnId << endl; + cv::Mat img_i = cv::imread(pKFi->mNameFile, cv::IMREAD_UNCHANGED); + //cout << "Image -> " << img_i.cols << ", " << img_i.rows << endl; + cv::cvtColor(img_i, img_i, CV_GRAY2BGR); + //cout << "Change of color in the image " << endl; + + vector vpMPs = pKFi->GetMapPointMatches(); + int num_points = 0; + for(int j=0; jisBad()) + { + continue; + } + + cv::KeyPoint point_img = pKFi->mvKeysUn[j]; + cv::Point2f reproj_p; + float u, v; + bool bIsInImage = pKFi->ProjectPointUnDistort(pMPij, reproj_p, u, v); + if(bIsInImage){ + //cout << "Reproj in the image" << endl; + cv::circle(img_i, point_img.pt, 1/*point_img.octave*/, cv::Scalar(0, 255, 0)); + cv::line(img_i, point_img.pt, reproj_p, cv::Scalar(0, 0, 255)); + num_points++; + } + else + { + //cout << "Reproj out of the image" << endl; + cv::circle(img_i, point_img.pt, point_img.octave, cv::Scalar(0, 0, 255)); + } + + } + //cout << "Image painted" << endl; + string filename_img = path_imgs + "KF" + to_string(mpCurrentKF->mnId) + "_" + to_string(pKFi->mnId) + name + "points" + to_string(num_points) + ".png"; + cv::imwrite(filename_img, img_i); + } + +} + +void Map::PreSave(std::set &spCams) +{ + int nMPWithoutObs = 0; + for(MapPoint* pMPi : mspMapPoints) + { + if(pMPi->GetObservations().size() == 0) + { + nMPWithoutObs++; + } + map> mpObs = pMPi->GetObservations(); + for(map>::iterator it= mpObs.begin(), end=mpObs.end(); it!=end; ++it) + { + if(it->first->GetMap() != this) + { + pMPi->EraseObservation(it->first); //We need to find where the KF is set as Bad but the observation is not removed + } + + } + } + cout << " Bad MapPoints removed" << endl; + + // Saves the id of KF origins + mvBackupKeyFrameOriginsId.reserve(mvpKeyFrameOrigins.size()); + for(int i = 0, numEl = mvpKeyFrameOrigins.size(); i < numEl; ++i) + { + mvBackupKeyFrameOriginsId.push_back(mvpKeyFrameOrigins[i]->mnId); + } + + mvpBackupMapPoints.clear(); + // Backup of set container to vector + //std::copy(mspMapPoints.begin(), mspMapPoints.end(), std::back_inserter(mvpBackupMapPoints)); + for(MapPoint* pMPi : mspMapPoints) + { + //cout << "Pre-save of mappoint " << pMPi->mnId << endl; + mvpBackupMapPoints.push_back(pMPi); + pMPi->PreSave(mspKeyFrames,mspMapPoints); + } + cout << " MapPoints back up done!!" << endl; + + mvpBackupKeyFrames.clear(); + //std::copy(mspKeyFrames.begin(), mspKeyFrames.end(), std::back_inserter(mvpBackupKeyFrames)); + for(KeyFrame* pKFi : mspKeyFrames) + { + mvpBackupKeyFrames.push_back(pKFi); + pKFi->PreSave(mspKeyFrames,mspMapPoints, spCams); + } + cout << " KeyFrames back up done!!" << endl; + + mnBackupKFinitialID = -1; + if(mpKFinitial) + { + mnBackupKFinitialID = mpKFinitial->mnId; + } + + mnBackupKFlowerID = -1; + if(mpKFlowerID) + { + mnBackupKFlowerID = mpKFlowerID->mnId; + } + +} + +void Map::PostLoad(KeyFrameDatabase* pKFDB, ORBVocabulary* pORBVoc, map& mpKeyFrameId, map &mpCams) +{ + std::copy(mvpBackupMapPoints.begin(), mvpBackupMapPoints.end(), std::inserter(mspMapPoints, mspMapPoints.begin())); + std::copy(mvpBackupKeyFrames.begin(), mvpBackupKeyFrames.end(), std::inserter(mspKeyFrames, mspKeyFrames.begin())); + + map mpMapPointId; + for(MapPoint* pMPi : mspMapPoints) + { + pMPi->UpdateMap(this); + mpMapPointId[pMPi->mnId] = pMPi; + } + + //map mpKeyFrameId; + for(KeyFrame* pKFi : mspKeyFrames) + { + pKFi->UpdateMap(this); + pKFi->SetORBVocabulary(pORBVoc); + pKFi->SetKeyFrameDatabase(pKFDB); + mpKeyFrameId[pKFi->mnId] = pKFi; + } + cout << "Number of KF: " << mspKeyFrames.size() << endl; + cout << "Number of MP: " << mspMapPoints.size() << endl; + + // References reconstruction between different instances + for(MapPoint* pMPi : mspMapPoints) + { + //cout << "Post-Load of mappoint " << pMPi->mnId << endl; + pMPi->PostLoad(mpKeyFrameId, mpMapPointId); + } + cout << "End to rebuild MapPoint references" << endl; + + for(KeyFrame* pKFi : mspKeyFrames) + { + pKFi->PostLoad(mpKeyFrameId, mpMapPointId, mpCams); + pKFDB->add(pKFi); + } + + cout << "End to rebuild KeyFrame references" << endl; + + mvpBackupMapPoints.clear(); +} + + +} //namespace ORB_SLAM3 diff --git a/third_party/ORB_SLAM3/src/MapDrawer.cc b/third_party/ORB_SLAM3/src/MapDrawer.cc new file mode 100644 index 0000000..1331a9b --- /dev/null +++ b/third_party/ORB_SLAM3/src/MapDrawer.cc @@ -0,0 +1,544 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + + +#include "MapDrawer.h" +#include "MapPoint.h" +#include "KeyFrame.h" +#include +#include + +namespace ORB_SLAM3 +{ + + +MapDrawer::MapDrawer(Atlas* pAtlas, const string &strSettingPath):mpAtlas(pAtlas) +{ + cv::FileStorage fSettings(strSettingPath, cv::FileStorage::READ); + + bool is_correct = ParseViewerParamFile(fSettings); + + if(!is_correct) + { + std::cerr << "**ERROR in the config file, the format is not correct**" << std::endl; + try + { + throw -1; + } + catch(exception &e) + { + + } + } +} + +bool MapDrawer::ParseViewerParamFile(cv::FileStorage &fSettings) +{ + bool b_miss_params = false; + + cv::FileNode node = fSettings["Viewer.KeyFrameSize"]; + if(!node.empty()) + { + mKeyFrameSize = node.real(); + } + else + { + std::cerr << "*Viewer.KeyFrameSize parameter doesn't exist or is not a real number*" << std::endl; + b_miss_params = true; + } + + node = fSettings["Viewer.KeyFrameLineWidth"]; + if(!node.empty()) + { + mKeyFrameLineWidth = node.real(); + } + else + { + std::cerr << "*Viewer.KeyFrameLineWidth parameter doesn't exist or is not a real number*" << std::endl; + b_miss_params = true; + } + + node = fSettings["Viewer.GraphLineWidth"]; + if(!node.empty()) + { + mGraphLineWidth = node.real(); + } + else + { + std::cerr << "*Viewer.GraphLineWidth parameter doesn't exist or is not a real number*" << std::endl; + b_miss_params = true; + } + + node = fSettings["Viewer.PointSize"]; + if(!node.empty()) + { + mPointSize = node.real(); + } + else + { + std::cerr << "*Viewer.PointSize parameter doesn't exist or is not a real number*" << std::endl; + b_miss_params = true; + } + + node = fSettings["Viewer.CameraSize"]; + if(!node.empty()) + { + mCameraSize = node.real(); + } + else + { + std::cerr << "*Viewer.CameraSize parameter doesn't exist or is not a real number*" << std::endl; + b_miss_params = true; + } + + node = fSettings["Viewer.CameraLineWidth"]; + if(!node.empty()) + { + mCameraLineWidth = node.real(); + } + else + { + std::cerr << "*Viewer.CameraLineWidth parameter doesn't exist or is not a real number*" << std::endl; + b_miss_params = true; + } + + return !b_miss_params; +} + +void MapDrawer::DrawMapPoints() +{ + const vector &vpMPs = mpAtlas->GetAllMapPoints(); + const vector &vpRefMPs = mpAtlas->GetReferenceMapPoints(); + + set spRefMPs(vpRefMPs.begin(), vpRefMPs.end()); + + if(vpMPs.empty()) + return; + + glPointSize(mPointSize); + glBegin(GL_POINTS); + glColor3f(0.0,0.0,0.0); + + for(size_t i=0, iend=vpMPs.size(); iisBad() || spRefMPs.count(vpMPs[i])) + continue; + cv::Mat pos = vpMPs[i]->GetWorldPos(); + glVertex3f(pos.at(0),pos.at(1),pos.at(2)); + } + glEnd(); + + glPointSize(mPointSize); + glBegin(GL_POINTS); + glColor3f(1.0,0.0,0.0); + + for(set::iterator sit=spRefMPs.begin(), send=spRefMPs.end(); sit!=send; sit++) + { + if((*sit)->isBad()) + continue; + cv::Mat pos = (*sit)->GetWorldPos(); + glVertex3f(pos.at(0),pos.at(1),pos.at(2)); + + } + + glEnd(); +} + +void MapDrawer::DrawKeyFrames(const bool bDrawKF, const bool bDrawGraph, const bool bDrawInertialGraph) +{ + const float &w = mKeyFrameSize; + const float h = w*0.75; + const float z = w*0.6; + + const vector vpKFs = mpAtlas->GetAllKeyFrames(); + + if(bDrawKF) + { + for(size_t i=0; iGetPoseInverse().t(); + unsigned int index_color = pKF->mnOriginMapId; + + glPushMatrix(); + + glMultMatrixf(Twc.ptr(0)); + + if(!pKF->GetParent()) // It is the first KF in the map + { + glLineWidth(mKeyFrameLineWidth*5); + glColor3f(1.0f,0.0f,0.0f); + glBegin(GL_LINES); + + //cout << "Initial KF: " << mpAtlas->GetCurrentMap()->GetOriginKF()->mnId << endl; + //cout << "Parent KF: " << vpKFs[i]->mnId << endl; + } + else + { + glLineWidth(mKeyFrameLineWidth); + //glColor3f(0.0f,0.0f,1.0f); + glColor3f(mfFrameColors[index_color][0],mfFrameColors[index_color][1],mfFrameColors[index_color][2]); + glBegin(GL_LINES); + } + + glVertex3f(0,0,0); + glVertex3f(w,h,z); + glVertex3f(0,0,0); + glVertex3f(w,-h,z); + glVertex3f(0,0,0); + glVertex3f(-w,-h,z); + glVertex3f(0,0,0); + glVertex3f(-w,h,z); + + glVertex3f(w,h,z); + glVertex3f(w,-h,z); + + glVertex3f(-w,h,z); + glVertex3f(-w,-h,z); + + glVertex3f(-w,h,z); + glVertex3f(w,h,z); + + glVertex3f(-w,-h,z); + glVertex3f(w,-h,z); + glEnd(); + + glPopMatrix(); + + //Draw lines with Loop and Merge candidates + /*glLineWidth(mGraphLineWidth); + glColor4f(1.0f,0.6f,0.0f,1.0f); + glBegin(GL_LINES); + cv::Mat Ow = pKF->GetCameraCenter(); + const vector vpLoopCandKFs = pKF->mvpLoopCandKFs; + if(!vpLoopCandKFs.empty()) + { + for(vector::const_iterator vit=vpLoopCandKFs.begin(), vend=vpLoopCandKFs.end(); vit!=vend; vit++) + { + cv::Mat Ow2 = (*vit)->GetCameraCenter(); + glVertex3f(Ow.at(0),Ow.at(1),Ow.at(2)); + glVertex3f(Ow2.at(0),Ow2.at(1),Ow2.at(2)); + } + } + const vector vpMergeCandKFs = pKF->mvpMergeCandKFs; + if(!vpMergeCandKFs.empty()) + { + for(vector::const_iterator vit=vpMergeCandKFs.begin(), vend=vpMergeCandKFs.end(); vit!=vend; vit++) + { + cv::Mat Ow2 = (*vit)->GetCameraCenter(); + glVertex3f(Ow.at(0),Ow.at(1),Ow.at(2)); + glVertex3f(Ow2.at(0),Ow2.at(1),Ow2.at(2)); + } + }*/ + + glEnd(); + } + } + + if(bDrawGraph) + { + glLineWidth(mGraphLineWidth); + glColor4f(0.0f,1.0f,0.0f,0.6f); + glBegin(GL_LINES); + + // cout << "-----------------Draw graph-----------------" << endl; + for(size_t i=0; i vCovKFs = vpKFs[i]->GetCovisiblesByWeight(100); + cv::Mat Ow = vpKFs[i]->GetCameraCenter(); + if(!vCovKFs.empty()) + { + for(vector::const_iterator vit=vCovKFs.begin(), vend=vCovKFs.end(); vit!=vend; vit++) + { + if((*vit)->mnIdmnId) + continue; + cv::Mat Ow2 = (*vit)->GetCameraCenter(); + glVertex3f(Ow.at(0),Ow.at(1),Ow.at(2)); + glVertex3f(Ow2.at(0),Ow2.at(1),Ow2.at(2)); + } + } + + // Spanning tree + KeyFrame* pParent = vpKFs[i]->GetParent(); + if(pParent) + { + cv::Mat Owp = pParent->GetCameraCenter(); + glVertex3f(Ow.at(0),Ow.at(1),Ow.at(2)); + glVertex3f(Owp.at(0),Owp.at(1),Owp.at(2)); + } + + // Loops + set sLoopKFs = vpKFs[i]->GetLoopEdges(); + for(set::iterator sit=sLoopKFs.begin(), send=sLoopKFs.end(); sit!=send; sit++) + { + if((*sit)->mnIdmnId) + continue; + cv::Mat Owl = (*sit)->GetCameraCenter(); + glVertex3f(Ow.at(0),Ow.at(1),Ow.at(2)); + glVertex3f(Owl.at(0),Owl.at(1),Owl.at(2)); + } + } + + glEnd(); + } + + if(bDrawInertialGraph && mpAtlas->isImuInitialized()) + { + glLineWidth(mGraphLineWidth); + glColor4f(1.0f,0.0f,0.0f,0.6f); + glBegin(GL_LINES); + + //Draw inertial links + for(size_t i=0; iGetCameraCenter(); + KeyFrame* pNext = pKFi->mNextKF; + if(pNext) + { + cv::Mat Owp = pNext->GetCameraCenter(); + glVertex3f(Ow.at(0),Ow.at(1),Ow.at(2)); + glVertex3f(Owp.at(0),Owp.at(1),Owp.at(2)); + } + } + + glEnd(); + } + + vector vpMaps = mpAtlas->GetAllMaps(); + + if(bDrawKF) + { + for(Map* pMap : vpMaps) + { + if(pMap == mpAtlas->GetCurrentMap()) + continue; + + vector vpKFs = pMap->GetAllKeyFrames(); + + for(size_t i=0; iGetPoseInverse().t(); + unsigned int index_color = pKF->mnOriginMapId; + + glPushMatrix(); + + glMultMatrixf(Twc.ptr(0)); + + if(!vpKFs[i]->GetParent()) // It is the first KF in the map + { + glLineWidth(mKeyFrameLineWidth*5); + glColor3f(1.0f,0.0f,0.0f); + glBegin(GL_LINES); + } + else + { + glLineWidth(mKeyFrameLineWidth); + //glColor3f(0.0f,0.0f,1.0f); + glColor3f(mfFrameColors[index_color][0],mfFrameColors[index_color][1],mfFrameColors[index_color][2]); + glBegin(GL_LINES); + } + + glVertex3f(0,0,0); + glVertex3f(w,h,z); + glVertex3f(0,0,0); + glVertex3f(w,-h,z); + glVertex3f(0,0,0); + glVertex3f(-w,-h,z); + glVertex3f(0,0,0); + glVertex3f(-w,h,z); + + glVertex3f(w,h,z); + glVertex3f(w,-h,z); + + glVertex3f(-w,h,z); + glVertex3f(-w,-h,z); + + glVertex3f(-w,h,z); + glVertex3f(w,h,z); + + glVertex3f(-w,-h,z); + glVertex3f(w,-h,z); + glEnd(); + + glPopMatrix(); + } + } + } +} + +void MapDrawer::DrawCurrentCamera(pangolin::OpenGlMatrix &Twc) +{ + const float &w = mCameraSize; + const float h = w*0.75; + const float z = w*0.6; + + glPushMatrix(); + +#ifdef HAVE_GLES + glMultMatrixf(Twc.m); +#else + glMultMatrixd(Twc.m); +#endif + + glLineWidth(mCameraLineWidth); + glColor3f(0.0f,1.0f,0.0f); + glBegin(GL_LINES); + glVertex3f(0,0,0); + glVertex3f(w,h,z); + glVertex3f(0,0,0); + glVertex3f(w,-h,z); + glVertex3f(0,0,0); + glVertex3f(-w,-h,z); + glVertex3f(0,0,0); + glVertex3f(-w,h,z); + + glVertex3f(w,h,z); + glVertex3f(w,-h,z); + + glVertex3f(-w,h,z); + glVertex3f(-w,-h,z); + + glVertex3f(-w,h,z); + glVertex3f(w,h,z); + + glVertex3f(-w,-h,z); + glVertex3f(w,-h,z); + glEnd(); + + glPopMatrix(); +} + + +void MapDrawer::SetCurrentCameraPose(const cv::Mat &Tcw) +{ + unique_lock lock(mMutexCamera); + mCameraPose = Tcw.clone(); +} + +void MapDrawer::GetCurrentOpenGLCameraMatrix(pangolin::OpenGlMatrix &M, pangolin::OpenGlMatrix &MOw) +{ + if(!mCameraPose.empty()) + { + cv::Mat Rwc(3,3,CV_32F); + cv::Mat twc(3,1,CV_32F); + { + unique_lock lock(mMutexCamera); + Rwc = mCameraPose.rowRange(0,3).colRange(0,3).t(); + twc = -Rwc*mCameraPose.rowRange(0,3).col(3); + } + + M.m[0] = Rwc.at(0,0); + M.m[1] = Rwc.at(1,0); + M.m[2] = Rwc.at(2,0); + M.m[3] = 0.0; + + M.m[4] = Rwc.at(0,1); + M.m[5] = Rwc.at(1,1); + M.m[6] = Rwc.at(2,1); + M.m[7] = 0.0; + + M.m[8] = Rwc.at(0,2); + M.m[9] = Rwc.at(1,2); + M.m[10] = Rwc.at(2,2); + M.m[11] = 0.0; + + M.m[12] = twc.at(0); + M.m[13] = twc.at(1); + M.m[14] = twc.at(2); + M.m[15] = 1.0; + + MOw.SetIdentity(); + MOw.m[12] = twc.at(0); + MOw.m[13] = twc.at(1); + MOw.m[14] = twc.at(2); + } + else + { + M.SetIdentity(); + MOw.SetIdentity(); + } +} + +void MapDrawer::GetCurrentOpenGLCameraMatrix(pangolin::OpenGlMatrix &M, pangolin::OpenGlMatrix &MOw, pangolin::OpenGlMatrix &MTwwp) +{ + if(!mCameraPose.empty()) + { + cv::Mat Rwc(3,3,CV_32F); + cv::Mat twc(3,1,CV_32F); + cv::Mat Rwwp(3,3,CV_32F); + { + unique_lock lock(mMutexCamera); + Rwc = mCameraPose.rowRange(0,3).colRange(0,3).t(); + twc = -Rwc*mCameraPose.rowRange(0,3).col(3); + } + + M.m[0] = Rwc.at(0,0); + M.m[1] = Rwc.at(1,0); + M.m[2] = Rwc.at(2,0); + M.m[3] = 0.0; + + M.m[4] = Rwc.at(0,1); + M.m[5] = Rwc.at(1,1); + M.m[6] = Rwc.at(2,1); + M.m[7] = 0.0; + + M.m[8] = Rwc.at(0,2); + M.m[9] = Rwc.at(1,2); + M.m[10] = Rwc.at(2,2); + M.m[11] = 0.0; + + M.m[12] = twc.at(0); + M.m[13] = twc.at(1); + M.m[14] = twc.at(2); + M.m[15] = 1.0; + + MOw.SetIdentity(); + MOw.m[12] = twc.at(0); + MOw.m[13] = twc.at(1); + MOw.m[14] = twc.at(2); + + MTwwp.SetIdentity(); + MTwwp.m[0] = Rwwp.at(0,0); + MTwwp.m[1] = Rwwp.at(1,0); + MTwwp.m[2] = Rwwp.at(2,0); + + MTwwp.m[4] = Rwwp.at(0,1); + MTwwp.m[5] = Rwwp.at(1,1); + MTwwp.m[6] = Rwwp.at(2,1); + + MTwwp.m[8] = Rwwp.at(0,2); + MTwwp.m[9] = Rwwp.at(1,2); + MTwwp.m[10] = Rwwp.at(2,2); + + MTwwp.m[12] = twc.at(0); + MTwwp.m[13] = twc.at(1); + MTwwp.m[14] = twc.at(2); + } + else + { + M.SetIdentity(); + MOw.SetIdentity(); + MTwwp.SetIdentity(); + } + +} + +} //namespace ORB_SLAM diff --git a/third_party/ORB_SLAM3/src/MapPoint.cc b/third_party/ORB_SLAM3/src/MapPoint.cc new file mode 100644 index 0000000..678b0d4 --- /dev/null +++ b/third_party/ORB_SLAM3/src/MapPoint.cc @@ -0,0 +1,634 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + +#include "MapPoint.h" +#include "ORBmatcher.h" + +#include + +namespace ORB_SLAM3 +{ + +long unsigned int MapPoint::nNextId=0; +mutex MapPoint::mGlobalMutex; + +MapPoint::MapPoint(): + mnFirstKFid(0), mnFirstFrame(0), nObs(0), mnTrackReferenceForFrame(0), + mnLastFrameSeen(0), mnBALocalForKF(0), mnFuseCandidateForKF(0), mnLoopPointForKF(0), mnCorrectedByKF(0), + mnCorrectedReference(0), mnBAGlobalForKF(0), mnVisible(1), mnFound(1), mbBad(false), + mpReplaced(static_cast(NULL)) +{ + mpReplaced = static_cast(NULL); +} + +MapPoint::MapPoint(const cv::Mat &Pos, KeyFrame *pRefKF, Map* pMap): + mnFirstKFid(pRefKF->mnId), mnFirstFrame(pRefKF->mnFrameId), nObs(0), mnTrackReferenceForFrame(0), + mnLastFrameSeen(0), mnBALocalForKF(0), mnFuseCandidateForKF(0), mnLoopPointForKF(0), mnCorrectedByKF(0), + mnCorrectedReference(0), mnBAGlobalForKF(0), mpRefKF(pRefKF), mnVisible(1), mnFound(1), mbBad(false), + mpReplaced(static_cast(NULL)), mfMinDistance(0), mfMaxDistance(0), mpMap(pMap), + mnOriginMapId(pMap->GetId()) +{ + Pos.copyTo(mWorldPos); + mNormalVector = cv::Mat::zeros(3,1,CV_32F); + + mbTrackInViewR = false; + mbTrackInView = false; + + // MapPoints can be created from Tracking and Local Mapping. This mutex avoid conflicts with id. + unique_lock lock(mpMap->mMutexPointCreation); + mnId=nNextId++; +} + +MapPoint::MapPoint(const double invDepth, cv::Point2f uv_init, KeyFrame* pRefKF, KeyFrame* pHostKF, Map* pMap): + mnFirstKFid(pRefKF->mnId), mnFirstFrame(pRefKF->mnFrameId), nObs(0), mnTrackReferenceForFrame(0), + mnLastFrameSeen(0), mnBALocalForKF(0), mnFuseCandidateForKF(0), mnLoopPointForKF(0), mnCorrectedByKF(0), + mnCorrectedReference(0), mnBAGlobalForKF(0), mpRefKF(pRefKF), mnVisible(1), mnFound(1), mbBad(false), + mpReplaced(static_cast(NULL)), mfMinDistance(0), mfMaxDistance(0), mpMap(pMap), + mnOriginMapId(pMap->GetId()) +{ + mInvDepth=invDepth; + mInitU=(double)uv_init.x; + mInitV=(double)uv_init.y; + mpHostKF = pHostKF; + + mNormalVector = cv::Mat::zeros(3,1,CV_32F); + + // Worldpos is not set + // MapPoints can be created from Tracking and Local Mapping. This mutex avoid conflicts with id. + unique_lock lock(mpMap->mMutexPointCreation); + mnId=nNextId++; +} + +MapPoint::MapPoint(const cv::Mat &Pos, Map* pMap, Frame* pFrame, const int &idxF): + mnFirstKFid(-1), mnFirstFrame(pFrame->mnId), nObs(0), mnTrackReferenceForFrame(0), mnLastFrameSeen(0), + mnBALocalForKF(0), mnFuseCandidateForKF(0),mnLoopPointForKF(0), mnCorrectedByKF(0), + mnCorrectedReference(0), mnBAGlobalForKF(0), mpRefKF(static_cast(NULL)), mnVisible(1), + mnFound(1), mbBad(false), mpReplaced(NULL), mpMap(pMap), mnOriginMapId(pMap->GetId()) +{ + Pos.copyTo(mWorldPos); + cv::Mat Ow; + if(pFrame -> Nleft == -1 || idxF < pFrame -> Nleft){ + Ow = pFrame->GetCameraCenter(); + } + else{ + cv::Mat Rwl = pFrame -> mRwc; + cv::Mat tlr = pFrame -> mTlr.col(3); + cv::Mat twl = pFrame -> mOw; + + Ow = Rwl * tlr + twl; + } + mNormalVector = mWorldPos - Ow; + mNormalVector = mNormalVector/cv::norm(mNormalVector); + + cv::Mat PC = Pos - Ow; + const float dist = cv::norm(PC); + const int level = (pFrame -> Nleft == -1) ? pFrame->mvKeysUn[idxF].octave + : (idxF < pFrame -> Nleft) ? pFrame->mvKeys[idxF].octave + : pFrame -> mvKeysRight[idxF].octave; + const float levelScaleFactor = pFrame->mvScaleFactors[level]; + const int nLevels = pFrame->mnScaleLevels; + + mfMaxDistance = dist*levelScaleFactor; + mfMinDistance = mfMaxDistance/pFrame->mvScaleFactors[nLevels-1]; + + pFrame->mDescriptors.row(idxF).copyTo(mDescriptor); + + // MapPoints can be created from Tracking and Local Mapping. This mutex avoid conflicts with id. + unique_lock lock(mpMap->mMutexPointCreation); + mnId=nNextId++; +} + +void MapPoint::SetWorldPos(const cv::Mat &Pos) +{ + unique_lock lock2(mGlobalMutex); + unique_lock lock(mMutexPos); + Pos.copyTo(mWorldPos); +} + +cv::Mat MapPoint::GetWorldPos() +{ + unique_lock lock(mMutexPos); + return mWorldPos.clone(); +} + +cv::Mat MapPoint::GetNormal() +{ + unique_lock lock(mMutexPos); + return mNormalVector.clone(); +} + +KeyFrame* MapPoint::GetReferenceKeyFrame() +{ + unique_lock lock(mMutexFeatures); + return mpRefKF; +} + +void MapPoint::AddObservation(KeyFrame* pKF, int idx) +{ + unique_lock lock(mMutexFeatures); + tuple indexes; + + if(mObservations.count(pKF)){ + indexes = mObservations[pKF]; + } + else{ + indexes = tuple(-1,-1); + } + + if(pKF -> NLeft != -1 && idx >= pKF -> NLeft){ + get<1>(indexes) = idx; + } + else{ + get<0>(indexes) = idx; + } + + mObservations[pKF]=indexes; + + if(!pKF->mpCamera2 && pKF->mvuRight[idx]>=0) + nObs+=2; + else + nObs++; +} + +void MapPoint::EraseObservation(KeyFrame* pKF) +{ + bool bBad=false; + { + unique_lock lock(mMutexFeatures); + if(mObservations.count(pKF)) + { + //int idx = mObservations[pKF]; + tuple indexes = mObservations[pKF]; + int leftIndex = get<0>(indexes), rightIndex = get<1>(indexes); + + if(leftIndex != -1){ + if(!pKF->mpCamera2 && pKF->mvuRight[leftIndex]>=0) + nObs-=2; + else + nObs--; + } + if(rightIndex != -1){ + nObs--; + } + + mObservations.erase(pKF); + + if(mpRefKF==pKF) + mpRefKF=mObservations.begin()->first; + + // If only 2 observations or less, discard point + if(nObs<=2) + bBad=true; + } + } + + if(bBad) + SetBadFlag(); +} + + +std::map> MapPoint::GetObservations() +{ + unique_lock lock(mMutexFeatures); + return mObservations; +} + +int MapPoint::Observations() +{ + unique_lock lock(mMutexFeatures); + return nObs; +} + +void MapPoint::SetBadFlag() +{ + map> obs; + { + unique_lock lock1(mMutexFeatures); + unique_lock lock2(mMutexPos); + mbBad=true; + obs = mObservations; + mObservations.clear(); + } + for(map>::iterator mit=obs.begin(), mend=obs.end(); mit!=mend; mit++) + { + KeyFrame* pKF = mit->first; + int leftIndex = get<0>(mit -> second), rightIndex = get<1>(mit -> second); + if(leftIndex != -1){ + pKF->EraseMapPointMatch(leftIndex); + } + if(rightIndex != -1){ + pKF->EraseMapPointMatch(rightIndex); + } + } + + mpMap->EraseMapPoint(this); +} + +MapPoint* MapPoint::GetReplaced() +{ + unique_lock lock1(mMutexFeatures); + unique_lock lock2(mMutexPos); + return mpReplaced; +} + +void MapPoint::Replace(MapPoint* pMP) +{ + if(pMP->mnId==this->mnId) + return; + + int nvisible, nfound; + map> obs; + { + unique_lock lock1(mMutexFeatures); + unique_lock lock2(mMutexPos); + obs=mObservations; + mObservations.clear(); + mbBad=true; + nvisible = mnVisible; + nfound = mnFound; + mpReplaced = pMP; + } + + for(map>::iterator mit=obs.begin(), mend=obs.end(); mit!=mend; mit++) + { + // Replace measurement in keyframe + KeyFrame* pKF = mit->first; + + tuple indexes = mit -> second; + int leftIndex = get<0>(indexes), rightIndex = get<1>(indexes); + + if(!pMP->IsInKeyFrame(pKF)) + { + if(leftIndex != -1){ + pKF->ReplaceMapPointMatch(leftIndex, pMP); + pMP->AddObservation(pKF,leftIndex); + } + if(rightIndex != -1){ + pKF->ReplaceMapPointMatch(rightIndex, pMP); + pMP->AddObservation(pKF,rightIndex); + } + } + else + { + if(leftIndex != -1){ + pKF->EraseMapPointMatch(leftIndex); + } + if(rightIndex != -1){ + pKF->EraseMapPointMatch(rightIndex); + } + } + } + pMP->IncreaseFound(nfound); + pMP->IncreaseVisible(nvisible); + pMP->ComputeDistinctiveDescriptors(); + + mpMap->EraseMapPoint(this); +} + +bool MapPoint::isBad() +{ + unique_lock lock1(mMutexFeatures,std::defer_lock); + unique_lock lock2(mMutexPos,std::defer_lock); + lock(lock1, lock2); + + return mbBad; +} + +void MapPoint::IncreaseVisible(int n) +{ + unique_lock lock(mMutexFeatures); + mnVisible+=n; +} + +void MapPoint::IncreaseFound(int n) +{ + unique_lock lock(mMutexFeatures); + mnFound+=n; +} + +float MapPoint::GetFoundRatio() +{ + unique_lock lock(mMutexFeatures); + return static_cast(mnFound)/mnVisible; +} + +void MapPoint::ComputeDistinctiveDescriptors() +{ + // Retrieve all observed descriptors + vector vDescriptors; + + map> observations; + + { + unique_lock lock1(mMutexFeatures); + if(mbBad) + return; + observations=mObservations; + } + + if(observations.empty()) + return; + + vDescriptors.reserve(observations.size()); + + for(map>::iterator mit=observations.begin(), mend=observations.end(); mit!=mend; mit++) + { + KeyFrame* pKF = mit->first; + + if(!pKF->isBad()){ + tuple indexes = mit -> second; + int leftIndex = get<0>(indexes), rightIndex = get<1>(indexes); + + if(leftIndex != -1){ + vDescriptors.push_back(pKF->mDescriptors.row(leftIndex)); + } + if(rightIndex != -1){ + vDescriptors.push_back(pKF->mDescriptors.row(rightIndex)); + } + } + } + + if(vDescriptors.empty()) + return; + + // Compute distances between them + const size_t N = vDescriptors.size(); + + float Distances[N][N]; + for(size_t i=0;i vDists(Distances[i],Distances[i]+N); + sort(vDists.begin(),vDists.end()); + int median = vDists[0.5*(N-1)]; + + if(median lock(mMutexFeatures); + mDescriptor = vDescriptors[BestIdx].clone(); + } +} + +cv::Mat MapPoint::GetDescriptor() +{ + unique_lock lock(mMutexFeatures); + return mDescriptor.clone(); +} + +tuple MapPoint::GetIndexInKeyFrame(KeyFrame *pKF) +{ + unique_lock lock(mMutexFeatures); + if(mObservations.count(pKF)) + return mObservations[pKF]; + else + return tuple(-1,-1); +} + +bool MapPoint::IsInKeyFrame(KeyFrame *pKF) +{ + unique_lock lock(mMutexFeatures); + return (mObservations.count(pKF)); +} + +void MapPoint::UpdateNormalAndDepth() +{ + map> observations; + KeyFrame* pRefKF; + cv::Mat Pos; + { + unique_lock lock1(mMutexFeatures); + unique_lock lock2(mMutexPos); + if(mbBad) + return; + observations=mObservations; + pRefKF=mpRefKF; + Pos = mWorldPos.clone(); + } + + if(observations.empty()) + return; + + cv::Mat normal = cv::Mat::zeros(3,1,CV_32F); + int n=0; + for(map>::iterator mit=observations.begin(), mend=observations.end(); mit!=mend; mit++) + { + KeyFrame* pKF = mit->first; + + tuple indexes = mit -> second; + int leftIndex = get<0>(indexes), rightIndex = get<1>(indexes); + + if(leftIndex != -1){ + cv::Mat Owi = pKF->GetCameraCenter(); + cv::Mat normali = mWorldPos - Owi; + normal = normal + normali/cv::norm(normali); + n++; + } + if(rightIndex != -1){ + cv::Mat Owi = pKF->GetRightCameraCenter(); + cv::Mat normali = mWorldPos - Owi; + normal = normal + normali/cv::norm(normali); + n++; + } + } + + cv::Mat PC = Pos - pRefKF->GetCameraCenter(); + const float dist = cv::norm(PC); + + tuple indexes = observations[pRefKF]; + int leftIndex = get<0>(indexes), rightIndex = get<1>(indexes); + int level; + if(pRefKF -> NLeft == -1){ + level = pRefKF->mvKeysUn[leftIndex].octave; + } + else if(leftIndex != -1){ + level = pRefKF -> mvKeys[leftIndex].octave; + } + else{ + level = pRefKF -> mvKeysRight[rightIndex - pRefKF -> NLeft].octave; + } + + //const int level = pRefKF->mvKeysUn[observations[pRefKF]].octave; + const float levelScaleFactor = pRefKF->mvScaleFactors[level]; + const int nLevels = pRefKF->mnScaleLevels; + + { + unique_lock lock3(mMutexPos); + mfMaxDistance = dist*levelScaleFactor; + mfMinDistance = mfMaxDistance/pRefKF->mvScaleFactors[nLevels-1]; + mNormalVector = normal/n; + } +} + +void MapPoint::SetNormalVector(cv::Mat& normal) +{ + unique_lock lock3(mMutexPos); + mNormalVector = normal; +} + +float MapPoint::GetMinDistanceInvariance() +{ + unique_lock lock(mMutexPos); + return 0.8f*mfMinDistance; +} + +float MapPoint::GetMaxDistanceInvariance() +{ + unique_lock lock(mMutexPos); + return 1.2f*mfMaxDistance; +} + +int MapPoint::PredictScale(const float ¤tDist, KeyFrame* pKF) +{ + float ratio; + { + unique_lock lock(mMutexPos); + ratio = mfMaxDistance/currentDist; + } + + int nScale = ceil(log(ratio)/pKF->mfLogScaleFactor); + if(nScale<0) + nScale = 0; + else if(nScale>=pKF->mnScaleLevels) + nScale = pKF->mnScaleLevels-1; + + return nScale; +} + +int MapPoint::PredictScale(const float ¤tDist, Frame* pF) +{ + float ratio; + { + unique_lock lock(mMutexPos); + ratio = mfMaxDistance/currentDist; + } + + int nScale = ceil(log(ratio)/pF->mfLogScaleFactor); + if(nScale<0) + nScale = 0; + else if(nScale>=pF->mnScaleLevels) + nScale = pF->mnScaleLevels-1; + + return nScale; +} + +void MapPoint::PrintObservations() +{ + cout << "MP_OBS: MP " << mnId << endl; + for(map>::iterator mit=mObservations.begin(), mend=mObservations.end(); mit!=mend; mit++) + { + KeyFrame* pKFi = mit->first; + tuple indexes = mit->second; + int leftIndex = get<0>(indexes), rightIndex = get<1>(indexes); + cout << "--OBS in KF " << pKFi->mnId << " in map " << pKFi->GetMap()->GetId() << endl; + } +} + +Map* MapPoint::GetMap() +{ + unique_lock lock(mMutexMap); + return mpMap; +} + +void MapPoint::UpdateMap(Map* pMap) +{ + unique_lock lock(mMutexMap); + mpMap = pMap; +} + +void MapPoint::PreSave(set& spKF,set& spMP) +{ + mBackupReplacedId = -1; + if(mpReplaced && spMP.find(mpReplaced) != spMP.end()) + mBackupReplacedId = mpReplaced->mnId; + + mBackupObservationsId1.clear(); + mBackupObservationsId2.clear(); + // Save the id and position in each KF who view it + for(std::map >::const_iterator it = mObservations.begin(), end = mObservations.end(); it != end; ++it) + { + KeyFrame* pKFi = it->first; + if(spKF.find(pKFi) != spKF.end()) + { + mBackupObservationsId1[it->first->mnId] = get<0>(it->second); + mBackupObservationsId2[it->first->mnId] = get<1>(it->second); + } + else + { + EraseObservation(pKFi); + } + } + + // Save the id of the reference KF + if(spKF.find(mpRefKF) != spKF.end()) + { + mBackupRefKFId = mpRefKF->mnId; + } +} + +void MapPoint::PostLoad(map& mpKFid, map& mpMPid) +{ + mpRefKF = mpKFid[mBackupRefKFId]; + if(!mpRefKF) + { + cout << "MP without KF reference " << mBackupRefKFId << "; Num obs: " << nObs << endl; + } + mpReplaced = static_cast(NULL); + if(mBackupReplacedId>=0) + { + map::iterator it = mpMPid.find(mBackupReplacedId); + if (it != mpMPid.end()) + mpReplaced = it->second; + } + + mObservations.clear(); + + for(map::const_iterator it = mBackupObservationsId1.begin(), end = mBackupObservationsId1.end(); it != end; ++it) + { + KeyFrame* pKFi = mpKFid[it->first]; + map::const_iterator it2 = mBackupObservationsId2.find(it->first); + std::tuple indexes = tuple(it->second,it2->second); + if(pKFi) + { + mObservations[pKFi] = indexes; + } + } + + mBackupObservationsId1.clear(); + mBackupObservationsId2.clear(); +} + +} //namespace ORB_SLAM diff --git a/third_party/ORB_SLAM3/src/ORBextractor.cc b/third_party/ORB_SLAM3/src/ORBextractor.cc new file mode 100644 index 0000000..7a78b40 --- /dev/null +++ b/third_party/ORB_SLAM3/src/ORBextractor.cc @@ -0,0 +1,1179 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ +/** +* Software License Agreement (BSD License) +* +* Copyright (c) 2009, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +*/ + + +#include +#include +#include +#include +#include +#include + +#include "ORBextractor.h" + + +using namespace cv; +using namespace std; + +namespace ORB_SLAM3 +{ + + const int PATCH_SIZE = 31; + const int HALF_PATCH_SIZE = 15; + const int EDGE_THRESHOLD = 19; + + + static float IC_Angle(const Mat& image, Point2f pt, const vector & u_max) + { + int m_01 = 0, m_10 = 0; + + const uchar* center = &image.at (cvRound(pt.y), cvRound(pt.x)); + + // Treat the center line differently, v=0 + for (int u = -HALF_PATCH_SIZE; u <= HALF_PATCH_SIZE; ++u) + m_10 += u * center[u]; + + // Go line by line in the circuI853lar patch + int step = (int)image.step1(); + for (int v = 1; v <= HALF_PATCH_SIZE; ++v) + { + // Proceed over the two lines + int v_sum = 0; + int d = u_max[v]; + for (int u = -d; u <= d; ++u) + { + int val_plus = center[u + v*step], val_minus = center[u - v*step]; + v_sum += (val_plus - val_minus); + m_10 += u * (val_plus + val_minus); + } + m_01 += v * v_sum; + } + + return fastAtan2((float)m_01, (float)m_10); + } + + + const float factorPI = (float)(CV_PI/180.f); + static void computeOrbDescriptor(const KeyPoint& kpt, + const Mat& img, const Point* pattern, + uchar* desc) + { + float angle = (float)kpt.angle*factorPI; + float a = (float)cos(angle), b = (float)sin(angle); + + const uchar* center = &img.at(cvRound(kpt.pt.y), cvRound(kpt.pt.x)); + const int step = (int)img.step; + +#define GET_VALUE(idx) \ + center[cvRound(pattern[idx].x*b + pattern[idx].y*a)*step + \ + cvRound(pattern[idx].x*a - pattern[idx].y*b)] + + + for (int i = 0; i < 32; ++i, pattern += 16) + { + int t0, t1, val; + t0 = GET_VALUE(0); t1 = GET_VALUE(1); + val = t0 < t1; + t0 = GET_VALUE(2); t1 = GET_VALUE(3); + val |= (t0 < t1) << 1; + t0 = GET_VALUE(4); t1 = GET_VALUE(5); + val |= (t0 < t1) << 2; + t0 = GET_VALUE(6); t1 = GET_VALUE(7); + val |= (t0 < t1) << 3; + t0 = GET_VALUE(8); t1 = GET_VALUE(9); + val |= (t0 < t1) << 4; + t0 = GET_VALUE(10); t1 = GET_VALUE(11); + val |= (t0 < t1) << 5; + t0 = GET_VALUE(12); t1 = GET_VALUE(13); + val |= (t0 < t1) << 6; + t0 = GET_VALUE(14); t1 = GET_VALUE(15); + val |= (t0 < t1) << 7; + + desc[i] = (uchar)val; + } + +#undef GET_VALUE + } + + + static int bit_pattern_31_[256*4] = + { + 8,-3, 9,5/*mean (0), correlation (0)*/, + 4,2, 7,-12/*mean (1.12461e-05), correlation (0.0437584)*/, + -11,9, -8,2/*mean (3.37382e-05), correlation (0.0617409)*/, + 7,-12, 12,-13/*mean (5.62303e-05), correlation (0.0636977)*/, + 2,-13, 2,12/*mean (0.000134953), correlation (0.085099)*/, + 1,-7, 1,6/*mean (0.000528565), correlation (0.0857175)*/, + -2,-10, -2,-4/*mean (0.0188821), correlation (0.0985774)*/, + -13,-13, -11,-8/*mean (0.0363135), correlation (0.0899616)*/, + -13,-3, -12,-9/*mean (0.121806), correlation (0.099849)*/, + 10,4, 11,9/*mean (0.122065), correlation (0.093285)*/, + -13,-8, -8,-9/*mean (0.162787), correlation (0.0942748)*/, + -11,7, -9,12/*mean (0.21561), correlation (0.0974438)*/, + 7,7, 12,6/*mean (0.160583), correlation (0.130064)*/, + -4,-5, -3,0/*mean (0.228171), correlation (0.132998)*/, + -13,2, -12,-3/*mean (0.00997526), correlation (0.145926)*/, + -9,0, -7,5/*mean (0.198234), correlation (0.143636)*/, + 12,-6, 12,-1/*mean (0.0676226), correlation (0.16689)*/, + -3,6, -2,12/*mean (0.166847), correlation (0.171682)*/, + -6,-13, -4,-8/*mean (0.101215), correlation (0.179716)*/, + 11,-13, 12,-8/*mean (0.200641), correlation (0.192279)*/, + 4,7, 5,1/*mean (0.205106), correlation (0.186848)*/, + 5,-3, 10,-3/*mean (0.234908), correlation (0.192319)*/, + 3,-7, 6,12/*mean (0.0709964), correlation (0.210872)*/, + -8,-7, -6,-2/*mean (0.0939834), correlation (0.212589)*/, + -2,11, -1,-10/*mean (0.127778), correlation (0.20866)*/, + -13,12, -8,10/*mean (0.14783), correlation (0.206356)*/, + -7,3, -5,-3/*mean (0.182141), correlation (0.198942)*/, + -4,2, -3,7/*mean (0.188237), correlation (0.21384)*/, + -10,-12, -6,11/*mean (0.14865), correlation (0.23571)*/, + 5,-12, 6,-7/*mean (0.222312), correlation (0.23324)*/, + 5,-6, 7,-1/*mean (0.229082), correlation (0.23389)*/, + 1,0, 4,-5/*mean (0.241577), correlation (0.215286)*/, + 9,11, 11,-13/*mean (0.00338507), correlation (0.251373)*/, + 4,7, 4,12/*mean (0.131005), correlation (0.257622)*/, + 2,-1, 4,4/*mean (0.152755), correlation (0.255205)*/, + -4,-12, -2,7/*mean (0.182771), correlation (0.244867)*/, + -8,-5, -7,-10/*mean (0.186898), correlation (0.23901)*/, + 4,11, 9,12/*mean (0.226226), correlation (0.258255)*/, + 0,-8, 1,-13/*mean (0.0897886), correlation (0.274827)*/, + -13,-2, -8,2/*mean (0.148774), correlation (0.28065)*/, + -3,-2, -2,3/*mean (0.153048), correlation (0.283063)*/, + -6,9, -4,-9/*mean (0.169523), correlation (0.278248)*/, + 8,12, 10,7/*mean (0.225337), correlation (0.282851)*/, + 0,9, 1,3/*mean (0.226687), correlation (0.278734)*/, + 7,-5, 11,-10/*mean (0.00693882), correlation (0.305161)*/, + -13,-6, -11,0/*mean (0.0227283), correlation (0.300181)*/, + 10,7, 12,1/*mean (0.125517), correlation (0.31089)*/, + -6,-3, -6,12/*mean (0.131748), correlation (0.312779)*/, + 10,-9, 12,-4/*mean (0.144827), correlation (0.292797)*/, + -13,8, -8,-12/*mean (0.149202), correlation (0.308918)*/, + -13,0, -8,-4/*mean (0.160909), correlation (0.310013)*/, + 3,3, 7,8/*mean (0.177755), correlation (0.309394)*/, + 5,7, 10,-7/*mean (0.212337), correlation (0.310315)*/, + -1,7, 1,-12/*mean (0.214429), correlation (0.311933)*/, + 3,-10, 5,6/*mean (0.235807), correlation (0.313104)*/, + 2,-4, 3,-10/*mean (0.00494827), correlation (0.344948)*/, + -13,0, -13,5/*mean (0.0549145), correlation (0.344675)*/, + -13,-7, -12,12/*mean (0.103385), correlation (0.342715)*/, + -13,3, -11,8/*mean (0.134222), correlation (0.322922)*/, + -7,12, -4,7/*mean (0.153284), correlation (0.337061)*/, + 6,-10, 12,8/*mean (0.154881), correlation (0.329257)*/, + -9,-1, -7,-6/*mean (0.200967), correlation (0.33312)*/, + -2,-5, 0,12/*mean (0.201518), correlation (0.340635)*/, + -12,5, -7,5/*mean (0.207805), correlation (0.335631)*/, + 3,-10, 8,-13/*mean (0.224438), correlation (0.34504)*/, + -7,-7, -4,5/*mean (0.239361), correlation (0.338053)*/, + -3,-2, -1,-7/*mean (0.240744), correlation (0.344322)*/, + 2,9, 5,-11/*mean (0.242949), correlation (0.34145)*/, + -11,-13, -5,-13/*mean (0.244028), correlation (0.336861)*/, + -1,6, 0,-1/*mean (0.247571), correlation (0.343684)*/, + 5,-3, 5,2/*mean (0.000697256), correlation (0.357265)*/, + -4,-13, -4,12/*mean (0.00213675), correlation (0.373827)*/, + -9,-6, -9,6/*mean (0.0126856), correlation (0.373938)*/, + -12,-10, -8,-4/*mean (0.0152497), correlation (0.364237)*/, + 10,2, 12,-3/*mean (0.0299933), correlation (0.345292)*/, + 7,12, 12,12/*mean (0.0307242), correlation (0.366299)*/, + -7,-13, -6,5/*mean (0.0534975), correlation (0.368357)*/, + -4,9, -3,4/*mean (0.099865), correlation (0.372276)*/, + 7,-1, 12,2/*mean (0.117083), correlation (0.364529)*/, + -7,6, -5,1/*mean (0.126125), correlation (0.369606)*/, + -13,11, -12,5/*mean (0.130364), correlation (0.358502)*/, + -3,7, -2,-6/*mean (0.131691), correlation (0.375531)*/, + 7,-8, 12,-7/*mean (0.160166), correlation (0.379508)*/, + -13,-7, -11,-12/*mean (0.167848), correlation (0.353343)*/, + 1,-3, 12,12/*mean (0.183378), correlation (0.371916)*/, + 2,-6, 3,0/*mean (0.228711), correlation (0.371761)*/, + -4,3, -2,-13/*mean (0.247211), correlation (0.364063)*/, + -1,-13, 1,9/*mean (0.249325), correlation (0.378139)*/, + 7,1, 8,-6/*mean (0.000652272), correlation (0.411682)*/, + 1,-1, 3,12/*mean (0.00248538), correlation (0.392988)*/, + 9,1, 12,6/*mean (0.0206815), correlation (0.386106)*/, + -1,-9, -1,3/*mean (0.0364485), correlation (0.410752)*/, + -13,-13, -10,5/*mean (0.0376068), correlation (0.398374)*/, + 7,7, 10,12/*mean (0.0424202), correlation (0.405663)*/, + 12,-5, 12,9/*mean (0.0942645), correlation (0.410422)*/, + 6,3, 7,11/*mean (0.1074), correlation (0.413224)*/, + 5,-13, 6,10/*mean (0.109256), correlation (0.408646)*/, + 2,-12, 2,3/*mean (0.131691), correlation (0.416076)*/, + 3,8, 4,-6/*mean (0.165081), correlation (0.417569)*/, + 2,6, 12,-13/*mean (0.171874), correlation (0.408471)*/, + 9,-12, 10,3/*mean (0.175146), correlation (0.41296)*/, + -8,4, -7,9/*mean (0.183682), correlation (0.402956)*/, + -11,12, -4,-6/*mean (0.184672), correlation (0.416125)*/, + 1,12, 2,-8/*mean (0.191487), correlation (0.386696)*/, + 6,-9, 7,-4/*mean (0.192668), correlation (0.394771)*/, + 2,3, 3,-2/*mean (0.200157), correlation (0.408303)*/, + 6,3, 11,0/*mean (0.204588), correlation (0.411762)*/, + 3,-3, 8,-8/*mean (0.205904), correlation (0.416294)*/, + 7,8, 9,3/*mean (0.213237), correlation (0.409306)*/, + -11,-5, -6,-4/*mean (0.243444), correlation (0.395069)*/, + -10,11, -5,10/*mean (0.247672), correlation (0.413392)*/, + -5,-8, -3,12/*mean (0.24774), correlation (0.411416)*/, + -10,5, -9,0/*mean (0.00213675), correlation (0.454003)*/, + 8,-1, 12,-6/*mean (0.0293635), correlation (0.455368)*/, + 4,-6, 6,-11/*mean (0.0404971), correlation (0.457393)*/, + -10,12, -8,7/*mean (0.0481107), correlation (0.448364)*/, + 4,-2, 6,7/*mean (0.050641), correlation (0.455019)*/, + -2,0, -2,12/*mean (0.0525978), correlation (0.44338)*/, + -5,-8, -5,2/*mean (0.0629667), correlation (0.457096)*/, + 7,-6, 10,12/*mean (0.0653846), correlation (0.445623)*/, + -9,-13, -8,-8/*mean (0.0858749), correlation (0.449789)*/, + -5,-13, -5,-2/*mean (0.122402), correlation (0.450201)*/, + 8,-8, 9,-13/*mean (0.125416), correlation (0.453224)*/, + -9,-11, -9,0/*mean (0.130128), correlation (0.458724)*/, + 1,-8, 1,-2/*mean (0.132467), correlation (0.440133)*/, + 7,-4, 9,1/*mean (0.132692), correlation (0.454)*/, + -2,1, -1,-4/*mean (0.135695), correlation (0.455739)*/, + 11,-6, 12,-11/*mean (0.142904), correlation (0.446114)*/, + -12,-9, -6,4/*mean (0.146165), correlation (0.451473)*/, + 3,7, 7,12/*mean (0.147627), correlation (0.456643)*/, + 5,5, 10,8/*mean (0.152901), correlation (0.455036)*/, + 0,-4, 2,8/*mean (0.167083), correlation (0.459315)*/, + -9,12, -5,-13/*mean (0.173234), correlation (0.454706)*/, + 0,7, 2,12/*mean (0.18312), correlation (0.433855)*/, + -1,2, 1,7/*mean (0.185504), correlation (0.443838)*/, + 5,11, 7,-9/*mean (0.185706), correlation (0.451123)*/, + 3,5, 6,-8/*mean (0.188968), correlation (0.455808)*/, + -13,-4, -8,9/*mean (0.191667), correlation (0.459128)*/, + -5,9, -3,-3/*mean (0.193196), correlation (0.458364)*/, + -4,-7, -3,-12/*mean (0.196536), correlation (0.455782)*/, + 6,5, 8,0/*mean (0.1972), correlation (0.450481)*/, + -7,6, -6,12/*mean (0.199438), correlation (0.458156)*/, + -13,6, -5,-2/*mean (0.211224), correlation (0.449548)*/, + 1,-10, 3,10/*mean (0.211718), correlation (0.440606)*/, + 4,1, 8,-4/*mean (0.213034), correlation (0.443177)*/, + -2,-2, 2,-13/*mean (0.234334), correlation (0.455304)*/, + 2,-12, 12,12/*mean (0.235684), correlation (0.443436)*/, + -2,-13, 0,-6/*mean (0.237674), correlation (0.452525)*/, + 4,1, 9,3/*mean (0.23962), correlation (0.444824)*/, + -6,-10, -3,-5/*mean (0.248459), correlation (0.439621)*/, + -3,-13, -1,1/*mean (0.249505), correlation (0.456666)*/, + 7,5, 12,-11/*mean (0.00119208), correlation (0.495466)*/, + 4,-2, 5,-7/*mean (0.00372245), correlation (0.484214)*/, + -13,9, -9,-5/*mean (0.00741116), correlation (0.499854)*/, + 7,1, 8,6/*mean (0.0208952), correlation (0.499773)*/, + 7,-8, 7,6/*mean (0.0220085), correlation (0.501609)*/, + -7,-4, -7,1/*mean (0.0233806), correlation (0.496568)*/, + -8,11, -7,-8/*mean (0.0236505), correlation (0.489719)*/, + -13,6, -12,-8/*mean (0.0268781), correlation (0.503487)*/, + 2,4, 3,9/*mean (0.0323324), correlation (0.501938)*/, + 10,-5, 12,3/*mean (0.0399235), correlation (0.494029)*/, + -6,-5, -6,7/*mean (0.0420153), correlation (0.486579)*/, + 8,-3, 9,-8/*mean (0.0548021), correlation (0.484237)*/, + 2,-12, 2,8/*mean (0.0616622), correlation (0.496642)*/, + -11,-2, -10,3/*mean (0.0627755), correlation (0.498563)*/, + -12,-13, -7,-9/*mean (0.0829622), correlation (0.495491)*/, + -11,0, -10,-5/*mean (0.0843342), correlation (0.487146)*/, + 5,-3, 11,8/*mean (0.0929937), correlation (0.502315)*/, + -2,-13, -1,12/*mean (0.113327), correlation (0.48941)*/, + -1,-8, 0,9/*mean (0.132119), correlation (0.467268)*/, + -13,-11, -12,-5/*mean (0.136269), correlation (0.498771)*/, + -10,-2, -10,11/*mean (0.142173), correlation (0.498714)*/, + -3,9, -2,-13/*mean (0.144141), correlation (0.491973)*/, + 2,-3, 3,2/*mean (0.14892), correlation (0.500782)*/, + -9,-13, -4,0/*mean (0.150371), correlation (0.498211)*/, + -4,6, -3,-10/*mean (0.152159), correlation (0.495547)*/, + -4,12, -2,-7/*mean (0.156152), correlation (0.496925)*/, + -6,-11, -4,9/*mean (0.15749), correlation (0.499222)*/, + 6,-3, 6,11/*mean (0.159211), correlation (0.503821)*/, + -13,11, -5,5/*mean (0.162427), correlation (0.501907)*/, + 11,11, 12,6/*mean (0.16652), correlation (0.497632)*/, + 7,-5, 12,-2/*mean (0.169141), correlation (0.484474)*/, + -1,12, 0,7/*mean (0.169456), correlation (0.495339)*/, + -4,-8, -3,-2/*mean (0.171457), correlation (0.487251)*/, + -7,1, -6,7/*mean (0.175), correlation (0.500024)*/, + -13,-12, -8,-13/*mean (0.175866), correlation (0.497523)*/, + -7,-2, -6,-8/*mean (0.178273), correlation (0.501854)*/, + -8,5, -6,-9/*mean (0.181107), correlation (0.494888)*/, + -5,-1, -4,5/*mean (0.190227), correlation (0.482557)*/, + -13,7, -8,10/*mean (0.196739), correlation (0.496503)*/, + 1,5, 5,-13/*mean (0.19973), correlation (0.499759)*/, + 1,0, 10,-13/*mean (0.204465), correlation (0.49873)*/, + 9,12, 10,-1/*mean (0.209334), correlation (0.49063)*/, + 5,-8, 10,-9/*mean (0.211134), correlation (0.503011)*/, + -1,11, 1,-13/*mean (0.212), correlation (0.499414)*/, + -9,-3, -6,2/*mean (0.212168), correlation (0.480739)*/, + -1,-10, 1,12/*mean (0.212731), correlation (0.502523)*/, + -13,1, -8,-10/*mean (0.21327), correlation (0.489786)*/, + 8,-11, 10,-6/*mean (0.214159), correlation (0.488246)*/, + 2,-13, 3,-6/*mean (0.216993), correlation (0.50287)*/, + 7,-13, 12,-9/*mean (0.223639), correlation (0.470502)*/, + -10,-10, -5,-7/*mean (0.224089), correlation (0.500852)*/, + -10,-8, -8,-13/*mean (0.228666), correlation (0.502629)*/, + 4,-6, 8,5/*mean (0.22906), correlation (0.498305)*/, + 3,12, 8,-13/*mean (0.233378), correlation (0.503825)*/, + -4,2, -3,-3/*mean (0.234323), correlation (0.476692)*/, + 5,-13, 10,-12/*mean (0.236392), correlation (0.475462)*/, + 4,-13, 5,-1/*mean (0.236842), correlation (0.504132)*/, + -9,9, -4,3/*mean (0.236977), correlation (0.497739)*/, + 0,3, 3,-9/*mean (0.24314), correlation (0.499398)*/, + -12,1, -6,1/*mean (0.243297), correlation (0.489447)*/, + 3,2, 4,-8/*mean (0.00155196), correlation (0.553496)*/, + -10,-10, -10,9/*mean (0.00239541), correlation (0.54297)*/, + 8,-13, 12,12/*mean (0.0034413), correlation (0.544361)*/, + -8,-12, -6,-5/*mean (0.003565), correlation (0.551225)*/, + 2,2, 3,7/*mean (0.00835583), correlation (0.55285)*/, + 10,6, 11,-8/*mean (0.00885065), correlation (0.540913)*/, + 6,8, 8,-12/*mean (0.0101552), correlation (0.551085)*/, + -7,10, -6,5/*mean (0.0102227), correlation (0.533635)*/, + -3,-9, -3,9/*mean (0.0110211), correlation (0.543121)*/, + -1,-13, -1,5/*mean (0.0113473), correlation (0.550173)*/, + -3,-7, -3,4/*mean (0.0140913), correlation (0.554774)*/, + -8,-2, -8,3/*mean (0.017049), correlation (0.55461)*/, + 4,2, 12,12/*mean (0.01778), correlation (0.546921)*/, + 2,-5, 3,11/*mean (0.0224022), correlation (0.549667)*/, + 6,-9, 11,-13/*mean (0.029161), correlation (0.546295)*/, + 3,-1, 7,12/*mean (0.0303081), correlation (0.548599)*/, + 11,-1, 12,4/*mean (0.0355151), correlation (0.523943)*/, + -3,0, -3,6/*mean (0.0417904), correlation (0.543395)*/, + 4,-11, 4,12/*mean (0.0487292), correlation (0.542818)*/, + 2,-4, 2,1/*mean (0.0575124), correlation (0.554888)*/, + -10,-6, -8,1/*mean (0.0594242), correlation (0.544026)*/, + -13,7, -11,1/*mean (0.0597391), correlation (0.550524)*/, + -13,12, -11,-13/*mean (0.0608974), correlation (0.55383)*/, + 6,0, 11,-13/*mean (0.065126), correlation (0.552006)*/, + 0,-1, 1,4/*mean (0.074224), correlation (0.546372)*/, + -13,3, -9,-2/*mean (0.0808592), correlation (0.554875)*/, + -9,8, -6,-3/*mean (0.0883378), correlation (0.551178)*/, + -13,-6, -8,-2/*mean (0.0901035), correlation (0.548446)*/, + 5,-9, 8,10/*mean (0.0949843), correlation (0.554694)*/, + 2,7, 3,-9/*mean (0.0994152), correlation (0.550979)*/, + -1,-6, -1,-1/*mean (0.10045), correlation (0.552714)*/, + 9,5, 11,-2/*mean (0.100686), correlation (0.552594)*/, + 11,-3, 12,-8/*mean (0.101091), correlation (0.532394)*/, + 3,0, 3,5/*mean (0.101147), correlation (0.525576)*/, + -1,4, 0,10/*mean (0.105263), correlation (0.531498)*/, + 3,-6, 4,5/*mean (0.110785), correlation (0.540491)*/, + -13,0, -10,5/*mean (0.112798), correlation (0.536582)*/, + 5,8, 12,11/*mean (0.114181), correlation (0.555793)*/, + 8,9, 9,-6/*mean (0.117431), correlation (0.553763)*/, + 7,-4, 8,-12/*mean (0.118522), correlation (0.553452)*/, + -10,4, -10,9/*mean (0.12094), correlation (0.554785)*/, + 7,3, 12,4/*mean (0.122582), correlation (0.555825)*/, + 9,-7, 10,-2/*mean (0.124978), correlation (0.549846)*/, + 7,0, 12,-2/*mean (0.127002), correlation (0.537452)*/, + -1,-6, 0,-11/*mean (0.127148), correlation (0.547401)*/ + }; + + ORBextractor::ORBextractor(int _nfeatures, float _scaleFactor, int _nlevels, + int _iniThFAST, int _minThFAST): + nfeatures(_nfeatures), scaleFactor(_scaleFactor), nlevels(_nlevels), + iniThFAST(_iniThFAST), minThFAST(_minThFAST) + { + mvScaleFactor.resize(nlevels); + mvLevelSigma2.resize(nlevels); + mvScaleFactor[0]=1.0f; + mvLevelSigma2[0]=1.0f; + for(int i=1; i= vmin; --v) + { + while (umax[v0] == umax[v0 + 1]) + ++v0; + umax[v] = v0; + ++v0; + } + } + + static void computeOrientation(const Mat& image, vector& keypoints, const vector& umax) + { + for (vector::iterator keypoint = keypoints.begin(), + keypointEnd = keypoints.end(); keypoint != keypointEnd; ++keypoint) + { + keypoint->angle = IC_Angle(image, keypoint->pt, umax); + } + } + + void ExtractorNode::DivideNode(ExtractorNode &n1, ExtractorNode &n2, ExtractorNode &n3, ExtractorNode &n4) + { + const int halfX = ceil(static_cast(UR.x-UL.x)/2); + const int halfY = ceil(static_cast(BR.y-UL.y)/2); + + //Define boundaries of childs + n1.UL = UL; + n1.UR = cv::Point2i(UL.x+halfX,UL.y); + n1.BL = cv::Point2i(UL.x,UL.y+halfY); + n1.BR = cv::Point2i(UL.x+halfX,UL.y+halfY); + n1.vKeys.reserve(vKeys.size()); + + n2.UL = n1.UR; + n2.UR = UR; + n2.BL = n1.BR; + n2.BR = cv::Point2i(UR.x,UL.y+halfY); + n2.vKeys.reserve(vKeys.size()); + + n3.UL = n1.BL; + n3.UR = n1.BR; + n3.BL = BL; + n3.BR = cv::Point2i(n1.BR.x,BL.y); + n3.vKeys.reserve(vKeys.size()); + + n4.UL = n3.UR; + n4.UR = n2.BR; + n4.BL = n3.BR; + n4.BR = BR; + n4.vKeys.reserve(vKeys.size()); + + //Associate points to childs + for(size_t i=0;i ORBextractor::DistributeOctTree(const vector& vToDistributeKeys, const int &minX, + const int &maxX, const int &minY, const int &maxY, const int &N, const int &level) + { + // Compute how many initial nodes + const int nIni = round(static_cast(maxX-minX)/(maxY-minY)); + + const float hX = static_cast(maxX-minX)/nIni; + + list lNodes; + + vector vpIniNodes; + vpIniNodes.resize(nIni); + + for(int i=0; i(i),0); + ni.UR = cv::Point2i(hX*static_cast(i+1),0); + ni.BL = cv::Point2i(ni.UL.x,maxY-minY); + ni.BR = cv::Point2i(ni.UR.x,maxY-minY); + ni.vKeys.reserve(vToDistributeKeys.size()); + + lNodes.push_back(ni); + vpIniNodes[i] = &lNodes.back(); + } + + //Associate points to childs + for(size_t i=0;ivKeys.push_back(kp); + } + + list::iterator lit = lNodes.begin(); + + while(lit!=lNodes.end()) + { + if(lit->vKeys.size()==1) + { + lit->bNoMore=true; + lit++; + } + else if(lit->vKeys.empty()) + lit = lNodes.erase(lit); + else + lit++; + } + + bool bFinish = false; + + int iteration = 0; + + vector > vSizeAndPointerToNode; + vSizeAndPointerToNode.reserve(lNodes.size()*4); + + while(!bFinish) + { + iteration++; + + int prevSize = lNodes.size(); + + lit = lNodes.begin(); + + int nToExpand = 0; + + vSizeAndPointerToNode.clear(); + + while(lit!=lNodes.end()) + { + if(lit->bNoMore) + { + // If node only contains one point do not subdivide and continue + lit++; + continue; + } + else + { + // If more than one point, subdivide + ExtractorNode n1,n2,n3,n4; + lit->DivideNode(n1,n2,n3,n4); + + // Add childs if they contain points + if(n1.vKeys.size()>0) + { + lNodes.push_front(n1); + if(n1.vKeys.size()>1) + { + nToExpand++; + vSizeAndPointerToNode.push_back(make_pair(n1.vKeys.size(),&lNodes.front())); + lNodes.front().lit = lNodes.begin(); + } + } + if(n2.vKeys.size()>0) + { + lNodes.push_front(n2); + if(n2.vKeys.size()>1) + { + nToExpand++; + vSizeAndPointerToNode.push_back(make_pair(n2.vKeys.size(),&lNodes.front())); + lNodes.front().lit = lNodes.begin(); + } + } + if(n3.vKeys.size()>0) + { + lNodes.push_front(n3); + if(n3.vKeys.size()>1) + { + nToExpand++; + vSizeAndPointerToNode.push_back(make_pair(n3.vKeys.size(),&lNodes.front())); + lNodes.front().lit = lNodes.begin(); + } + } + if(n4.vKeys.size()>0) + { + lNodes.push_front(n4); + if(n4.vKeys.size()>1) + { + nToExpand++; + vSizeAndPointerToNode.push_back(make_pair(n4.vKeys.size(),&lNodes.front())); + lNodes.front().lit = lNodes.begin(); + } + } + + lit=lNodes.erase(lit); + continue; + } + } + + // Finish if there are more nodes than required features + // or all nodes contain just one point + if((int)lNodes.size()>=N || (int)lNodes.size()==prevSize) + { + bFinish = true; + } + else if(((int)lNodes.size()+nToExpand*3)>N) + { + + while(!bFinish) + { + + prevSize = lNodes.size(); + + vector > vPrevSizeAndPointerToNode = vSizeAndPointerToNode; + vSizeAndPointerToNode.clear(); + + sort(vPrevSizeAndPointerToNode.begin(),vPrevSizeAndPointerToNode.end()); + for(int j=vPrevSizeAndPointerToNode.size()-1;j>=0;j--) + { + ExtractorNode n1,n2,n3,n4; + vPrevSizeAndPointerToNode[j].second->DivideNode(n1,n2,n3,n4); + + // Add childs if they contain points + if(n1.vKeys.size()>0) + { + lNodes.push_front(n1); + if(n1.vKeys.size()>1) + { + vSizeAndPointerToNode.push_back(make_pair(n1.vKeys.size(),&lNodes.front())); + lNodes.front().lit = lNodes.begin(); + } + } + if(n2.vKeys.size()>0) + { + lNodes.push_front(n2); + if(n2.vKeys.size()>1) + { + vSizeAndPointerToNode.push_back(make_pair(n2.vKeys.size(),&lNodes.front())); + lNodes.front().lit = lNodes.begin(); + } + } + if(n3.vKeys.size()>0) + { + lNodes.push_front(n3); + if(n3.vKeys.size()>1) + { + vSizeAndPointerToNode.push_back(make_pair(n3.vKeys.size(),&lNodes.front())); + lNodes.front().lit = lNodes.begin(); + } + } + if(n4.vKeys.size()>0) + { + lNodes.push_front(n4); + if(n4.vKeys.size()>1) + { + vSizeAndPointerToNode.push_back(make_pair(n4.vKeys.size(),&lNodes.front())); + lNodes.front().lit = lNodes.begin(); + } + } + + lNodes.erase(vPrevSizeAndPointerToNode[j].second->lit); + + if((int)lNodes.size()>=N) + break; + } + + if((int)lNodes.size()>=N || (int)lNodes.size()==prevSize) + bFinish = true; + + } + } + } + + // Retain the best point in each node + vector vResultKeys; + vResultKeys.reserve(nfeatures); + for(list::iterator lit=lNodes.begin(); lit!=lNodes.end(); lit++) + { + vector &vNodeKeys = lit->vKeys; + cv::KeyPoint* pKP = &vNodeKeys[0]; + float maxResponse = pKP->response; + + for(size_t k=1;kmaxResponse) + { + pKP = &vNodeKeys[k]; + maxResponse = vNodeKeys[k].response; + } + } + + vResultKeys.push_back(*pKP); + } + + return vResultKeys; + } + + void ORBextractor::ComputeKeyPointsOctTree(vector >& allKeypoints) + { + allKeypoints.resize(nlevels); + + const float W = 30; + + for (int level = 0; level < nlevels; ++level) + { + const int minBorderX = EDGE_THRESHOLD-3; + const int minBorderY = minBorderX; + const int maxBorderX = mvImagePyramid[level].cols-EDGE_THRESHOLD+3; + const int maxBorderY = mvImagePyramid[level].rows-EDGE_THRESHOLD+3; + + vector vToDistributeKeys; + vToDistributeKeys.reserve(nfeatures*10); + + const float width = (maxBorderX-minBorderX); + const float height = (maxBorderY-minBorderY); + + const int nCols = width/W; + const int nRows = height/W; + const int wCell = ceil(width/nCols); + const int hCell = ceil(height/nRows); + + for(int i=0; i=maxBorderY-3) + continue; + if(maxY>maxBorderY) + maxY = maxBorderY; + + for(int j=0; j=maxBorderX-6) + continue; + if(maxX>maxBorderX) + maxX = maxBorderX; + + vector vKeysCell; + + FAST(mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX), + vKeysCell,iniThFAST,true); + + /*if(bRight && j <= 13){ + FAST(mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX), + vKeysCell,10,true); + } + else if(!bRight && j >= 16){ + FAST(mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX), + vKeysCell,10,true); + } + else{ + FAST(mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX), + vKeysCell,iniThFAST,true); + }*/ + + + if(vKeysCell.empty()) + { + FAST(mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX), + vKeysCell,minThFAST,true); + /*if(bRight && j <= 13){ + FAST(mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX), + vKeysCell,5,true); + } + else if(!bRight && j >= 16){ + FAST(mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX), + vKeysCell,5,true); + } + else{ + FAST(mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX), + vKeysCell,minThFAST,true); + }*/ + } + + if(!vKeysCell.empty()) + { + for(vector::iterator vit=vKeysCell.begin(); vit!=vKeysCell.end();vit++) + { + (*vit).pt.x+=j*wCell; + (*vit).pt.y+=i*hCell; + vToDistributeKeys.push_back(*vit); + } + } + + } + } + + vector & keypoints = allKeypoints[level]; + keypoints.reserve(nfeatures); + + keypoints = DistributeOctTree(vToDistributeKeys, minBorderX, maxBorderX, + minBorderY, maxBorderY,mnFeaturesPerLevel[level], level); + + const int scaledPatchSize = PATCH_SIZE*mvScaleFactor[level]; + + // Add border to coordinates and scale information + const int nkps = keypoints.size(); + for(int i=0; i > &allKeypoints) + { + allKeypoints.resize(nlevels); + + float imageRatio = (float)mvImagePyramid[0].cols/mvImagePyramid[0].rows; + + for (int level = 0; level < nlevels; ++level) + { + const int nDesiredFeatures = mnFeaturesPerLevel[level]; + + const int levelCols = sqrt((float)nDesiredFeatures/(5*imageRatio)); + const int levelRows = imageRatio*levelCols; + + const int minBorderX = EDGE_THRESHOLD; + const int minBorderY = minBorderX; + const int maxBorderX = mvImagePyramid[level].cols-EDGE_THRESHOLD; + const int maxBorderY = mvImagePyramid[level].rows-EDGE_THRESHOLD; + + const int W = maxBorderX - minBorderX; + const int H = maxBorderY - minBorderY; + const int cellW = ceil((float)W/levelCols); + const int cellH = ceil((float)H/levelRows); + + const int nCells = levelRows*levelCols; + const int nfeaturesCell = ceil((float)nDesiredFeatures/nCells); + + vector > > cellKeyPoints(levelRows, vector >(levelCols)); + + vector > nToRetain(levelRows,vector(levelCols,0)); + vector > nTotal(levelRows,vector(levelCols,0)); + vector > bNoMore(levelRows,vector(levelCols,false)); + vector iniXCol(levelCols); + vector iniYRow(levelRows); + int nNoMore = 0; + int nToDistribute = 0; + + + float hY = cellH + 6; + + for(int i=0; infeaturesCell) + { + nToRetain[i][j] = nfeaturesCell; + bNoMore[i][j] = false; + } + else + { + nToRetain[i][j] = nKeys; + nToDistribute += nfeaturesCell-nKeys; + bNoMore[i][j] = true; + nNoMore++; + } + + } + } + + + // Retain by score + + while(nToDistribute>0 && nNoMorenNewFeaturesCell) + { + nToRetain[i][j] = nNewFeaturesCell; + bNoMore[i][j] = false; + } + else + { + nToRetain[i][j] = nTotal[i][j]; + nToDistribute += nNewFeaturesCell-nTotal[i][j]; + bNoMore[i][j] = true; + nNoMore++; + } + } + } + } + } + + vector & keypoints = allKeypoints[level]; + keypoints.reserve(nDesiredFeatures*2); + + const int scaledPatchSize = PATCH_SIZE*mvScaleFactor[level]; + + // Retain by score and transform coordinates + for(int i=0; i &keysCell = cellKeyPoints[i][j]; + KeyPointsFilter::retainBest(keysCell,nToRetain[i][j]); + if((int)keysCell.size()>nToRetain[i][j]) + keysCell.resize(nToRetain[i][j]); + + + for(size_t k=0, kend=keysCell.size(); knDesiredFeatures) + { + KeyPointsFilter::retainBest(keypoints,nDesiredFeatures); + keypoints.resize(nDesiredFeatures); + } + } + + // and compute orientations + for (int level = 0; level < nlevels; ++level) + computeOrientation(mvImagePyramid[level], allKeypoints[level], umax); + } + + static void computeDescriptors(const Mat& image, vector& keypoints, Mat& descriptors, + const vector& pattern) + { + descriptors = Mat::zeros((int)keypoints.size(), 32, CV_8UC1); + + for (size_t i = 0; i < keypoints.size(); i++) + computeOrbDescriptor(keypoints[i], image, &pattern[0], descriptors.ptr((int)i)); + } + + int ORBextractor::operator()( InputArray _image, InputArray _mask, vector& _keypoints, + OutputArray _descriptors, std::vector &vLappingArea) + { + //cout << "[ORBextractor]: Max Features: " << nfeatures << endl; + if(_image.empty()) + return -1; + + Mat image = _image.getMat(); + assert(image.type() == CV_8UC1 ); + + // Pre-compute the scale pyramid + ComputePyramid(image); + + vector < vector > allKeypoints; + ComputeKeyPointsOctTree(allKeypoints); + //ComputeKeyPointsOld(allKeypoints); + + Mat descriptors; + + int nkeypoints = 0; + for (int level = 0; level < nlevels; ++level) + nkeypoints += (int)allKeypoints[level].size(); + if( nkeypoints == 0 ) + _descriptors.release(); + else + { + _descriptors.create(nkeypoints, 32, CV_8U); + descriptors = _descriptors.getMat(); + } + + //_keypoints.clear(); + //_keypoints.reserve(nkeypoints); + _keypoints = vector(nkeypoints); + + int offset = 0; + //Modified for speeding up stereo fisheye matching + int monoIndex = 0, stereoIndex = nkeypoints-1; + for (int level = 0; level < nlevels; ++level) + { + vector& keypoints = allKeypoints[level]; + int nkeypointsLevel = (int)keypoints.size(); + + if(nkeypointsLevel==0) + continue; + + // preprocess the resized image + Mat workingMat = mvImagePyramid[level].clone(); + GaussianBlur(workingMat, workingMat, Size(7, 7), 2, 2, BORDER_REFLECT_101); + + // Compute the descriptors + //Mat desc = descriptors.rowRange(offset, offset + nkeypointsLevel); + Mat desc = cv::Mat(nkeypointsLevel, 32, CV_8U); + computeDescriptors(workingMat, keypoints, desc, pattern); + + offset += nkeypointsLevel; + + + float scale = mvScaleFactor[level]; //getScale(level, firstLevel, scaleFactor); + int i = 0; + for (vector::iterator keypoint = keypoints.begin(), + keypointEnd = keypoints.end(); keypoint != keypointEnd; ++keypoint){ + + // Scale keypoint coordinates + if (level != 0){ + keypoint->pt *= scale; + } + + if(keypoint->pt.x >= vLappingArea[0] && keypoint->pt.x <= vLappingArea[1]){ + _keypoints.at(stereoIndex) = (*keypoint); + desc.row(i).copyTo(descriptors.row(stereoIndex)); + stereoIndex--; + } + else{ + _keypoints.at(monoIndex) = (*keypoint); + desc.row(i).copyTo(descriptors.row(monoIndex)); + monoIndex++; + } + i++; + } + } + //cout << "[ORBextractor]: extracted " << _keypoints.size() << " KeyPoints" << endl; + return monoIndex; + } + + void ORBextractor::ComputePyramid(cv::Mat image) + { + for (int level = 0; level < nlevels; ++level) + { + float scale = mvInvScaleFactor[level]; + Size sz(cvRound((float)image.cols*scale), cvRound((float)image.rows*scale)); + Size wholeSize(sz.width + EDGE_THRESHOLD*2, sz.height + EDGE_THRESHOLD*2); + Mat temp(wholeSize, image.type()), masktemp; + mvImagePyramid[level] = temp(Rect(EDGE_THRESHOLD, EDGE_THRESHOLD, sz.width, sz.height)); + + // Compute the resized image + if( level != 0 ) + { + resize(mvImagePyramid[level-1], mvImagePyramid[level], sz, 0, 0, INTER_LINEAR); + + copyMakeBorder(mvImagePyramid[level], temp, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD, + BORDER_REFLECT_101+BORDER_ISOLATED); + } + else + { + copyMakeBorder(image, temp, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD, + BORDER_REFLECT_101); + } + } + + } + +} //namespace ORB_SLAM diff --git a/third_party/ORB_SLAM3/src/ORBmatcher.cc b/third_party/ORB_SLAM3/src/ORBmatcher.cc new file mode 100644 index 0000000..2637d72 --- /dev/null +++ b/third_party/ORB_SLAM3/src/ORBmatcher.cc @@ -0,0 +1,2367 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + + +#include "ORBmatcher.h" + +#include + +#include +#include + +#include "Thirdparty/DBoW2/DBoW2/FeatureVector.h" + +#include + +using namespace std; + +namespace ORB_SLAM3 +{ + +const int ORBmatcher::TH_HIGH = 100; +const int ORBmatcher::TH_LOW = 50; +const int ORBmatcher::HISTO_LENGTH = 30; + +ORBmatcher::ORBmatcher(float nnratio, bool checkOri): mfNNratio(nnratio), mbCheckOrientation(checkOri) +{ +} + +int ORBmatcher::SearchByProjection(Frame &F, const vector &vpMapPoints, const float th, const bool bFarPoints, const float thFarPoints) +{ + int nmatches=0, left = 0, right = 0; + + const bool bFactor = th!=1.0; + + for(size_t iMP=0; iMPmbTrackInView && !pMP->mbTrackInViewR) + continue; + + if(bFarPoints && pMP->mTrackDepth>thFarPoints) + continue; + + if(pMP->isBad()) + continue; + + if(pMP->mbTrackInView) + { + const int &nPredictedLevel = pMP->mnTrackScaleLevel; + + // The size of the window will depend on the viewing direction + float r = RadiusByViewingCos(pMP->mTrackViewCos); + + if(bFactor) + r*=th; + + const vector vIndices = + F.GetFeaturesInArea(pMP->mTrackProjX,pMP->mTrackProjY,r*F.mvScaleFactors[nPredictedLevel],nPredictedLevel-1,nPredictedLevel); + + if(!vIndices.empty()){ + const cv::Mat MPdescriptor = pMP->GetDescriptor(); + + int bestDist=256; + int bestLevel= -1; + int bestDist2=256; + int bestLevel2 = -1; + int bestIdx =-1 ; + + // Get best and second matches with near keypoints + for(vector::const_iterator vit=vIndices.begin(), vend=vIndices.end(); vit!=vend; vit++) + { + const size_t idx = *vit; + + if(F.mvpMapPoints[idx]) + if(F.mvpMapPoints[idx]->Observations()>0) + continue; + + if(F.Nleft == -1 && F.mvuRight[idx]>0) + { + const float er = fabs(pMP->mTrackProjXR-F.mvuRight[idx]); + if(er>r*F.mvScaleFactors[nPredictedLevel]) + continue; + } + + const cv::Mat &d = F.mDescriptors.row(idx); + + const int dist = DescriptorDistance(MPdescriptor,d); + + if(distmfNNratio*bestDist2) + continue; + + if(bestLevel!=bestLevel2 || bestDist<=mfNNratio*bestDist2){ + F.mvpMapPoints[bestIdx]=pMP; + + if(F.Nleft != -1 && F.mvLeftToRightMatch[bestIdx] != -1){ //Also match with the stereo observation at right camera + F.mvpMapPoints[F.mvLeftToRightMatch[bestIdx] + F.Nleft] = pMP; + nmatches++; + right++; + } + + nmatches++; + left++; + } + } + } + } + + if(F.Nleft != -1 && pMP->mbTrackInViewR){ + const int &nPredictedLevel = pMP->mnTrackScaleLevelR; + if(nPredictedLevel != -1){ + float r = RadiusByViewingCos(pMP->mTrackViewCosR); + + const vector vIndices = + F.GetFeaturesInArea(pMP->mTrackProjXR,pMP->mTrackProjYR,r*F.mvScaleFactors[nPredictedLevel],nPredictedLevel-1,nPredictedLevel,true); + + if(vIndices.empty()) + continue; + + const cv::Mat MPdescriptor = pMP->GetDescriptor(); + + int bestDist=256; + int bestLevel= -1; + int bestDist2=256; + int bestLevel2 = -1; + int bestIdx =-1 ; + + // Get best and second matches with near keypoints + for(vector::const_iterator vit=vIndices.begin(), vend=vIndices.end(); vit!=vend; vit++) + { + const size_t idx = *vit; + + if(F.mvpMapPoints[idx + F.Nleft]) + if(F.mvpMapPoints[idx + F.Nleft]->Observations()>0) + continue; + + + const cv::Mat &d = F.mDescriptors.row(idx + F.Nleft); + + const int dist = DescriptorDistance(MPdescriptor,d); + + if(distmfNNratio*bestDist2) + continue; + + if(F.Nleft != -1 && F.mvRightToLeftMatch[bestIdx] != -1){ //Also match with the stereo observation at right camera + F.mvpMapPoints[F.mvRightToLeftMatch[bestIdx]] = pMP; + nmatches++; + left++; + } + + + F.mvpMapPoints[bestIdx + F.Nleft]=pMP; + nmatches++; + right++; + } + } + } + } + return nmatches; +} + +float ORBmatcher::RadiusByViewingCos(const float &viewCos) +{ + if(viewCos>0.998) + return 2.5; + else + return 4.0; +} + + +bool ORBmatcher::CheckDistEpipolarLine(const cv::KeyPoint &kp1,const cv::KeyPoint &kp2,const cv::Mat &F12,const KeyFrame* pKF2, const bool b1) +{ + // Epipolar line in second image l = x1'F12 = [a b c] + const float a = kp1.pt.x*F12.at(0,0)+kp1.pt.y*F12.at(1,0)+F12.at(2,0); + const float b = kp1.pt.x*F12.at(0,1)+kp1.pt.y*F12.at(1,1)+F12.at(2,1); + const float c = kp1.pt.x*F12.at(0,2)+kp1.pt.y*F12.at(1,2)+F12.at(2,2); + + const float num = a*kp2.pt.x+b*kp2.pt.y+c; + + const float den = a*a+b*b; + + if(den==0) + return false; + + const float dsqr = num*num/den; + + if(!b1) + return dsqr<3.84*pKF2->mvLevelSigma2[kp2.octave]; + else + return dsqr<6.63*pKF2->mvLevelSigma2[kp2.octave]; +} + +bool ORBmatcher::CheckDistEpipolarLine2(const cv::KeyPoint &kp1, const cv::KeyPoint &kp2, const cv::Mat &F12, const KeyFrame *pKF2, const float unc) +{ + // Epipolar line in second image l = x1'F12 = [a b c] + const float a = kp1.pt.x*F12.at(0,0)+kp1.pt.y*F12.at(1,0)+F12.at(2,0); + const float b = kp1.pt.x*F12.at(0,1)+kp1.pt.y*F12.at(1,1)+F12.at(2,1); + const float c = kp1.pt.x*F12.at(0,2)+kp1.pt.y*F12.at(1,2)+F12.at(2,2); + + const float num = a*kp2.pt.x+b*kp2.pt.y+c; + + const float den = a*a+b*b; + + if(den==0) + return false; + + const float dsqr = num*num/den; + + if(unc==1.f) + return dsqr<3.84*pKF2->mvLevelSigma2[kp2.octave]; + else + return dsqr<3.84*pKF2->mvLevelSigma2[kp2.octave]*unc; +} + +int ORBmatcher::SearchByBoW(KeyFrame* pKF,Frame &F, vector &vpMapPointMatches) +{ + const vector vpMapPointsKF = pKF->GetMapPointMatches(); + + vpMapPointMatches = vector(F.N,static_cast(NULL)); + + const DBoW2::FeatureVector &vFeatVecKF = pKF->mFeatVec; + + int nmatches=0; + + vector rotHist[HISTO_LENGTH]; + for(int i=0;ifirst == Fit->first) + { + const vector vIndicesKF = KFit->second; + const vector vIndicesF = Fit->second; + + for(size_t iKF=0; iKFisBad()) + continue; + + const cv::Mat &dKF= pKF->mDescriptors.row(realIdxKF); + + int bestDist1=256; + int bestIdxF =-1 ; + int bestDist2=256; + + int bestDist1R=256; + int bestIdxFR =-1 ; + int bestDist2R=256; + + for(size_t iF=0; iF= F.Nleft && dist= F.Nleft && dist(bestDist1)(bestDist2)) + { + vpMapPointMatches[bestIdxF]=pMP; + + const cv::KeyPoint &kp = + (!pKF->mpCamera2) ? pKF->mvKeysUn[realIdxKF] : + (realIdxKF >= pKF -> NLeft) ? pKF -> mvKeysRight[realIdxKF - pKF -> NLeft] + : pKF -> mvKeys[realIdxKF]; + + if(mbCheckOrientation) + { + cv::KeyPoint &Fkp = + (!pKF->mpCamera2 || F.Nleft == -1) ? F.mvKeys[bestIdxF] : + (bestIdxF >= F.Nleft) ? F.mvKeysRight[bestIdxF - F.Nleft] + : F.mvKeys[bestIdxF]; + + float rot = kp.angle-Fkp.angle; + if(rot<0.0) + rot+=360.0f; + int bin = round(rot*factor); + if(bin==HISTO_LENGTH) + bin=0; + assert(bin>=0 && bin(bestDist1R)(bestDist2R) || true) + { + vpMapPointMatches[bestIdxFR]=pMP; + + const cv::KeyPoint &kp = + (!pKF->mpCamera2) ? pKF->mvKeysUn[realIdxKF] : + (realIdxKF >= pKF -> NLeft) ? pKF -> mvKeysRight[realIdxKF - pKF -> NLeft] + : pKF -> mvKeys[realIdxKF]; + + if(mbCheckOrientation) + { + cv::KeyPoint &Fkp = + (!F.mpCamera2) ? F.mvKeys[bestIdxFR] : + (bestIdxFR >= F.Nleft) ? F.mvKeysRight[bestIdxFR - F.Nleft] + : F.mvKeys[bestIdxFR]; + + float rot = kp.angle-Fkp.angle; + if(rot<0.0) + rot+=360.0f; + int bin = round(rot*factor); + if(bin==HISTO_LENGTH) + bin=0; + assert(bin>=0 && binfirst < Fit->first) + { + KFit = vFeatVecKF.lower_bound(Fit->first); + } + else + { + Fit = F.mFeatVec.lower_bound(KFit->first); + } + } + + if(mbCheckOrientation) + { + int ind1=-1; + int ind2=-1; + int ind3=-1; + + ComputeThreeMaxima(rotHist,HISTO_LENGTH,ind1,ind2,ind3); + + for(int i=0; i(NULL); + nmatches--; + } + } + } + + return nmatches; +} + +int ORBmatcher::SearchByProjection(KeyFrame* pKF, cv::Mat Scw, const vector &vpPoints, + vector &vpMatched, int th, float ratioHamming) +{ + // Get Calibration Parameters for later projection + const float &fx = pKF->fx; + const float &fy = pKF->fy; + const float &cx = pKF->cx; + const float &cy = pKF->cy; + + // Decompose Scw + cv::Mat sRcw = Scw.rowRange(0,3).colRange(0,3); + const float scw = sqrt(sRcw.row(0).dot(sRcw.row(0))); + cv::Mat Rcw = sRcw/scw; + cv::Mat tcw = Scw.rowRange(0,3).col(3)/scw; + cv::Mat Ow = -Rcw.t()*tcw; + + // Set of MapPoints already found in the KeyFrame + set spAlreadyFound(vpMatched.begin(), vpMatched.end()); + spAlreadyFound.erase(static_cast(NULL)); + + int nmatches=0; + + // For each Candidate MapPoint Project and Match + for(int iMP=0, iendMP=vpPoints.size(); iMPisBad() || spAlreadyFound.count(pMP)) + continue; + + // Get 3D Coords. + cv::Mat p3Dw = pMP->GetWorldPos(); + + // Transform into Camera Coords. + cv::Mat p3Dc = Rcw*p3Dw+tcw; + + // Depth must be positive + if(p3Dc.at(2)<0.0) + continue; + + // Project into Image + const float x = p3Dc.at(0); + const float y = p3Dc.at(1); + const float z = p3Dc.at(2); + + const cv::Point2f uv = pKF->mpCamera->project(cv::Point3f(x,y,z)); + + // Point must be inside the image + if(!pKF->IsInImage(uv.x,uv.y)) + continue; + + // Depth must be inside the scale invariance region of the point + const float maxDistance = pMP->GetMaxDistanceInvariance(); + const float minDistance = pMP->GetMinDistanceInvariance(); + cv::Mat PO = p3Dw-Ow; + const float dist = cv::norm(PO); + + if(distmaxDistance) + continue; + + // Viewing angle must be less than 60 deg + cv::Mat Pn = pMP->GetNormal(); + + if(PO.dot(Pn)<0.5*dist) + continue; + + int nPredictedLevel = pMP->PredictScale(dist,pKF); + + // Search in a radius + const float radius = th*pKF->mvScaleFactors[nPredictedLevel]; + + const vector vIndices = pKF->GetFeaturesInArea(uv.x,uv.y,radius); + + if(vIndices.empty()) + continue; + + // Match to the most similar keypoint in the radius + const cv::Mat dMP = pMP->GetDescriptor(); + + int bestDist = 256; + int bestIdx = -1; + for(vector::const_iterator vit=vIndices.begin(), vend=vIndices.end(); vit!=vend; vit++) + { + const size_t idx = *vit; + if(vpMatched[idx]) + continue; + + const int &kpLevel= pKF->mvKeysUn[idx].octave; + + if(kpLevelnPredictedLevel) + continue; + + const cv::Mat &dKF = pKF->mDescriptors.row(idx); + + const int dist = DescriptorDistance(dMP,dKF); + + if(dist &vpPoints, const std::vector &vpPointsKFs, + std::vector &vpMatched, std::vector &vpMatchedKF, int th, float ratioHamming) +{ + // Get Calibration Parameters for later projection + const float &fx = pKF->fx; + const float &fy = pKF->fy; + const float &cx = pKF->cx; + const float &cy = pKF->cy; + + // Decompose Scw + cv::Mat sRcw = Scw.rowRange(0,3).colRange(0,3); + const float scw = sqrt(sRcw.row(0).dot(sRcw.row(0))); + cv::Mat Rcw = sRcw/scw; + cv::Mat tcw = Scw.rowRange(0,3).col(3)/scw; + cv::Mat Ow = -Rcw.t()*tcw; + + // Set of MapPoints already found in the KeyFrame + set spAlreadyFound(vpMatched.begin(), vpMatched.end()); + spAlreadyFound.erase(static_cast(NULL)); + + int nmatches=0; + + // For each Candidate MapPoint Project and Match + for(int iMP=0, iendMP=vpPoints.size(); iMPisBad() || spAlreadyFound.count(pMP)) + continue; + + // Get 3D Coords. + cv::Mat p3Dw = pMP->GetWorldPos(); + + // Transform into Camera Coords. + cv::Mat p3Dc = Rcw*p3Dw+tcw; + + // Depth must be positive + if(p3Dc.at(2)<0.0) + continue; + + // Project into Image + const float invz = 1/p3Dc.at(2); + const float x = p3Dc.at(0)*invz; + const float y = p3Dc.at(1)*invz; + + const float u = fx*x+cx; + const float v = fy*y+cy; + + // Point must be inside the image + if(!pKF->IsInImage(u,v)) + continue; + + // Depth must be inside the scale invariance region of the point + const float maxDistance = pMP->GetMaxDistanceInvariance(); + const float minDistance = pMP->GetMinDistanceInvariance(); + cv::Mat PO = p3Dw-Ow; + const float dist = cv::norm(PO); + + if(distmaxDistance) + continue; + + // Viewing angle must be less than 60 deg + cv::Mat Pn = pMP->GetNormal(); + + if(PO.dot(Pn)<0.5*dist) + continue; + + int nPredictedLevel = pMP->PredictScale(dist,pKF); + + // Search in a radius + const float radius = th*pKF->mvScaleFactors[nPredictedLevel]; + + const vector vIndices = pKF->GetFeaturesInArea(u,v,radius); + + if(vIndices.empty()) + continue; + + // Match to the most similar keypoint in the radius + const cv::Mat dMP = pMP->GetDescriptor(); + + int bestDist = 256; + int bestIdx = -1; + for(vector::const_iterator vit=vIndices.begin(), vend=vIndices.end(); vit!=vend; vit++) + { + const size_t idx = *vit; + if(vpMatched[idx]) + continue; + + const int &kpLevel= pKF->mvKeysUn[idx].octave; + + if(kpLevelnPredictedLevel) + continue; + + const cv::Mat &dKF = pKF->mDescriptors.row(idx); + + const int dist = DescriptorDistance(dMP,dKF); + + if(dist &vbPrevMatched, vector &vnMatches12, int windowSize) +{ + int nmatches=0; + vnMatches12 = vector(F1.mvKeysUn.size(),-1); + + vector rotHist[HISTO_LENGTH]; + for(int i=0;i vMatchedDistance(F2.mvKeysUn.size(),INT_MAX); + vector vnMatches21(F2.mvKeysUn.size(),-1); + + for(size_t i1=0, iend1=F1.mvKeysUn.size(); i10) + continue; + + vector vIndices2 = F2.GetFeaturesInArea(vbPrevMatched[i1].x,vbPrevMatched[i1].y, windowSize,level1,level1); + + if(vIndices2.empty()) + continue; + + cv::Mat d1 = F1.mDescriptors.row(i1); + + int bestDist = INT_MAX; + int bestDist2 = INT_MAX; + int bestIdx2 = -1; + + for(vector::iterator vit=vIndices2.begin(); vit!=vIndices2.end(); vit++) + { + size_t i2 = *vit; + + cv::Mat d2 = F2.mDescriptors.row(i2); + + int dist = DescriptorDistance(d1,d2); + + if(vMatchedDistance[i2]<=dist) + continue; + + if(dist=0) + { + vnMatches12[vnMatches21[bestIdx2]]=-1; + nmatches--; + } + vnMatches12[i1]=bestIdx2; + vnMatches21[bestIdx2]=i1; + vMatchedDistance[bestIdx2]=bestDist; + nmatches++; + + if(mbCheckOrientation) + { + float rot = F1.mvKeysUn[i1].angle-F2.mvKeysUn[bestIdx2].angle; + if(rot<0.0) + rot+=360.0f; + int bin = round(rot*factor); + if(bin==HISTO_LENGTH) + bin=0; + assert(bin>=0 && bin=0) + { + vnMatches12[idx1]=-1; + nmatches--; + } + } + } + + } + + //Update prev matched + for(size_t i1=0, iend1=vnMatches12.size(); i1=0) + vbPrevMatched[i1]=F2.mvKeysUn[vnMatches12[i1]].pt; + + return nmatches; +} + +int ORBmatcher::SearchByBoW(KeyFrame *pKF1, KeyFrame *pKF2, vector &vpMatches12) +{ + const vector &vKeysUn1 = pKF1->mvKeysUn; + const DBoW2::FeatureVector &vFeatVec1 = pKF1->mFeatVec; + const vector vpMapPoints1 = pKF1->GetMapPointMatches(); + const cv::Mat &Descriptors1 = pKF1->mDescriptors; + + const vector &vKeysUn2 = pKF2->mvKeysUn; + const DBoW2::FeatureVector &vFeatVec2 = pKF2->mFeatVec; + const vector vpMapPoints2 = pKF2->GetMapPointMatches(); + const cv::Mat &Descriptors2 = pKF2->mDescriptors; + + vpMatches12 = vector(vpMapPoints1.size(),static_cast(NULL)); + vector vbMatched2(vpMapPoints2.size(),false); + + vector rotHist[HISTO_LENGTH]; + for(int i=0;ifirst == f2it->first) + { + for(size_t i1=0, iend1=f1it->second.size(); i1second[i1]; + if(pKF1 -> NLeft != -1 && idx1 >= pKF1 -> mvKeysUn.size()){ + continue; + } + + MapPoint* pMP1 = vpMapPoints1[idx1]; + if(!pMP1) + continue; + if(pMP1->isBad()) + continue; + + const cv::Mat &d1 = Descriptors1.row(idx1); + + int bestDist1=256; + int bestIdx2 =-1 ; + int bestDist2=256; + + for(size_t i2=0, iend2=f2it->second.size(); i2second[i2]; + + if(pKF2 -> NLeft != -1 && idx2 >= pKF2 -> mvKeysUn.size()){ + continue; + } + + MapPoint* pMP2 = vpMapPoints2[idx2]; + + if(vbMatched2[idx2] || !pMP2) + continue; + + if(pMP2->isBad()) + continue; + + const cv::Mat &d2 = Descriptors2.row(idx2); + + int dist = DescriptorDistance(d1,d2); + + if(dist(bestDist1)(bestDist2)) + { + vpMatches12[idx1]=vpMapPoints2[bestIdx2]; + vbMatched2[bestIdx2]=true; + + if(mbCheckOrientation) + { + float rot = vKeysUn1[idx1].angle-vKeysUn2[bestIdx2].angle; + if(rot<0.0) + rot+=360.0f; + int bin = round(rot*factor); + if(bin==HISTO_LENGTH) + bin=0; + assert(bin>=0 && binfirst < f2it->first) + { + f1it = vFeatVec1.lower_bound(f2it->first); + } + else + { + f2it = vFeatVec2.lower_bound(f1it->first); + } + } + + if(mbCheckOrientation) + { + int ind1=-1; + int ind2=-1; + int ind3=-1; + + ComputeThreeMaxima(rotHist,HISTO_LENGTH,ind1,ind2,ind3); + + for(int i=0; i(NULL); + nmatches--; + } + } + } + + return nmatches; +} + +int ORBmatcher::SearchForTriangulation(KeyFrame *pKF1, KeyFrame *pKF2, cv::Mat F12, + vector > &vMatchedPairs, const bool bOnlyStereo, const bool bCoarse) +{ + const DBoW2::FeatureVector &vFeatVec1 = pKF1->mFeatVec; + const DBoW2::FeatureVector &vFeatVec2 = pKF2->mFeatVec; + + //Compute epipole in second image + cv::Mat Cw = pKF1->GetCameraCenter(); + cv::Mat R2w = pKF2->GetRotation(); + cv::Mat t2w = pKF2->GetTranslation(); + cv::Mat C2 = R2w*Cw+t2w; + + cv::Point2f ep = pKF2->mpCamera->project(C2); + + cv::Mat R1w = pKF1->GetRotation(); + cv::Mat t1w = pKF1->GetTranslation(); + + cv::Mat R12; + cv::Mat t12; + + cv::Mat Rll,Rlr,Rrl,Rrr; + cv::Mat tll,tlr,trl,trr; + + GeometricCamera* pCamera1 = pKF1->mpCamera, *pCamera2 = pKF2->mpCamera; + + if(!pKF1->mpCamera2 && !pKF2->mpCamera2){ + R12 = R1w*R2w.t(); + t12 = -R1w*R2w.t()*t2w+t1w; + } + else{ + Rll = pKF1->GetRotation() * pKF2->GetRotation().t(); + Rlr = pKF1->GetRotation() * pKF2->GetRightRotation().t(); + Rrl = pKF1->GetRightRotation() * pKF2->GetRotation().t(); + Rrr = pKF1->GetRightRotation() * pKF2->GetRightRotation().t(); + + tll = pKF1->GetRotation() * (-pKF2->GetRotation().t() * pKF2->GetTranslation()) + pKF1->GetTranslation(); + tlr = pKF1->GetRotation() * (-pKF2->GetRightRotation().t() * pKF2->GetRightTranslation()) + pKF1->GetTranslation(); + trl = pKF1->GetRightRotation() * (-pKF2->GetRotation().t() * pKF2->GetTranslation()) + pKF1->GetRightTranslation(); + trr = pKF1->GetRightRotation() * (-pKF2->GetRightRotation().t() * pKF2->GetRightTranslation()) + pKF1->GetRightTranslation(); + } + + // Find matches between not tracked keypoints + // Matching speed-up by ORB Vocabulary + // Compare only ORB that share the same node + + int nmatches=0; + vector vbMatched2(pKF2->N,false); + vector vMatches12(pKF1->N,-1); + + vector rotHist[HISTO_LENGTH]; + for(int i=0;ifirst == f2it->first) + { + for(size_t i1=0, iend1=f1it->second.size(); i1second[i1]; + + MapPoint* pMP1 = pKF1->GetMapPoint(idx1); + + // If there is already a MapPoint skip + if(pMP1) + { + continue; + } + + const bool bStereo1 = (!pKF1->mpCamera2 && pKF1->mvuRight[idx1]>=0); + + if(bOnlyStereo) + if(!bStereo1) + continue; + + + const cv::KeyPoint &kp1 = (pKF1 -> NLeft == -1) ? pKF1->mvKeysUn[idx1] + : (idx1 < pKF1 -> NLeft) ? pKF1 -> mvKeys[idx1] + : pKF1 -> mvKeysRight[idx1 - pKF1 -> NLeft]; + + const bool bRight1 = (pKF1 -> NLeft == -1 || idx1 < pKF1 -> NLeft) ? false + : true; + //if(bRight1) continue; + const cv::Mat &d1 = pKF1->mDescriptors.row(idx1); + + int bestDist = TH_LOW; + int bestIdx2 = -1; + + for(size_t i2=0, iend2=f2it->second.size(); i2second[i2]; + + MapPoint* pMP2 = pKF2->GetMapPoint(idx2); + + // If we have already matched or there is a MapPoint skip + if(vbMatched2[idx2] || pMP2) + continue; + + const bool bStereo2 = (!pKF2->mpCamera2 && pKF2->mvuRight[idx2]>=0); + + if(bOnlyStereo) + if(!bStereo2) + continue; + + const cv::Mat &d2 = pKF2->mDescriptors.row(idx2); + + const int dist = DescriptorDistance(d1,d2); + + if(dist>TH_LOW || dist>bestDist) + continue; + + const cv::KeyPoint &kp2 = (pKF2 -> NLeft == -1) ? pKF2->mvKeysUn[idx2] + : (idx2 < pKF2 -> NLeft) ? pKF2 -> mvKeys[idx2] + : pKF2 -> mvKeysRight[idx2 - pKF2 -> NLeft]; + const bool bRight2 = (pKF2 -> NLeft == -1 || idx2 < pKF2 -> NLeft) ? false + : true; + + if(!bStereo1 && !bStereo2 && !pKF1->mpCamera2) + { + const float distex = ep.x-kp2.pt.x; + const float distey = ep.y-kp2.pt.y; + if(distex*distex+distey*distey<100*pKF2->mvScaleFactors[kp2.octave]) + { + continue; + } + } + + if(pKF1->mpCamera2 && pKF2->mpCamera2){ + if(bRight1 && bRight2){ + R12 = Rrr; + t12 = trr; + + pCamera1 = pKF1->mpCamera2; + pCamera2 = pKF2->mpCamera2; + } + else if(bRight1 && !bRight2){ + R12 = Rrl; + t12 = trl; + + pCamera1 = pKF1->mpCamera2; + pCamera2 = pKF2->mpCamera; + } + else if(!bRight1 && bRight2){ + R12 = Rlr; + t12 = tlr; + + pCamera1 = pKF1->mpCamera; + pCamera2 = pKF2->mpCamera2; + } + else{ + R12 = Rll; + t12 = tll; + + pCamera1 = pKF1->mpCamera; + pCamera2 = pKF2->mpCamera; + } + + } + + + if(pCamera1->epipolarConstrain(pCamera2,kp1,kp2,R12,t12,pKF1->mvLevelSigma2[kp1.octave],pKF2->mvLevelSigma2[kp2.octave])||bCoarse) // MODIFICATION_2 + { + bestIdx2 = idx2; + bestDist = dist; + } + } + + if(bestIdx2>=0) + { + const cv::KeyPoint &kp2 = (pKF2 -> NLeft == -1) ? pKF2->mvKeysUn[bestIdx2] + : (bestIdx2 < pKF2 -> NLeft) ? pKF2 -> mvKeys[bestIdx2] + : pKF2 -> mvKeysRight[bestIdx2 - pKF2 -> NLeft]; + vMatches12[idx1]=bestIdx2; + nmatches++; + + if(mbCheckOrientation) + { + float rot = kp1.angle-kp2.angle; + if(rot<0.0) + rot+=360.0f; + int bin = round(rot*factor); + if(bin==HISTO_LENGTH) + bin=0; + assert(bin>=0 && binfirst < f2it->first) + { + f1it = vFeatVec1.lower_bound(f2it->first); + } + else + { + f2it = vFeatVec2.lower_bound(f1it->first); + } + } + + if(mbCheckOrientation) + { + int ind1=-1; + int ind2=-1; + int ind3=-1; + + ComputeThreeMaxima(rotHist,HISTO_LENGTH,ind1,ind2,ind3); + + for(int i=0; i > &vMatchedPairs, const bool bOnlyStereo, vector &vMatchedPoints) + { + const DBoW2::FeatureVector &vFeatVec1 = pKF1->mFeatVec; + const DBoW2::FeatureVector &vFeatVec2 = pKF2->mFeatVec; + + //Compute epipole in second image + cv::Mat Cw = pKF1->GetCameraCenter(); + cv::Mat R2w = pKF2->GetRotation(); + cv::Mat t2w = pKF2->GetTranslation(); + cv::Mat C2 = R2w*Cw+t2w; + + cv::Point2f ep = pKF2->mpCamera->project(C2); + + cv::Mat R1w = pKF1->GetRotation(); + cv::Mat t1w = pKF1->GetTranslation(); + + GeometricCamera* pCamera1 = pKF1->mpCamera, *pCamera2 = pKF2->mpCamera; + cv::Mat Tcw1,Tcw2; + + // Find matches between not tracked keypoints + // Matching speed-up by ORB Vocabulary + // Compare only ORB that share the same node + + int nmatches=0; + vector vbMatched2(pKF2->N,false); + vector vMatches12(pKF1->N,-1); + + vector vMatchesPoints12(pKF1 -> N); + + vector rotHist[HISTO_LENGTH]; + for(int i=0;ifirst == f2it->first) + { + for(size_t i1=0, iend1=f1it->second.size(); i1second[i1]; + + MapPoint* pMP1 = pKF1->GetMapPoint(idx1); + + // If there is already a MapPoint skip + if(pMP1) + continue; + + const cv::KeyPoint &kp1 = (pKF1 -> NLeft == -1) ? pKF1->mvKeysUn[idx1] + : (idx1 < pKF1 -> NLeft) ? pKF1 -> mvKeys[idx1] + : pKF1 -> mvKeysRight[idx1 - pKF1 -> NLeft]; + + const bool bRight1 = (pKF1 -> NLeft == -1 || idx1 < pKF1 -> NLeft) ? false + : true; + + + const cv::Mat &d1 = pKF1->mDescriptors.row(idx1); + + int bestDist = TH_LOW; + int bestIdx2 = -1; + + cv::Mat bestPoint; + + for(size_t i2=0, iend2=f2it->second.size(); i2second[i2]; + + MapPoint* pMP2 = pKF2->GetMapPoint(idx2); + + // If we have already matched or there is a MapPoint skip + if(vbMatched2[idx2] || pMP2) + continue; + + const cv::Mat &d2 = pKF2->mDescriptors.row(idx2); + + const int dist = DescriptorDistance(d1,d2); + + if(dist>TH_LOW || dist>bestDist){ + continue; + } + + + const cv::KeyPoint &kp2 = (pKF2 -> NLeft == -1) ? pKF2->mvKeysUn[idx2] + : (idx2 < pKF2 -> NLeft) ? pKF2 -> mvKeys[idx2] + : pKF2 -> mvKeysRight[idx2 - pKF2 -> NLeft]; + const bool bRight2 = (pKF2 -> NLeft == -1 || idx2 < pKF2 -> NLeft) ? false + : true; + + if(bRight1){ + Tcw1 = pKF1->GetRightPose(); + pCamera1 = pKF1->mpCamera2; + } else{ + Tcw1 = pKF1->GetPose(); + pCamera1 = pKF1->mpCamera; + } + + if(bRight2){ + Tcw2 = pKF2->GetRightPose(); + pCamera2 = pKF2->mpCamera2; + } else{ + Tcw2 = pKF2->GetPose(); + pCamera2 = pKF2->mpCamera; + } + + cv::Mat x3D; + if(pCamera1->matchAndtriangulate(kp1,kp2,pCamera2,Tcw1,Tcw2,pKF1->mvLevelSigma2[kp1.octave],pKF2->mvLevelSigma2[kp2.octave],x3D)){ + bestIdx2 = idx2; + bestDist = dist; + bestPoint = x3D; + } + + } + + if(bestIdx2>=0) + { + const cv::KeyPoint &kp2 = (pKF2 -> NLeft == -1) ? pKF2->mvKeysUn[bestIdx2] + : (bestIdx2 < pKF2 -> NLeft) ? pKF2 -> mvKeys[bestIdx2] + : pKF2 -> mvKeysRight[bestIdx2 - pKF2 -> NLeft]; + vMatches12[idx1]=bestIdx2; + vMatchesPoints12[idx1] = bestPoint; + nmatches++; + if(bRight1) right++; + + if(mbCheckOrientation) + { + float rot = kp1.angle-kp2.angle; + if(rot<0.0) + rot+=360.0f; + int bin = round(rot*factor); + if(bin==HISTO_LENGTH) + bin=0; + assert(bin>=0 && binfirst < f2it->first) + { + f1it = vFeatVec1.lower_bound(f2it->first); + } + else + { + f2it = vFeatVec2.lower_bound(f1it->first); + } + } + + if(mbCheckOrientation) + { + int ind1=-1; + int ind2=-1; + int ind3=-1; + + ComputeThreeMaxima(rotHist,HISTO_LENGTH,ind1,ind2,ind3); + + for(int i=0; i &vpMapPoints, const float th, const bool bRight) +{ + cv::Mat Rcw,tcw, Ow; + GeometricCamera* pCamera; + + if(bRight){ + Rcw = pKF->GetRightRotation(); + tcw = pKF->GetRightTranslation(); + Ow = pKF->GetRightCameraCenter(); + + pCamera = pKF->mpCamera2; + } + else{ + Rcw = pKF->GetRotation(); + tcw = pKF->GetTranslation(); + Ow = pKF->GetCameraCenter(); + + pCamera = pKF->mpCamera; + } + + const float &fx = pKF->fx; + const float &fy = pKF->fy; + const float &cx = pKF->cx; + const float &cy = pKF->cy; + const float &bf = pKF->mbf; + + int nFused=0; + + const int nMPs = vpMapPoints.size(); + + // For debbuging + int count_notMP = 0, count_bad=0, count_isinKF = 0, count_negdepth = 0, count_notinim = 0, count_dist = 0, count_normal=0, count_notidx = 0, count_thcheck = 0; + for(int i=0; iisBad() || pMP->IsInKeyFrame(pKF)) + continue;*/ + if(pMP->isBad()) + { + count_bad++; + continue; + } + else if(pMP->IsInKeyFrame(pKF)) + { + count_isinKF++; + continue; + } + + + cv::Mat p3Dw = pMP->GetWorldPos(); + cv::Mat p3Dc = Rcw*p3Dw + tcw; + + // Depth must be positive + if(p3Dc.at(2)<0.0f) + { + count_negdepth++; + continue; + } + + const float invz = 1/p3Dc.at(2); + const float x = p3Dc.at(0); + const float y = p3Dc.at(1); + const float z = p3Dc.at(2); + + const cv::Point2f uv = pCamera->project(cv::Point3f(x,y,z)); + + // Point must be inside the image + if(!pKF->IsInImage(uv.x,uv.y)) + { + count_notinim++; + continue; + } + + const float ur = uv.x-bf*invz; + + const float maxDistance = pMP->GetMaxDistanceInvariance(); + const float minDistance = pMP->GetMinDistanceInvariance(); + cv::Mat PO = p3Dw-Ow; + const float dist3D = cv::norm(PO); + + // Depth must be inside the scale pyramid of the image + if(dist3DmaxDistance) + { + count_dist++; + continue; + } + + // Viewing angle must be less than 60 deg + cv::Mat Pn = pMP->GetNormal(); + + if(PO.dot(Pn)<0.5*dist3D) + { + count_normal++; + continue; + } + + int nPredictedLevel = pMP->PredictScale(dist3D,pKF); + + // Search in a radius + const float radius = th*pKF->mvScaleFactors[nPredictedLevel]; + + const vector vIndices = pKF->GetFeaturesInArea(uv.x,uv.y,radius,bRight); + + if(vIndices.empty()) + { + count_notidx++; + continue; + } + + // Match to the most similar keypoint in the radius + + const cv::Mat dMP = pMP->GetDescriptor(); + + int bestDist = 256; + int bestIdx = -1; + for(vector::const_iterator vit=vIndices.begin(), vend=vIndices.end(); vit!=vend; vit++) + { + size_t idx = *vit; + const cv::KeyPoint &kp = (pKF -> NLeft == -1) ? pKF->mvKeysUn[idx] + : (!bRight) ? pKF -> mvKeys[idx] + : pKF -> mvKeysRight[idx]; + + const int &kpLevel= kp.octave; + + if(kpLevelnPredictedLevel) + continue; + + if(pKF->mvuRight[idx]>=0) + { + // Check reprojection error in stereo + const float &kpx = kp.pt.x; + const float &kpy = kp.pt.y; + const float &kpr = pKF->mvuRight[idx]; + const float ex = uv.x-kpx; + const float ey = uv.y-kpy; + const float er = ur-kpr; + const float e2 = ex*ex+ey*ey+er*er; + + if(e2*pKF->mvInvLevelSigma2[kpLevel]>7.8) + continue; + } + else + { + const float &kpx = kp.pt.x; + const float &kpy = kp.pt.y; + const float ex = uv.x-kpx; + const float ey = uv.y-kpy; + const float e2 = ex*ex+ey*ey; + + if(e2*pKF->mvInvLevelSigma2[kpLevel]>5.99) + continue; + } + + if(bRight) idx += pKF->NLeft; + + const cv::Mat &dKF = pKF->mDescriptors.row(idx); + + const int dist = DescriptorDistance(dMP,dKF); + + if(distGetMapPoint(bestIdx); + if(pMPinKF) + { + if(!pMPinKF->isBad()) + { + if(pMPinKF->Observations()>pMP->Observations()) + pMP->Replace(pMPinKF); + else + pMPinKF->Replace(pMP); + } + } + else + { + pMP->AddObservation(pKF,bestIdx); + pKF->AddMapPoint(pMP,bestIdx); + } + nFused++; + } + else + count_thcheck++; + + } + + /*cout << "count_notMP = " << count_notMP << endl; + cout << "count_bad = " << count_bad << endl; + cout << "count_isinKF = " << count_isinKF << endl; + cout << "count_negdepth = " << count_negdepth << endl; + cout << "count_notinim = " << count_notinim << endl; + cout << "count_dist = " << count_dist << endl; + cout << "count_normal = " << count_normal << endl; + cout << "count_notidx = " << count_notidx << endl; + cout << "count_thcheck = " << count_thcheck << endl; + cout << "tot fused points: " << nFused << endl;*/ + return nFused; +} + +int ORBmatcher::Fuse(KeyFrame *pKF, cv::Mat Scw, const vector &vpPoints, float th, vector &vpReplacePoint) +{ + // Get Calibration Parameters for later projection + const float &fx = pKF->fx; + const float &fy = pKF->fy; + const float &cx = pKF->cx; + const float &cy = pKF->cy; + + // Decompose Scw + cv::Mat sRcw = Scw.rowRange(0,3).colRange(0,3); + const float scw = sqrt(sRcw.row(0).dot(sRcw.row(0))); + cv::Mat Rcw = sRcw/scw; + cv::Mat tcw = Scw.rowRange(0,3).col(3)/scw; + cv::Mat Ow = -Rcw.t()*tcw; + + // Set of MapPoints already found in the KeyFrame + const set spAlreadyFound = pKF->GetMapPoints(); + + int nFused=0; + + const int nPoints = vpPoints.size(); + + // For each candidate MapPoint project and match + for(int iMP=0; iMPisBad() || spAlreadyFound.count(pMP)) + continue; + + // Get 3D Coords. + cv::Mat p3Dw = pMP->GetWorldPos(); + + // Transform into Camera Coords. + cv::Mat p3Dc = Rcw*p3Dw+tcw; + + // Depth must be positive + if(p3Dc.at(2)<0.0f) + continue; + + // Project into Image + const float x = p3Dc.at(0); + const float y = p3Dc.at(1); + const float z = p3Dc.at(2); + + const cv::Point2f uv = pKF->mpCamera->project(cv::Point3f(x,y,z)); + + // Point must be inside the image + if(!pKF->IsInImage(uv.x,uv.y)) + continue; + + // Depth must be inside the scale pyramid of the image + const float maxDistance = pMP->GetMaxDistanceInvariance(); + const float minDistance = pMP->GetMinDistanceInvariance(); + cv::Mat PO = p3Dw-Ow; + const float dist3D = cv::norm(PO); + + if(dist3DmaxDistance) + continue; + + // Viewing angle must be less than 60 deg + cv::Mat Pn = pMP->GetNormal(); + + if(PO.dot(Pn)<0.5*dist3D) + continue; + + // Compute predicted scale level + const int nPredictedLevel = pMP->PredictScale(dist3D,pKF); + + // Search in a radius + const float radius = th*pKF->mvScaleFactors[nPredictedLevel]; + + const vector vIndices = pKF->GetFeaturesInArea(uv.x,uv.y,radius); + + if(vIndices.empty()) + continue; + + // Match to the most similar keypoint in the radius + + const cv::Mat dMP = pMP->GetDescriptor(); + + int bestDist = INT_MAX; + int bestIdx = -1; + for(vector::const_iterator vit=vIndices.begin(); vit!=vIndices.end(); vit++) + { + const size_t idx = *vit; + const int &kpLevel = pKF->mvKeysUn[idx].octave; + + if(kpLevelnPredictedLevel) + continue; + + const cv::Mat &dKF = pKF->mDescriptors.row(idx); + + int dist = DescriptorDistance(dMP,dKF); + + if(distGetMapPoint(bestIdx); + if(pMPinKF) + { + if(!pMPinKF->isBad()) + vpReplacePoint[iMP] = pMPinKF; + } + else + { + pMP->AddObservation(pKF,bestIdx); + pKF->AddMapPoint(pMP,bestIdx); + } + nFused++; + } + } + + return nFused; +} + +int ORBmatcher::SearchBySim3(KeyFrame *pKF1, KeyFrame *pKF2, vector &vpMatches12, + const float &s12, const cv::Mat &R12, const cv::Mat &t12, const float th) +{ + const float &fx = pKF1->fx; + const float &fy = pKF1->fy; + const float &cx = pKF1->cx; + const float &cy = pKF1->cy; + + // Camera 1 from world + cv::Mat R1w = pKF1->GetRotation(); + cv::Mat t1w = pKF1->GetTranslation(); + + //Camera 2 from world + cv::Mat R2w = pKF2->GetRotation(); + cv::Mat t2w = pKF2->GetTranslation(); + + //Transformation between cameras + cv::Mat sR12 = s12*R12; + cv::Mat sR21 = (1.0/s12)*R12.t(); + cv::Mat t21 = -sR21*t12; + + const vector vpMapPoints1 = pKF1->GetMapPointMatches(); + const int N1 = vpMapPoints1.size(); + + const vector vpMapPoints2 = pKF2->GetMapPointMatches(); + const int N2 = vpMapPoints2.size(); + + vector vbAlreadyMatched1(N1,false); + vector vbAlreadyMatched2(N2,false); + + for(int i=0; i(pMP->GetIndexInKeyFrame(pKF2)); + if(idx2>=0 && idx2 vnMatch1(N1,-1); + vector vnMatch2(N2,-1); + + // Transform from KF1 to KF2 and search + for(int i1=0; i1isBad()) + continue; + + cv::Mat p3Dw = pMP->GetWorldPos(); + cv::Mat p3Dc1 = R1w*p3Dw + t1w; + cv::Mat p3Dc2 = sR21*p3Dc1 + t21; + + // Depth must be positive + if(p3Dc2.at(2)<0.0) + continue; + + const float invz = 1.0/p3Dc2.at(2); + const float x = p3Dc2.at(0)*invz; + const float y = p3Dc2.at(1)*invz; + + const float u = fx*x+cx; + const float v = fy*y+cy; + + // Point must be inside the image + if(!pKF2->IsInImage(u,v)) + continue; + + const float maxDistance = pMP->GetMaxDistanceInvariance(); + const float minDistance = pMP->GetMinDistanceInvariance(); + const float dist3D = cv::norm(p3Dc2); + + // Depth must be inside the scale invariance region + if(dist3DmaxDistance ) + continue; + + // Compute predicted octave + const int nPredictedLevel = pMP->PredictScale(dist3D,pKF2); + + // Search in a radius + const float radius = th*pKF2->mvScaleFactors[nPredictedLevel]; + + const vector vIndices = pKF2->GetFeaturesInArea(u,v,radius); + + if(vIndices.empty()) + continue; + + // Match to the most similar keypoint in the radius + const cv::Mat dMP = pMP->GetDescriptor(); + + int bestDist = INT_MAX; + int bestIdx = -1; + for(vector::const_iterator vit=vIndices.begin(), vend=vIndices.end(); vit!=vend; vit++) + { + const size_t idx = *vit; + + const cv::KeyPoint &kp = pKF2->mvKeysUn[idx]; + + if(kp.octavenPredictedLevel) + continue; + + const cv::Mat &dKF = pKF2->mDescriptors.row(idx); + + const int dist = DescriptorDistance(dMP,dKF); + + if(distisBad()) + continue; + + cv::Mat p3Dw = pMP->GetWorldPos(); + cv::Mat p3Dc2 = R2w*p3Dw + t2w; + cv::Mat p3Dc1 = sR12*p3Dc2 + t12; + + // Depth must be positive + if(p3Dc1.at(2)<0.0) + continue; + + const float invz = 1.0/p3Dc1.at(2); + const float x = p3Dc1.at(0)*invz; + const float y = p3Dc1.at(1)*invz; + + const float u = fx*x+cx; + const float v = fy*y+cy; + + // Point must be inside the image + if(!pKF1->IsInImage(u,v)) + continue; + + const float maxDistance = pMP->GetMaxDistanceInvariance(); + const float minDistance = pMP->GetMinDistanceInvariance(); + const float dist3D = cv::norm(p3Dc1); + + // Depth must be inside the scale pyramid of the image + if(dist3DmaxDistance) + continue; + + // Compute predicted octave + const int nPredictedLevel = pMP->PredictScale(dist3D,pKF1); + + // Search in a radius of 2.5*sigma(ScaleLevel) + const float radius = th*pKF1->mvScaleFactors[nPredictedLevel]; + + const vector vIndices = pKF1->GetFeaturesInArea(u,v,radius); + + if(vIndices.empty()) + continue; + + // Match to the most similar keypoint in the radius + const cv::Mat dMP = pMP->GetDescriptor(); + + int bestDist = INT_MAX; + int bestIdx = -1; + for(vector::const_iterator vit=vIndices.begin(), vend=vIndices.end(); vit!=vend; vit++) + { + const size_t idx = *vit; + + const cv::KeyPoint &kp = pKF1->mvKeysUn[idx]; + + if(kp.octavenPredictedLevel) + continue; + + const cv::Mat &dKF = pKF1->mDescriptors.row(idx); + + const int dist = DescriptorDistance(dMP,dKF); + + if(dist=0) + { + int idx1 = vnMatch2[idx2]; + if(idx1==i1) + { + vpMatches12[i1] = vpMapPoints2[idx2]; + nFound++; + } + } + } + + return nFound; +} + + int ORBmatcher::SearchByProjection(Frame &CurrentFrame, const Frame &LastFrame, const float th, const bool bMono) + { + int nmatches = 0; + + // Rotation Histogram (to check rotation consistency) + vector rotHist[HISTO_LENGTH]; + for(int i=0;i(2)>CurrentFrame.mb && !bMono; + const bool bBackward = -tlc.at(2)>CurrentFrame.mb && !bMono; + + for(int i=0; iGetWorldPos(); + cv::Mat x3Dc = Rcw*x3Dw+tcw; + + const float xc = x3Dc.at(0); + const float yc = x3Dc.at(1); + const float invzc = 1.0/x3Dc.at(2); + + if(invzc<0) + continue; + + cv::Point2f uv = CurrentFrame.mpCamera->project(x3Dc); + + if(uv.xCurrentFrame.mnMaxX) + continue; + if(uv.yCurrentFrame.mnMaxY) + continue; + + int nLastOctave = (LastFrame.Nleft == -1 || i < LastFrame.Nleft) ? LastFrame.mvKeys[i].octave + : LastFrame.mvKeysRight[i - LastFrame.Nleft].octave; + + // Search in a window. Size depends on scale + float radius = th*CurrentFrame.mvScaleFactors[nLastOctave]; + + vector vIndices2; + + if(bForward) + vIndices2 = CurrentFrame.GetFeaturesInArea(uv.x,uv.y, radius, nLastOctave); + else if(bBackward) + vIndices2 = CurrentFrame.GetFeaturesInArea(uv.x,uv.y, radius, 0, nLastOctave); + else + vIndices2 = CurrentFrame.GetFeaturesInArea(uv.x,uv.y, radius, nLastOctave-1, nLastOctave+1); + + if(vIndices2.empty()) + continue; + + const cv::Mat dMP = pMP->GetDescriptor(); + + int bestDist = 256; + int bestIdx2 = -1; + + for(vector::const_iterator vit=vIndices2.begin(), vend=vIndices2.end(); vit!=vend; vit++) + { + const size_t i2 = *vit; + + if(CurrentFrame.mvpMapPoints[i2]) + if(CurrentFrame.mvpMapPoints[i2]->Observations()>0) + continue; + + if(CurrentFrame.Nleft == -1 && CurrentFrame.mvuRight[i2]>0) + { + const float ur = uv.x - CurrentFrame.mbf*invzc; + const float er = fabs(ur - CurrentFrame.mvuRight[i2]); + if(er>radius) + continue; + } + + const cv::Mat &d = CurrentFrame.mDescriptors.row(i2); + + const int dist = DescriptorDistance(dMP,d); + + if(dist=0 && binproject(x3Dr); + + int nLastOctave = (LastFrame.Nleft == -1 || i < LastFrame.Nleft) ? LastFrame.mvKeys[i].octave + : LastFrame.mvKeysRight[i - LastFrame.Nleft].octave; + + // Search in a window. Size depends on scale + float radius = th*CurrentFrame.mvScaleFactors[nLastOctave]; + + vector vIndices2; + + if(bForward) + vIndices2 = CurrentFrame.GetFeaturesInArea(uv.x,uv.y, radius, nLastOctave, -1,true); + else if(bBackward) + vIndices2 = CurrentFrame.GetFeaturesInArea(uv.x,uv.y, radius, 0, nLastOctave, true); + else + vIndices2 = CurrentFrame.GetFeaturesInArea(uv.x,uv.y, radius, nLastOctave-1, nLastOctave+1, true); + + const cv::Mat dMP = pMP->GetDescriptor(); + + int bestDist = 256; + int bestIdx2 = -1; + + for(vector::const_iterator vit=vIndices2.begin(), vend=vIndices2.end(); vit!=vend; vit++) + { + const size_t i2 = *vit; + if(CurrentFrame.mvpMapPoints[i2 + CurrentFrame.Nleft]) + if(CurrentFrame.mvpMapPoints[i2 + CurrentFrame.Nleft]->Observations()>0) + continue; + + const cv::Mat &d = CurrentFrame.mDescriptors.row(i2 + CurrentFrame.Nleft); + + const int dist = DescriptorDistance(dMP,d); + + if(dist=0 && bin(NULL); + nmatches--; + } + } + } + } + + return nmatches; + } + +int ORBmatcher::SearchByProjection(Frame &CurrentFrame, KeyFrame *pKF, const set &sAlreadyFound, const float th , const int ORBdist) +{ + int nmatches = 0; + + const cv::Mat Rcw = CurrentFrame.mTcw.rowRange(0,3).colRange(0,3); + const cv::Mat tcw = CurrentFrame.mTcw.rowRange(0,3).col(3); + const cv::Mat Ow = -Rcw.t()*tcw; + + // Rotation Histogram (to check rotation consistency) + vector rotHist[HISTO_LENGTH]; + for(int i=0;i vpMPs = pKF->GetMapPointMatches(); + + for(size_t i=0, iend=vpMPs.size(); iisBad() && !sAlreadyFound.count(pMP)) + { + //Project + cv::Mat x3Dw = pMP->GetWorldPos(); + cv::Mat x3Dc = Rcw*x3Dw+tcw; + + const cv::Point2f uv = CurrentFrame.mpCamera->project(x3Dc); + + if(uv.xCurrentFrame.mnMaxX) + continue; + if(uv.yCurrentFrame.mnMaxY) + continue; + + // Compute predicted scale level + cv::Mat PO = x3Dw-Ow; + float dist3D = cv::norm(PO); + + const float maxDistance = pMP->GetMaxDistanceInvariance(); + const float minDistance = pMP->GetMinDistanceInvariance(); + + // Depth must be inside the scale pyramid of the image + if(dist3DmaxDistance) + continue; + + int nPredictedLevel = pMP->PredictScale(dist3D,&CurrentFrame); + + // Search in a window + const float radius = th*CurrentFrame.mvScaleFactors[nPredictedLevel]; + + const vector vIndices2 = CurrentFrame.GetFeaturesInArea(uv.x, uv.y, radius, nPredictedLevel-1, nPredictedLevel+1); + + if(vIndices2.empty()) + continue; + + const cv::Mat dMP = pMP->GetDescriptor(); + + int bestDist = 256; + int bestIdx2 = -1; + + for(vector::const_iterator vit=vIndices2.begin(); vit!=vIndices2.end(); vit++) + { + const size_t i2 = *vit; + if(CurrentFrame.mvpMapPoints[i2]) + continue; + + const cv::Mat &d = CurrentFrame.mDescriptors.row(i2); + + const int dist = DescriptorDistance(dMP,d); + + if(distmvKeysUn[i].angle-CurrentFrame.mvKeysUn[bestIdx2].angle; + if(rot<0.0) + rot+=360.0f; + int bin = round(rot*factor); + if(bin==HISTO_LENGTH) + bin=0; + assert(bin>=0 && bin* histo, const int L, int &ind1, int &ind2, int &ind3) +{ + int max1=0; + int max2=0; + int max3=0; + + for(int i=0; imax1) + { + max3=max2; + max2=max1; + max1=s; + ind3=ind2; + ind2=ind1; + ind1=i; + } + else if(s>max2) + { + max3=max2; + max2=s; + ind3=ind2; + ind2=i; + } + else if(s>max3) + { + max3=s; + ind3=i; + } + } + + if(max2<0.1f*(float)max1) + { + ind2=-1; + ind3=-1; + } + else if(max3<0.1f*(float)max1) + { + ind3=-1; + } +} + + +// Bit set count operation from +// http://graphics.stanford.edu/~seander/bithacks.html#CountBitsSetParallel +int ORBmatcher::DescriptorDistance(const cv::Mat &a, const cv::Mat &b) +{ + const int *pa = a.ptr(); + const int *pb = b.ptr(); + + int dist=0; + + for(int i=0; i<8; i++, pa++, pb++) + { + unsigned int v = *pa ^ *pb; + v = v - ((v >> 1) & 0x55555555); + v = (v & 0x33333333) + ((v >> 2) & 0x33333333); + dist += (((v + (v >> 4)) & 0xF0F0F0F) * 0x1010101) >> 24; + } + + return dist; +} + +} //namespace ORB_SLAM diff --git a/third_party/ORB_SLAM3/src/OptimizableTypes.cpp b/third_party/ORB_SLAM3/src/OptimizableTypes.cpp new file mode 100644 index 0000000..2d222f1 --- /dev/null +++ b/third_party/ORB_SLAM3/src/OptimizableTypes.cpp @@ -0,0 +1,332 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + +#include "OptimizableTypes.h" + +namespace ORB_SLAM3 { + bool EdgeSE3ProjectXYZOnlyPose::read(std::istream& is){ + for (int i=0; i<2; i++){ + is >> _measurement[i]; + } + for (int i=0; i<2; i++) + for (int j=i; j<2; j++) { + is >> information()(i,j); + if (i!=j) + information()(j,i)=information()(i,j); + } + return true; + } + + bool EdgeSE3ProjectXYZOnlyPose::write(std::ostream& os) const { + + for (int i=0; i<2; i++){ + os << measurement()[i] << " "; + } + + for (int i=0; i<2; i++) + for (int j=i; j<2; j++){ + os << " " << information()(i,j); + } + return os.good(); + } + + + void EdgeSE3ProjectXYZOnlyPose::linearizeOplus() { + g2o::VertexSE3Expmap * vi = static_cast(_vertices[0]); + Eigen::Vector3d xyz_trans = vi->estimate().map(Xw); + + double x = xyz_trans[0]; + double y = xyz_trans[1]; + double z = xyz_trans[2]; + + Eigen::Matrix SE3deriv; + SE3deriv << 0.f, z, -y, 1.f, 0.f, 0.f, + -z , 0.f, x, 0.f, 1.f, 0.f, + y , -x , 0.f, 0.f, 0.f, 1.f; + + _jacobianOplusXi = -pCamera->projectJac(xyz_trans) * SE3deriv; + } + + bool EdgeSE3ProjectXYZOnlyPoseToBody::read(std::istream& is){ + for (int i=0; i<2; i++){ + is >> _measurement[i]; + } + for (int i=0; i<2; i++) + for (int j=i; j<2; j++) { + is >> information()(i,j); + if (i!=j) + information()(j,i)=information()(i,j); + } + return true; + } + + bool EdgeSE3ProjectXYZOnlyPoseToBody::write(std::ostream& os) const { + + for (int i=0; i<2; i++){ + os << measurement()[i] << " "; + } + + for (int i=0; i<2; i++) + for (int j=i; j<2; j++){ + os << " " << information()(i,j); + } + return os.good(); + } + + void EdgeSE3ProjectXYZOnlyPoseToBody::linearizeOplus() { + g2o::VertexSE3Expmap * vi = static_cast(_vertices[0]); + g2o::SE3Quat T_lw(vi->estimate()); + Eigen::Vector3d X_l = T_lw.map(Xw); + Eigen::Vector3d X_r = mTrl.map(T_lw.map(Xw)); + + double x_w = X_l[0]; + double y_w = X_l[1]; + double z_w = X_l[2]; + + Eigen::Matrix SE3deriv; + SE3deriv << 0.f, z_w, -y_w, 1.f, 0.f, 0.f, + -z_w , 0.f, x_w, 0.f, 1.f, 0.f, + y_w , -x_w , 0.f, 0.f, 0.f, 1.f; + + _jacobianOplusXi = -pCamera->projectJac(X_r) * mTrl.rotation().toRotationMatrix() * SE3deriv; + } + + EdgeSE3ProjectXYZ::EdgeSE3ProjectXYZ() : BaseBinaryEdge<2, Eigen::Vector2d, g2o::VertexSBAPointXYZ, g2o::VertexSE3Expmap>() { + } + + bool EdgeSE3ProjectXYZ::read(std::istream& is){ + for (int i=0; i<2; i++){ + is >> _measurement[i]; + } + for (int i=0; i<2; i++) + for (int j=i; j<2; j++) { + is >> information()(i,j); + if (i!=j) + information()(j,i)=information()(i,j); + } + return true; + } + + bool EdgeSE3ProjectXYZ::write(std::ostream& os) const { + + for (int i=0; i<2; i++){ + os << measurement()[i] << " "; + } + + for (int i=0; i<2; i++) + for (int j=i; j<2; j++){ + os << " " << information()(i,j); + } + return os.good(); + } + + + void EdgeSE3ProjectXYZ::linearizeOplus() { + g2o::VertexSE3Expmap * vj = static_cast(_vertices[1]); + g2o::SE3Quat T(vj->estimate()); + g2o::VertexSBAPointXYZ* vi = static_cast(_vertices[0]); + Eigen::Vector3d xyz = vi->estimate(); + Eigen::Vector3d xyz_trans = T.map(xyz); + + double x = xyz_trans[0]; + double y = xyz_trans[1]; + double z = xyz_trans[2]; + + auto projectJac = -pCamera->projectJac(xyz_trans); + + _jacobianOplusXi = projectJac * T.rotation().toRotationMatrix(); + + Eigen::Matrix SE3deriv; + SE3deriv << 0.f, z, -y, 1.f, 0.f, 0.f, + -z , 0.f, x, 0.f, 1.f, 0.f, + y , -x , 0.f, 0.f, 0.f, 1.f; + + _jacobianOplusXj = projectJac * SE3deriv; + } + + EdgeSE3ProjectXYZToBody::EdgeSE3ProjectXYZToBody() : BaseBinaryEdge<2, Eigen::Vector2d, g2o::VertexSBAPointXYZ, g2o::VertexSE3Expmap>() { + } + + bool EdgeSE3ProjectXYZToBody::read(std::istream& is){ + for (int i=0; i<2; i++){ + is >> _measurement[i]; + } + for (int i=0; i<2; i++) + for (int j=i; j<2; j++) { + is >> information()(i,j); + if (i!=j) + information()(j,i)=information()(i,j); + } + return true; + } + + bool EdgeSE3ProjectXYZToBody::write(std::ostream& os) const { + + for (int i=0; i<2; i++){ + os << measurement()[i] << " "; + } + + for (int i=0; i<2; i++) + for (int j=i; j<2; j++){ + os << " " << information()(i,j); + } + return os.good(); + } + + + void EdgeSE3ProjectXYZToBody::linearizeOplus() { + g2o::VertexSE3Expmap * vj = static_cast(_vertices[1]); + g2o::SE3Quat T_lw(vj->estimate()); + g2o::SE3Quat T_rw = mTrl * T_lw; + g2o::VertexSBAPointXYZ* vi = static_cast(_vertices[0]); + Eigen::Vector3d X_w = vi->estimate(); + Eigen::Vector3d X_l = T_lw.map(X_w); + Eigen::Vector3d X_r = mTrl.map(T_lw.map(X_w)); + + _jacobianOplusXi = -pCamera->projectJac(X_r) * T_rw.rotation().toRotationMatrix(); + + double x = X_l[0]; + double y = X_l[1]; + double z = X_l[2]; + + Eigen::Matrix SE3deriv; + SE3deriv << 0.f, z, -y, 1.f, 0.f, 0.f, + -z , 0.f, x, 0.f, 1.f, 0.f, + y , -x , 0.f, 0.f, 0.f, 1.f; + + _jacobianOplusXj = -pCamera->projectJac(X_r) * mTrl.rotation().toRotationMatrix() * SE3deriv; + } + + + VertexSim3Expmap::VertexSim3Expmap() : BaseVertex<7, g2o::Sim3>() + { + _marginalized=false; + _fix_scale = false; + } + + bool VertexSim3Expmap::read(std::istream& is) + { + g2o::Vector7d cam2world; + for (int i=0; i<6; i++){ + is >> cam2world[i]; + } + is >> cam2world[6]; + + float nextParam; + for(size_t i = 0; i < pCamera1->size(); i++){ + is >> nextParam; + pCamera1->setParameter(nextParam,i); + } + + for(size_t i = 0; i < pCamera2->size(); i++){ + is >> nextParam; + pCamera2->setParameter(nextParam,i); + } + + setEstimate(g2o::Sim3(cam2world).inverse()); + return true; + } + + bool VertexSim3Expmap::write(std::ostream& os) const + { + g2o::Sim3 cam2world(estimate().inverse()); + g2o::Vector7d lv=cam2world.log(); + for (int i=0; i<7; i++){ + os << lv[i] << " "; + } + + for(size_t i = 0; i < pCamera1->size(); i++){ + os << pCamera1->getParameter(i) << " "; + } + + for(size_t i = 0; i < pCamera2->size(); i++){ + os << pCamera2->getParameter(i) << " "; + } + + return os.good(); + } + + EdgeSim3ProjectXYZ::EdgeSim3ProjectXYZ() : + g2o::BaseBinaryEdge<2, Eigen::Vector2d, g2o::VertexSBAPointXYZ, VertexSim3Expmap>() + { + } + + bool EdgeSim3ProjectXYZ::read(std::istream& is) + { + for (int i=0; i<2; i++) + { + is >> _measurement[i]; + } + + for (int i=0; i<2; i++) + for (int j=i; j<2; j++) { + is >> information()(i,j); + if (i!=j) + information()(j,i)=information()(i,j); + } + return true; + } + + bool EdgeSim3ProjectXYZ::write(std::ostream& os) const + { + for (int i=0; i<2; i++){ + os << _measurement[i] << " "; + } + + for (int i=0; i<2; i++) + for (int j=i; j<2; j++){ + os << " " << information()(i,j); + } + return os.good(); + } + + EdgeInverseSim3ProjectXYZ::EdgeInverseSim3ProjectXYZ() : + g2o::BaseBinaryEdge<2, Eigen::Vector2d, g2o::VertexSBAPointXYZ, VertexSim3Expmap>() + { + } + + bool EdgeInverseSim3ProjectXYZ::read(std::istream& is) + { + for (int i=0; i<2; i++) + { + is >> _measurement[i]; + } + + for (int i=0; i<2; i++) + for (int j=i; j<2; j++) { + is >> information()(i,j); + if (i!=j) + information()(j,i)=information()(i,j); + } + return true; + } + + bool EdgeInverseSim3ProjectXYZ::write(std::ostream& os) const + { + for (int i=0; i<2; i++){ + os << _measurement[i] << " "; + } + + for (int i=0; i<2; i++) + for (int j=i; j<2; j++){ + os << " " << information()(i,j); + } + return os.good(); + } + +} diff --git a/third_party/ORB_SLAM3/src/Optimizer.cc b/third_party/ORB_SLAM3/src/Optimizer.cc new file mode 100644 index 0000000..e4e3572 --- /dev/null +++ b/third_party/ORB_SLAM3/src/Optimizer.cc @@ -0,0 +1,8463 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + + +#include "Optimizer.h" + + +#include + +#include +#include +#include +#include + +#include "Thirdparty/g2o/g2o/core/sparse_block_matrix.h" +#include "Thirdparty/g2o/g2o/core/block_solver.h" +#include "Thirdparty/g2o/g2o/core/optimization_algorithm_levenberg.h" +#include "Thirdparty/g2o/g2o/core/optimization_algorithm_gauss_newton.h" +#include "Thirdparty/g2o/g2o/solvers/linear_solver_eigen.h" +#include "Thirdparty/g2o/g2o/types/types_six_dof_expmap.h" +#include "Thirdparty/g2o/g2o/core/robust_kernel_impl.h" +#include "Thirdparty/g2o/g2o/solvers/linear_solver_dense.h" +#include "G2oTypes.h" +#include "Converter.h" + +#include +#include + +#include + +#include "OptimizableTypes.h" + + +namespace ORB_SLAM3 +{ + +bool sortByVal(const pair &a, const pair &b) +{ + return (a.second < b.second); +} + +void Optimizer::GlobalBundleAdjustemnt(Map* pMap, int nIterations, bool* pbStopFlag, const unsigned long nLoopKF, const bool bRobust) +{ + vector vpKFs = pMap->GetAllKeyFrames(); + vector vpMP = pMap->GetAllMapPoints(); + BundleAdjustment(vpKFs,vpMP,nIterations,pbStopFlag, nLoopKF, bRobust); +} + + +void Optimizer::BundleAdjustment(const vector &vpKFs, const vector &vpMP, + int nIterations, bool* pbStopFlag, const unsigned long nLoopKF, const bool bRobust) +{ + vector vbNotIncludedMP; + vbNotIncludedMP.resize(vpMP.size()); + + Map* pMap = vpKFs[0]->GetMap(); + + g2o::SparseOptimizer optimizer; + g2o::BlockSolver_6_3::LinearSolverType * linearSolver; + + linearSolver = new g2o::LinearSolverEigen(); + + g2o::BlockSolver_6_3 * solver_ptr = new g2o::BlockSolver_6_3(linearSolver); + + g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg(solver_ptr); + optimizer.setAlgorithm(solver); + optimizer.setVerbose(false); + + if(pbStopFlag) + optimizer.setForceStopFlag(pbStopFlag); + + long unsigned int maxKFid = 0; + + const int nExpectedSize = (vpKFs.size())*vpMP.size(); + + vector vpEdgesMono; + vpEdgesMono.reserve(nExpectedSize); + + vector vpEdgesBody; + vpEdgesBody.reserve(nExpectedSize); + + vector vpEdgeKFMono; + vpEdgeKFMono.reserve(nExpectedSize); + + vector vpEdgeKFBody; + vpEdgeKFBody.reserve(nExpectedSize); + + vector vpMapPointEdgeMono; + vpMapPointEdgeMono.reserve(nExpectedSize); + + vector vpMapPointEdgeBody; + vpMapPointEdgeBody.reserve(nExpectedSize); + + vector vpEdgesStereo; + vpEdgesStereo.reserve(nExpectedSize); + + vector vpEdgeKFStereo; + vpEdgeKFStereo.reserve(nExpectedSize); + + vector vpMapPointEdgeStereo; + vpMapPointEdgeStereo.reserve(nExpectedSize); + + + // Set KeyFrame vertices + + for(size_t i=0; iisBad()) + continue; + g2o::VertexSE3Expmap * vSE3 = new g2o::VertexSE3Expmap(); + vSE3->setEstimate(Converter::toSE3Quat(pKF->GetPose())); + vSE3->setId(pKF->mnId); + vSE3->setFixed(pKF->mnId==pMap->GetInitKFid()); + optimizer.addVertex(vSE3); + if(pKF->mnId>maxKFid) + maxKFid=pKF->mnId; + //cout << "KF id: " << pKF->mnId << endl; + } + + const float thHuber2D = sqrt(5.99); + const float thHuber3D = sqrt(7.815); + + // Set MapPoint vertices + //cout << "start inserting MPs" << endl; + + for(size_t i=0; iisBad()) + continue; + g2o::VertexSBAPointXYZ* vPoint = new g2o::VertexSBAPointXYZ(); + vPoint->setEstimate(Converter::toVector3d(pMP->GetWorldPos())); + const int id = pMP->mnId+maxKFid+1; + vPoint->setId(id); + vPoint->setMarginalized(true); + optimizer.addVertex(vPoint); + + const map> observations = pMP->GetObservations(); + + int nEdges = 0; + //SET EDGES + for(map>::const_iterator mit=observations.begin(); mit!=observations.end(); mit++) + { + KeyFrame* pKF = mit->first; + if(pKF->isBad() || pKF->mnId>maxKFid) + continue; + if(optimizer.vertex(id) == NULL || optimizer.vertex(pKF->mnId) == NULL) + continue; + nEdges++; + + const int leftIndex = get<0>(mit->second); + + if(leftIndex != -1 && pKF->mvuRight[get<0>(mit->second)]<0) + { + const cv::KeyPoint &kpUn = pKF->mvKeysUn[leftIndex]; + + Eigen::Matrix obs; + obs << kpUn.pt.x, kpUn.pt.y; + + ORB_SLAM3::EdgeSE3ProjectXYZ* e = new ORB_SLAM3::EdgeSE3ProjectXYZ(); + + e->setVertex(0, dynamic_cast(optimizer.vertex(id))); + e->setVertex(1, dynamic_cast(optimizer.vertex(pKF->mnId))); + e->setMeasurement(obs); + const float &invSigma2 = pKF->mvInvLevelSigma2[kpUn.octave]; + e->setInformation(Eigen::Matrix2d::Identity()*invSigma2); + + if(bRobust) + { + g2o::RobustKernelHuber* rk = new g2o::RobustKernelHuber; + e->setRobustKernel(rk); + rk->setDelta(thHuber2D); + } + + e->pCamera = pKF->mpCamera; + + optimizer.addEdge(e); + + vpEdgesMono.push_back(e); + vpEdgeKFMono.push_back(pKF); + vpMapPointEdgeMono.push_back(pMP); + } + else if(leftIndex != -1 && pKF->mvuRight[leftIndex] >= 0) //Stereo observation + { + const cv::KeyPoint &kpUn = pKF->mvKeysUn[leftIndex]; + + Eigen::Matrix obs; + const float kp_ur = pKF->mvuRight[get<0>(mit->second)]; + obs << kpUn.pt.x, kpUn.pt.y, kp_ur; + + g2o::EdgeStereoSE3ProjectXYZ* e = new g2o::EdgeStereoSE3ProjectXYZ(); + + e->setVertex(0, dynamic_cast(optimizer.vertex(id))); + e->setVertex(1, dynamic_cast(optimizer.vertex(pKF->mnId))); + e->setMeasurement(obs); + const float &invSigma2 = pKF->mvInvLevelSigma2[kpUn.octave]; + Eigen::Matrix3d Info = Eigen::Matrix3d::Identity()*invSigma2; + e->setInformation(Info); + + if(bRobust) + { + g2o::RobustKernelHuber* rk = new g2o::RobustKernelHuber; + e->setRobustKernel(rk); + rk->setDelta(thHuber3D); + } + + e->fx = pKF->fx; + e->fy = pKF->fy; + e->cx = pKF->cx; + e->cy = pKF->cy; + e->bf = pKF->mbf; + + optimizer.addEdge(e); + + vpEdgesStereo.push_back(e); + vpEdgeKFStereo.push_back(pKF); + vpMapPointEdgeStereo.push_back(pMP); + } + + if(pKF->mpCamera2){ + int rightIndex = get<1>(mit->second); + + if(rightIndex != -1 && rightIndex < pKF->mvKeysRight.size()){ + rightIndex -= pKF->NLeft; + + Eigen::Matrix obs; + cv::KeyPoint kp = pKF->mvKeysRight[rightIndex]; + obs << kp.pt.x, kp.pt.y; + + ORB_SLAM3::EdgeSE3ProjectXYZToBody *e = new ORB_SLAM3::EdgeSE3ProjectXYZToBody(); + + e->setVertex(0, dynamic_cast(optimizer.vertex(id))); + e->setVertex(1, dynamic_cast(optimizer.vertex(pKF->mnId))); + e->setMeasurement(obs); + const float &invSigma2 = pKF->mvInvLevelSigma2[kp.octave]; + e->setInformation(Eigen::Matrix2d::Identity()*invSigma2); + + g2o::RobustKernelHuber* rk = new g2o::RobustKernelHuber; + e->setRobustKernel(rk); + rk->setDelta(thHuber2D); + + e->mTrl = Converter::toSE3Quat(pKF->mTrl); + + e->pCamera = pKF->mpCamera2; + + optimizer.addEdge(e); + vpEdgesBody.push_back(e); + vpEdgeKFBody.push_back(pKF); + vpMapPointEdgeBody.push_back(pMP); + } + } + } + + + + if(nEdges==0) + { + optimizer.removeVertex(vPoint); + vbNotIncludedMP[i]=true; + } + else + { + vbNotIncludedMP[i]=false; + } + } + + //cout << "end inserting MPs" << endl; + // Optimize! + optimizer.setVerbose(false); + optimizer.initializeOptimization(); + optimizer.optimize(nIterations); + Verbose::PrintMess("BA: End of the optimization", Verbose::VERBOSITY_NORMAL); + + // Recover optimized data + + //Keyframes + for(size_t i=0; iisBad()) + continue; + g2o::VertexSE3Expmap* vSE3 = static_cast(optimizer.vertex(pKF->mnId)); + + g2o::SE3Quat SE3quat = vSE3->estimate(); + if(nLoopKF==pMap->GetOriginKF()->mnId) + { + pKF->SetPose(Converter::toCvMat(SE3quat)); + } + else + { + /*if(!vSE3->fixed()) + { + //cout << "KF " << pKF->mnId << ": " << endl; + pKF->mHessianPose = cv::Mat(6, 6, CV_64F); + pKF->mbHasHessian = true; + for(int r=0; r<6; ++r) + { + for(int c=0; c<6; ++c) + { + //cout << vSE3->hessian(r, c) << ", "; + pKF->mHessianPose.at(r, c) = vSE3->hessian(r, c); + } + //cout << endl; + } + }*/ + + + pKF->mTcwGBA.create(4,4,CV_32F); + Converter::toCvMat(SE3quat).copyTo(pKF->mTcwGBA); + pKF->mnBAGlobalForKF = nLoopKF; + + cv::Mat mTwc = pKF->GetPoseInverse(); + cv::Mat mTcGBA_c = pKF->mTcwGBA * mTwc; + cv::Vec3d vector_dist = mTcGBA_c.rowRange(0, 3).col(3); + double dist = cv::norm(vector_dist); + if(dist > 1) + { + int numMonoBadPoints = 0, numMonoOptPoints = 0; + int numStereoBadPoints = 0, numStereoOptPoints = 0; + vector vpMonoMPsOpt, vpStereoMPsOpt; + + for(size_t i=0, iend=vpEdgesMono.size(); iisBad()) + continue; + + if(e->chi2()>5.991 || !e->isDepthPositive()) + { + numMonoBadPoints++; + + } + else + { + numMonoOptPoints++; + vpMonoMPsOpt.push_back(pMP); + } + + } + + for(size_t i=0, iend=vpEdgesStereo.size(); iisBad()) + continue; + + if(e->chi2()>7.815 || !e->isDepthPositive()) + { + numStereoBadPoints++; + } + else + { + numStereoOptPoints++; + vpStereoMPsOpt.push_back(pMP); + } + } + Verbose::PrintMess("GBA: KF " + to_string(pKF->mnId) + " had been moved " + to_string(dist) + " meters", Verbose::VERBOSITY_DEBUG); + Verbose::PrintMess("--Number of observations: " + to_string(numMonoOptPoints) + " in mono and " + to_string(numStereoOptPoints) + " in stereo", Verbose::VERBOSITY_DEBUG); + Verbose::PrintMess("--Number of discarded observations: " + to_string(numMonoBadPoints) + " in mono and " + to_string(numStereoBadPoints) + " in stereo", Verbose::VERBOSITY_DEBUG); + } + } + } + Verbose::PrintMess("BA: KFs updated", Verbose::VERBOSITY_DEBUG); + + //Points + for(size_t i=0; iisBad()) + continue; + g2o::VertexSBAPointXYZ* vPoint = static_cast(optimizer.vertex(pMP->mnId+maxKFid+1)); + + if(nLoopKF==pMap->GetOriginKF()->mnId) + { + pMP->SetWorldPos(Converter::toCvMat(vPoint->estimate())); + pMP->UpdateNormalAndDepth(); + } + else + { + pMP->mPosGBA.create(3,1,CV_32F); + Converter::toCvMat(vPoint->estimate()).copyTo(pMP->mPosGBA); + pMP->mnBAGlobalForKF = nLoopKF; + } + } +} + +void Optimizer::FullInertialBA(Map *pMap, int its, const bool bFixLocal, const long unsigned int nLoopId, bool *pbStopFlag, bool bInit, float priorG, float priorA, Eigen::VectorXd *vSingVal, bool *bHess) +{ + long unsigned int maxKFid = pMap->GetMaxKFid(); + const vector vpKFs = pMap->GetAllKeyFrames(); + const vector vpMPs = pMap->GetAllMapPoints(); + + // Setup optimizer + g2o::SparseOptimizer optimizer; + g2o::BlockSolverX::LinearSolverType * linearSolver; + + linearSolver = new g2o::LinearSolverEigen(); + + g2o::BlockSolverX * solver_ptr = new g2o::BlockSolverX(linearSolver); + + g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg(solver_ptr); + solver->setUserLambdaInit(1e-5); + optimizer.setAlgorithm(solver); + optimizer.setVerbose(false); + + if(pbStopFlag) + optimizer.setForceStopFlag(pbStopFlag); + + int nNonFixed = 0; + + // Set KeyFrame vertices + KeyFrame* pIncKF; + for(size_t i=0; imnId>maxKFid) + continue; + VertexPose * VP = new VertexPose(pKFi); + VP->setId(pKFi->mnId); + pIncKF=pKFi; + bool bFixed = false; + if(bFixLocal) + { + bFixed = (pKFi->mnBALocalForKF>=(maxKFid-1)) || (pKFi->mnBAFixedForKF>=(maxKFid-1)); + if(!bFixed) + nNonFixed++; + VP->setFixed(bFixed); + } + optimizer.addVertex(VP); + + if(pKFi->bImu) + { + VertexVelocity* VV = new VertexVelocity(pKFi); + VV->setId(maxKFid+3*(pKFi->mnId)+1); + VV->setFixed(bFixed); + optimizer.addVertex(VV); + if (!bInit) + { + VertexGyroBias* VG = new VertexGyroBias(pKFi); + VG->setId(maxKFid+3*(pKFi->mnId)+2); + VG->setFixed(bFixed); + optimizer.addVertex(VG); + VertexAccBias* VA = new VertexAccBias(pKFi); + VA->setId(maxKFid+3*(pKFi->mnId)+3); + VA->setFixed(bFixed); + optimizer.addVertex(VA); + } + } + } + + if (bInit) + { + VertexGyroBias* VG = new VertexGyroBias(pIncKF); + VG->setId(4*maxKFid+2); + VG->setFixed(false); + optimizer.addVertex(VG); + VertexAccBias* VA = new VertexAccBias(pIncKF); + VA->setId(4*maxKFid+3); + VA->setFixed(false); + optimizer.addVertex(VA); + } + + if(bFixLocal) + { + if(nNonFixed<3) + return; + } + + // IMU links + for(size_t i=0;imPrevKF) + { + Verbose::PrintMess("NOT INERTIAL LINK TO PREVIOUS FRAME!", Verbose::VERBOSITY_NORMAL); + continue; + } + + if(pKFi->mPrevKF && pKFi->mnId<=maxKFid) + { + if(pKFi->isBad() || pKFi->mPrevKF->mnId>maxKFid) + continue; + if(pKFi->bImu && pKFi->mPrevKF->bImu) + { + pKFi->mpImuPreintegrated->SetNewBias(pKFi->mPrevKF->GetImuBias()); + g2o::HyperGraph::Vertex* VP1 = optimizer.vertex(pKFi->mPrevKF->mnId); + g2o::HyperGraph::Vertex* VV1 = optimizer.vertex(maxKFid+3*(pKFi->mPrevKF->mnId)+1); + + g2o::HyperGraph::Vertex* VG1; + g2o::HyperGraph::Vertex* VA1; + g2o::HyperGraph::Vertex* VG2; + g2o::HyperGraph::Vertex* VA2; + if (!bInit) + { + VG1 = optimizer.vertex(maxKFid+3*(pKFi->mPrevKF->mnId)+2); + VA1 = optimizer.vertex(maxKFid+3*(pKFi->mPrevKF->mnId)+3); + VG2 = optimizer.vertex(maxKFid+3*(pKFi->mnId)+2); + VA2 = optimizer.vertex(maxKFid+3*(pKFi->mnId)+3); + } + else + { + VG1 = optimizer.vertex(4*maxKFid+2); + VA1 = optimizer.vertex(4*maxKFid+3); + } + + g2o::HyperGraph::Vertex* VP2 = optimizer.vertex(pKFi->mnId); + g2o::HyperGraph::Vertex* VV2 = optimizer.vertex(maxKFid+3*(pKFi->mnId)+1); + + if (!bInit) + { + if(!VP1 || !VV1 || !VG1 || !VA1 || !VP2 || !VV2 || !VG2 || !VA2) + { + cout << "Error" << VP1 << ", "<< VV1 << ", "<< VG1 << ", "<< VA1 << ", " << VP2 << ", " << VV2 << ", "<< VG2 << ", "<< VA2 <mpImuPreintegrated); + ei->setVertex(0,dynamic_cast(VP1)); + ei->setVertex(1,dynamic_cast(VV1)); + ei->setVertex(2,dynamic_cast(VG1)); + ei->setVertex(3,dynamic_cast(VA1)); + ei->setVertex(4,dynamic_cast(VP2)); + ei->setVertex(5,dynamic_cast(VV2)); + + g2o::RobustKernelHuber* rki = new g2o::RobustKernelHuber; + ei->setRobustKernel(rki); + rki->setDelta(sqrt(16.92)); + + optimizer.addEdge(ei); + + if (!bInit) + { + EdgeGyroRW* egr= new EdgeGyroRW(); + egr->setVertex(0,VG1); + egr->setVertex(1,VG2); + cv::Mat cvInfoG = pKFi->mpImuPreintegrated->C.rowRange(9,12).colRange(9,12).inv(cv::DECOMP_SVD); + Eigen::Matrix3d InfoG; + for(int r=0;r<3;r++) + for(int c=0;c<3;c++) + InfoG(r,c)=cvInfoG.at(r,c); + egr->setInformation(InfoG); + egr->computeError(); + optimizer.addEdge(egr); + + EdgeAccRW* ear = new EdgeAccRW(); + ear->setVertex(0,VA1); + ear->setVertex(1,VA2); + cv::Mat cvInfoA = pKFi->mpImuPreintegrated->C.rowRange(12,15).colRange(12,15).inv(cv::DECOMP_SVD); + Eigen::Matrix3d InfoA; + for(int r=0;r<3;r++) + for(int c=0;c<3;c++) + InfoA(r,c)=cvInfoA.at(r,c); + ear->setInformation(InfoA); + ear->computeError(); + optimizer.addEdge(ear); + } + } + else + { + cout << pKFi->mnId << " or " << pKFi->mPrevKF->mnId << " no imu" << endl; + } + } + } + + if (bInit) + { + g2o::HyperGraph::Vertex* VG = optimizer.vertex(4*maxKFid+2); + g2o::HyperGraph::Vertex* VA = optimizer.vertex(4*maxKFid+3); + + // Add prior to comon biases + EdgePriorAcc* epa = new EdgePriorAcc(cv::Mat::zeros(3,1,CV_32F)); + epa->setVertex(0,dynamic_cast(VA)); + double infoPriorA = priorA; // + epa->setInformation(infoPriorA*Eigen::Matrix3d::Identity()); + optimizer.addEdge(epa); + + EdgePriorGyro* epg = new EdgePriorGyro(cv::Mat::zeros(3,1,CV_32F)); + epg->setVertex(0,dynamic_cast(VG)); + double infoPriorG = priorG; // + epg->setInformation(infoPriorG*Eigen::Matrix3d::Identity()); + optimizer.addEdge(epg); + } + + const float thHuberMono = sqrt(5.991); + const float thHuberStereo = sqrt(7.815); + + const unsigned long iniMPid = maxKFid*5; + + vector vbNotIncludedMP(vpMPs.size(),false); + + for(size_t i=0; isetEstimate(Converter::toVector3d(pMP->GetWorldPos())); + unsigned long id = pMP->mnId+iniMPid+1; + vPoint->setId(id); + vPoint->setMarginalized(true); + optimizer.addVertex(vPoint); + + const map> observations = pMP->GetObservations(); + + + bool bAllFixed = true; + + //Set edges + for(map>::const_iterator mit=observations.begin(), mend=observations.end(); mit!=mend; mit++) + { + KeyFrame* pKFi = mit->first; + + if(pKFi->mnId>maxKFid) + continue; + + if(!pKFi->isBad()) + { + const int leftIndex = get<0>(mit->second); + cv::KeyPoint kpUn; + + if(leftIndex != -1 && pKFi->mvuRight[get<0>(mit->second)]<0) // Monocular observation + { + kpUn = pKFi->mvKeysUn[leftIndex]; + Eigen::Matrix obs; + obs << kpUn.pt.x, kpUn.pt.y; + + EdgeMono* e = new EdgeMono(0); + + g2o::OptimizableGraph::Vertex* VP = dynamic_cast(optimizer.vertex(pKFi->mnId)); + if(bAllFixed) + if(!VP->fixed()) + bAllFixed=false; + + e->setVertex(0, dynamic_cast(optimizer.vertex(id))); + e->setVertex(1, VP); + e->setMeasurement(obs); + const float invSigma2 = pKFi->mvInvLevelSigma2[kpUn.octave]; + + e->setInformation(Eigen::Matrix2d::Identity()*invSigma2); + + g2o::RobustKernelHuber* rk = new g2o::RobustKernelHuber; + e->setRobustKernel(rk); + rk->setDelta(thHuberMono); + + optimizer.addEdge(e); + } + else if(leftIndex != -1 && pKFi->mvuRight[leftIndex] >= 0) // stereo observation + { + kpUn = pKFi->mvKeysUn[leftIndex]; + const float kp_ur = pKFi->mvuRight[leftIndex]; + Eigen::Matrix obs; + obs << kpUn.pt.x, kpUn.pt.y, kp_ur; + + EdgeStereo* e = new EdgeStereo(0); + + g2o::OptimizableGraph::Vertex* VP = dynamic_cast(optimizer.vertex(pKFi->mnId)); + if(bAllFixed) + if(!VP->fixed()) + bAllFixed=false; + + e->setVertex(0, dynamic_cast(optimizer.vertex(id))); + e->setVertex(1, VP); + e->setMeasurement(obs); + const float invSigma2 = pKFi->mvInvLevelSigma2[kpUn.octave]; + + e->setInformation(Eigen::Matrix3d::Identity()*invSigma2); + + g2o::RobustKernelHuber* rk = new g2o::RobustKernelHuber; + e->setRobustKernel(rk); + rk->setDelta(thHuberStereo); + + optimizer.addEdge(e); + } + + if(pKFi->mpCamera2){ // Monocular right observation + int rightIndex = get<1>(mit->second); + + if(rightIndex != -1 && rightIndex < pKFi->mvKeysRight.size()){ + rightIndex -= pKFi->NLeft; + + Eigen::Matrix obs; + kpUn = pKFi->mvKeysRight[rightIndex]; + obs << kpUn.pt.x, kpUn.pt.y; + + EdgeMono *e = new EdgeMono(1); + + g2o::OptimizableGraph::Vertex* VP = dynamic_cast(optimizer.vertex(pKFi->mnId)); + if(bAllFixed) + if(!VP->fixed()) + bAllFixed=false; + + e->setVertex(0, dynamic_cast(optimizer.vertex(id))); + e->setVertex(1, VP); + e->setMeasurement(obs); + const float invSigma2 = pKFi->mvInvLevelSigma2[kpUn.octave]; + e->setInformation(Eigen::Matrix2d::Identity()*invSigma2); + + g2o::RobustKernelHuber* rk = new g2o::RobustKernelHuber; + e->setRobustKernel(rk); + rk->setDelta(thHuberMono); + + optimizer.addEdge(e); + } + } + } + } + + if(bAllFixed) + { + optimizer.removeVertex(vPoint); + vbNotIncludedMP[i]=true; + } + } + + if(pbStopFlag) + if(*pbStopFlag) + return; + + + optimizer.initializeOptimization(); + optimizer.optimize(its); + + + // Recover optimized data + //Keyframes + for(size_t i=0; imnId>maxKFid) + continue; + VertexPose* VP = static_cast(optimizer.vertex(pKFi->mnId)); + if(nLoopId==0) + { + cv::Mat Tcw = Converter::toCvSE3(VP->estimate().Rcw[0], VP->estimate().tcw[0]); + pKFi->SetPose(Tcw); + } + else + { + pKFi->mTcwGBA = cv::Mat::eye(4,4,CV_32F); + Converter::toCvMat(VP->estimate().Rcw[0]).copyTo(pKFi->mTcwGBA.rowRange(0,3).colRange(0,3)); + Converter::toCvMat(VP->estimate().tcw[0]).copyTo(pKFi->mTcwGBA.rowRange(0,3).col(3)); + pKFi->mnBAGlobalForKF = nLoopId; + + } + if(pKFi->bImu) + { + VertexVelocity* VV = static_cast(optimizer.vertex(maxKFid+3*(pKFi->mnId)+1)); + if(nLoopId==0) + { + pKFi->SetVelocity(Converter::toCvMat(VV->estimate())); + } + else + { + pKFi->mVwbGBA = Converter::toCvMat(VV->estimate()); + } + + VertexGyroBias* VG; + VertexAccBias* VA; + if (!bInit) + { + VG = static_cast(optimizer.vertex(maxKFid+3*(pKFi->mnId)+2)); + VA = static_cast(optimizer.vertex(maxKFid+3*(pKFi->mnId)+3)); + } + else + { + VG = static_cast(optimizer.vertex(4*maxKFid+2)); + VA = static_cast(optimizer.vertex(4*maxKFid+3)); + } + + Vector6d vb; + vb << VG->estimate(), VA->estimate(); + IMU::Bias b (vb[3],vb[4],vb[5],vb[0],vb[1],vb[2]); + if(nLoopId==0) + { + pKFi->SetNewBias(b); + } + else + { + pKFi->mBiasGBA = b; + } + } + } + + //Points + for(size_t i=0; i(optimizer.vertex(pMP->mnId+iniMPid+1)); + + if(nLoopId==0) + { + pMP->SetWorldPos(Converter::toCvMat(vPoint->estimate())); + pMP->UpdateNormalAndDepth(); + } + else + { + pMP->mPosGBA.create(3,1,CV_32F); + Converter::toCvMat(vPoint->estimate()).copyTo(pMP->mPosGBA); + pMP->mnBAGlobalForKF = nLoopId; + } + + } + + pMap->IncreaseChangeIndex(); +} + + +int Optimizer::PoseOptimization(Frame *pFrame) +{ + g2o::SparseOptimizer optimizer; + g2o::BlockSolver_6_3::LinearSolverType * linearSolver; + + linearSolver = new g2o::LinearSolverDense(); + + g2o::BlockSolver_6_3 * solver_ptr = new g2o::BlockSolver_6_3(linearSolver); + + g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg(solver_ptr); + optimizer.setAlgorithm(solver); + + int nInitialCorrespondences=0; + + // Set Frame vertex + g2o::VertexSE3Expmap * vSE3 = new g2o::VertexSE3Expmap(); + vSE3->setEstimate(Converter::toSE3Quat(pFrame->mTcw)); + vSE3->setId(0); + vSE3->setFixed(false); + optimizer.addVertex(vSE3); + + // Set MapPoint vertices + const int N = pFrame->N; + + vector vpEdgesMono; + vector vpEdgesMono_FHR; + vector vnIndexEdgeMono, vnIndexEdgeRight; + vpEdgesMono.reserve(N); + vpEdgesMono_FHR.reserve(N); + vnIndexEdgeMono.reserve(N); + vnIndexEdgeRight.reserve(N); + + vector vpEdgesStereo; + vector vnIndexEdgeStereo; + vpEdgesStereo.reserve(N); + vnIndexEdgeStereo.reserve(N); + + const float deltaMono = sqrt(5.991); + const float deltaStereo = sqrt(7.815); + + { + unique_lock lock(MapPoint::mGlobalMutex); + + for(int i=0; imvpMapPoints[i]; + if(pMP) + { + //Conventional SLAM + if(!pFrame->mpCamera2){ + // Monocular observation + if(pFrame->mvuRight[i]<0) + { + nInitialCorrespondences++; + pFrame->mvbOutlier[i] = false; + + Eigen::Matrix obs; + const cv::KeyPoint &kpUn = pFrame->mvKeysUn[i]; + obs << kpUn.pt.x, kpUn.pt.y; + + ORB_SLAM3::EdgeSE3ProjectXYZOnlyPose* e = new ORB_SLAM3::EdgeSE3ProjectXYZOnlyPose(); + + e->setVertex(0, dynamic_cast(optimizer.vertex(0))); + e->setMeasurement(obs); + const float invSigma2 = pFrame->mvInvLevelSigma2[kpUn.octave]; + e->setInformation(Eigen::Matrix2d::Identity()*invSigma2); + + g2o::RobustKernelHuber* rk = new g2o::RobustKernelHuber; + e->setRobustKernel(rk); + rk->setDelta(deltaMono); + + e->pCamera = pFrame->mpCamera; + cv::Mat Xw = pMP->GetWorldPos(); + e->Xw[0] = Xw.at(0); + e->Xw[1] = Xw.at(1); + e->Xw[2] = Xw.at(2); + + optimizer.addEdge(e); + + vpEdgesMono.push_back(e); + vnIndexEdgeMono.push_back(i); + } + else // Stereo observation + { + nInitialCorrespondences++; + pFrame->mvbOutlier[i] = false; + + //SET EDGE + Eigen::Matrix obs; + const cv::KeyPoint &kpUn = pFrame->mvKeysUn[i]; + const float &kp_ur = pFrame->mvuRight[i]; + obs << kpUn.pt.x, kpUn.pt.y, kp_ur; + + g2o::EdgeStereoSE3ProjectXYZOnlyPose* e = new g2o::EdgeStereoSE3ProjectXYZOnlyPose(); + + e->setVertex(0, dynamic_cast(optimizer.vertex(0))); + e->setMeasurement(obs); + const float invSigma2 = pFrame->mvInvLevelSigma2[kpUn.octave]; + Eigen::Matrix3d Info = Eigen::Matrix3d::Identity()*invSigma2; + e->setInformation(Info); + + g2o::RobustKernelHuber* rk = new g2o::RobustKernelHuber; + e->setRobustKernel(rk); + rk->setDelta(deltaStereo); + + e->fx = pFrame->fx; + e->fy = pFrame->fy; + e->cx = pFrame->cx; + e->cy = pFrame->cy; + e->bf = pFrame->mbf; + cv::Mat Xw = pMP->GetWorldPos(); + e->Xw[0] = Xw.at(0); + e->Xw[1] = Xw.at(1); + e->Xw[2] = Xw.at(2); + + optimizer.addEdge(e); + + vpEdgesStereo.push_back(e); + vnIndexEdgeStereo.push_back(i); + } + } + //SLAM with respect a rigid body + else{ + nInitialCorrespondences++; + + cv::KeyPoint kpUn; + + if (i < pFrame->Nleft) { //Left camera observation + kpUn = pFrame->mvKeys[i]; + + pFrame->mvbOutlier[i] = false; + + Eigen::Matrix obs; + obs << kpUn.pt.x, kpUn.pt.y; + + ORB_SLAM3::EdgeSE3ProjectXYZOnlyPose *e = new ORB_SLAM3::EdgeSE3ProjectXYZOnlyPose(); + + e->setVertex(0, dynamic_cast(optimizer.vertex(0))); + e->setMeasurement(obs); + const float invSigma2 = pFrame->mvInvLevelSigma2[kpUn.octave]; + e->setInformation(Eigen::Matrix2d::Identity() * invSigma2); + + g2o::RobustKernelHuber *rk = new g2o::RobustKernelHuber; + e->setRobustKernel(rk); + rk->setDelta(deltaMono); + + e->pCamera = pFrame->mpCamera; + cv::Mat Xw = pMP->GetWorldPos(); + e->Xw[0] = Xw.at(0); + e->Xw[1] = Xw.at(1); + e->Xw[2] = Xw.at(2); + + optimizer.addEdge(e); + + vpEdgesMono.push_back(e); + vnIndexEdgeMono.push_back(i); + } + else { //Right camera observation + //continue; + kpUn = pFrame->mvKeysRight[i - pFrame->Nleft]; + + Eigen::Matrix obs; + obs << kpUn.pt.x, kpUn.pt.y; + + pFrame->mvbOutlier[i] = false; + + ORB_SLAM3::EdgeSE3ProjectXYZOnlyPoseToBody *e = new ORB_SLAM3::EdgeSE3ProjectXYZOnlyPoseToBody(); + + e->setVertex(0, dynamic_cast(optimizer.vertex(0))); + e->setMeasurement(obs); + const float invSigma2 = pFrame->mvInvLevelSigma2[kpUn.octave]; + e->setInformation(Eigen::Matrix2d::Identity() * invSigma2); + + g2o::RobustKernelHuber *rk = new g2o::RobustKernelHuber; + e->setRobustKernel(rk); + rk->setDelta(deltaMono); + + e->pCamera = pFrame->mpCamera2; + cv::Mat Xw = pMP->GetWorldPos(); + e->Xw[0] = Xw.at(0); + e->Xw[1] = Xw.at(1); + e->Xw[2] = Xw.at(2); + + e->mTrl = Converter::toSE3Quat(pFrame->mTrl); + + optimizer.addEdge(e); + + vpEdgesMono_FHR.push_back(e); + vnIndexEdgeRight.push_back(i); + } + } + } + } + } + + //cout << "PO: vnIndexEdgeMono.size() = " << vnIndexEdgeMono.size() << " vnIndexEdgeRight.size() = " << vnIndexEdgeRight.size() << endl; + if(nInitialCorrespondences<3) + return 0; + + // We perform 4 optimizations, after each optimization we classify observation as inlier/outlier + // At the next optimization, outliers are not included, but at the end they can be classified as inliers again. + const float chi2Mono[4]={5.991,5.991,5.991,5.991}; + const float chi2Stereo[4]={7.815,7.815,7.815, 7.815}; + const int its[4]={10,10,10,10}; + + int nBad=0; + for(size_t it=0; it<4; it++) + { + + vSE3->setEstimate(Converter::toSE3Quat(pFrame->mTcw)); + optimizer.initializeOptimization(0); + optimizer.optimize(its[it]); + + nBad=0; + for(size_t i=0, iend=vpEdgesMono.size(); imvbOutlier[idx]) + { + e->computeError(); + } + + const float chi2 = e->chi2(); + + if(chi2>chi2Mono[it]) + { + pFrame->mvbOutlier[idx]=true; + e->setLevel(1); + nBad++; + } + else + { + pFrame->mvbOutlier[idx]=false; + e->setLevel(0); + } + + if(it==2) + e->setRobustKernel(0); + } + + for(size_t i=0, iend=vpEdgesMono_FHR.size(); imvbOutlier[idx]) + { + e->computeError(); + } + + const float chi2 = e->chi2(); + + if(chi2>chi2Mono[it]) + { + pFrame->mvbOutlier[idx]=true; + e->setLevel(1); + nBad++; + } + else + { + pFrame->mvbOutlier[idx]=false; + e->setLevel(0); + } + + if(it==2) + e->setRobustKernel(0); + } + + for(size_t i=0, iend=vpEdgesStereo.size(); imvbOutlier[idx]) + { + e->computeError(); + } + + const float chi2 = e->chi2(); + + if(chi2>chi2Stereo[it]) + { + pFrame->mvbOutlier[idx]=true; + e->setLevel(1); + nBad++; + } + else + { + e->setLevel(0); + pFrame->mvbOutlier[idx]=false; + } + + if(it==2) + e->setRobustKernel(0); + } + + if(optimizer.edges().size()<10) + break; + } + + // Recover optimized pose and return number of inliers + g2o::VertexSE3Expmap* vSE3_recov = static_cast(optimizer.vertex(0)); + g2o::SE3Quat SE3quat_recov = vSE3_recov->estimate(); + cv::Mat pose = Converter::toCvMat(SE3quat_recov); + pFrame->SetPose(pose); + + //cout << "[PoseOptimization]: initial correspondences-> " << nInitialCorrespondences << " --- outliers-> " << nBad << endl; + + return nInitialCorrespondences-nBad; +} + +void Optimizer::LocalBundleAdjustment(KeyFrame *pKF, bool* pbStopFlag, vector &vpNonEnoughOptKFs) +{ + // Local KeyFrames: First Breath Search from Current Keyframe + list lLocalKeyFrames; + + lLocalKeyFrames.push_back(pKF); + pKF->mnBALocalForKF = pKF->mnId; + Map* pCurrentMap = pKF->GetMap(); + + const vector vNeighKFs = pKF->GetVectorCovisibleKeyFrames(); + for(int i=0, iend=vNeighKFs.size(); imnBALocalForKF = pKF->mnId; + if(!pKFi->isBad() && pKFi->GetMap() == pCurrentMap) + lLocalKeyFrames.push_back(pKFi); + } + for(KeyFrame* pKFi : vpNonEnoughOptKFs) + { + if(!pKFi->isBad() && pKFi->GetMap() == pCurrentMap && pKFi->mnBALocalForKF != pKF->mnId) + { + pKFi->mnBALocalForKF = pKF->mnId; + lLocalKeyFrames.push_back(pKFi); + } + } + + // Local MapPoints seen in Local KeyFrames + list lLocalMapPoints; + set sNumObsMP; + int num_fixedKF; + for(list::iterator lit=lLocalKeyFrames.begin() , lend=lLocalKeyFrames.end(); lit!=lend; lit++) + { + KeyFrame* pKFi = *lit; + if(pKFi->mnId==pCurrentMap->GetInitKFid()) + { + num_fixedKF = 1; + } + vector vpMPs = pKFi->GetMapPointMatches(); + for(vector::iterator vit=vpMPs.begin(), vend=vpMPs.end(); vit!=vend; vit++) + { + MapPoint* pMP = *vit; + if(pMP) + if(!pMP->isBad() && pMP->GetMap() == pCurrentMap) + { + + if(pMP->mnBALocalForKF!=pKF->mnId) + { + lLocalMapPoints.push_back(pMP); + pMP->mnBALocalForKF=pKF->mnId; + } + + } + } + } + + // Fixed Keyframes. Keyframes that see Local MapPoints but that are not Local Keyframes + list lFixedCameras; + for(list::iterator lit=lLocalMapPoints.begin(), lend=lLocalMapPoints.end(); lit!=lend; lit++) + { + map> observations = (*lit)->GetObservations(); + for(map>::iterator mit=observations.begin(), mend=observations.end(); mit!=mend; mit++) + { + KeyFrame* pKFi = mit->first; + + if(pKFi->mnBALocalForKF!=pKF->mnId && pKFi->mnBAFixedForKF!=pKF->mnId ) + { + pKFi->mnBAFixedForKF=pKF->mnId; + if(!pKFi->isBad() && pKFi->GetMap() == pCurrentMap) + lFixedCameras.push_back(pKFi); + } + } + } + num_fixedKF = lFixedCameras.size() + num_fixedKF; + if(num_fixedKF < 2) + { + //Verbose::PrintMess("LM-LBA: New Fixed KFs had been set", Verbose::VERBOSITY_NORMAL); + //TODO We set 2 KFs to fixed to avoid a degree of freedom in scale + list::iterator lit=lLocalKeyFrames.begin(); + int lowerId = pKF->mnId; + KeyFrame* pLowerKf; + int secondLowerId = pKF->mnId; + KeyFrame* pSecondLowerKF; + + for(; lit != lLocalKeyFrames.end(); lit++) + { + KeyFrame* pKFi = *lit; + if(pKFi == pKF || pKFi->mnId == pCurrentMap->GetInitKFid()) + { + continue; + } + + if(pKFi->mnId < lowerId) + { + lowerId = pKFi->mnId; + pLowerKf = pKFi; + } + else if(pKFi->mnId < secondLowerId) + { + secondLowerId = pKFi->mnId; + pSecondLowerKF = pKFi; + } + } + lFixedCameras.push_back(pLowerKf); + lLocalKeyFrames.remove(pLowerKf); + num_fixedKF++; + if(num_fixedKF < 2) + { + lFixedCameras.push_back(pSecondLowerKF); + lLocalKeyFrames.remove(pSecondLowerKF); + num_fixedKF++; + } + } + + if(num_fixedKF == 0) + { + Verbose::PrintMess("LM-LBA: There are 0 fixed KF in the optimizations, LBA aborted", Verbose::VERBOSITY_NORMAL); + //return; + } + //Verbose::PrintMess("LM-LBA: There are " + to_string(lLocalKeyFrames.size()) + " KFs and " + to_string(lLocalMapPoints.size()) + " MPs to optimize. " + to_string(num_fixedKF) + " KFs are fixed", Verbose::VERBOSITY_DEBUG); + + // Setup optimizer + g2o::SparseOptimizer optimizer; + g2o::BlockSolver_6_3::LinearSolverType * linearSolver; + + linearSolver = new g2o::LinearSolverEigen(); + + g2o::BlockSolver_6_3 * solver_ptr = new g2o::BlockSolver_6_3(linearSolver); + + g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg(solver_ptr); + if (pCurrentMap->IsInertial()) + solver->setUserLambdaInit(100.0); // TODO uncomment + //cout << "LM-LBA: lambda init: " << solver->userLambdaInit() << endl; + + optimizer.setAlgorithm(solver); + optimizer.setVerbose(false); + + if(pbStopFlag) + optimizer.setForceStopFlag(pbStopFlag); + + unsigned long maxKFid = 0; + + // Set Local KeyFrame vertices + for(list::iterator lit=lLocalKeyFrames.begin(), lend=lLocalKeyFrames.end(); lit!=lend; lit++) + { + KeyFrame* pKFi = *lit; + g2o::VertexSE3Expmap * vSE3 = new g2o::VertexSE3Expmap(); + vSE3->setEstimate(Converter::toSE3Quat(pKFi->GetPose())); + vSE3->setId(pKFi->mnId); + vSE3->setFixed(pKFi->mnId==pCurrentMap->GetInitKFid()); + optimizer.addVertex(vSE3); + if(pKFi->mnId>maxKFid) + maxKFid=pKFi->mnId; + } + + // Set Fixed KeyFrame vertices + for(list::iterator lit=lFixedCameras.begin(), lend=lFixedCameras.end(); lit!=lend; lit++) + { + KeyFrame* pKFi = *lit; + g2o::VertexSE3Expmap * vSE3 = new g2o::VertexSE3Expmap(); + vSE3->setEstimate(Converter::toSE3Quat(pKFi->GetPose())); + vSE3->setId(pKFi->mnId); + vSE3->setFixed(true); + optimizer.addVertex(vSE3); + if(pKFi->mnId>maxKFid) + maxKFid=pKFi->mnId; + } + + Verbose::PrintMess("LM-LBA: opt/fixed KFs: " + to_string(lLocalKeyFrames.size()) + "/" + to_string(lFixedCameras.size()), Verbose::VERBOSITY_DEBUG); + Verbose::PrintMess("LM-LBA: local MPs: " + to_string(lLocalMapPoints.size()), Verbose::VERBOSITY_DEBUG); + + // Set MapPoint vertices + const int nExpectedSize = (lLocalKeyFrames.size()+lFixedCameras.size())*lLocalMapPoints.size(); + + vector vpEdgesMono; + vpEdgesMono.reserve(nExpectedSize); + + vector vpEdgesBody; + vpEdgesBody.reserve(nExpectedSize); + + vector vpEdgeKFMono; + vpEdgeKFMono.reserve(nExpectedSize); + + vector vpEdgeKFBody; + vpEdgeKFBody.reserve(nExpectedSize); + + vector vpMapPointEdgeMono; + vpMapPointEdgeMono.reserve(nExpectedSize); + + vector vpMapPointEdgeBody; + vpMapPointEdgeBody.reserve(nExpectedSize); + + vector vpEdgesStereo; + vpEdgesStereo.reserve(nExpectedSize); + + vector vpEdgeKFStereo; + vpEdgeKFStereo.reserve(nExpectedSize); + + vector vpMapPointEdgeStereo; + vpMapPointEdgeStereo.reserve(nExpectedSize); + + const float thHuberMono = sqrt(5.991); + const float thHuberStereo = sqrt(7.815); + + int nPoints = 0; + + int nKFs = lLocalKeyFrames.size()+lFixedCameras.size(), nEdges = 0; + + for(list::iterator lit=lLocalMapPoints.begin(), lend=lLocalMapPoints.end(); lit!=lend; lit++) + { + MapPoint* pMP = *lit; + g2o::VertexSBAPointXYZ* vPoint = new g2o::VertexSBAPointXYZ(); + vPoint->setEstimate(Converter::toVector3d(pMP->GetWorldPos())); + int id = pMP->mnId+maxKFid+1; + vPoint->setId(id); + vPoint->setMarginalized(true); + optimizer.addVertex(vPoint); + nPoints++; + + const map> observations = pMP->GetObservations(); + + //Set edges + for(map>::const_iterator mit=observations.begin(), mend=observations.end(); mit!=mend; mit++) + { + KeyFrame* pKFi = mit->first; + + if(!pKFi->isBad() && pKFi->GetMap() == pCurrentMap) + { + const int cam0Index = get<0>(mit->second); + + // Monocular observation of Camera 0 + if(cam0Index != -1 && pKFi->mvuRight[cam0Index]<0) + { + const cv::KeyPoint &kpUn = pKFi->mvKeysUn[cam0Index]; + Eigen::Matrix obs; + obs << kpUn.pt.x, kpUn.pt.y; + + ORB_SLAM3::EdgeSE3ProjectXYZ* e = new ORB_SLAM3::EdgeSE3ProjectXYZ(); + + e->setVertex(0, dynamic_cast(optimizer.vertex(id))); + e->setVertex(1, dynamic_cast(optimizer.vertex(pKFi->mnId))); + e->setMeasurement(obs); + const float &invSigma2 = pKFi->mvInvLevelSigma2[kpUn.octave]; + e->setInformation(Eigen::Matrix2d::Identity()*invSigma2); + + g2o::RobustKernelHuber* rk = new g2o::RobustKernelHuber; + e->setRobustKernel(rk); + rk->setDelta(thHuberMono); + + e->pCamera = pKFi->mpCamera; + + optimizer.addEdge(e); + vpEdgesMono.push_back(e); + vpEdgeKFMono.push_back(pKFi); + vpMapPointEdgeMono.push_back(pMP); + + nEdges++; + } + else if(cam0Index != -1 && pKFi->mvuRight[cam0Index]>=0)// Stereo observation (with rectified images) + { + const cv::KeyPoint &kpUn = pKFi->mvKeysUn[cam0Index]; + Eigen::Matrix obs; + const float kp_ur = pKFi->mvuRight[cam0Index]; + obs << kpUn.pt.x, kpUn.pt.y, kp_ur; + + g2o::EdgeStereoSE3ProjectXYZ* e = new g2o::EdgeStereoSE3ProjectXYZ(); + + e->setVertex(0, dynamic_cast(optimizer.vertex(id))); + e->setVertex(1, dynamic_cast(optimizer.vertex(pKFi->mnId))); + e->setMeasurement(obs); + const float &invSigma2 = pKFi->mvInvLevelSigma2[kpUn.octave]; + Eigen::Matrix3d Info = Eigen::Matrix3d::Identity()*invSigma2; + e->setInformation(Info); + + g2o::RobustKernelHuber* rk = new g2o::RobustKernelHuber; + e->setRobustKernel(rk); + rk->setDelta(thHuberStereo); + + e->fx = pKFi->fx; + e->fy = pKFi->fy; + e->cx = pKFi->cx; + e->cy = pKFi->cy; + e->bf = pKFi->mbf; + + optimizer.addEdge(e); + vpEdgesStereo.push_back(e); + vpEdgeKFStereo.push_back(pKFi); + vpMapPointEdgeStereo.push_back(pMP); + + nEdges++; + } + + // Monocular observation of Camera 0 + if(pKFi->mpCamera2){ + int rightIndex = get<1>(mit->second); + + if(rightIndex != -1 ){ + rightIndex -= pKFi->NLeft; + + Eigen::Matrix obs; + cv::KeyPoint kp = pKFi->mvKeysRight[rightIndex]; + obs << kp.pt.x, kp.pt.y; + + ORB_SLAM3::EdgeSE3ProjectXYZToBody *e = new ORB_SLAM3::EdgeSE3ProjectXYZToBody(); + + e->setVertex(0, dynamic_cast(optimizer.vertex(id))); + e->setVertex(1, dynamic_cast(optimizer.vertex(pKFi->mnId))); + e->setMeasurement(obs); + const float &invSigma2 = pKFi->mvInvLevelSigma2[kp.octave]; + e->setInformation(Eigen::Matrix2d::Identity()*invSigma2); + + g2o::RobustKernelHuber* rk = new g2o::RobustKernelHuber; + e->setRobustKernel(rk); + rk->setDelta(thHuberMono); + + e->mTrl = Converter::toSE3Quat(pKFi->mTrl); + + e->pCamera = pKFi->mpCamera2; + + optimizer.addEdge(e); + vpEdgesBody.push_back(e); + vpEdgeKFBody.push_back(pKFi); + vpMapPointEdgeBody.push_back(pMP); + + nEdges++; + } + } + } + } + } + + if(pbStopFlag) + if(*pbStopFlag) + { + return; + } + + optimizer.initializeOptimization(); + + //std::chrono::steady_clock::time_point begin = std::chrono::steady_clock::now(); + int numPerform_it = optimizer.optimize(5); + //std::chrono::steady_clock::time_point end = std::chrono::steady_clock::now(); + + + + //std::cout << "LBA time = " << std::chrono::duration_cast(end - begin).count() << "[ms]" << std::endl; + //std::cout << "Keyframes: " << nKFs << " --- MapPoints: " << nPoints << " --- Edges: " << nEdges << endl; + + bool bDoMore= true; + + if(pbStopFlag) + if(*pbStopFlag) + bDoMore = false; + + if(bDoMore) + { + + // Check inlier observations + int nMonoBadObs = 0; + for(size_t i=0, iend=vpEdgesMono.size(); iisBad()) + continue; + + if(e->chi2()>5.991 || !e->isDepthPositive()) + { + //e->setLevel(1); + nMonoBadObs++; + } + + //e->setRobustKernel(0); + } + + int nBodyBadObs = 0; + for(size_t i=0, iend=vpEdgesBody.size(); iisBad()) + continue; + + if(e->chi2()>5.991 || !e->isDepthPositive()) + { + //e->setLevel(1); + nBodyBadObs++; + } + + //e->setRobustKernel(0); + } + + int nStereoBadObs = 0; + for(size_t i=0, iend=vpEdgesStereo.size(); iisBad()) + continue; + + if(e->chi2()>7.815 || !e->isDepthPositive()) + { + //e->setLevel(1); + nStereoBadObs++; + } + + //e->setRobustKernel(0); + } + Verbose::PrintMess("LM-LBA: First optimization has " + to_string(nMonoBadObs) + " monocular and " + to_string(nStereoBadObs) + " stereo bad observations", Verbose::VERBOSITY_DEBUG); + + // Optimize again without the outliers + //Verbose::PrintMess("LM-LBA: second optimization", Verbose::VERBOSITY_DEBUG); + //optimizer.initializeOptimization(0); + //numPerform_it = optimizer.optimize(10); + numPerform_it += optimizer.optimize(5); + + } + + vector > vToErase; + vToErase.reserve(vpEdgesMono.size()+vpEdgesBody.size()+vpEdgesStereo.size()); + + // Check inlier observations + for(size_t i=0, iend=vpEdgesMono.size(); iisBad()) + continue; + + if(e->chi2()>5.991 || !e->isDepthPositive()) + { + KeyFrame* pKFi = vpEdgeKFMono[i]; + vToErase.push_back(make_pair(pKFi,pMP)); + } + } + + for(size_t i=0, iend=vpEdgesBody.size(); iisBad()) + continue; + + if(e->chi2()>5.991 || !e->isDepthPositive()) + { + KeyFrame* pKFi = vpEdgeKFBody[i]; + vToErase.push_back(make_pair(pKFi,pMP)); + } + } + + for(size_t i=0, iend=vpEdgesStereo.size(); iisBad()) + continue; + + if(e->chi2()>7.815 || !e->isDepthPositive()) + { + KeyFrame* pKFi = vpEdgeKFStereo[i]; + vToErase.push_back(make_pair(pKFi,pMP)); + } + } + + Verbose::PrintMess("LM-LBA: outlier observations: " + to_string(vToErase.size()), Verbose::VERBOSITY_DEBUG); + Verbose::PrintMess("LM-LBA: total of observations: " + to_string(vpMapPointEdgeMono.size()+vpMapPointEdgeStereo.size()), Verbose::VERBOSITY_DEBUG); + bool bRedrawError = false; + bool bWriteStats = false; + + // Get Map Mutex + unique_lock lock(pCurrentMap->mMutexMapUpdate); + + if(!vToErase.empty()) + { + + //cout << "LM-LBA: There are " << vToErase.size() << " observations whose will be deleted from the map" << endl; + for(size_t i=0;iEraseMapPointMatch(pMPi); + pMPi->EraseObservation(pKFi); + } + } + + // Recover optimized data + //Keyframes + vpNonEnoughOptKFs.clear(); + for(list::iterator lit=lLocalKeyFrames.begin(), lend=lLocalKeyFrames.end(); lit!=lend; lit++) + { + KeyFrame* pKFi = *lit; + g2o::VertexSE3Expmap* vSE3 = static_cast(optimizer.vertex(pKFi->mnId)); + g2o::SE3Quat SE3quat = vSE3->estimate(); + cv::Mat Tiw = Converter::toCvMat(SE3quat); + cv::Mat Tco_cn = pKFi->GetPose() * Tiw.inv(); + cv::Vec3d trasl = Tco_cn.rowRange(0,3).col(3); + double dist = cv::norm(trasl); + pKFi->SetPose(Converter::toCvMat(SE3quat)); + + pKFi->mnNumberOfOpt += numPerform_it; + //cout << "LM-LBA: KF " << pKFi->mnId << " had performed " << pKFi->mnNumberOfOpt << " iterations" << endl; + if(pKFi->mnNumberOfOpt < 10) + { + vpNonEnoughOptKFs.push_back(pKFi); + } + } + + //Points + for(list::iterator lit=lLocalMapPoints.begin(), lend=lLocalMapPoints.end(); lit!=lend; lit++) + { + MapPoint* pMP = *lit; + g2o::VertexSBAPointXYZ* vPoint = static_cast(optimizer.vertex(pMP->mnId+maxKFid+1)); + pMP->SetWorldPos(Converter::toCvMat(vPoint->estimate())); + pMP->UpdateNormalAndDepth(); + } + + pCurrentMap->IncreaseChangeIndex(); +} + +void Optimizer::LocalBundleAdjustment(KeyFrame *pKF, bool* pbStopFlag, Map* pMap, int& num_fixedKF) +{ + //cout << "LBA" << endl; + // Local KeyFrames: First Breath Search from Current Keyframe + list lLocalKeyFrames; + + lLocalKeyFrames.push_back(pKF); + pKF->mnBALocalForKF = pKF->mnId; + Map* pCurrentMap = pKF->GetMap(); + + const vector vNeighKFs = pKF->GetVectorCovisibleKeyFrames(); + for(int i=0, iend=vNeighKFs.size(); imnBALocalForKF = pKF->mnId; + if(!pKFi->isBad() && pKFi->GetMap() == pCurrentMap) + lLocalKeyFrames.push_back(pKFi); + } + + // Local MapPoints seen in Local KeyFrames + num_fixedKF = 0; + list lLocalMapPoints; + set sNumObsMP; + for(list::iterator lit=lLocalKeyFrames.begin() , lend=lLocalKeyFrames.end(); lit!=lend; lit++) + { + KeyFrame* pKFi = *lit; + if(pKFi->mnId==pMap->GetInitKFid()) + { + num_fixedKF = 1; + } + vector vpMPs = pKFi->GetMapPointMatches(); + for(vector::iterator vit=vpMPs.begin(), vend=vpMPs.end(); vit!=vend; vit++) + { + MapPoint* pMP = *vit; + if(pMP) + if(!pMP->isBad() && pMP->GetMap() == pCurrentMap) + { + + if(pMP->mnBALocalForKF!=pKF->mnId) + { + lLocalMapPoints.push_back(pMP); + pMP->mnBALocalForKF=pKF->mnId; + } + } + } + } + + // Fixed Keyframes. Keyframes that see Local MapPoints but that are not Local Keyframes + list lFixedCameras; + for(list::iterator lit=lLocalMapPoints.begin(), lend=lLocalMapPoints.end(); lit!=lend; lit++) + { + map> observations = (*lit)->GetObservations(); + for(map>::iterator mit=observations.begin(), mend=observations.end(); mit!=mend; mit++) + { + KeyFrame* pKFi = mit->first; + + if(pKFi->mnBALocalForKF!=pKF->mnId && pKFi->mnBAFixedForKF!=pKF->mnId ) + { + pKFi->mnBAFixedForKF=pKF->mnId; + if(!pKFi->isBad() && pKFi->GetMap() == pCurrentMap) + lFixedCameras.push_back(pKFi); + } + } + } + num_fixedKF = lFixedCameras.size() + num_fixedKF; + if(num_fixedKF < 2) + { + //Verbose::PrintMess("LM-LBA: New Fixed KFs had been set", Verbose::VERBOSITY_NORMAL); + //TODO We set 2 KFs to fixed to avoid a degree of freedom in scale + list::iterator lit=lLocalKeyFrames.begin(); + int lowerId = pKF->mnId; + KeyFrame* pLowerKf; + int secondLowerId = pKF->mnId; + KeyFrame* pSecondLowerKF; + + for(; lit != lLocalKeyFrames.end(); lit++) + { + KeyFrame* pKFi = *lit; + if(pKFi == pKF || pKFi->mnId == pMap->GetInitKFid()) + { + continue; + } + + if(pKFi->mnId < lowerId) + { + lowerId = pKFi->mnId; + pLowerKf = pKFi; + } + else if(pKFi->mnId < secondLowerId) + { + secondLowerId = pKFi->mnId; + pSecondLowerKF = pKFi; + } + } + lFixedCameras.push_back(pLowerKf); + lLocalKeyFrames.remove(pLowerKf); + num_fixedKF++; + if(num_fixedKF < 2) + { + lFixedCameras.push_back(pSecondLowerKF); + lLocalKeyFrames.remove(pSecondLowerKF); + num_fixedKF++; + } + } + + if(num_fixedKF == 0) + { + Verbose::PrintMess("LM-LBA: There are 0 fixed KF in the optimizations, LBA aborted", Verbose::VERBOSITY_NORMAL); + //return; + } + //Verbose::PrintMess("LM-LBA: There are " + to_string(lLocalKeyFrames.size()) + " KFs and " + to_string(lLocalMapPoints.size()) + " MPs to optimize. " + to_string(num_fixedKF) + " KFs are fixed", Verbose::VERBOSITY_DEBUG); + + // Setup optimizer + g2o::SparseOptimizer optimizer; + g2o::BlockSolver_6_3::LinearSolverType * linearSolver; + + linearSolver = new g2o::LinearSolverEigen(); + + g2o::BlockSolver_6_3 * solver_ptr = new g2o::BlockSolver_6_3(linearSolver); + + g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg(solver_ptr); + if (pMap->IsInertial()) + solver->setUserLambdaInit(100.0); // TODO uncomment + //cout << "LM-LBA: lambda init: " << solver->userLambdaInit() << endl; + + optimizer.setAlgorithm(solver); + optimizer.setVerbose(false); + + if(pbStopFlag) + optimizer.setForceStopFlag(pbStopFlag); + + unsigned long maxKFid = 0; + + // Set Local KeyFrame vertices + for(list::iterator lit=lLocalKeyFrames.begin(), lend=lLocalKeyFrames.end(); lit!=lend; lit++) + { + KeyFrame* pKFi = *lit; + g2o::VertexSE3Expmap * vSE3 = new g2o::VertexSE3Expmap(); + vSE3->setEstimate(Converter::toSE3Quat(pKFi->GetPose())); + vSE3->setId(pKFi->mnId); + vSE3->setFixed(pKFi->mnId==pMap->GetInitKFid()); + optimizer.addVertex(vSE3); + if(pKFi->mnId>maxKFid) + maxKFid=pKFi->mnId; + } + //Verbose::PrintMess("LM-LBA: KFs to optimize added", Verbose::VERBOSITY_DEBUG); + + // Set Fixed KeyFrame vertices + for(list::iterator lit=lFixedCameras.begin(), lend=lFixedCameras.end(); lit!=lend; lit++) + { + KeyFrame* pKFi = *lit; + g2o::VertexSE3Expmap * vSE3 = new g2o::VertexSE3Expmap(); + vSE3->setEstimate(Converter::toSE3Quat(pKFi->GetPose())); + vSE3->setId(pKFi->mnId); + vSE3->setFixed(true); + optimizer.addVertex(vSE3); + if(pKFi->mnId>maxKFid) + maxKFid=pKFi->mnId; + } + + // Set MapPoint vertices + const int nExpectedSize = (lLocalKeyFrames.size()+lFixedCameras.size())*lLocalMapPoints.size(); + + vector vpEdgesMono; + vpEdgesMono.reserve(nExpectedSize); + + vector vpEdgesBody; + vpEdgesBody.reserve(nExpectedSize); + + vector vpEdgeKFMono; + vpEdgeKFMono.reserve(nExpectedSize); + + vector vpEdgeKFBody; + vpEdgeKFBody.reserve(nExpectedSize); + + vector vpMapPointEdgeMono; + vpMapPointEdgeMono.reserve(nExpectedSize); + + vector vpMapPointEdgeBody; + vpMapPointEdgeBody.reserve(nExpectedSize); + + vector vpEdgesStereo; + vpEdgesStereo.reserve(nExpectedSize); + + vector vpEdgeKFStereo; + vpEdgeKFStereo.reserve(nExpectedSize); + + vector vpMapPointEdgeStereo; + vpMapPointEdgeStereo.reserve(nExpectedSize); + + const float thHuberMono = sqrt(5.991); + const float thHuberStereo = sqrt(7.815); + + int nPoints = 0; + + int nKFs = lLocalKeyFrames.size()+lFixedCameras.size(), nEdges = 0; + + for(list::iterator lit=lLocalMapPoints.begin(), lend=lLocalMapPoints.end(); lit!=lend; lit++) + { + MapPoint* pMP = *lit; + g2o::VertexSBAPointXYZ* vPoint = new g2o::VertexSBAPointXYZ(); + vPoint->setEstimate(Converter::toVector3d(pMP->GetWorldPos())); + int id = pMP->mnId+maxKFid+1; + vPoint->setId(id); + vPoint->setMarginalized(true); + optimizer.addVertex(vPoint); + nPoints++; + + const map> observations = pMP->GetObservations(); + + //Set edges + for(map>::const_iterator mit=observations.begin(), mend=observations.end(); mit!=mend; mit++) + { + KeyFrame* pKFi = mit->first; + + if(!pKFi->isBad() && pKFi->GetMap() == pCurrentMap) + { + const int leftIndex = get<0>(mit->second); + + // Monocular observation + if(leftIndex != -1 && pKFi->mvuRight[get<0>(mit->second)]<0) + { + const cv::KeyPoint &kpUn = pKFi->mvKeysUn[leftIndex]; + Eigen::Matrix obs; + obs << kpUn.pt.x, kpUn.pt.y; + + ORB_SLAM3::EdgeSE3ProjectXYZ* e = new ORB_SLAM3::EdgeSE3ProjectXYZ(); + + e->setVertex(0, dynamic_cast(optimizer.vertex(id))); + e->setVertex(1, dynamic_cast(optimizer.vertex(pKFi->mnId))); + e->setMeasurement(obs); + const float &invSigma2 = pKFi->mvInvLevelSigma2[kpUn.octave]; + e->setInformation(Eigen::Matrix2d::Identity()*invSigma2); + + g2o::RobustKernelHuber* rk = new g2o::RobustKernelHuber; + e->setRobustKernel(rk); + rk->setDelta(thHuberMono); + + e->pCamera = pKFi->mpCamera; + + optimizer.addEdge(e); + vpEdgesMono.push_back(e); + vpEdgeKFMono.push_back(pKFi); + vpMapPointEdgeMono.push_back(pMP); + + nEdges++; + } + else if(leftIndex != -1 && pKFi->mvuRight[get<0>(mit->second)]>=0)// Stereo observation + { + const cv::KeyPoint &kpUn = pKFi->mvKeysUn[leftIndex]; + Eigen::Matrix obs; + const float kp_ur = pKFi->mvuRight[get<0>(mit->second)]; + obs << kpUn.pt.x, kpUn.pt.y, kp_ur; + + g2o::EdgeStereoSE3ProjectXYZ* e = new g2o::EdgeStereoSE3ProjectXYZ(); + + e->setVertex(0, dynamic_cast(optimizer.vertex(id))); + e->setVertex(1, dynamic_cast(optimizer.vertex(pKFi->mnId))); + e->setMeasurement(obs); + const float &invSigma2 = pKFi->mvInvLevelSigma2[kpUn.octave]; + Eigen::Matrix3d Info = Eigen::Matrix3d::Identity()*invSigma2; + e->setInformation(Info); + + g2o::RobustKernelHuber* rk = new g2o::RobustKernelHuber; + e->setRobustKernel(rk); + rk->setDelta(thHuberStereo); + + e->fx = pKFi->fx; + e->fy = pKFi->fy; + e->cx = pKFi->cx; + e->cy = pKFi->cy; + e->bf = pKFi->mbf; + + optimizer.addEdge(e); + vpEdgesStereo.push_back(e); + vpEdgeKFStereo.push_back(pKFi); + vpMapPointEdgeStereo.push_back(pMP); + + nEdges++; + } + + if(pKFi->mpCamera2){ + int rightIndex = get<1>(mit->second); + + if(rightIndex != -1 ){ + rightIndex -= pKFi->NLeft; + + Eigen::Matrix obs; + cv::KeyPoint kp = pKFi->mvKeysRight[rightIndex]; + obs << kp.pt.x, kp.pt.y; + + ORB_SLAM3::EdgeSE3ProjectXYZToBody *e = new ORB_SLAM3::EdgeSE3ProjectXYZToBody(); + + e->setVertex(0, dynamic_cast(optimizer.vertex(id))); + e->setVertex(1, dynamic_cast(optimizer.vertex(pKFi->mnId))); + e->setMeasurement(obs); + const float &invSigma2 = pKFi->mvInvLevelSigma2[kp.octave]; + e->setInformation(Eigen::Matrix2d::Identity()*invSigma2); + + g2o::RobustKernelHuber* rk = new g2o::RobustKernelHuber; + e->setRobustKernel(rk); + rk->setDelta(thHuberMono); + + e->mTrl = Converter::toSE3Quat(pKFi->mTrl); + + e->pCamera = pKFi->mpCamera2; + + optimizer.addEdge(e); + vpEdgesBody.push_back(e); + vpEdgeKFBody.push_back(pKFi); + vpMapPointEdgeBody.push_back(pMP); + + nEdges++; + } + } + } + } + } + + //Verbose::PrintMess("LM-LBA: total observations: " + to_string(vpMapPointEdgeMono.size()+vpMapPointEdgeStereo.size()), Verbose::VERBOSITY_DEBUG); + + if(pbStopFlag) + if(*pbStopFlag) + return; + + optimizer.initializeOptimization(); + + std::chrono::steady_clock::time_point begin = std::chrono::steady_clock::now(); + optimizer.optimize(5); + std::chrono::steady_clock::time_point end = std::chrono::steady_clock::now(); + + //std::cout << "LBA time = " << std::chrono::duration_cast(end - begin).count() << "[ms]" << std::endl; + //std::cout << "Keyframes: " << nKFs << " --- MapPoints: " << nPoints << " --- Edges: " << nEdges << endl; + + bool bDoMore= true; + + if(pbStopFlag) + if(*pbStopFlag) + bDoMore = false; + + if(bDoMore) + { + + // Check inlier observations + int nMonoBadObs = 0; + for(size_t i=0, iend=vpEdgesMono.size(); iisBad()) + continue; + + if(e->chi2()>5.991 || !e->isDepthPositive()) + { + // e->setLevel(1); // MODIFICATION + nMonoBadObs++; + } + + //e->setRobustKernel(0); + } + + int nBodyBadObs = 0; + for(size_t i=0, iend=vpEdgesBody.size(); iisBad()) + continue; + + if(e->chi2()>5.991 || !e->isDepthPositive()) + { + //e->setLevel(1); + nBodyBadObs++; + } + + //e->setRobustKernel(0); + } + + int nStereoBadObs = 0; + for(size_t i=0, iend=vpEdgesStereo.size(); iisBad()) + continue; + + if(e->chi2()>7.815 || !e->isDepthPositive()) + { + //TODO e->setLevel(1); + nStereoBadObs++; + } + + //TODO e->setRobustKernel(0); + } + //Verbose::PrintMess("LM-LBA: First optimization has " + to_string(nMonoBadObs) + " monocular and " + to_string(nStereoBadObs) + " stereo bad observations", Verbose::VERBOSITY_DEBUG); + + // Optimize again without the outliers + //Verbose::PrintMess("LM-LBA: second optimization", Verbose::VERBOSITY_DEBUG); + optimizer.initializeOptimization(0); + optimizer.optimize(10); + + } + + vector > vToErase; + vToErase.reserve(vpEdgesMono.size()+vpEdgesBody.size()+vpEdgesStereo.size()); + + // Check inlier observations + for(size_t i=0, iend=vpEdgesMono.size(); iisBad()) + continue; + + if(e->chi2()>5.991 || !e->isDepthPositive()) + { + KeyFrame* pKFi = vpEdgeKFMono[i]; + vToErase.push_back(make_pair(pKFi,pMP)); + } + } + + for(size_t i=0, iend=vpEdgesBody.size(); iisBad()) + continue; + + if(e->chi2()>5.991 || !e->isDepthPositive()) + { + KeyFrame* pKFi = vpEdgeKFBody[i]; + vToErase.push_back(make_pair(pKFi,pMP)); + } + } + + for(size_t i=0, iend=vpEdgesStereo.size(); iisBad()) + continue; + + if(e->chi2()>7.815 || !e->isDepthPositive()) + { + KeyFrame* pKFi = vpEdgeKFStereo[i]; + vToErase.push_back(make_pair(pKFi,pMP)); + } + } + + //Verbose::PrintMess("LM-LBA: outlier observations: " + to_string(vToErase.size()), Verbose::VERBOSITY_DEBUG); + bool bRedrawError = false; + if(vToErase.size() >= (vpMapPointEdgeMono.size()+vpMapPointEdgeStereo.size()) * 0.5) + { + Verbose::PrintMess("LM-LBA: ERROR IN THE OPTIMIZATION, MOST OF THE POINTS HAS BECOME OUTLIERS", Verbose::VERBOSITY_NORMAL); + + return; + bRedrawError = true; + string folder_name = "test_LBA"; + string name = "_PreLM_LBA"; + name = "_PreLM_LBA_Fixed"; + + } + + + // Get Map Mutex + unique_lock lock(pMap->mMutexMapUpdate); + + if(!vToErase.empty()) + { + map mspInitialConnectedKFs; + map mspInitialObservationKFs; + if(bRedrawError) + { + for(KeyFrame* pKFi : lLocalKeyFrames) + { + + mspInitialConnectedKFs[pKFi] = pKFi->GetConnectedKeyFrames().size(); + mspInitialObservationKFs[pKFi] = pKFi->GetNumberMPs(); + } + } + + //cout << "LM-LBA: There are " << vToErase.size() << " observations whose will be deleted from the map" << endl; + for(size_t i=0;iEraseMapPointMatch(pMPi); + pMPi->EraseObservation(pKFi); + } + + map mspFinalConnectedKFs; + map mspFinalObservationKFs; + if(bRedrawError) + { + ofstream f_lba; + f_lba.open("test_LBA/LBA_failure_KF" + to_string(pKF->mnId) +".txt"); + f_lba << "# KF id, Initial Num CovKFs, Final Num CovKFs, Initial Num MPs, Fimal Num MPs" << endl; + f_lba << fixed; + + for(KeyFrame* pKFi : lLocalKeyFrames) + { + pKFi->UpdateConnections(); + int finalNumberCovKFs = pKFi->GetConnectedKeyFrames().size(); + int finalNumberMPs = pKFi->GetNumberMPs(); + f_lba << pKFi->mnId << ", " << mspInitialConnectedKFs[pKFi] << ", " << finalNumberCovKFs << ", " << mspInitialObservationKFs[pKFi] << ", " << finalNumberMPs << endl; + + mspFinalConnectedKFs[pKFi] = finalNumberCovKFs; + mspFinalObservationKFs[pKFi] = finalNumberMPs; + } + + f_lba.close(); + } + } + + // Recover optimized data + //Keyframes + bool bShowStats = false; + for(list::iterator lit=lLocalKeyFrames.begin(), lend=lLocalKeyFrames.end(); lit!=lend; lit++) + { + KeyFrame* pKFi = *lit; + g2o::VertexSE3Expmap* vSE3 = static_cast(optimizer.vertex(pKFi->mnId)); + g2o::SE3Quat SE3quat = vSE3->estimate(); + cv::Mat Tiw = Converter::toCvMat(SE3quat); + cv::Mat Tco_cn = pKFi->GetPose() * Tiw.inv(); + cv::Vec3d trasl = Tco_cn.rowRange(0,3).col(3); + double dist = cv::norm(trasl); + pKFi->SetPose(Converter::toCvMat(SE3quat)); + + if(dist > 1.0) + { + bShowStats = true; + Verbose::PrintMess("LM-LBA: Too much distance in KF " + to_string(pKFi->mnId) + ", " + to_string(dist) + " meters. Current KF " + to_string(pKF->mnId), Verbose::VERBOSITY_DEBUG); + Verbose::PrintMess("LM-LBA: Number of connections between the KFs " + to_string(pKF->GetWeight((pKFi))), Verbose::VERBOSITY_DEBUG); + + int numMonoMP = 0, numBadMonoMP = 0; + int numStereoMP = 0, numBadStereoMP = 0; + for(size_t i=0, iend=vpEdgesMono.size(); iisBad()) + continue; + + if(e->chi2()>5.991 || !e->isDepthPositive()) + { + numBadMonoMP++; + } + else + { + numMonoMP++; + } + } + + for(size_t i=0, iend=vpEdgesStereo.size(); iisBad()) + continue; + + if(e->chi2()>7.815 || !e->isDepthPositive()) + { + numBadStereoMP++; + } + else + { + numStereoMP++; + } + } + Verbose::PrintMess("LM-LBA: Good observations in mono " + to_string(numMonoMP) + " and stereo " + to_string(numStereoMP), Verbose::VERBOSITY_DEBUG); + Verbose::PrintMess("LM-LBA: Bad observations in mono " + to_string(numBadMonoMP) + " and stereo " + to_string(numBadStereoMP), Verbose::VERBOSITY_DEBUG); + } + } + + //Points + for(list::iterator lit=lLocalMapPoints.begin(), lend=lLocalMapPoints.end(); lit!=lend; lit++) + { + MapPoint* pMP = *lit; + g2o::VertexSBAPointXYZ* vPoint = static_cast(optimizer.vertex(pMP->mnId+maxKFid+1)); + pMP->SetWorldPos(Converter::toCvMat(vPoint->estimate())); + pMP->UpdateNormalAndDepth(); + } + + if(bRedrawError) + { + string folder_name = "test_LBA"; + string name = "_PostLM_LBA"; + //pMap->printReprojectionError(lLocalKeyFrames, pKF, name, folder_name); + name = "_PostLM_LBA_Fixed"; + //pMap->printReprojectionError(lFixedCameras, pKF, name, folder_name); + } + + // TODO Check this changeindex + pMap->IncreaseChangeIndex(); +} + + +void Optimizer::OptimizeEssentialGraph(Map* pMap, KeyFrame* pLoopKF, KeyFrame* pCurKF, + const LoopClosing::KeyFrameAndPose &NonCorrectedSim3, + const LoopClosing::KeyFrameAndPose &CorrectedSim3, + const map > &LoopConnections, const bool &bFixScale) +{ + // Setup optimizer + g2o::SparseOptimizer optimizer; + optimizer.setVerbose(false); + g2o::BlockSolver_7_3::LinearSolverType * linearSolver = + new g2o::LinearSolverEigen(); + g2o::BlockSolver_7_3 * solver_ptr= new g2o::BlockSolver_7_3(linearSolver); + g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg(solver_ptr); + + solver->setUserLambdaInit(1e-16); + optimizer.setAlgorithm(solver); + + const vector vpKFs = pMap->GetAllKeyFrames(); + const vector vpMPs = pMap->GetAllMapPoints(); + + const unsigned int nMaxKFid = pMap->GetMaxKFid(); + + vector > vScw(nMaxKFid+1); + vector > vCorrectedSwc(nMaxKFid+1); + vector vpVertices(nMaxKFid+1); + + vector vZvectors(nMaxKFid+1); // For debugging + Eigen::Vector3d z_vec; + z_vec << 0.0, 0.0, 1.0; + + const int minFeat = 100; // MODIFICATION originally was set to 100 + + // Set KeyFrame vertices + for(size_t i=0, iend=vpKFs.size(); iisBad()) + continue; + g2o::VertexSim3Expmap* VSim3 = new g2o::VertexSim3Expmap(); + + const int nIDi = pKF->mnId; + + LoopClosing::KeyFrameAndPose::const_iterator it = CorrectedSim3.find(pKF); + + if(it!=CorrectedSim3.end()) + { + vScw[nIDi] = it->second; + VSim3->setEstimate(it->second); + } + else + { + Eigen::Matrix Rcw = Converter::toMatrix3d(pKF->GetRotation()); + Eigen::Matrix tcw = Converter::toVector3d(pKF->GetTranslation()); + g2o::Sim3 Siw(Rcw,tcw,1.0); + vScw[nIDi] = Siw; + VSim3->setEstimate(Siw); + } + + if(pKF->mnId==pMap->GetInitKFid()) + VSim3->setFixed(true); + + VSim3->setId(nIDi); + VSim3->setMarginalized(false); + VSim3->_fix_scale = bFixScale; + + optimizer.addVertex(VSim3); + vZvectors[nIDi]=vScw[nIDi].rotation().toRotationMatrix()*z_vec; // For debugging + + vpVertices[nIDi]=VSim3; + } + + + set > sInsertedEdges; + + const Eigen::Matrix matLambda = Eigen::Matrix::Identity(); + + // Set Loop edges + int count_loop = 0; + for(map >::const_iterator mit = LoopConnections.begin(), mend=LoopConnections.end(); mit!=mend; mit++) + { + KeyFrame* pKF = mit->first; + const long unsigned int nIDi = pKF->mnId; + const set &spConnections = mit->second; + const g2o::Sim3 Siw = vScw[nIDi]; + const g2o::Sim3 Swi = Siw.inverse(); + + for(set::const_iterator sit=spConnections.begin(), send=spConnections.end(); sit!=send; sit++) + { + const long unsigned int nIDj = (*sit)->mnId; + if((nIDi!=pCurKF->mnId || nIDj!=pLoopKF->mnId) && pKF->GetWeight(*sit)setVertex(1, dynamic_cast(optimizer.vertex(nIDj))); + e->setVertex(0, dynamic_cast(optimizer.vertex(nIDi))); + e->setMeasurement(Sji); + + e->information() = matLambda; + + optimizer.addEdge(e); + count_loop++; + sInsertedEdges.insert(make_pair(min(nIDi,nIDj),max(nIDi,nIDj))); + } + } + + int count_spa_tree = 0; + int count_cov = 0; + int count_imu = 0; + int count_kf = 0; + // Set normal edges + for(size_t i=0, iend=vpKFs.size(); imnId; + + g2o::Sim3 Swi; + + LoopClosing::KeyFrameAndPose::const_iterator iti = NonCorrectedSim3.find(pKF); + + if(iti!=NonCorrectedSim3.end()) + Swi = (iti->second).inverse(); + else + Swi = vScw[nIDi].inverse(); + + KeyFrame* pParentKF = pKF->GetParent(); + + // Spanning tree edge + if(pParentKF) + { + int nIDj = pParentKF->mnId; + + g2o::Sim3 Sjw; + + LoopClosing::KeyFrameAndPose::const_iterator itj = NonCorrectedSim3.find(pParentKF); + + if(itj!=NonCorrectedSim3.end()) + Sjw = itj->second; + else + Sjw = vScw[nIDj]; + + g2o::Sim3 Sji = Sjw * Swi; + + g2o::EdgeSim3* e = new g2o::EdgeSim3(); + e->setVertex(1, dynamic_cast(optimizer.vertex(nIDj))); + e->setVertex(0, dynamic_cast(optimizer.vertex(nIDi))); + e->setMeasurement(Sji); + count_kf++; + count_spa_tree++; + e->information() = matLambda; + optimizer.addEdge(e); + } + + // Loop edges + const set sLoopEdges = pKF->GetLoopEdges(); + for(set::const_iterator sit=sLoopEdges.begin(), send=sLoopEdges.end(); sit!=send; sit++) + { + KeyFrame* pLKF = *sit; + if(pLKF->mnIdmnId) + { + g2o::Sim3 Slw; + + LoopClosing::KeyFrameAndPose::const_iterator itl = NonCorrectedSim3.find(pLKF); + + if(itl!=NonCorrectedSim3.end()) + Slw = itl->second; + else + Slw = vScw[pLKF->mnId]; + + g2o::Sim3 Sli = Slw * Swi; + g2o::EdgeSim3* el = new g2o::EdgeSim3(); + el->setVertex(1, dynamic_cast(optimizer.vertex(pLKF->mnId))); + el->setVertex(0, dynamic_cast(optimizer.vertex(nIDi))); + el->setMeasurement(Sli); + el->information() = matLambda; + optimizer.addEdge(el); + count_kf++; + count_loop++; + } + } + + // Covisibility graph edges + const vector vpConnectedKFs = pKF->GetCovisiblesByWeight(minFeat); + for(vector::const_iterator vit=vpConnectedKFs.begin(); vit!=vpConnectedKFs.end(); vit++) + { + KeyFrame* pKFn = *vit; + if(pKFn && pKFn!=pParentKF && !pKF->hasChild(pKFn) && !sLoopEdges.count(pKFn)) + { + if(!pKFn->isBad() && pKFn->mnIdmnId) + { + if(sInsertedEdges.count(make_pair(min(pKF->mnId,pKFn->mnId),max(pKF->mnId,pKFn->mnId)))) + continue; + + g2o::Sim3 Snw; + + LoopClosing::KeyFrameAndPose::const_iterator itn = NonCorrectedSim3.find(pKFn); + + if(itn!=NonCorrectedSim3.end()) + Snw = itn->second; + else + Snw = vScw[pKFn->mnId]; + + g2o::Sim3 Sni = Snw * Swi; + + g2o::EdgeSim3* en = new g2o::EdgeSim3(); + en->setVertex(1, dynamic_cast(optimizer.vertex(pKFn->mnId))); + en->setVertex(0, dynamic_cast(optimizer.vertex(nIDi))); + en->setMeasurement(Sni); + en->information() = matLambda; + optimizer.addEdge(en); + count_kf++; + count_cov++; + } + } + } + + // Inertial edges if inertial + if(pKF->bImu && pKF->mPrevKF) + { + g2o::Sim3 Spw; + LoopClosing::KeyFrameAndPose::const_iterator itp = NonCorrectedSim3.find(pKF->mPrevKF); + if(itp!=NonCorrectedSim3.end()) + Spw = itp->second; + else + Spw = vScw[pKF->mPrevKF->mnId]; + + g2o::Sim3 Spi = Spw * Swi; + g2o::EdgeSim3* ep = new g2o::EdgeSim3(); + ep->setVertex(1, dynamic_cast(optimizer.vertex(pKF->mPrevKF->mnId))); + ep->setVertex(0, dynamic_cast(optimizer.vertex(nIDi))); + ep->setMeasurement(Spi); + ep->information() = matLambda; + optimizer.addEdge(ep); + count_kf++; + count_imu++; + } + /*if(count_kf<3) + cout << "EG: kf with " << count_kf << " edges!! ID: " << pKF->mnId << endl;*/ + } + + //cout << "EG: Number of KFs: " << vpKFs.size() << endl; + //cout << "EG: spaning tree edges: " << count_spa_tree << endl; + //cout << "EG: Loop edges: " << count_loop << endl; + //cout << "EG: covisible edges: " << count_cov << endl; + //cout << "EG: imu edges: " << count_imu << endl; + // Optimize! + optimizer.initializeOptimization(); + optimizer.computeActiveErrors(); + float err0 = optimizer.activeRobustChi2(); + optimizer.optimize(20); + optimizer.computeActiveErrors(); + float errEnd = optimizer.activeRobustChi2(); + //cout << "err_0/err_end: " << err0 << "/" << errEnd << endl; + unique_lock lock(pMap->mMutexMapUpdate); + + // SE3 Pose Recovering. Sim3:[sR t;0 1] -> SE3:[R t/s;0 1] + for(size_t i=0;imnId; + + g2o::VertexSim3Expmap* VSim3 = static_cast(optimizer.vertex(nIDi)); + g2o::Sim3 CorrectedSiw = VSim3->estimate(); + vCorrectedSwc[nIDi]=CorrectedSiw.inverse(); + Eigen::Matrix3d eigR = CorrectedSiw.rotation().toRotationMatrix(); + Eigen::Vector3d eigt = CorrectedSiw.translation(); + double s = CorrectedSiw.scale(); + + eigt *=(1./s); //[R t/s;0 1] + + cv::Mat Tiw = Converter::toCvSE3(eigR,eigt); + + pKFi->SetPose(Tiw); + // cout << "angle KF " << nIDi << ": " << (180.0/3.1415)*acos(vZvectors[nIDi].dot(eigR*z_vec)) << endl; + + } + + // Correct points. Transform to "non-optimized" reference keyframe pose and transform back with optimized pose + for(size_t i=0, iend=vpMPs.size(); iisBad()) + continue; + + int nIDr; + if(pMP->mnCorrectedByKF==pCurKF->mnId) + { + nIDr = pMP->mnCorrectedReference; + } + else + { + KeyFrame* pRefKF = pMP->GetReferenceKeyFrame(); + nIDr = pRefKF->mnId; + } + + + g2o::Sim3 Srw = vScw[nIDr]; + g2o::Sim3 correctedSwr = vCorrectedSwc[nIDr]; + + cv::Mat P3Dw = pMP->GetWorldPos(); + Eigen::Matrix eigP3Dw = Converter::toVector3d(P3Dw); + Eigen::Matrix eigCorrectedP3Dw = correctedSwr.map(Srw.map(eigP3Dw)); + + cv::Mat cvCorrectedP3Dw = Converter::toCvMat(eigCorrectedP3Dw); + pMP->SetWorldPos(cvCorrectedP3Dw); + + pMP->UpdateNormalAndDepth(); + } + + // TODO Check this changeindex + pMap->IncreaseChangeIndex(); +} + +void Optimizer::OptimizeEssentialGraph6DoF(KeyFrame* pCurKF, vector &vpFixedKFs, vector &vpFixedCorrectedKFs, + vector &vpNonFixedKFs, vector &vpNonCorrectedMPs, double scale) +{ + Verbose::PrintMess("Opt_Essential: There are " + to_string(vpFixedKFs.size()) + " KFs fixed in the merged map", Verbose::VERBOSITY_DEBUG); + Verbose::PrintMess("Opt_Essential: There are " + to_string(vpFixedCorrectedKFs.size()) + " KFs fixed in the old map", Verbose::VERBOSITY_DEBUG); + Verbose::PrintMess("Opt_Essential: There are " + to_string(vpNonFixedKFs.size()) + " KFs non-fixed in the merged map", Verbose::VERBOSITY_DEBUG); + Verbose::PrintMess("Opt_Essential: There are " + to_string(vpNonCorrectedMPs.size()) + " MPs non-corrected in the merged map", Verbose::VERBOSITY_DEBUG); + + g2o::SparseOptimizer optimizer; + optimizer.setVerbose(false); + g2o::BlockSolver_6_3::LinearSolverType * linearSolver = + new g2o::LinearSolverEigen(); + g2o::BlockSolver_6_3 * solver_ptr= new g2o::BlockSolver_6_3(linearSolver); + g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg(solver_ptr); + + solver->setUserLambdaInit(1e-16); + optimizer.setAlgorithm(solver); + + Map* pMap = pCurKF->GetMap(); + const unsigned int nMaxKFid = pMap->GetMaxKFid(); + + vector > vScw(nMaxKFid+1); + vector > vScw_bef(nMaxKFid+1); + vector > vCorrectedSwc(nMaxKFid+1); + vector vpVertices(nMaxKFid+1); + vector vbFromOtherMap(nMaxKFid+1); + + const int minFeat = 100; + + + for(KeyFrame* pKFi : vpFixedKFs) + { + if(pKFi->isBad()) + continue; + + g2o::VertexSE3Expmap* VSE3 = new g2o::VertexSE3Expmap(); + + const int nIDi = pKFi->mnId; + + Eigen::Matrix Rcw = Converter::toMatrix3d(pKFi->GetRotation()); + Eigen::Matrix tcw = Converter::toVector3d(pKFi->GetTranslation()); + g2o::SE3Quat Siw(Rcw,tcw); + vScw[nIDi] = Siw; + vCorrectedSwc[nIDi]=Siw.inverse(); // This KFs mustn't be corrected + VSE3->setEstimate(Siw); + + VSE3->setFixed(true); + + VSE3->setId(nIDi); + VSE3->setMarginalized(false); + //VSim3->_fix_scale = true; //TODO + vbFromOtherMap[nIDi] = false; + + optimizer.addVertex(VSE3); + + vpVertices[nIDi]=VSE3; + } + cout << "Opt_Essential: vpFixedKFs loaded" << endl; + + set sIdKF; + for(KeyFrame* pKFi : vpFixedCorrectedKFs) + { + if(pKFi->isBad()) + continue; + + g2o::VertexSE3Expmap* VSE3 = new g2o::VertexSE3Expmap(); + + const int nIDi = pKFi->mnId; + + Eigen::Matrix Rcw = Converter::toMatrix3d(pKFi->GetRotation()); + Eigen::Matrix tcw = Converter::toVector3d(pKFi->GetTranslation()); + g2o::SE3Quat Siw(Rcw,tcw); + vScw[nIDi] = Siw; + vCorrectedSwc[nIDi]=Siw.inverse(); // This KFs mustn't be corrected + VSE3->setEstimate(Siw); + + cv::Mat Tcw_bef = pKFi->mTcwBefMerge; + Eigen::Matrix Rcw_bef = Converter::toMatrix3d(Tcw_bef.rowRange(0,3).colRange(0,3)); + Eigen::Matrix tcw_bef = Converter::toVector3d(Tcw_bef.rowRange(0,3).col(3)) / scale; + vScw_bef[nIDi] = g2o::SE3Quat(Rcw_bef,tcw_bef); + + VSE3->setFixed(true); + + VSE3->setId(nIDi); + VSE3->setMarginalized(false); + //VSim3->_fix_scale = true; + vbFromOtherMap[nIDi] = true; + + optimizer.addVertex(VSE3); + + vpVertices[nIDi]=VSE3; + + sIdKF.insert(nIDi); + } + Verbose::PrintMess("Opt_Essential: vpFixedCorrectedKFs loaded", Verbose::VERBOSITY_DEBUG); + + for(KeyFrame* pKFi : vpNonFixedKFs) + { + if(pKFi->isBad()) + continue; + + const int nIDi = pKFi->mnId; + + if(sIdKF.count(nIDi)) // It has already added in the corrected merge KFs + continue; + + g2o::VertexSE3Expmap* VSE3 = new g2o::VertexSE3Expmap(); + + //cv::Mat Tcw = pKFi->mTcwBefMerge; + //Eigen::Matrix Rcw = Converter::toMatrix3d(Tcw.rowRange(0,3).colRange(0,3)); + //Eigen::Matrix tcw = Converter::toVector3d(Tcw.rowRange(0,3).col(3)); + Eigen::Matrix Rcw = Converter::toMatrix3d(pKFi->GetRotation()); + Eigen::Matrix tcw = Converter::toVector3d(pKFi->GetTranslation()) / scale; + g2o::SE3Quat Siw(Rcw,tcw); + vScw_bef[nIDi] = Siw; + VSE3->setEstimate(Siw); + + VSE3->setFixed(false); + + VSE3->setId(nIDi); + VSE3->setMarginalized(false); + //VSim3->_fix_scale = true; + vbFromOtherMap[nIDi] = true; + + optimizer.addVertex(VSE3); + + vpVertices[nIDi]=VSE3; + + sIdKF.insert(nIDi); + + } + Verbose::PrintMess("Opt_Essential: vpNonFixedKFs loaded", Verbose::VERBOSITY_DEBUG); + + vector vpKFs; + vpKFs.reserve(vpFixedKFs.size() + vpFixedCorrectedKFs.size() + vpNonFixedKFs.size()); + vpKFs.insert(vpKFs.end(),vpFixedKFs.begin(),vpFixedKFs.end()); + vpKFs.insert(vpKFs.end(),vpFixedCorrectedKFs.begin(),vpFixedCorrectedKFs.end()); + vpKFs.insert(vpKFs.end(),vpNonFixedKFs.begin(),vpNonFixedKFs.end()); + set spKFs(vpKFs.begin(), vpKFs.end()); + + Verbose::PrintMess("Opt_Essential: List of KF loaded", Verbose::VERBOSITY_DEBUG); + + const Eigen::Matrix matLambda = Eigen::Matrix::Identity(); + + for(KeyFrame* pKFi : vpKFs) + { + int num_connections = 0; + const int nIDi = pKFi->mnId; + + g2o::SE3Quat Swi = vScw[nIDi].inverse(); + g2o::SE3Quat Swi_bef; + if(vbFromOtherMap[nIDi]) + { + Swi_bef = vScw_bef[nIDi].inverse(); + } + /*if(pKFi->mnMergeCorrectedForKF == pCurKF->mnId) + { + Swi = vScw[nIDi].inverse(); + } + else + { + cv::Mat Twi = pKFi->mTwcBefMerge; + Swi = g2o::Sim3(Converter::toMatrix3d(Twi.rowRange(0, 3).colRange(0, 3)), + Converter::toVector3d(Twi.rowRange(0, 3).col(3)),1.0); + }*/ + + + KeyFrame* pParentKFi = pKFi->GetParent(); + + // Spanning tree edge + if(pParentKFi && spKFs.find(pParentKFi) != spKFs.end()) + { + int nIDj = pParentKFi->mnId; + + g2o::SE3Quat Sjw = vScw[nIDj]; + g2o::SE3Quat Sjw_bef; + if(vbFromOtherMap[nIDj]) + { + Sjw_bef = vScw_bef[nIDj]; + } + + /*if(pParentKFi->mnMergeCorrectedForKF == pCurKF->mnId) + { + Sjw = vScw[nIDj]; + } + else + { + cv::Mat Tjw = pParentKFi->mTcwBefMerge; + Sjw = g2o::Sim3(Converter::toMatrix3d(Tjw.rowRange(0, 3).colRange(0, 3)), + Converter::toVector3d(Tjw.rowRange(0, 3).col(3)),1.0); + }*/ + + g2o::SE3Quat Sji; + + if(vbFromOtherMap[nIDi] && vbFromOtherMap[nIDj]) + { + Sji = Sjw_bef * Swi_bef; + } + else + { + Sji = Sjw * Swi; + } + + g2o::EdgeSE3* e = new g2o::EdgeSE3(); + e->setVertex(1, dynamic_cast(optimizer.vertex(nIDj))); + e->setVertex(0, dynamic_cast(optimizer.vertex(nIDi))); + e->setMeasurement(Sji); + + e->information() = matLambda; + optimizer.addEdge(e); + num_connections++; + } + + // Loop edges + const set sLoopEdges = pKFi->GetLoopEdges(); + for(set::const_iterator sit=sLoopEdges.begin(), send=sLoopEdges.end(); sit!=send; sit++) + { + KeyFrame* pLKF = *sit; + if(spKFs.find(pLKF) != spKFs.end() && pLKF->mnIdmnId) + { + g2o::SE3Quat Slw = vScw[pLKF->mnId]; + g2o::SE3Quat Slw_bef; + if(vbFromOtherMap[pLKF->mnId]) + { + Slw_bef = vScw_bef[pLKF->mnId]; + } + + /*if(pLKF->mnMergeCorrectedForKF == pCurKF->mnId) + { + Slw = vScw[pLKF->mnId]; + } + else + { + cv::Mat Tlw = pLKF->mTcwBefMerge; + Slw = g2o::Sim3(Converter::toMatrix3d(Tlw.rowRange(0, 3).colRange(0, 3)), + Converter::toVector3d(Tlw.rowRange(0, 3).col(3)),1.0); + }*/ + + g2o::SE3Quat Sli; + + if(vbFromOtherMap[nIDi] && vbFromOtherMap[pLKF->mnId]) + { + Sli = Slw_bef * Swi_bef; + } + else + { + Sli = Slw * Swi; + } + + g2o::EdgeSE3* el = new g2o::EdgeSE3(); + el->setVertex(1, dynamic_cast(optimizer.vertex(pLKF->mnId))); + el->setVertex(0, dynamic_cast(optimizer.vertex(nIDi))); + el->setMeasurement(Sli); + el->information() = matLambda; + optimizer.addEdge(el); + num_connections++; + } + } + + // Covisibility graph edges + const vector vpConnectedKFs = pKFi->GetCovisiblesByWeight(minFeat); + for(vector::const_iterator vit=vpConnectedKFs.begin(); vit!=vpConnectedKFs.end(); vit++) + { + KeyFrame* pKFn = *vit; + if(pKFn && pKFn!=pParentKFi && !pKFi->hasChild(pKFn) && !sLoopEdges.count(pKFn) && spKFs.find(pKFn) != spKFs.end()) + { + if(!pKFn->isBad() && pKFn->mnIdmnId) + { + g2o::SE3Quat Snw = vScw[pKFn->mnId]; + + g2o::SE3Quat Snw_bef; + if(vbFromOtherMap[pKFn->mnId]) + { + Snw_bef = vScw_bef[pKFn->mnId]; + } + /*if(pKFn->mnMergeCorrectedForKF == pCurKF->mnId) + { + Snw = vScw[pKFn->mnId]; + } + else + { + cv::Mat Tnw = pKFn->mTcwBefMerge; + Snw = g2o::Sim3(Converter::toMatrix3d(Tnw.rowRange(0, 3).colRange(0, 3)), + Converter::toVector3d(Tnw.rowRange(0, 3).col(3)),1.0); + }*/ + + g2o::SE3Quat Sni; + + if(vbFromOtherMap[nIDi] && vbFromOtherMap[pKFn->mnId]) + { + Sni = Snw_bef * Swi_bef; + } + else + { + Sni = Snw * Swi; + } + + g2o::EdgeSE3* en = new g2o::EdgeSE3(); + en->setVertex(1, dynamic_cast(optimizer.vertex(pKFn->mnId))); + en->setVertex(0, dynamic_cast(optimizer.vertex(nIDi))); + en->setMeasurement(Sni); + en->information() = matLambda; + optimizer.addEdge(en); + num_connections++; + } + } + } + + if(num_connections == 0 ) + { + Verbose::PrintMess("Opt_Essential: KF " + to_string(pKFi->mnId) + " has 0 connections", Verbose::VERBOSITY_DEBUG); + } + } + + // Optimize! + optimizer.initializeOptimization(); + optimizer.optimize(20); + + Verbose::PrintMess("Opt_Essential: Finish the optimization", Verbose::VERBOSITY_DEBUG); + + unique_lock lock(pMap->mMutexMapUpdate); + + Verbose::PrintMess("Opt_Essential: Apply the new pose to the KFs", Verbose::VERBOSITY_DEBUG); + // SE3 Pose Recovering. Sim3:[sR t;0 1] -> SE3:[R t/s;0 1] + for(KeyFrame* pKFi : vpNonFixedKFs) + { + if(pKFi->isBad()) + continue; + + const int nIDi = pKFi->mnId; + + g2o::VertexSE3Expmap* VSE3 = static_cast(optimizer.vertex(nIDi)); + g2o::SE3Quat CorrectedSiw = VSE3->estimate(); + vCorrectedSwc[nIDi]=CorrectedSiw.inverse(); + Eigen::Matrix3d eigR = CorrectedSiw.rotation().toRotationMatrix(); + Eigen::Vector3d eigt = CorrectedSiw.translation(); + //double s = CorrectedSiw.scale(); + + //eigt *=(1./s); //[R t/s;0 1] + + cv::Mat Tiw = Converter::toCvSE3(eigR,eigt); + + /*{ + cv::Mat Tco_cn = pKFi->GetPose() * Tiw.inv(); + cv::Vec3d trasl = Tco_cn.rowRange(0,3).col(3); + double dist = cv::norm(trasl); + if(dist > 1.0) + { + cout << "--Distance: " << dist << " meters" << endl; + cout << "--To much distance correction in EssentGraph: It has connected " << pKFi->GetVectorCovisibleKeyFrames().size() << " KFs" << endl; + } + + string strNameFile = pKFi->mNameFile; + cv::Mat imLeft = cv::imread(strNameFile, CV_LOAD_IMAGE_UNCHANGED); + + cv::cvtColor(imLeft, imLeft, CV_GRAY2BGR); + + vector vpMapPointsKFi = pKFi->GetMapPointMatches(); + for(int j=0; jisBad()) + { + continue; + } + string strNumOBs = to_string(vpMapPointsKFi[j]->Observations()); + cv::circle(imLeft, pKFi->mvKeys[j].pt, 2, cv::Scalar(0, 255, 0)); + cv::putText(imLeft, strNumOBs, pKFi->mvKeys[j].pt, CV_FONT_HERSHEY_DUPLEX, 1, cv::Scalar(255, 0, 0)); + } + + string namefile = "./test_OptEssent/Essent_" + to_string(pCurKF->mnId) + "_KF" + to_string(pKFi->mnId) +"_D" + to_string(dist) +".png"; + cv::imwrite(namefile, imLeft); + }*/ + + pKFi->mTcwBefMerge = pKFi->GetPose(); + pKFi->mTwcBefMerge = pKFi->GetPoseInverse(); + pKFi->SetPose(Tiw); + } + + Verbose::PrintMess("Opt_Essential: Apply the new pose to the MPs", Verbose::VERBOSITY_DEBUG); + cout << "Opt_Essential: number of points -> " << vpNonCorrectedMPs.size() << endl; + // Correct points. Transform to "non-optimized" reference keyframe pose and transform back with optimized pose + for(MapPoint* pMPi : vpNonCorrectedMPs) + { + if(pMPi->isBad()) + continue; + + //Verbose::PrintMess("Opt_Essential: MP id " + to_string(pMPi->mnId), Verbose::VERBOSITY_DEBUG); + /*int nIDr; + if(pMPi->mnCorrectedByKF==pCurKF->mnId) + { + nIDr = pMPi->mnCorrectedReference; + } + else + { + + }*/ + KeyFrame* pRefKF = pMPi->GetReferenceKeyFrame(); + g2o::SE3Quat Srw; + g2o::SE3Quat correctedSwr; + while(pRefKF->isBad()) + { + if(!pRefKF) + { + Verbose::PrintMess("MP " + to_string(pMPi->mnId) + " without a valid reference KF", Verbose::VERBOSITY_DEBUG); + break; + } + + pMPi->EraseObservation(pRefKF); + pRefKF = pMPi->GetReferenceKeyFrame(); + } + /*if(pRefKF->mnMergeCorrectedForKF == pCurKF->mnId) + { + int nIDr = pRefKF->mnId; + + Srw = vScw[nIDr]; + correctedSwr = vCorrectedSwc[nIDr]; + } + else + {*/ + //cv::Mat TNonCorrectedwr = pRefKF->mTwcBefMerge; + //Eigen::Matrix RNonCorrectedwr = Converter::toMatrix3d(TNonCorrectedwr.rowRange(0,3).colRange(0,3)); + //Eigen::Matrix tNonCorrectedwr = Converter::toVector3d(TNonCorrectedwr.rowRange(0,3).col(3)); + Srw = vScw_bef[pRefKF->mnId]; //g2o::SE3Quat(RNonCorrectedwr,tNonCorrectedwr).inverse(); + + cv::Mat Twr = pRefKF->GetPoseInverse(); + Eigen::Matrix Rwr = Converter::toMatrix3d(Twr.rowRange(0,3).colRange(0,3)); + Eigen::Matrix twr = Converter::toVector3d(Twr.rowRange(0,3).col(3)); + correctedSwr = g2o::SE3Quat(Rwr,twr); + //} + //cout << "Opt_Essential: Loaded the KF reference position" << endl; + + cv::Mat P3Dw = pMPi->GetWorldPos() / scale; + Eigen::Matrix eigP3Dw = Converter::toVector3d(P3Dw); + Eigen::Matrix eigCorrectedP3Dw = correctedSwr.map(Srw.map(eigP3Dw)); + + //cout << "Opt_Essential: Calculated the new MP position" << endl; + cv::Mat cvCorrectedP3Dw = Converter::toCvMat(eigCorrectedP3Dw); + //cout << "Opt_Essential: Converted the position to the OpenCV format" << endl; + pMPi->SetWorldPos(cvCorrectedP3Dw); + //cout << "Opt_Essential: Loaded the corrected position in the MP object" << endl; + + pMPi->UpdateNormalAndDepth(); + } + + Verbose::PrintMess("Opt_Essential: End of the optimization", Verbose::VERBOSITY_DEBUG); +} + +void Optimizer::OptimizeEssentialGraph(KeyFrame* pCurKF, vector &vpFixedKFs, vector &vpFixedCorrectedKFs, + vector &vpNonFixedKFs, vector &vpNonCorrectedMPs) +{ + Verbose::PrintMess("Opt_Essential: There are " + to_string(vpFixedKFs.size()) + " KFs fixed in the merged map", Verbose::VERBOSITY_DEBUG); + Verbose::PrintMess("Opt_Essential: There are " + to_string(vpFixedCorrectedKFs.size()) + " KFs fixed in the old map", Verbose::VERBOSITY_DEBUG); + Verbose::PrintMess("Opt_Essential: There are " + to_string(vpNonFixedKFs.size()) + " KFs non-fixed in the merged map", Verbose::VERBOSITY_DEBUG); + Verbose::PrintMess("Opt_Essential: There are " + to_string(vpNonCorrectedMPs.size()) + " MPs non-corrected in the merged map", Verbose::VERBOSITY_DEBUG); + + g2o::SparseOptimizer optimizer; + optimizer.setVerbose(false); + g2o::BlockSolver_7_3::LinearSolverType * linearSolver = + new g2o::LinearSolverEigen(); + g2o::BlockSolver_7_3 * solver_ptr= new g2o::BlockSolver_7_3(linearSolver); + g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg(solver_ptr); + + solver->setUserLambdaInit(1e-16); + optimizer.setAlgorithm(solver); + + Map* pMap = pCurKF->GetMap(); + const unsigned int nMaxKFid = pMap->GetMaxKFid(); + + vector > vScw(nMaxKFid+1); + vector > vCorrectedSwc(nMaxKFid+1); + vector vpVertices(nMaxKFid+1); + + const int minFeat = 100; + + + for(KeyFrame* pKFi : vpFixedKFs) + { + if(pKFi->isBad()) + continue; + + g2o::VertexSim3Expmap* VSim3 = new g2o::VertexSim3Expmap(); + + const int nIDi = pKFi->mnId; + + Eigen::Matrix Rcw = Converter::toMatrix3d(pKFi->GetRotation()); + Eigen::Matrix tcw = Converter::toVector3d(pKFi->GetTranslation()); + g2o::Sim3 Siw(Rcw,tcw,1.0); + vScw[nIDi] = Siw; + vCorrectedSwc[nIDi]=Siw.inverse(); // This KFs mustn't be corrected + VSim3->setEstimate(Siw); + + VSim3->setFixed(true); + + VSim3->setId(nIDi); + VSim3->setMarginalized(false); + VSim3->_fix_scale = true; //TODO + + optimizer.addVertex(VSim3); + + vpVertices[nIDi]=VSim3; + } + Verbose::PrintMess("Opt_Essential: vpFixedKFs loaded", Verbose::VERBOSITY_DEBUG); + + set sIdKF; + for(KeyFrame* pKFi : vpFixedCorrectedKFs) + { + if(pKFi->isBad()) + continue; + + g2o::VertexSim3Expmap* VSim3 = new g2o::VertexSim3Expmap(); + + const int nIDi = pKFi->mnId; + + Eigen::Matrix Rcw = Converter::toMatrix3d(pKFi->GetRotation()); + Eigen::Matrix tcw = Converter::toVector3d(pKFi->GetTranslation()); + g2o::Sim3 Siw(Rcw,tcw,1.0); + //vScw[nIDi] = Siw; + vCorrectedSwc[nIDi]=Siw.inverse(); // This KFs mustn't be corrected + VSim3->setEstimate(Siw); + + cv::Mat Tcw_bef = pKFi->mTcwBefMerge; + Eigen::Matrix Rcw_bef = Converter::toMatrix3d(Tcw_bef.rowRange(0,3).colRange(0,3)); + Eigen::Matrix tcw_bef = Converter::toVector3d(Tcw_bef.rowRange(0,3).col(3)); + vScw[nIDi] = g2o::Sim3(Rcw_bef,tcw_bef,1.0); + + VSim3->setFixed(true); + + VSim3->setId(nIDi); + VSim3->setMarginalized(false); + + optimizer.addVertex(VSim3); + + vpVertices[nIDi]=VSim3; + + sIdKF.insert(nIDi); + } + Verbose::PrintMess("Opt_Essential: vpFixedCorrectedKFs loaded", Verbose::VERBOSITY_DEBUG); + + for(KeyFrame* pKFi : vpNonFixedKFs) + { + if(pKFi->isBad()) + continue; + + const int nIDi = pKFi->mnId; + + if(sIdKF.count(nIDi)) // It has already added in the corrected merge KFs + continue; + + g2o::VertexSim3Expmap* VSim3 = new g2o::VertexSim3Expmap(); + + //cv::Mat Tcw = pKFi->mTcwBefMerge; + //Eigen::Matrix Rcw = Converter::toMatrix3d(Tcw.rowRange(0,3).colRange(0,3)); + //Eigen::Matrix tcw = Converter::toVector3d(Tcw.rowRange(0,3).col(3)); + Eigen::Matrix Rcw = Converter::toMatrix3d(pKFi->GetRotation()); + Eigen::Matrix tcw = Converter::toVector3d(pKFi->GetTranslation()); + g2o::Sim3 Siw(Rcw,tcw,1.0); + vScw[nIDi] = Siw; + VSim3->setEstimate(Siw); + + VSim3->setFixed(false); + + VSim3->setId(nIDi); + VSim3->setMarginalized(false); + + optimizer.addVertex(VSim3); + + vpVertices[nIDi]=VSim3; + + sIdKF.insert(nIDi); + + } + Verbose::PrintMess("Opt_Essential: vpNonFixedKFs loaded", Verbose::VERBOSITY_DEBUG); + + vector vpKFs; + vpKFs.reserve(vpFixedKFs.size() + vpFixedCorrectedKFs.size() + vpNonFixedKFs.size()); + vpKFs.insert(vpKFs.end(),vpFixedKFs.begin(),vpFixedKFs.end()); + vpKFs.insert(vpKFs.end(),vpFixedCorrectedKFs.begin(),vpFixedCorrectedKFs.end()); + vpKFs.insert(vpKFs.end(),vpNonFixedKFs.begin(),vpNonFixedKFs.end()); + set spKFs(vpKFs.begin(), vpKFs.end()); + + Verbose::PrintMess("Opt_Essential: List of KF loaded", Verbose::VERBOSITY_DEBUG); + + const Eigen::Matrix matLambda = Eigen::Matrix::Identity(); + + for(KeyFrame* pKFi : vpKFs) + { + int num_connections = 0; + const int nIDi = pKFi->mnId; + + g2o::Sim3 Swi = vScw[nIDi].inverse(); + /*if(pKFi->mnMergeCorrectedForKF == pCurKF->mnId) + { + Swi = vScw[nIDi].inverse(); + } + else + { + cv::Mat Twi = pKFi->mTwcBefMerge; + Swi = g2o::Sim3(Converter::toMatrix3d(Twi.rowRange(0, 3).colRange(0, 3)), + Converter::toVector3d(Twi.rowRange(0, 3).col(3)),1.0); + }*/ + + + KeyFrame* pParentKFi = pKFi->GetParent(); + + // Spanning tree edge + if(pParentKFi && spKFs.find(pParentKFi) != spKFs.end()) + { + int nIDj = pParentKFi->mnId; + + g2o::Sim3 Sjw = vScw[nIDj]; + + /*if(pParentKFi->mnMergeCorrectedForKF == pCurKF->mnId) + { + Sjw = vScw[nIDj]; + } + else + { + cv::Mat Tjw = pParentKFi->mTcwBefMerge; + Sjw = g2o::Sim3(Converter::toMatrix3d(Tjw.rowRange(0, 3).colRange(0, 3)), + Converter::toVector3d(Tjw.rowRange(0, 3).col(3)),1.0); + }*/ + + g2o::Sim3 Sji = Sjw * Swi; + + g2o::EdgeSim3* e = new g2o::EdgeSim3(); + e->setVertex(1, dynamic_cast(optimizer.vertex(nIDj))); + e->setVertex(0, dynamic_cast(optimizer.vertex(nIDi))); + e->setMeasurement(Sji); + + e->information() = matLambda; + optimizer.addEdge(e); + num_connections++; + } + + // Loop edges + const set sLoopEdges = pKFi->GetLoopEdges(); + for(set::const_iterator sit=sLoopEdges.begin(), send=sLoopEdges.end(); sit!=send; sit++) + { + KeyFrame* pLKF = *sit; + if(spKFs.find(pLKF) != spKFs.end() && pLKF->mnIdmnId) + { + g2o::Sim3 Slw = vScw[pLKF->mnId]; + + /*if(pLKF->mnMergeCorrectedForKF == pCurKF->mnId) + { + Slw = vScw[pLKF->mnId]; + } + else + { + cv::Mat Tlw = pLKF->mTcwBefMerge; + Slw = g2o::Sim3(Converter::toMatrix3d(Tlw.rowRange(0, 3).colRange(0, 3)), + Converter::toVector3d(Tlw.rowRange(0, 3).col(3)),1.0); + }*/ + + g2o::Sim3 Sli = Slw * Swi; + g2o::EdgeSim3* el = new g2o::EdgeSim3(); + el->setVertex(1, dynamic_cast(optimizer.vertex(pLKF->mnId))); + el->setVertex(0, dynamic_cast(optimizer.vertex(nIDi))); + el->setMeasurement(Sli); + el->information() = matLambda; + optimizer.addEdge(el); + num_connections++; + } + } + + // Covisibility graph edges + const vector vpConnectedKFs = pKFi->GetCovisiblesByWeight(minFeat); + for(vector::const_iterator vit=vpConnectedKFs.begin(); vit!=vpConnectedKFs.end(); vit++) + { + KeyFrame* pKFn = *vit; + if(pKFn && pKFn!=pParentKFi && !pKFi->hasChild(pKFn) && !sLoopEdges.count(pKFn) && spKFs.find(pKFn) != spKFs.end()) + { + if(!pKFn->isBad() && pKFn->mnIdmnId) + { + + g2o::Sim3 Snw = vScw[pKFn->mnId]; + /*if(pKFn->mnMergeCorrectedForKF == pCurKF->mnId) + { + Snw = vScw[pKFn->mnId]; + } + else + { + cv::Mat Tnw = pKFn->mTcwBefMerge; + Snw = g2o::Sim3(Converter::toMatrix3d(Tnw.rowRange(0, 3).colRange(0, 3)), + Converter::toVector3d(Tnw.rowRange(0, 3).col(3)),1.0); + }*/ + + g2o::Sim3 Sni = Snw * Swi; + + g2o::EdgeSim3* en = new g2o::EdgeSim3(); + en->setVertex(1, dynamic_cast(optimizer.vertex(pKFn->mnId))); + en->setVertex(0, dynamic_cast(optimizer.vertex(nIDi))); + en->setMeasurement(Sni); + en->information() = matLambda; + optimizer.addEdge(en); + num_connections++; + } + } + } + + if(num_connections == 0 ) + { + Verbose::PrintMess("Opt_Essential: KF " + to_string(pKFi->mnId) + " has 0 connections", Verbose::VERBOSITY_DEBUG); + } + } + + // Optimize! + optimizer.initializeOptimization(); + optimizer.optimize(20); + + Verbose::PrintMess("Opt_Essential: Finish the optimization", Verbose::VERBOSITY_DEBUG); + + unique_lock lock(pMap->mMutexMapUpdate); + + Verbose::PrintMess("Opt_Essential: Apply the new pose to the KFs", Verbose::VERBOSITY_DEBUG); + // SE3 Pose Recovering. Sim3:[sR t;0 1] -> SE3:[R t/s;0 1] + for(KeyFrame* pKFi : vpNonFixedKFs) + { + if(pKFi->isBad()) + continue; + + const int nIDi = pKFi->mnId; + + g2o::VertexSim3Expmap* VSim3 = static_cast(optimizer.vertex(nIDi)); + g2o::Sim3 CorrectedSiw = VSim3->estimate(); + vCorrectedSwc[nIDi]=CorrectedSiw.inverse(); + Eigen::Matrix3d eigR = CorrectedSiw.rotation().toRotationMatrix(); + Eigen::Vector3d eigt = CorrectedSiw.translation(); + double s = CorrectedSiw.scale(); + + eigt *=(1./s); //[R t/s;0 1] + + cv::Mat Tiw = Converter::toCvSE3(eigR,eigt); + + /*{ + cv::Mat Tco_cn = pKFi->GetPose() * Tiw.inv(); + cv::Vec3d trasl = Tco_cn.rowRange(0,3).col(3); + double dist = cv::norm(trasl); + if(dist > 1.0) + { + cout << "--Distance: " << dist << " meters" << endl; + cout << "--To much distance correction in EssentGraph: It has connected " << pKFi->GetVectorCovisibleKeyFrames().size() << " KFs" << endl; + } + string strNameFile = pKFi->mNameFile; + cv::Mat imLeft = cv::imread(strNameFile, CV_LOAD_IMAGE_UNCHANGED); + cv::cvtColor(imLeft, imLeft, CV_GRAY2BGR); + vector vpMapPointsKFi = pKFi->GetMapPointMatches(); + for(int j=0; jisBad()) + { + continue; + } + string strNumOBs = to_string(vpMapPointsKFi[j]->Observations()); + cv::circle(imLeft, pKFi->mvKeys[j].pt, 2, cv::Scalar(0, 255, 0)); + cv::putText(imLeft, strNumOBs, pKFi->mvKeys[j].pt, CV_FONT_HERSHEY_DUPLEX, 1, cv::Scalar(255, 0, 0)); + } + string namefile = "./test_OptEssent/Essent_" + to_string(pCurKF->mnId) + "_KF" + to_string(pKFi->mnId) +"_D" + to_string(dist) +".png"; + cv::imwrite(namefile, imLeft); + }*/ + + pKFi->mTcwBefMerge = pKFi->GetPose(); + pKFi->mTwcBefMerge = pKFi->GetPoseInverse(); + pKFi->SetPose(Tiw); + } + + Verbose::PrintMess("Opt_Essential: Apply the new pose to the MPs", Verbose::VERBOSITY_DEBUG); + // Correct points. Transform to "non-optimized" reference keyframe pose and transform back with optimized pose + for(MapPoint* pMPi : vpNonCorrectedMPs) + { + if(pMPi->isBad()) + continue; + + Verbose::PrintMess("Opt_Essential: MP id " + to_string(pMPi->mnId), Verbose::VERBOSITY_DEBUG); + /*int nIDr; + if(pMPi->mnCorrectedByKF==pCurKF->mnId) + { + nIDr = pMPi->mnCorrectedReference; + } + else + { + }*/ + KeyFrame* pRefKF = pMPi->GetReferenceKeyFrame(); + g2o::Sim3 Srw; + g2o::Sim3 correctedSwr; + while(pRefKF->isBad()) + { + if(!pRefKF) + { + Verbose::PrintMess("MP " + to_string(pMPi->mnId) + " without a valid reference KF", Verbose::VERBOSITY_DEBUG); + break; + } + + pMPi->EraseObservation(pRefKF); + pRefKF = pMPi->GetReferenceKeyFrame(); + } + /*if(pRefKF->mnMergeCorrectedForKF == pCurKF->mnId) + { + int nIDr = pRefKF->mnId; + Srw = vScw[nIDr]; + correctedSwr = vCorrectedSwc[nIDr]; + } + else + {*/ + cv::Mat TNonCorrectedwr = pRefKF->mTwcBefMerge; + Eigen::Matrix RNonCorrectedwr = Converter::toMatrix3d(TNonCorrectedwr.rowRange(0,3).colRange(0,3)); + Eigen::Matrix tNonCorrectedwr = Converter::toVector3d(TNonCorrectedwr.rowRange(0,3).col(3)); + Srw = g2o::Sim3(RNonCorrectedwr,tNonCorrectedwr,1.0).inverse(); + + cv::Mat Twr = pRefKF->GetPoseInverse(); + Eigen::Matrix Rwr = Converter::toMatrix3d(Twr.rowRange(0,3).colRange(0,3)); + Eigen::Matrix twr = Converter::toVector3d(Twr.rowRange(0,3).col(3)); + correctedSwr = g2o::Sim3(Rwr,twr,1.0); + //} + //cout << "Opt_Essential: Loaded the KF reference position" << endl; + + cv::Mat P3Dw = pMPi->GetWorldPos(); + Eigen::Matrix eigP3Dw = Converter::toVector3d(P3Dw); + Eigen::Matrix eigCorrectedP3Dw = correctedSwr.map(Srw.map(eigP3Dw)); + + //cout << "Opt_Essential: Calculated the new MP position" << endl; + cv::Mat cvCorrectedP3Dw = Converter::toCvMat(eigCorrectedP3Dw); + //cout << "Opt_Essential: Converted the position to the OpenCV format" << endl; + pMPi->SetWorldPos(cvCorrectedP3Dw); + //cout << "Opt_Essential: Loaded the corrected position in the MP object" << endl; + + pMPi->UpdateNormalAndDepth(); + } + + Verbose::PrintMess("Opt_Essential: End of the optimization", Verbose::VERBOSITY_DEBUG); +} + +void Optimizer::OptimizeEssentialGraph(KeyFrame* pCurKF, + const LoopClosing::KeyFrameAndPose &NonCorrectedSim3, + const LoopClosing::KeyFrameAndPose &CorrectedSim3) +{ + // Setup optimizer + Map* pMap = pCurKF->GetMap(); + g2o::SparseOptimizer optimizer; + optimizer.setVerbose(false); + g2o::BlockSolver_7_3::LinearSolverType * linearSolver = + new g2o::LinearSolverEigen(); + g2o::BlockSolver_7_3 * solver_ptr= new g2o::BlockSolver_7_3(linearSolver); + g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg(solver_ptr); + + solver->setUserLambdaInit(1e-16); + optimizer.setAlgorithm(solver); + + const vector vpKFs = pMap->GetAllKeyFrames(); + const vector vpMPs = pMap->GetAllMapPoints(); + + const unsigned int nMaxKFid = pMap->GetMaxKFid(); + + vector > vScw(nMaxKFid+1); + vector > vCorrectedSwc(nMaxKFid+1); + vector vpVertices(nMaxKFid+1); + + const int minFeat = 100; // TODO Check. originally 100 + + // Set KeyFrame vertices + for(size_t i=0, iend=vpKFs.size(); iisBad()) + continue; + g2o::VertexSim3Expmap* VSim3 = new g2o::VertexSim3Expmap(); + + const int nIDi = pKF->mnId; + + Eigen::Matrix Rcw = Converter::toMatrix3d(pKF->GetRotation()); + Eigen::Matrix tcw = Converter::toVector3d(pKF->GetTranslation()); + g2o::Sim3 Siw(Rcw,tcw,1.0); + vScw[nIDi] = Siw; + VSim3->setEstimate(Siw); + + if(pKF->mnBALocalForKF==pCurKF->mnId || pKF->mnBAFixedForKF==pCurKF->mnId){ + cout << "fixed fk: " << pKF->mnId << endl; + VSim3->setFixed(true); + } + else + VSim3->setFixed(false); + + VSim3->setId(nIDi); + VSim3->setMarginalized(false); + // TODO Check + // VSim3->_fix_scale = bFixScale; + + optimizer.addVertex(VSim3); + + vpVertices[nIDi]=VSim3; + } + + + set > sInsertedEdges; + + const Eigen::Matrix matLambda = Eigen::Matrix::Identity(); + + int count_edges[3] = {0,0,0}; + // Set normal edges + for(size_t i=0, iend=vpKFs.size(); imnId; + + g2o::Sim3 Swi; + + LoopClosing::KeyFrameAndPose::const_iterator iti = NonCorrectedSim3.find(pKF); + + if(iti!=NonCorrectedSim3.end()) + Swi = (iti->second).inverse(); + else + Swi = vScw[nIDi].inverse(); + + KeyFrame* pParentKF = pKF->GetParent(); + + // Spanning tree edge + if(pParentKF) + { + int nIDj = pParentKF->mnId; + + g2o::Sim3 Sjw; + LoopClosing::KeyFrameAndPose::const_iterator itj = NonCorrectedSim3.find(pParentKF); + + if(itj!=NonCorrectedSim3.end()) + Sjw = itj->second; + else + Sjw = vScw[nIDj]; + + g2o::Sim3 Sji = Sjw * Swi; + + g2o::EdgeSim3* e = new g2o::EdgeSim3(); + e->setVertex(1, dynamic_cast(optimizer.vertex(nIDj))); + e->setVertex(0, dynamic_cast(optimizer.vertex(nIDi))); + e->setMeasurement(Sji); + + e->information() = matLambda; + optimizer.addEdge(e); + count_edges[0]++; + } + + // Loop edges + const set sLoopEdges = pKF->GetLoopEdges(); + for(set::const_iterator sit=sLoopEdges.begin(), send=sLoopEdges.end(); sit!=send; sit++) + { + KeyFrame* pLKF = *sit; + if(pLKF->mnIdmnId) + { + g2o::Sim3 Slw; + LoopClosing::KeyFrameAndPose::const_iterator itl = NonCorrectedSim3.find(pLKF); + + if(itl!=NonCorrectedSim3.end()) + Slw = itl->second; + else + Slw = vScw[pLKF->mnId]; + + g2o::Sim3 Sli = Slw * Swi; + g2o::EdgeSim3* el = new g2o::EdgeSim3(); + el->setVertex(1, dynamic_cast(optimizer.vertex(pLKF->mnId))); + el->setVertex(0, dynamic_cast(optimizer.vertex(nIDi))); + el->setMeasurement(Sli); + el->information() = matLambda; + optimizer.addEdge(el); + count_edges[1]++; + } + } + + // Covisibility graph edges + const vector vpConnectedKFs = pKF->GetCovisiblesByWeight(minFeat); + for(vector::const_iterator vit=vpConnectedKFs.begin(); vit!=vpConnectedKFs.end(); vit++) + { + KeyFrame* pKFn = *vit; + if(pKFn && pKFn!=pParentKF && !pKF->hasChild(pKFn) && !sLoopEdges.count(pKFn)) + { + if(!pKFn->isBad() && pKFn->mnIdmnId) + { + // just one edge between frames + if(sInsertedEdges.count(make_pair(min(pKF->mnId,pKFn->mnId),max(pKF->mnId,pKFn->mnId)))) + continue; + + g2o::Sim3 Snw; + + LoopClosing::KeyFrameAndPose::const_iterator itn = NonCorrectedSim3.find(pKFn); + + if(itn!=NonCorrectedSim3.end()) + Snw = itn->second; + else + Snw = vScw[pKFn->mnId]; + + g2o::Sim3 Sni = Snw * Swi; + + g2o::EdgeSim3* en = new g2o::EdgeSim3(); + en->setVertex(1, dynamic_cast(optimizer.vertex(pKFn->mnId))); + en->setVertex(0, dynamic_cast(optimizer.vertex(nIDi))); + en->setMeasurement(Sni); + en->information() = matLambda; + optimizer.addEdge(en); + count_edges[2]++; + } + } + } + } + + Verbose::PrintMess("edges pose graph: " + to_string(count_edges[0]) + ", " + to_string(count_edges[1]) + ", " + to_string(count_edges[2]), Verbose::VERBOSITY_DEBUG); + // Optimize! + optimizer.initializeOptimization(); + optimizer.setVerbose(false); + optimizer.optimize(20); + + unique_lock lock(pMap->mMutexMapUpdate); + + // SE3 Pose Recovering. Sim3:[sR t;0 1] -> SE3:[R t/s;0 1] + for(size_t i=0;imnId; + + g2o::VertexSim3Expmap* VSim3 = static_cast(optimizer.vertex(nIDi)); + g2o::Sim3 CorrectedSiw = VSim3->estimate(); + vCorrectedSwc[nIDi]=CorrectedSiw.inverse(); + Eigen::Matrix3d eigR = CorrectedSiw.rotation().toRotationMatrix(); + Eigen::Vector3d eigt = CorrectedSiw.translation(); + double s = CorrectedSiw.scale(); + + eigt *=(1./s); //[R t/s;0 1] + + cv::Mat Tiw = Converter::toCvSE3(eigR,eigt); + + pKFi->SetPose(Tiw); + } + + // Correct points. Transform to "non-optimized" reference keyframe pose and transform back with optimized pose + for(size_t i=0, iend=vpMPs.size(); iisBad()) + continue; + + int nIDr; + if(pMP->mnCorrectedByKF==pCurKF->mnId) + { + nIDr = pMP->mnCorrectedReference; + } + else + { + KeyFrame* pRefKF = pMP->GetReferenceKeyFrame(); + nIDr = pRefKF->mnId; + } + + + g2o::Sim3 Srw = vScw[nIDr]; + g2o::Sim3 correctedSwr = vCorrectedSwc[nIDr]; + + cv::Mat P3Dw = pMP->GetWorldPos(); + Eigen::Matrix eigP3Dw = Converter::toVector3d(P3Dw); + Eigen::Matrix eigCorrectedP3Dw = correctedSwr.map(Srw.map(eigP3Dw)); + + cv::Mat cvCorrectedP3Dw = Converter::toCvMat(eigCorrectedP3Dw); + pMP->SetWorldPos(cvCorrectedP3Dw); + + pMP->UpdateNormalAndDepth(); + } + + // TODO Check this changeindex + pMap->IncreaseChangeIndex(); +} + +int Optimizer::OptimizeSim3(KeyFrame *pKF1, KeyFrame *pKF2, vector &vpMatches1, g2o::Sim3 &g2oS12, const float th2, const bool bFixScale) +{ + g2o::SparseOptimizer optimizer; + g2o::BlockSolverX::LinearSolverType * linearSolver; + + linearSolver = new g2o::LinearSolverDense(); + + g2o::BlockSolverX * solver_ptr = new g2o::BlockSolverX(linearSolver); + + g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg(solver_ptr); + optimizer.setAlgorithm(solver); + + // Calibration + const cv::Mat &K1 = pKF1->mK; + const cv::Mat &K2 = pKF2->mK; + + // Camera poses + const cv::Mat R1w = pKF1->GetRotation(); + const cv::Mat t1w = pKF1->GetTranslation(); + const cv::Mat R2w = pKF2->GetRotation(); + const cv::Mat t2w = pKF2->GetTranslation(); + + // Set Sim3 vertex + g2o::VertexSim3Expmap * vSim3 = new g2o::VertexSim3Expmap(); + vSim3->_fix_scale=bFixScale; + vSim3->setEstimate(g2oS12); + vSim3->setId(0); + vSim3->setFixed(false); + vSim3->_principle_point1[0] = K1.at(0,2); + vSim3->_principle_point1[1] = K1.at(1,2); + vSim3->_focal_length1[0] = K1.at(0,0); + vSim3->_focal_length1[1] = K1.at(1,1); + vSim3->_principle_point2[0] = K2.at(0,2); + vSim3->_principle_point2[1] = K2.at(1,2); + vSim3->_focal_length2[0] = K2.at(0,0); + vSim3->_focal_length2[1] = K2.at(1,1); + optimizer.addVertex(vSim3); + + // Set MapPoint vertices + const int N = vpMatches1.size(); + const vector vpMapPoints1 = pKF1->GetMapPointMatches(); + vector vpEdges12; + vector vpEdges21; + vector vnIndexEdge; + + vnIndexEdge.reserve(2*N); + vpEdges12.reserve(2*N); + vpEdges21.reserve(2*N); + + const float deltaHuber = sqrt(th2); + + int nCorrespondences = 0; + + for(int i=0; i(pMP2->GetIndexInKeyFrame(pKF2)); + + if(pMP1 && pMP2) + { + if(!pMP1->isBad() && !pMP2->isBad() && i2>=0) + { + g2o::VertexSBAPointXYZ* vPoint1 = new g2o::VertexSBAPointXYZ(); + cv::Mat P3D1w = pMP1->GetWorldPos(); + cv::Mat P3D1c = R1w*P3D1w + t1w; + vPoint1->setEstimate(Converter::toVector3d(P3D1c)); + vPoint1->setId(id1); + vPoint1->setFixed(true); + optimizer.addVertex(vPoint1); + + g2o::VertexSBAPointXYZ* vPoint2 = new g2o::VertexSBAPointXYZ(); + cv::Mat P3D2w = pMP2->GetWorldPos(); + cv::Mat P3D2c = R2w*P3D2w + t2w; + vPoint2->setEstimate(Converter::toVector3d(P3D2c)); + vPoint2->setId(id2); + vPoint2->setFixed(true); + optimizer.addVertex(vPoint2); + } + else + continue; + } + else + continue; + + nCorrespondences++; + + // Set edge x1 = S12*X2 + Eigen::Matrix obs1; + const cv::KeyPoint &kpUn1 = pKF1->mvKeysUn[i]; + obs1 << kpUn1.pt.x, kpUn1.pt.y; + + g2o::EdgeSim3ProjectXYZ* e12 = new g2o::EdgeSim3ProjectXYZ(); + e12->setVertex(0, dynamic_cast(optimizer.vertex(id2))); + e12->setVertex(1, dynamic_cast(optimizer.vertex(0))); + e12->setMeasurement(obs1); + const float &invSigmaSquare1 = pKF1->mvInvLevelSigma2[kpUn1.octave]; + e12->setInformation(Eigen::Matrix2d::Identity()*invSigmaSquare1); + + g2o::RobustKernelHuber* rk1 = new g2o::RobustKernelHuber; + e12->setRobustKernel(rk1); + rk1->setDelta(deltaHuber); + optimizer.addEdge(e12); + + // Set edge x2 = S21*X1 + Eigen::Matrix obs2; + const cv::KeyPoint &kpUn2 = pKF2->mvKeysUn[i2]; + obs2 << kpUn2.pt.x, kpUn2.pt.y; + + g2o::EdgeInverseSim3ProjectXYZ* e21 = new g2o::EdgeInverseSim3ProjectXYZ(); + + e21->setVertex(0, dynamic_cast(optimizer.vertex(id1))); + e21->setVertex(1, dynamic_cast(optimizer.vertex(0))); + e21->setMeasurement(obs2); + float invSigmaSquare2 = pKF2->mvInvLevelSigma2[kpUn2.octave]; + e21->setInformation(Eigen::Matrix2d::Identity()*invSigmaSquare2); + + g2o::RobustKernelHuber* rk2 = new g2o::RobustKernelHuber; + e21->setRobustKernel(rk2); + rk2->setDelta(deltaHuber); + optimizer.addEdge(e21); + + vpEdges12.push_back(e12); + vpEdges21.push_back(e21); + vnIndexEdge.push_back(i); + } + + // Optimize! + optimizer.initializeOptimization(); + optimizer.optimize(5); + + // Check inliers + int nBad=0; + for(size_t i=0; ichi2()>th2 || e21->chi2()>th2) + { + size_t idx = vnIndexEdge[i]; + vpMatches1[idx]=static_cast(NULL); + optimizer.removeEdge(e12); + optimizer.removeEdge(e21); + vpEdges12[i]=static_cast(NULL); + vpEdges21[i]=static_cast(NULL); + nBad++; + } + } + + int nMoreIterations; + if(nBad>0) + nMoreIterations=10; + else + nMoreIterations=5; + + if(nCorrespondences-nBad<10) + return 0; + + // Optimize again only with inliers + + optimizer.initializeOptimization(); + optimizer.optimize(nMoreIterations); + + int nIn = 0; + for(size_t i=0; ichi2()>th2 || e21->chi2()>th2) + { + size_t idx = vnIndexEdge[i]; + vpMatches1[idx]=static_cast(NULL); + } + else + nIn++; + } + + // Recover optimized Sim3 + g2o::VertexSim3Expmap* vSim3_recov = static_cast(optimizer.vertex(0)); + g2oS12= vSim3_recov->estimate(); + + return nIn; +} + + +int Optimizer::OptimizeSim3(KeyFrame *pKF1, KeyFrame *pKF2, vector &vpMatches1, g2o::Sim3 &g2oS12, const float th2, + const bool bFixScale, Eigen::Matrix &mAcumHessian, const bool bAllPoints) +{ + g2o::SparseOptimizer optimizer; + g2o::BlockSolverX::LinearSolverType * linearSolver; + + linearSolver = new g2o::LinearSolverDense(); + + g2o::BlockSolverX * solver_ptr = new g2o::BlockSolverX(linearSolver); + + g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg(solver_ptr); + optimizer.setAlgorithm(solver); + + // Camera poses + const cv::Mat R1w = pKF1->GetRotation(); + const cv::Mat t1w = pKF1->GetTranslation(); + const cv::Mat R2w = pKF2->GetRotation(); + const cv::Mat t2w = pKF2->GetTranslation(); + + // Set Sim3 vertex + ORB_SLAM3::VertexSim3Expmap * vSim3 = new ORB_SLAM3::VertexSim3Expmap(); + vSim3->_fix_scale=bFixScale; + vSim3->setEstimate(g2oS12); + vSim3->setId(0); + vSim3->setFixed(false); + vSim3->pCamera1 = pKF1->mpCamera; + vSim3->pCamera2 = pKF2->mpCamera; + optimizer.addVertex(vSim3); + + // Set MapPoint vertices + const int N = vpMatches1.size(); + const vector vpMapPoints1 = pKF1->GetMapPointMatches(); + vector vpEdges12; + vector vpEdges21; + vector vnIndexEdge; + vector vbIsInKF2; + + vnIndexEdge.reserve(2*N); + vpEdges12.reserve(2*N); + vpEdges21.reserve(2*N); + vbIsInKF2.reserve(2*N); + + const float deltaHuber = sqrt(th2); + + int nCorrespondences = 0; + int nBadMPs = 0; + int nInKF2 = 0; + int nOutKF2 = 0; + int nMatchWithoutMP = 0; + + vector vIdsOnlyInKF2; + + for(int i=0; i(pMP2->GetIndexInKeyFrame(pKF2)); + /*if(i2 < 0) + cout << "Sim3-OPT: Error, there is a matched which is not find it" << endl;*/ + + cv::Mat P3D1c; + cv::Mat P3D2c; + + if(pMP1 && pMP2) + { + //if(!pMP1->isBad() && !pMP2->isBad() && i2>=0) + if(!pMP1->isBad() && !pMP2->isBad()) + { + g2o::VertexSBAPointXYZ* vPoint1 = new g2o::VertexSBAPointXYZ(); + cv::Mat P3D1w = pMP1->GetWorldPos(); + P3D1c = R1w*P3D1w + t1w; + vPoint1->setEstimate(Converter::toVector3d(P3D1c)); + vPoint1->setId(id1); + vPoint1->setFixed(true); + optimizer.addVertex(vPoint1); + + g2o::VertexSBAPointXYZ* vPoint2 = new g2o::VertexSBAPointXYZ(); + cv::Mat P3D2w = pMP2->GetWorldPos(); + P3D2c = R2w*P3D2w + t2w; + vPoint2->setEstimate(Converter::toVector3d(P3D2c)); + vPoint2->setId(id2); + vPoint2->setFixed(true); + optimizer.addVertex(vPoint2); + } + else + { + nBadMPs++; + continue; + } + } + else + { + nMatchWithoutMP++; + + //TODO The 3D position in KF1 doesn't exist + if(!pMP2->isBad()) + { + g2o::VertexSBAPointXYZ* vPoint2 = new g2o::VertexSBAPointXYZ(); + cv::Mat P3D2w = pMP2->GetWorldPos(); + P3D2c = R2w*P3D2w + t2w; + vPoint2->setEstimate(Converter::toVector3d(P3D2c)); + vPoint2->setId(id2); + vPoint2->setFixed(true); + optimizer.addVertex(vPoint2); + + vIdsOnlyInKF2.push_back(id2); + } + continue; + } + + if(i2<0 && !bAllPoints) + { + Verbose::PrintMess(" Remove point -> i2: " + to_string(i2) + "; bAllPoints: " + to_string(bAllPoints), Verbose::VERBOSITY_DEBUG); + continue; + } + + if(P3D2c.at(2) < 0) + { + Verbose::PrintMess("Sim3: Z coordinate is negative", Verbose::VERBOSITY_DEBUG); + continue; + } + + nCorrespondences++; + + // Set edge x1 = S12*X2 + Eigen::Matrix obs1; + const cv::KeyPoint &kpUn1 = pKF1->mvKeysUn[i]; + obs1 << kpUn1.pt.x, kpUn1.pt.y; + + ORB_SLAM3::EdgeSim3ProjectXYZ* e12 = new ORB_SLAM3::EdgeSim3ProjectXYZ(); + + e12->setVertex(0, dynamic_cast(optimizer.vertex(id2))); + e12->setVertex(1, dynamic_cast(optimizer.vertex(0))); + e12->setMeasurement(obs1); + const float &invSigmaSquare1 = pKF1->mvInvLevelSigma2[kpUn1.octave]; + e12->setInformation(Eigen::Matrix2d::Identity()*invSigmaSquare1); + + g2o::RobustKernelHuber* rk1 = new g2o::RobustKernelHuber; + e12->setRobustKernel(rk1); + rk1->setDelta(deltaHuber); + optimizer.addEdge(e12); + + // Set edge x2 = S21*X1 + Eigen::Matrix obs2; + cv::KeyPoint kpUn2; + bool inKF2; + if(i2 >= 0) + { + kpUn2 = pKF2->mvKeysUn[i2]; + obs2 << kpUn2.pt.x, kpUn2.pt.y; + inKF2 = true; + + nInKF2++; + } + else + { + float invz = 1/P3D2c.at(2); + float x = P3D2c.at(0)*invz; + float y = P3D2c.at(1)*invz; + + obs2 << x, y; + kpUn2 = cv::KeyPoint(cv::Point2f(x, y), pMP2->mnTrackScaleLevel); + + inKF2 = false; + nOutKF2++; + } + + ORB_SLAM3::EdgeInverseSim3ProjectXYZ* e21 = new ORB_SLAM3::EdgeInverseSim3ProjectXYZ(); + + e21->setVertex(0, dynamic_cast(optimizer.vertex(id1))); + e21->setVertex(1, dynamic_cast(optimizer.vertex(0))); + e21->setMeasurement(obs2); + float invSigmaSquare2 = pKF2->mvInvLevelSigma2[kpUn2.octave]; + e21->setInformation(Eigen::Matrix2d::Identity()*invSigmaSquare2); + + g2o::RobustKernelHuber* rk2 = new g2o::RobustKernelHuber; + e21->setRobustKernel(rk2); + rk2->setDelta(deltaHuber); + optimizer.addEdge(e21); + + vpEdges12.push_back(e12); + vpEdges21.push_back(e21); + vnIndexEdge.push_back(i); + + vbIsInKF2.push_back(inKF2); + } + + Verbose::PrintMess("Sim3: There are " + to_string(nCorrespondences) + " matches, " + to_string(nInKF2) + " are in the KF and " + to_string(nOutKF2) + " are in the connected KFs. There are " + to_string(nMatchWithoutMP) + " matches which have not an associate MP", Verbose::VERBOSITY_DEBUG); + + // Optimize! + optimizer.initializeOptimization(); + optimizer.optimize(5); + + // Check inliers + int nBad=0; + int nBadOutKF2 = 0; + for(size_t i=0; ichi2()>th2 || e21->chi2()>th2) + { + size_t idx = vnIndexEdge[i]; + vpMatches1[idx]=static_cast(NULL); + optimizer.removeEdge(e12); + optimizer.removeEdge(e21); + vpEdges12[i]=static_cast(NULL); + vpEdges21[i]=static_cast(NULL); + nBad++; + + if(!vbIsInKF2[i]) + { + nBadOutKF2++; + } + continue; + } + + //Check if remove the robust adjustment improve the result + e12->setRobustKernel(0); + e21->setRobustKernel(0); + } + + Verbose::PrintMess("Sim3: First Opt -> Correspondences: " + to_string(nCorrespondences) + "; nBad: " + to_string(nBad) + "; nBadOutKF2: " + to_string(nBadOutKF2), Verbose::VERBOSITY_DEBUG); + + int nMoreIterations; + if(nBad>0) + nMoreIterations=10; + else + nMoreIterations=5; + + if(nCorrespondences-nBad<10) + return 0; + + // Optimize again only with inliers + + optimizer.initializeOptimization(); + optimizer.optimize(nMoreIterations); + + int nIn = 0; + mAcumHessian = Eigen::MatrixXd::Zero(7, 7); + for(size_t i=0; icomputeError(); + e21->computeError(); + + if(e12->chi2()>th2 || e21->chi2()>th2) + { + size_t idx = vnIndexEdge[i]; + vpMatches1[idx]=static_cast(NULL); + } + else + { + nIn++; + //mAcumHessian += e12->GetHessian(); + } + } + + // Recover optimized Sim3 + //Verbose::PrintMess("Sim3: Initial seed " + g2oS12, Verbose::VERBOSITY_DEBUG); + g2o::VertexSim3Expmap* vSim3_recov = static_cast(optimizer.vertex(0)); + g2oS12= vSim3_recov->estimate(); + //Verbose::PrintMess("Sim3: Optimized solution " + g2oS12, Verbose::VERBOSITY_DEBUG); + + return nIn; +} + +int Optimizer::OptimizeSim3(KeyFrame *pKF1, KeyFrame *pKF2, vector &vpMatches1, vector &vpMatches1KF, g2o::Sim3 &g2oS12, const float th2, + const bool bFixScale, Eigen::Matrix &mAcumHessian, const bool bAllPoints) +{ + g2o::SparseOptimizer optimizer; + g2o::BlockSolverX::LinearSolverType * linearSolver; + + linearSolver = new g2o::LinearSolverDense(); + + g2o::BlockSolverX * solver_ptr = new g2o::BlockSolverX(linearSolver); + + g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg(solver_ptr); + optimizer.setAlgorithm(solver); + + // Calibration + const cv::Mat &K1 = pKF1->mK; + const cv::Mat &K2 = pKF2->mK; + + // Camera poses + const cv::Mat R1w = pKF1->GetRotation(); + const cv::Mat t1w = pKF1->GetTranslation(); + Verbose::PrintMess("Extracted rotation and traslation from the first KF ", Verbose::VERBOSITY_DEBUG); + const cv::Mat R2w = pKF2->GetRotation(); + const cv::Mat t2w = pKF2->GetTranslation(); + Verbose::PrintMess("Extracted rotation and traslation from the second KF ", Verbose::VERBOSITY_DEBUG); + + // Set Sim3 vertex + g2o::VertexSim3Expmap * vSim3 = new g2o::VertexSim3Expmap(); + vSim3->_fix_scale=bFixScale; + vSim3->setEstimate(g2oS12); + vSim3->setId(0); + vSim3->setFixed(false); + vSim3->_principle_point1[0] = K1.at(0,2); + vSim3->_principle_point1[1] = K1.at(1,2); + vSim3->_focal_length1[0] = K1.at(0,0); + vSim3->_focal_length1[1] = K1.at(1,1); + vSim3->_principle_point2[0] = K2.at(0,2); + vSim3->_principle_point2[1] = K2.at(1,2); + vSim3->_focal_length2[0] = K2.at(0,0); + vSim3->_focal_length2[1] = K2.at(1,1); + optimizer.addVertex(vSim3); + + // Set MapPoint vertices + const int N = vpMatches1.size(); + const vector vpMapPoints1 = pKF1->GetMapPointMatches(); + vector vpEdges12; + vector vpEdges21; + vector vnIndexEdge; + + vnIndexEdge.reserve(2*N); + vpEdges12.reserve(2*N); + vpEdges21.reserve(2*N); + + const float deltaHuber = sqrt(th2); + + int nCorrespondences = 0; + + KeyFrame* pKFm = pKF2; + for(int i=0; i(pMP2->GetIndexInKeyFrame(pKFm)); + if(i2 < 0) + Verbose::PrintMess("Sim3-OPT: Error, there is a matched which is not find it", Verbose::VERBOSITY_DEBUG); + + cv::Mat P3D2c; + + if(pMP1 && pMP2) + { + //if(!pMP1->isBad() && !pMP2->isBad() && i2>=0) + if(!pMP1->isBad() && !pMP2->isBad()) + { + g2o::VertexSBAPointXYZ* vPoint1 = new g2o::VertexSBAPointXYZ(); + cv::Mat P3D1w = pMP1->GetWorldPos(); + cv::Mat P3D1c = R1w*P3D1w + t1w; + vPoint1->setEstimate(Converter::toVector3d(P3D1c)); + vPoint1->setId(id1); + vPoint1->setFixed(true); + optimizer.addVertex(vPoint1); + + g2o::VertexSBAPointXYZ* vPoint2 = new g2o::VertexSBAPointXYZ(); + cv::Mat P3D2w = pMP2->GetWorldPos(); + P3D2c = R2w*P3D2w + t2w; + vPoint2->setEstimate(Converter::toVector3d(P3D2c)); + vPoint2->setId(id2); + vPoint2->setFixed(true); + optimizer.addVertex(vPoint2); + } + else + continue; + } + else + continue; + + if(i2<0 && !bAllPoints) + { + Verbose::PrintMess(" Remove point -> i2: " + to_string(i2) + "; bAllPoints: " + to_string(bAllPoints), Verbose::VERBOSITY_DEBUG); + continue; + } + + nCorrespondences++; + + // Set edge x1 = S12*X2 + Eigen::Matrix obs1; + const cv::KeyPoint &kpUn1 = pKF1->mvKeysUn[i]; + obs1 << kpUn1.pt.x, kpUn1.pt.y; + + ORB_SLAM3::EdgeSim3ProjectXYZ* e12 = new ORB_SLAM3::EdgeSim3ProjectXYZ(); + e12->setVertex(0, dynamic_cast(optimizer.vertex(id2))); + e12->setVertex(1, dynamic_cast(optimizer.vertex(0))); + e12->setMeasurement(obs1); + const float &invSigmaSquare1 = pKF1->mvInvLevelSigma2[kpUn1.octave]; + e12->setInformation(Eigen::Matrix2d::Identity()*invSigmaSquare1); + + g2o::RobustKernelHuber* rk1 = new g2o::RobustKernelHuber; + e12->setRobustKernel(rk1); + rk1->setDelta(deltaHuber); + optimizer.addEdge(e12); + + // Set edge x2 = S21*X1 + Eigen::Matrix obs2; + cv::KeyPoint kpUn2; + if(i2 >= 0 && pKFm == pKF2) + { + kpUn2 = pKFm->mvKeysUn[i2]; + obs2 << kpUn2.pt.x, kpUn2.pt.y; + } + else + { + float invz = 1/P3D2c.at(2); + float x = P3D2c.at(0)*invz; + float y = P3D2c.at(1)*invz; + + // Project in image and check it is not outside + float u = pKF2->fx * x + pKFm->cx; + float v = pKF2->fy * y + pKFm->cy; + obs2 << u, v; + kpUn2 = cv::KeyPoint(cv::Point2f(u, v), pMP2->mnTrackScaleLevel); + } + + ORB_SLAM3::EdgeInverseSim3ProjectXYZ* e21 = new ORB_SLAM3::EdgeInverseSim3ProjectXYZ(); + + e21->setVertex(0, dynamic_cast(optimizer.vertex(id1))); + e21->setVertex(1, dynamic_cast(optimizer.vertex(0))); + e21->setMeasurement(obs2); + float invSigmaSquare2 = pKFm->mvInvLevelSigma2[kpUn2.octave]; + e21->setInformation(Eigen::Matrix2d::Identity()*invSigmaSquare2); + + g2o::RobustKernelHuber* rk2 = new g2o::RobustKernelHuber; + e21->setRobustKernel(rk2); + rk2->setDelta(deltaHuber); + optimizer.addEdge(e21); + + vpEdges12.push_back(e12); + vpEdges21.push_back(e21); + vnIndexEdge.push_back(i); + } + + // Optimize! + optimizer.initializeOptimization(); + optimizer.optimize(5); + + // Check inliers + int nBad=0; + for(size_t i=0; ichi2()>th2 || e21->chi2()>th2) + { + size_t idx = vnIndexEdge[i]; + vpMatches1[idx]=static_cast(NULL); + optimizer.removeEdge(e12); + optimizer.removeEdge(e21); + vpEdges12[i]=static_cast(NULL); + vpEdges21[i]=static_cast(NULL); + nBad++; + continue; + } + + //Check if remove the robust adjustment improve the result + e12->setRobustKernel(0); + e21->setRobustKernel(0); + } + + //cout << "Sim3 -> Correspondences: " << nCorrespondences << "; nBad: " << nBad << endl; + + int nMoreIterations; + if(nBad>0) + nMoreIterations=10; + else + nMoreIterations=5; + + if(nCorrespondences-nBad<10) + return 0; + + // Optimize again only with inliers + + optimizer.initializeOptimization(); + optimizer.optimize(nMoreIterations); + + int nIn = 0; + mAcumHessian = Eigen::MatrixXd::Zero(7, 7); + for(size_t i=0; icomputeError(); + e21->computeError(); + + if(e12->chi2()>th2 || e21->chi2()>th2) + { + size_t idx = vnIndexEdge[i]; + vpMatches1[idx]=static_cast(NULL); + } + else + { + nIn++; + //mAcumHessian += e12->GetHessian(); + } + } + + // Recover optimized Sim3 + ORB_SLAM3::VertexSim3Expmap* vSim3_recov = static_cast(optimizer.vertex(0)); + g2oS12= vSim3_recov->estimate(); + + return nIn; +} + + +void Optimizer::LocalInertialBA(KeyFrame *pKF, bool *pbStopFlag, Map *pMap, bool bLarge, bool bRecInit) +{ + std::chrono::steady_clock::time_point t0 = std::chrono::steady_clock::now(); + Map* pCurrentMap = pKF->GetMap(); + + int maxOpt=10; + int opt_it=10; + if(bLarge) + { + maxOpt=25; + opt_it=4; + } + const int Nd = std::min((int)pCurrentMap->KeyFramesInMap()-2,maxOpt); + const unsigned long maxKFid = pKF->mnId; + + vector vpOptimizableKFs; + const vector vpNeighsKFs = pKF->GetVectorCovisibleKeyFrames(); + list lpOptVisKFs; + + vpOptimizableKFs.reserve(Nd); + vpOptimizableKFs.push_back(pKF); + pKF->mnBALocalForKF = pKF->mnId; + for(int i=1; imPrevKF) + { + vpOptimizableKFs.push_back(vpOptimizableKFs.back()->mPrevKF); + vpOptimizableKFs.back()->mnBALocalForKF = pKF->mnId; + } + else + break; + } + + int N = vpOptimizableKFs.size(); + + // Optimizable points seen by temporal optimizable keyframes + list lLocalMapPoints; + for(int i=0; i vpMPs = vpOptimizableKFs[i]->GetMapPointMatches(); + for(vector::iterator vit=vpMPs.begin(), vend=vpMPs.end(); vit!=vend; vit++) + { + MapPoint* pMP = *vit; + if(pMP) + if(!pMP->isBad()) + if(pMP->mnBALocalForKF!=pKF->mnId) + { + lLocalMapPoints.push_back(pMP); + pMP->mnBALocalForKF=pKF->mnId; + } + } + } + + // Fixed Keyframe: First frame previous KF to optimization window) + list lFixedKeyFrames; + if(vpOptimizableKFs.back()->mPrevKF) + { + lFixedKeyFrames.push_back(vpOptimizableKFs.back()->mPrevKF); + vpOptimizableKFs.back()->mPrevKF->mnBAFixedForKF=pKF->mnId; + } + else + { + vpOptimizableKFs.back()->mnBALocalForKF=0; + vpOptimizableKFs.back()->mnBAFixedForKF=pKF->mnId; + lFixedKeyFrames.push_back(vpOptimizableKFs.back()); + vpOptimizableKFs.pop_back(); + } + + // Optimizable visual KFs + const int maxCovKF = 0; + for(int i=0, iend=vpNeighsKFs.size(); i= maxCovKF) + break; + + KeyFrame* pKFi = vpNeighsKFs[i]; + if(pKFi->mnBALocalForKF == pKF->mnId || pKFi->mnBAFixedForKF == pKF->mnId) + continue; + pKFi->mnBALocalForKF = pKF->mnId; + if(!pKFi->isBad() && pKFi->GetMap() == pCurrentMap) + { + lpOptVisKFs.push_back(pKFi); + + vector vpMPs = pKFi->GetMapPointMatches(); + for(vector::iterator vit=vpMPs.begin(), vend=vpMPs.end(); vit!=vend; vit++) + { + MapPoint* pMP = *vit; + if(pMP) + if(!pMP->isBad()) + if(pMP->mnBALocalForKF!=pKF->mnId) + { + lLocalMapPoints.push_back(pMP); + pMP->mnBALocalForKF=pKF->mnId; + } + } + } + } + + // Fixed KFs which are not covisible optimizable + const int maxFixKF = 200; + + for(list::iterator lit=lLocalMapPoints.begin(), lend=lLocalMapPoints.end(); lit!=lend; lit++) + { + map> observations = (*lit)->GetObservations(); + for(map>::iterator mit=observations.begin(), mend=observations.end(); mit!=mend; mit++) + { + KeyFrame* pKFi = mit->first; + + if(pKFi->mnBALocalForKF!=pKF->mnId && pKFi->mnBAFixedForKF!=pKF->mnId) + { + pKFi->mnBAFixedForKF=pKF->mnId; + if(!pKFi->isBad()) + { + lFixedKeyFrames.push_back(pKFi); + break; + } + } + } + if(lFixedKeyFrames.size()>=maxFixKF) + break; + } + + bool bNonFixed = (lFixedKeyFrames.size() == 0); + + // Setup optimizer + g2o::SparseOptimizer optimizer; + g2o::BlockSolverX::LinearSolverType * linearSolver; + linearSolver = new g2o::LinearSolverEigen(); + + g2o::BlockSolverX * solver_ptr = new g2o::BlockSolverX(linearSolver); + + if(bLarge) + { + g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg(solver_ptr); + solver->setUserLambdaInit(1e-2); // to avoid iterating for finding optimal lambda + optimizer.setAlgorithm(solver); + } + else + { + g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg(solver_ptr); + solver->setUserLambdaInit(1e0); + optimizer.setAlgorithm(solver); + } + + + // Set Local temporal KeyFrame vertices + N=vpOptimizableKFs.size(); + for(int i=0; isetId(pKFi->mnId); + VP->setFixed(false); + optimizer.addVertex(VP); + + if(pKFi->bImu) + { + VertexVelocity* VV = new VertexVelocity(pKFi); + VV->setId(maxKFid+3*(pKFi->mnId)+1); + VV->setFixed(false); + optimizer.addVertex(VV); + VertexGyroBias* VG = new VertexGyroBias(pKFi); + VG->setId(maxKFid+3*(pKFi->mnId)+2); + VG->setFixed(false); + optimizer.addVertex(VG); + VertexAccBias* VA = new VertexAccBias(pKFi); + VA->setId(maxKFid+3*(pKFi->mnId)+3); + VA->setFixed(false); + optimizer.addVertex(VA); + } + } + + // Set Local visual KeyFrame vertices + for(list::iterator it=lpOptVisKFs.begin(), itEnd = lpOptVisKFs.end(); it!=itEnd; it++) + { + KeyFrame* pKFi = *it; + VertexPose * VP = new VertexPose(pKFi); + VP->setId(pKFi->mnId); + VP->setFixed(false); + optimizer.addVertex(VP); + } + + // Set Fixed KeyFrame vertices + for(list::iterator lit=lFixedKeyFrames.begin(), lend=lFixedKeyFrames.end(); lit!=lend; lit++) + { + KeyFrame* pKFi = *lit; + VertexPose * VP = new VertexPose(pKFi); + VP->setId(pKFi->mnId); + VP->setFixed(true); + optimizer.addVertex(VP); + + if(pKFi->bImu) // This should be done only for keyframe just before temporal window + { + VertexVelocity* VV = new VertexVelocity(pKFi); + VV->setId(maxKFid+3*(pKFi->mnId)+1); + VV->setFixed(true); + optimizer.addVertex(VV); + VertexGyroBias* VG = new VertexGyroBias(pKFi); + VG->setId(maxKFid+3*(pKFi->mnId)+2); + VG->setFixed(true); + optimizer.addVertex(VG); + VertexAccBias* VA = new VertexAccBias(pKFi); + VA->setId(maxKFid+3*(pKFi->mnId)+3); + VA->setFixed(true); + optimizer.addVertex(VA); + } + } + + // Create intertial constraints + vector vei(N,(EdgeInertial*)NULL); + vector vegr(N,(EdgeGyroRW*)NULL); + vector vear(N,(EdgeAccRW*)NULL); + + for(int i=0;imPrevKF) + { + cout << "NOT INERTIAL LINK TO PREVIOUS FRAME!!!!" << endl; + continue; + } + if(pKFi->bImu && pKFi->mPrevKF->bImu && pKFi->mpImuPreintegrated) + { + pKFi->mpImuPreintegrated->SetNewBias(pKFi->mPrevKF->GetImuBias()); + g2o::HyperGraph::Vertex* VP1 = optimizer.vertex(pKFi->mPrevKF->mnId); + g2o::HyperGraph::Vertex* VV1 = optimizer.vertex(maxKFid+3*(pKFi->mPrevKF->mnId)+1); + g2o::HyperGraph::Vertex* VG1 = optimizer.vertex(maxKFid+3*(pKFi->mPrevKF->mnId)+2); + g2o::HyperGraph::Vertex* VA1 = optimizer.vertex(maxKFid+3*(pKFi->mPrevKF->mnId)+3); + g2o::HyperGraph::Vertex* VP2 = optimizer.vertex(pKFi->mnId); + g2o::HyperGraph::Vertex* VV2 = optimizer.vertex(maxKFid+3*(pKFi->mnId)+1); + g2o::HyperGraph::Vertex* VG2 = optimizer.vertex(maxKFid+3*(pKFi->mnId)+2); + g2o::HyperGraph::Vertex* VA2 = optimizer.vertex(maxKFid+3*(pKFi->mnId)+3); + + if(!VP1 || !VV1 || !VG1 || !VA1 || !VP2 || !VV2 || !VG2 || !VA2) + { + cerr << "Error " << VP1 << ", "<< VV1 << ", "<< VG1 << ", "<< VA1 << ", " << VP2 << ", " << VV2 << ", "<< VG2 << ", "<< VA2 <mpImuPreintegrated); + + vei[i]->setVertex(0,dynamic_cast(VP1)); + vei[i]->setVertex(1,dynamic_cast(VV1)); + vei[i]->setVertex(2,dynamic_cast(VG1)); + vei[i]->setVertex(3,dynamic_cast(VA1)); + vei[i]->setVertex(4,dynamic_cast(VP2)); + vei[i]->setVertex(5,dynamic_cast(VV2)); + + if(i==N-1 || bRecInit) + { + // All inertial residuals are included without robust cost function, but not that one linking the + // last optimizable keyframe inside of the local window and the first fixed keyframe out. The + // information matrix for this measurement is also downweighted. This is done to avoid accumulating + // error due to fixing variables. + g2o::RobustKernelHuber* rki = new g2o::RobustKernelHuber; + vei[i]->setRobustKernel(rki); + if(i==N-1) + vei[i]->setInformation(vei[i]->information()*1e-2); + rki->setDelta(sqrt(16.92)); + } + optimizer.addEdge(vei[i]); + + vegr[i] = new EdgeGyroRW(); + vegr[i]->setVertex(0,VG1); + vegr[i]->setVertex(1,VG2); + cv::Mat cvInfoG = pKFi->mpImuPreintegrated->C.rowRange(9,12).colRange(9,12).inv(cv::DECOMP_SVD); + Eigen::Matrix3d InfoG; + + for(int r=0;r<3;r++) + for(int c=0;c<3;c++) + InfoG(r,c)=cvInfoG.at(r,c); + vegr[i]->setInformation(InfoG); + optimizer.addEdge(vegr[i]); + + // cout << "b"; + vear[i] = new EdgeAccRW(); + vear[i]->setVertex(0,VA1); + vear[i]->setVertex(1,VA2); + cv::Mat cvInfoA = pKFi->mpImuPreintegrated->C.rowRange(12,15).colRange(12,15).inv(cv::DECOMP_SVD); + Eigen::Matrix3d InfoA; + for(int r=0;r<3;r++) + for(int c=0;c<3;c++) + InfoA(r,c)=cvInfoA.at(r,c); + vear[i]->setInformation(InfoA); + + optimizer.addEdge(vear[i]); + } + else + cout << "ERROR building inertial edge" << endl; + } + + // Set MapPoint vertices + const int nExpectedSize = (N+lFixedKeyFrames.size())*lLocalMapPoints.size(); + + // Mono + vector vpEdgesMono; + vpEdgesMono.reserve(nExpectedSize); + + vector vpEdgeKFMono; + vpEdgeKFMono.reserve(nExpectedSize); + + vector vpMapPointEdgeMono; + vpMapPointEdgeMono.reserve(nExpectedSize); + + // Stereo + vector vpEdgesStereo; + vpEdgesStereo.reserve(nExpectedSize); + + vector vpEdgeKFStereo; + vpEdgeKFStereo.reserve(nExpectedSize); + + vector vpMapPointEdgeStereo; + vpMapPointEdgeStereo.reserve(nExpectedSize); + + + + const float thHuberMono = sqrt(5.991); + const float chi2Mono2 = 5.991; + const float thHuberStereo = sqrt(7.815); + const float chi2Stereo2 = 7.815; + + const unsigned long iniMPid = maxKFid*5; + + map mVisEdges; + for(int i=0;imnId] = 0; + } + for(list::iterator lit=lFixedKeyFrames.begin(), lend=lFixedKeyFrames.end(); lit!=lend; lit++) + { + mVisEdges[(*lit)->mnId] = 0; + } + + for(list::iterator lit=lLocalMapPoints.begin(), lend=lLocalMapPoints.end(); lit!=lend; lit++) + { + MapPoint* pMP = *lit; + g2o::VertexSBAPointXYZ* vPoint = new g2o::VertexSBAPointXYZ(); + vPoint->setEstimate(Converter::toVector3d(pMP->GetWorldPos())); + + unsigned long id = pMP->mnId+iniMPid+1; + vPoint->setId(id); + vPoint->setMarginalized(true); + optimizer.addVertex(vPoint); + const map> observations = pMP->GetObservations(); + + // Create visual constraints + for(map>::const_iterator mit=observations.begin(), mend=observations.end(); mit!=mend; mit++) + { + KeyFrame* pKFi = mit->first; + + if(pKFi->mnBALocalForKF!=pKF->mnId && pKFi->mnBAFixedForKF!=pKF->mnId) + continue; + + if(!pKFi->isBad() && pKFi->GetMap() == pCurrentMap) + { + const int leftIndex = get<0>(mit->second); + + cv::KeyPoint kpUn; + + // Monocular left observation + if(leftIndex != -1 && pKFi->mvuRight[leftIndex]<0) + { + mVisEdges[pKFi->mnId]++; + + kpUn = pKFi->mvKeysUn[leftIndex]; + Eigen::Matrix obs; + obs << kpUn.pt.x, kpUn.pt.y; + + EdgeMono* e = new EdgeMono(0); + + e->setVertex(0, dynamic_cast(optimizer.vertex(id))); + e->setVertex(1, dynamic_cast(optimizer.vertex(pKFi->mnId))); + e->setMeasurement(obs); + + // Add here uncerteinty + const float unc2 = pKFi->mpCamera->uncertainty2(obs); + + const float &invSigma2 = pKFi->mvInvLevelSigma2[kpUn.octave]/unc2; + e->setInformation(Eigen::Matrix2d::Identity()*invSigma2); + + g2o::RobustKernelHuber* rk = new g2o::RobustKernelHuber; + e->setRobustKernel(rk); + rk->setDelta(thHuberMono); + + optimizer.addEdge(e); + vpEdgesMono.push_back(e); + vpEdgeKFMono.push_back(pKFi); + vpMapPointEdgeMono.push_back(pMP); + } + // Stereo-observation + else if(leftIndex != -1)// Stereo observation + { + kpUn = pKFi->mvKeysUn[leftIndex]; + mVisEdges[pKFi->mnId]++; + + const float kp_ur = pKFi->mvuRight[leftIndex]; + Eigen::Matrix obs; + obs << kpUn.pt.x, kpUn.pt.y, kp_ur; + + EdgeStereo* e = new EdgeStereo(0); + + e->setVertex(0, dynamic_cast(optimizer.vertex(id))); + e->setVertex(1, dynamic_cast(optimizer.vertex(pKFi->mnId))); + e->setMeasurement(obs); + + // Add here uncerteinty + const float unc2 = pKFi->mpCamera->uncertainty2(obs.head(2)); + + const float &invSigma2 = pKFi->mvInvLevelSigma2[kpUn.octave]/unc2; + e->setInformation(Eigen::Matrix3d::Identity()*invSigma2); + + g2o::RobustKernelHuber* rk = new g2o::RobustKernelHuber; + e->setRobustKernel(rk); + rk->setDelta(thHuberStereo); + + optimizer.addEdge(e); + vpEdgesStereo.push_back(e); + vpEdgeKFStereo.push_back(pKFi); + vpMapPointEdgeStereo.push_back(pMP); + } + + // Monocular right observation + if(pKFi->mpCamera2){ + int rightIndex = get<1>(mit->second); + + if(rightIndex != -1 ){ + rightIndex -= pKFi->NLeft; + mVisEdges[pKFi->mnId]++; + + Eigen::Matrix obs; + cv::KeyPoint kp = pKFi->mvKeysRight[rightIndex]; + obs << kp.pt.x, kp.pt.y; + + EdgeMono* e = new EdgeMono(1); + + e->setVertex(0, dynamic_cast(optimizer.vertex(id))); + e->setVertex(1, dynamic_cast(optimizer.vertex(pKFi->mnId))); + e->setMeasurement(obs); + + // Add here uncerteinty + const float unc2 = pKFi->mpCamera->uncertainty2(obs); + + const float &invSigma2 = pKFi->mvInvLevelSigma2[kpUn.octave]/unc2; + e->setInformation(Eigen::Matrix2d::Identity()*invSigma2); + + g2o::RobustKernelHuber* rk = new g2o::RobustKernelHuber; + e->setRobustKernel(rk); + rk->setDelta(thHuberMono); + + optimizer.addEdge(e); + vpEdgesMono.push_back(e); + vpEdgeKFMono.push_back(pKFi); + vpMapPointEdgeMono.push_back(pMP); + } + } + } + } + } + + //cout << "Total map points: " << lLocalMapPoints.size() << endl; + for(map::iterator mit=mVisEdges.begin(), mend=mVisEdges.end(); mit!=mend; mit++) + { + assert(mit->second>=3); + } + + optimizer.initializeOptimization(); + optimizer.computeActiveErrors(); + std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now(); + float err = optimizer.activeRobustChi2(); + optimizer.optimize(opt_it); // Originally to 2 + float err_end = optimizer.activeRobustChi2(); + if(pbStopFlag) + optimizer.setForceStopFlag(pbStopFlag); + + + std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now(); + + vector > vToErase; + vToErase.reserve(vpEdgesMono.size()+vpEdgesStereo.size()); + + // Check inlier observations + // Mono + for(size_t i=0, iend=vpEdgesMono.size(); imTrackDepth<10.f; + + if(pMP->isBad()) + continue; + + if((e->chi2()>chi2Mono2 && !bClose) || (e->chi2()>1.5f*chi2Mono2 && bClose) || !e->isDepthPositive()) + { + KeyFrame* pKFi = vpEdgeKFMono[i]; + vToErase.push_back(make_pair(pKFi,pMP)); + } + } + + + // Stereo + for(size_t i=0, iend=vpEdgesStereo.size(); iisBad()) + continue; + + if(e->chi2()>chi2Stereo2) + { + KeyFrame* pKFi = vpEdgeKFStereo[i]; + vToErase.push_back(make_pair(pKFi,pMP)); + } + } + + // Get Map Mutex and erase outliers + unique_lock lock(pMap->mMutexMapUpdate); + + + // TODO: Some convergence problems have been detected here + //cout << "err0 = " << err << endl; + //cout << "err_end = " << err_end << endl; + if((2*err < err_end || isnan(err) || isnan(err_end)) && !bLarge) //bGN) + { + cout << "FAIL LOCAL-INERTIAL BA!!!!" << endl; + return; + } + + + + if(!vToErase.empty()) + { + for(size_t i=0;iEraseMapPointMatch(pMPi); + pMPi->EraseObservation(pKFi); + } + } + + + + // Display main statistcis of optimization + Verbose::PrintMess("LIBA KFs: " + to_string(N), Verbose::VERBOSITY_DEBUG); + Verbose::PrintMess("LIBA bNonFixed?: " + to_string(bNonFixed), Verbose::VERBOSITY_DEBUG); + Verbose::PrintMess("LIBA KFs visual outliers: " + to_string(vToErase.size()), Verbose::VERBOSITY_DEBUG); + + for(list::iterator lit=lFixedKeyFrames.begin(), lend=lFixedKeyFrames.end(); lit!=lend; lit++) + (*lit)->mnBAFixedForKF = 0; + + // Recover optimized data + // Local temporal Keyframes + N=vpOptimizableKFs.size(); + for(int i=0; i(optimizer.vertex(pKFi->mnId)); + cv::Mat Tcw = Converter::toCvSE3(VP->estimate().Rcw[0], VP->estimate().tcw[0]); + pKFi->SetPose(Tcw); + pKFi->mnBALocalForKF=0; + + if(pKFi->bImu) + { + VertexVelocity* VV = static_cast(optimizer.vertex(maxKFid+3*(pKFi->mnId)+1)); + pKFi->SetVelocity(Converter::toCvMat(VV->estimate())); + VertexGyroBias* VG = static_cast(optimizer.vertex(maxKFid+3*(pKFi->mnId)+2)); + VertexAccBias* VA = static_cast(optimizer.vertex(maxKFid+3*(pKFi->mnId)+3)); + Vector6d b; + b << VG->estimate(), VA->estimate(); + pKFi->SetNewBias(IMU::Bias(b[3],b[4],b[5],b[0],b[1],b[2])); + + } + } + + // Local visual KeyFrame + for(list::iterator it=lpOptVisKFs.begin(), itEnd = lpOptVisKFs.end(); it!=itEnd; it++) + { + KeyFrame* pKFi = *it; + VertexPose* VP = static_cast(optimizer.vertex(pKFi->mnId)); + cv::Mat Tcw = Converter::toCvSE3(VP->estimate().Rcw[0], VP->estimate().tcw[0]); + pKFi->SetPose(Tcw); + pKFi->mnBALocalForKF=0; + } + + //Points + for(list::iterator lit=lLocalMapPoints.begin(), lend=lLocalMapPoints.end(); lit!=lend; lit++) + { + MapPoint* pMP = *lit; + g2o::VertexSBAPointXYZ* vPoint = static_cast(optimizer.vertex(pMP->mnId+iniMPid+1)); + pMP->SetWorldPos(Converter::toCvMat(vPoint->estimate())); + pMP->UpdateNormalAndDepth(); + } + + pMap->IncreaseChangeIndex(); + + std::chrono::steady_clock::time_point t3 = std::chrono::steady_clock::now(); + + /*double t_const = std::chrono::duration_cast >(t1 - t0).count(); + double t_opt = std::chrono::duration_cast >(t2 - t1).count(); + double t_rec = std::chrono::duration_cast >(t3 - t2).count(); + /*std::cout << " Construction time: " << t_const << std::endl; + std::cout << " Optimization time: " << t_opt << std::endl; + std::cout << " Recovery time: " << t_rec << std::endl; + std::cout << " Total time: " << t_const+t_opt+t_rec << std::endl; + std::cout << " Optimization iterations: " << opt_it << std::endl;*/ + +} + +Eigen::MatrixXd Optimizer::Marginalize(const Eigen::MatrixXd &H, const int &start, const int &end) +{ + // Goal + // a | ab | ac a* | 0 | ac* + // ba | b | bc --> 0 | 0 | 0 + // ca | cb | c ca* | 0 | c* + + // Size of block before block to marginalize + const int a = start; + // Size of block to marginalize + const int b = end-start+1; + // Size of block after block to marginalize + const int c = H.cols() - (end+1); + + // Reorder as follows: + // a | ab | ac a | ac | ab + // ba | b | bc --> ca | c | cb + // ca | cb | c ba | bc | b + + Eigen::MatrixXd Hn = Eigen::MatrixXd::Zero(H.rows(),H.cols()); + if(a>0) + { + Hn.block(0,0,a,a) = H.block(0,0,a,a); + Hn.block(0,a+c,a,b) = H.block(0,a,a,b); + Hn.block(a+c,0,b,a) = H.block(a,0,b,a); + } + if(a>0 && c>0) + { + Hn.block(0,a,a,c) = H.block(0,a+b,a,c); + Hn.block(a,0,c,a) = H.block(a+b,0,c,a); + } + if(c>0) + { + Hn.block(a,a,c,c) = H.block(a+b,a+b,c,c); + Hn.block(a,a+c,c,b) = H.block(a+b,a,c,b); + Hn.block(a+c,a,b,c) = H.block(a,a+b,b,c); + } + Hn.block(a+c,a+c,b,b) = H.block(a,a,b,b); + + // Perform marginalization (Schur complement) + Eigen::JacobiSVD svd(Hn.block(a+c,a+c,b,b),Eigen::ComputeThinU | Eigen::ComputeThinV); + Eigen::JacobiSVD::SingularValuesType singularValues_inv=svd.singularValues(); + for (int i=0; i1e-6) + singularValues_inv(i)=1.0/singularValues_inv(i); + else singularValues_inv(i)=0; + } + Eigen::MatrixXd invHb = svd.matrixV()*singularValues_inv.asDiagonal()*svd.matrixU().transpose(); + Hn.block(0,0,a+c,a+c) = Hn.block(0,0,a+c,a+c) - Hn.block(0,a+c,a+c,b)*invHb*Hn.block(a+c,0,b,a+c); + Hn.block(a+c,a+c,b,b) = Eigen::MatrixXd::Zero(b,b); + Hn.block(0,a+c,a+c,b) = Eigen::MatrixXd::Zero(a+c,b); + Hn.block(a+c,0,b,a+c) = Eigen::MatrixXd::Zero(b,a+c); + + // Inverse reorder + // a* | ac* | 0 a* | 0 | ac* + // ca* | c* | 0 --> 0 | 0 | 0 + // 0 | 0 | 0 ca* | 0 | c* + Eigen::MatrixXd res = Eigen::MatrixXd::Zero(H.rows(),H.cols()); + if(a>0) + { + res.block(0,0,a,a) = Hn.block(0,0,a,a); + res.block(0,a,a,b) = Hn.block(0,a+c,a,b); + res.block(a,0,b,a) = Hn.block(a+c,0,b,a); + } + if(a>0 && c>0) + { + res.block(0,a+b,a,c) = Hn.block(0,a,a,c); + res.block(a+b,0,c,a) = Hn.block(a,0,c,a); + } + if(c>0) + { + res.block(a+b,a+b,c,c) = Hn.block(a,a,c,c); + res.block(a+b,a,c,b) = Hn.block(a,a+c,c,b); + res.block(a,a+b,b,c) = Hn.block(a+c,a,b,c); + } + + res.block(a,a,b,b) = Hn.block(a+c,a+c,b,b); + + return res; +} + +Eigen::MatrixXd Optimizer::Condition(const Eigen::MatrixXd &H, const int &start, const int &end) +{ + // Size of block before block to condition + const int a = start; + // Size of block to condition + const int b = end+1-start; + + // Set to zero elements related to block b(start:end,start:end) + // a | ab | ac a | 0 | ac + // ba | b | bc --> 0 | 0 | 0 + // ca | cb | c ca | 0 | c + + Eigen::MatrixXd Hn = H; + + Hn.block(a,0,b,H.cols()) = Eigen::MatrixXd::Zero(b,H.cols()); + Hn.block(0,a,H.rows(),b) = Eigen::MatrixXd::Zero(H.rows(),b); + + return Hn; +} + +Eigen::MatrixXd Optimizer::Sparsify(const Eigen::MatrixXd &H, const int &start1, const int &end1, const int &start2, const int &end2) +{ + // Goal: remove link between a and b + // p(a,b,c) ~ p(a,b,c)*p(a|c)/p(a|b,c) => H' = H + H1 - H2 + // H1: marginalize b and condition c + // H2: condition b and c + Eigen::MatrixXd Hac = Marginalize(H,start2,end2); + Eigen::MatrixXd Hbc = Marginalize(H,start1,end1); + Eigen::MatrixXd Hc = Marginalize(Hac,start1,end1); + + return Hac+Hbc-Hc; +} + + +void Optimizer::InertialOptimization(Map *pMap, Eigen::Matrix3d &Rwg, double &scale, Eigen::Vector3d &bg, Eigen::Vector3d &ba, bool bMono, Eigen::MatrixXd &covInertial, bool bFixedVel, bool bGauss, float priorG, float priorA) +{ + Verbose::PrintMess("inertial optimization", Verbose::VERBOSITY_NORMAL); + int its = 200; // Check number of iterations + long unsigned int maxKFid = pMap->GetMaxKFid(); + const vector vpKFs = pMap->GetAllKeyFrames(); + + // Setup optimizer + g2o::SparseOptimizer optimizer; + g2o::BlockSolverX::LinearSolverType * linearSolver; + + linearSolver = new g2o::LinearSolverEigen(); + + g2o::BlockSolverX * solver_ptr = new g2o::BlockSolverX(linearSolver); + + g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg(solver_ptr); + + if (priorG!=0.f) + solver->setUserLambdaInit(1e3); + + optimizer.setAlgorithm(solver); + + + // Set KeyFrame vertices (fixed poses and optimizable velocities) + for(size_t i=0; imnId>maxKFid) + continue; + VertexPose * VP = new VertexPose(pKFi); + VP->setId(pKFi->mnId); + VP->setFixed(true); + optimizer.addVertex(VP); + + VertexVelocity* VV = new VertexVelocity(pKFi); + VV->setId(maxKFid+(pKFi->mnId)+1); + if (bFixedVel) + VV->setFixed(true); + else + VV->setFixed(false); + + optimizer.addVertex(VV); + } + + // Biases + VertexGyroBias* VG = new VertexGyroBias(vpKFs.front()); + VG->setId(maxKFid*2+2); + if (bFixedVel) + VG->setFixed(true); + else + VG->setFixed(false); + optimizer.addVertex(VG); + VertexAccBias* VA = new VertexAccBias(vpKFs.front()); + VA->setId(maxKFid*2+3); + if (bFixedVel) + VA->setFixed(true); + else + VA->setFixed(false); + + optimizer.addVertex(VA); + // prior acc bias + EdgePriorAcc* epa = new EdgePriorAcc(cv::Mat::zeros(3,1,CV_32F)); + epa->setVertex(0,dynamic_cast(VA)); + double infoPriorA = priorA; + epa->setInformation(infoPriorA*Eigen::Matrix3d::Identity()); + optimizer.addEdge(epa); + EdgePriorGyro* epg = new EdgePriorGyro(cv::Mat::zeros(3,1,CV_32F)); + epg->setVertex(0,dynamic_cast(VG)); + double infoPriorG = priorG; + epg->setInformation(infoPriorG*Eigen::Matrix3d::Identity()); + optimizer.addEdge(epg); + + // Gravity and scale + VertexGDir* VGDir = new VertexGDir(Rwg); + VGDir->setId(maxKFid*2+4); + VGDir->setFixed(false); + optimizer.addVertex(VGDir); + VertexScale* VS = new VertexScale(scale); + VS->setId(maxKFid*2+5); + VS->setFixed(!bMono); // Fixed for stereo case + optimizer.addVertex(VS); + + // Graph edges + // IMU links with gravity and scale + vector vpei; + vpei.reserve(vpKFs.size()); + vector > vppUsedKF; + vppUsedKF.reserve(vpKFs.size()); + std::cout << "build optimization graph" << std::endl; + + for(size_t i=0;imPrevKF && pKFi->mnId<=maxKFid) + { + if(pKFi->isBad() || pKFi->mPrevKF->mnId>maxKFid) + continue; + if(!pKFi->mpImuPreintegrated) + std::cout << "Not preintegrated measurement" << std::endl; + + pKFi->mpImuPreintegrated->SetNewBias(pKFi->mPrevKF->GetImuBias()); + g2o::HyperGraph::Vertex* VP1 = optimizer.vertex(pKFi->mPrevKF->mnId); + g2o::HyperGraph::Vertex* VV1 = optimizer.vertex(maxKFid+(pKFi->mPrevKF->mnId)+1); + g2o::HyperGraph::Vertex* VP2 = optimizer.vertex(pKFi->mnId); + g2o::HyperGraph::Vertex* VV2 = optimizer.vertex(maxKFid+(pKFi->mnId)+1); + g2o::HyperGraph::Vertex* VG = optimizer.vertex(maxKFid*2+2); + g2o::HyperGraph::Vertex* VA = optimizer.vertex(maxKFid*2+3); + g2o::HyperGraph::Vertex* VGDir = optimizer.vertex(maxKFid*2+4); + g2o::HyperGraph::Vertex* VS = optimizer.vertex(maxKFid*2+5); + if(!VP1 || !VV1 || !VG || !VA || !VP2 || !VV2 || !VGDir || !VS) + { + cout << "Error" << VP1 << ", "<< VV1 << ", "<< VG << ", "<< VA << ", " << VP2 << ", " << VV2 << ", "<< VGDir << ", "<< VS <mpImuPreintegrated); + ei->setVertex(0,dynamic_cast(VP1)); + ei->setVertex(1,dynamic_cast(VV1)); + ei->setVertex(2,dynamic_cast(VG)); + ei->setVertex(3,dynamic_cast(VA)); + ei->setVertex(4,dynamic_cast(VP2)); + ei->setVertex(5,dynamic_cast(VV2)); + ei->setVertex(6,dynamic_cast(VGDir)); + ei->setVertex(7,dynamic_cast(VS)); + + vpei.push_back(ei); + + vppUsedKF.push_back(make_pair(pKFi->mPrevKF,pKFi)); + optimizer.addEdge(ei); + + } + } + + // Compute error for different scales + std::set setEdges = optimizer.edges(); + + std::cout << "start optimization" << std::endl; + optimizer.setVerbose(false); + optimizer.initializeOptimization(); + optimizer.optimize(its); + + std::cout << "end optimization" << std::endl; + + scale = VS->estimate(); + + // Recover optimized data + // Biases + VG = static_cast(optimizer.vertex(maxKFid*2+2)); + VA = static_cast(optimizer.vertex(maxKFid*2+3)); + Vector6d vb; + vb << VG->estimate(), VA->estimate(); + bg << VG->estimate(); + ba << VA->estimate(); + scale = VS->estimate(); + + + IMU::Bias b (vb[3],vb[4],vb[5],vb[0],vb[1],vb[2]); + Rwg = VGDir->estimate().Rwg; + + cv::Mat cvbg = Converter::toCvMat(bg); + + //Keyframes velocities and biases + std::cout << "update Keyframes velocities and biases" << std::endl; + + const int N = vpKFs.size(); + for(size_t i=0; imnId>maxKFid) + continue; + + VertexVelocity* VV = static_cast(optimizer.vertex(maxKFid+(pKFi->mnId)+1)); + Eigen::Vector3d Vw = VV->estimate(); // Velocity is scaled after + pKFi->SetVelocity(Converter::toCvMat(Vw)); + + if (cv::norm(pKFi->GetGyroBias()-cvbg)>0.01) + { + pKFi->SetNewBias(b); + if (pKFi->mpImuPreintegrated) + pKFi->mpImuPreintegrated->Reintegrate(); + } + else + pKFi->SetNewBias(b); + + + } +} + + +void Optimizer::InertialOptimization(Map *pMap, Eigen::Vector3d &bg, Eigen::Vector3d &ba, float priorG, float priorA) +{ + int its = 200; // Check number of iterations + long unsigned int maxKFid = pMap->GetMaxKFid(); + const vector vpKFs = pMap->GetAllKeyFrames(); + + // Setup optimizer + g2o::SparseOptimizer optimizer; + g2o::BlockSolverX::LinearSolverType * linearSolver; + + linearSolver = new g2o::LinearSolverEigen(); + + g2o::BlockSolverX * solver_ptr = new g2o::BlockSolverX(linearSolver); + + g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg(solver_ptr); + solver->setUserLambdaInit(1e3); + + optimizer.setAlgorithm(solver); + + + // Set KeyFrame vertices (fixed poses and optimizable velocities) + for(size_t i=0; imnId>maxKFid) + continue; + VertexPose * VP = new VertexPose(pKFi); + VP->setId(pKFi->mnId); + VP->setFixed(true); + optimizer.addVertex(VP); + + VertexVelocity* VV = new VertexVelocity(pKFi); + VV->setId(maxKFid+(pKFi->mnId)+1); + VV->setFixed(false); + + optimizer.addVertex(VV); + } + + // Biases + VertexGyroBias* VG = new VertexGyroBias(vpKFs.front()); + VG->setId(maxKFid*2+2); + VG->setFixed(false); + optimizer.addVertex(VG); + + VertexAccBias* VA = new VertexAccBias(vpKFs.front()); + VA->setId(maxKFid*2+3); + VA->setFixed(false); + + optimizer.addVertex(VA); + // prior acc bias + EdgePriorAcc* epa = new EdgePriorAcc(cv::Mat::zeros(3,1,CV_32F)); + epa->setVertex(0,dynamic_cast(VA)); + double infoPriorA = priorA; + epa->setInformation(infoPriorA*Eigen::Matrix3d::Identity()); + optimizer.addEdge(epa); + EdgePriorGyro* epg = new EdgePriorGyro(cv::Mat::zeros(3,1,CV_32F)); + epg->setVertex(0,dynamic_cast(VG)); + double infoPriorG = priorG; + epg->setInformation(infoPriorG*Eigen::Matrix3d::Identity()); + optimizer.addEdge(epg); + + // Gravity and scale + VertexGDir* VGDir = new VertexGDir(Eigen::Matrix3d::Identity()); + VGDir->setId(maxKFid*2+4); + VGDir->setFixed(true); + optimizer.addVertex(VGDir); + VertexScale* VS = new VertexScale(1.0); + VS->setId(maxKFid*2+5); + VS->setFixed(true); // Fixed since scale is obtained from already well initialized map + optimizer.addVertex(VS); + + // Graph edges + // IMU links with gravity and scale + vector vpei; + vpei.reserve(vpKFs.size()); + vector > vppUsedKF; + vppUsedKF.reserve(vpKFs.size()); + + for(size_t i=0;imPrevKF && pKFi->mnId<=maxKFid) + { + if(pKFi->isBad() || pKFi->mPrevKF->mnId>maxKFid) + continue; + + pKFi->mpImuPreintegrated->SetNewBias(pKFi->mPrevKF->GetImuBias()); + g2o::HyperGraph::Vertex* VP1 = optimizer.vertex(pKFi->mPrevKF->mnId); + g2o::HyperGraph::Vertex* VV1 = optimizer.vertex(maxKFid+(pKFi->mPrevKF->mnId)+1); + g2o::HyperGraph::Vertex* VP2 = optimizer.vertex(pKFi->mnId); + g2o::HyperGraph::Vertex* VV2 = optimizer.vertex(maxKFid+(pKFi->mnId)+1); + g2o::HyperGraph::Vertex* VG = optimizer.vertex(maxKFid*2+2); + g2o::HyperGraph::Vertex* VA = optimizer.vertex(maxKFid*2+3); + g2o::HyperGraph::Vertex* VGDir = optimizer.vertex(maxKFid*2+4); + g2o::HyperGraph::Vertex* VS = optimizer.vertex(maxKFid*2+5); + if(!VP1 || !VV1 || !VG || !VA || !VP2 || !VV2 || !VGDir || !VS) + { + cout << "Error" << VP1 << ", "<< VV1 << ", "<< VG << ", "<< VA << ", " << VP2 << ", " << VV2 << ", "<< VGDir << ", "<< VS <mpImuPreintegrated); + ei->setVertex(0,dynamic_cast(VP1)); + ei->setVertex(1,dynamic_cast(VV1)); + ei->setVertex(2,dynamic_cast(VG)); + ei->setVertex(3,dynamic_cast(VA)); + ei->setVertex(4,dynamic_cast(VP2)); + ei->setVertex(5,dynamic_cast(VV2)); + ei->setVertex(6,dynamic_cast(VGDir)); + ei->setVertex(7,dynamic_cast(VS)); + + vpei.push_back(ei); + + vppUsedKF.push_back(make_pair(pKFi->mPrevKF,pKFi)); + optimizer.addEdge(ei); + + } + } + + // Compute error for different scales + optimizer.setVerbose(false); + optimizer.initializeOptimization(); + optimizer.optimize(its); + + + // Recover optimized data + // Biases + VG = static_cast(optimizer.vertex(maxKFid*2+2)); + VA = static_cast(optimizer.vertex(maxKFid*2+3)); + Vector6d vb; + vb << VG->estimate(), VA->estimate(); + bg << VG->estimate(); + ba << VA->estimate(); + + IMU::Bias b (vb[3],vb[4],vb[5],vb[0],vb[1],vb[2]); + + cv::Mat cvbg = Converter::toCvMat(bg); + + //Keyframes velocities and biases + const int N = vpKFs.size(); + for(size_t i=0; imnId>maxKFid) + continue; + + VertexVelocity* VV = static_cast(optimizer.vertex(maxKFid+(pKFi->mnId)+1)); + Eigen::Vector3d Vw = VV->estimate(); + pKFi->SetVelocity(Converter::toCvMat(Vw)); + + if (cv::norm(pKFi->GetGyroBias()-cvbg)>0.01) + { + pKFi->SetNewBias(b); + if (pKFi->mpImuPreintegrated) + pKFi->mpImuPreintegrated->Reintegrate(); + } + else + pKFi->SetNewBias(b); + } +} + +void Optimizer::InertialOptimization(vector vpKFs, Eigen::Vector3d &bg, Eigen::Vector3d &ba, float priorG, float priorA) +{ + int its = 200; // Check number of iterations + long unsigned int maxKFid = vpKFs[0]->GetMap()->GetMaxKFid(); + + // Setup optimizer + g2o::SparseOptimizer optimizer; + g2o::BlockSolverX::LinearSolverType * linearSolver; + + linearSolver = new g2o::LinearSolverEigen(); + + g2o::BlockSolverX * solver_ptr = new g2o::BlockSolverX(linearSolver); + + g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg(solver_ptr); + solver->setUserLambdaInit(1e3); + + optimizer.setAlgorithm(solver); + + + // Set KeyFrame vertices (fixed poses and optimizable velocities) + for(size_t i=0; imnId>maxKFid) + // continue; + VertexPose * VP = new VertexPose(pKFi); + VP->setId(pKFi->mnId); + VP->setFixed(true); + optimizer.addVertex(VP); + + VertexVelocity* VV = new VertexVelocity(pKFi); + VV->setId(maxKFid+(pKFi->mnId)+1); + VV->setFixed(false); + + optimizer.addVertex(VV); + } + + // Biases + VertexGyroBias* VG = new VertexGyroBias(vpKFs.front()); + VG->setId(maxKFid*2+2); + VG->setFixed(false); + optimizer.addVertex(VG); + + VertexAccBias* VA = new VertexAccBias(vpKFs.front()); + VA->setId(maxKFid*2+3); + VA->setFixed(false); + + optimizer.addVertex(VA); + // prior acc bias + EdgePriorAcc* epa = new EdgePriorAcc(cv::Mat::zeros(3,1,CV_32F)); + epa->setVertex(0,dynamic_cast(VA)); + double infoPriorA = priorA; + epa->setInformation(infoPriorA*Eigen::Matrix3d::Identity()); + optimizer.addEdge(epa); + EdgePriorGyro* epg = new EdgePriorGyro(cv::Mat::zeros(3,1,CV_32F)); + epg->setVertex(0,dynamic_cast(VG)); + double infoPriorG = priorG; + epg->setInformation(infoPriorG*Eigen::Matrix3d::Identity()); + optimizer.addEdge(epg); + + // Gravity and scale + VertexGDir* VGDir = new VertexGDir(Eigen::Matrix3d::Identity()); + VGDir->setId(maxKFid*2+4); + VGDir->setFixed(true); + optimizer.addVertex(VGDir); + VertexScale* VS = new VertexScale(1.0); + VS->setId(maxKFid*2+5); + VS->setFixed(true); // Fixed since scale is obtained from already well initialized map + optimizer.addVertex(VS); + + // Graph edges + // IMU links with gravity and scale + vector vpei; + vpei.reserve(vpKFs.size()); + vector > vppUsedKF; + vppUsedKF.reserve(vpKFs.size()); + + for(size_t i=0;imPrevKF && pKFi->mnId<=maxKFid) + { + if(pKFi->isBad() || pKFi->mPrevKF->mnId>maxKFid) + continue; + + pKFi->mpImuPreintegrated->SetNewBias(pKFi->mPrevKF->GetImuBias()); + g2o::HyperGraph::Vertex* VP1 = optimizer.vertex(pKFi->mPrevKF->mnId); + g2o::HyperGraph::Vertex* VV1 = optimizer.vertex(maxKFid+(pKFi->mPrevKF->mnId)+1); + g2o::HyperGraph::Vertex* VP2 = optimizer.vertex(pKFi->mnId); + g2o::HyperGraph::Vertex* VV2 = optimizer.vertex(maxKFid+(pKFi->mnId)+1); + g2o::HyperGraph::Vertex* VG = optimizer.vertex(maxKFid*2+2); + g2o::HyperGraph::Vertex* VA = optimizer.vertex(maxKFid*2+3); + g2o::HyperGraph::Vertex* VGDir = optimizer.vertex(maxKFid*2+4); + g2o::HyperGraph::Vertex* VS = optimizer.vertex(maxKFid*2+5); + if(!VP1 || !VV1 || !VG || !VA || !VP2 || !VV2 || !VGDir || !VS) + { + cout << "Error" << VP1 << ", "<< VV1 << ", "<< VG << ", "<< VA << ", " << VP2 << ", " << VV2 << ", "<< VGDir << ", "<< VS <mpImuPreintegrated); + ei->setVertex(0,dynamic_cast(VP1)); + ei->setVertex(1,dynamic_cast(VV1)); + ei->setVertex(2,dynamic_cast(VG)); + ei->setVertex(3,dynamic_cast(VA)); + ei->setVertex(4,dynamic_cast(VP2)); + ei->setVertex(5,dynamic_cast(VV2)); + ei->setVertex(6,dynamic_cast(VGDir)); + ei->setVertex(7,dynamic_cast(VS)); + + vpei.push_back(ei); + + vppUsedKF.push_back(make_pair(pKFi->mPrevKF,pKFi)); + optimizer.addEdge(ei); + + } + } + + // Compute error for different scales + optimizer.setVerbose(false); + optimizer.initializeOptimization(); + optimizer.optimize(its); + + + // Recover optimized data + // Biases + VG = static_cast(optimizer.vertex(maxKFid*2+2)); + VA = static_cast(optimizer.vertex(maxKFid*2+3)); + Vector6d vb; + vb << VG->estimate(), VA->estimate(); + bg << VG->estimate(); + ba << VA->estimate(); + + IMU::Bias b (vb[3],vb[4],vb[5],vb[0],vb[1],vb[2]); + + cv::Mat cvbg = Converter::toCvMat(bg); + + //Keyframes velocities and biases + const int N = vpKFs.size(); + for(size_t i=0; imnId>maxKFid) + continue; + + VertexVelocity* VV = static_cast(optimizer.vertex(maxKFid+(pKFi->mnId)+1)); + Eigen::Vector3d Vw = VV->estimate(); + pKFi->SetVelocity(Converter::toCvMat(Vw)); + + if (cv::norm(pKFi->GetGyroBias()-cvbg)>0.01) + { + pKFi->SetNewBias(b); + if (pKFi->mpImuPreintegrated) + pKFi->mpImuPreintegrated->Reintegrate(); + } + else + pKFi->SetNewBias(b); + } +} + + +void Optimizer::InertialOptimization(Map *pMap, Eigen::Matrix3d &Rwg, double &scale) +{ + int its = 10; + long unsigned int maxKFid = pMap->GetMaxKFid(); + const vector vpKFs = pMap->GetAllKeyFrames(); + + // Setup optimizer + g2o::SparseOptimizer optimizer; + g2o::BlockSolverX::LinearSolverType * linearSolver; + + linearSolver = new g2o::LinearSolverEigen(); + + g2o::BlockSolverX * solver_ptr = new g2o::BlockSolverX(linearSolver); + + g2o::OptimizationAlgorithmGaussNewton* solver = new g2o::OptimizationAlgorithmGaussNewton(solver_ptr); + optimizer.setAlgorithm(solver); + + // Set KeyFrame vertices (all variables are fixed) + for(size_t i=0; imnId>maxKFid) + continue; + VertexPose * VP = new VertexPose(pKFi); + VP->setId(pKFi->mnId); + VP->setFixed(true); + optimizer.addVertex(VP); + + VertexVelocity* VV = new VertexVelocity(pKFi); + VV->setId(maxKFid+1+(pKFi->mnId)); + VV->setFixed(true); + optimizer.addVertex(VV); + + // Vertex of fixed biases + VertexGyroBias* VG = new VertexGyroBias(vpKFs.front()); + VG->setId(2*(maxKFid+1)+(pKFi->mnId)); + VG->setFixed(true); + optimizer.addVertex(VG); + VertexAccBias* VA = new VertexAccBias(vpKFs.front()); + VA->setId(3*(maxKFid+1)+(pKFi->mnId)); + VA->setFixed(true); + optimizer.addVertex(VA); + } + + // Gravity and scale + VertexGDir* VGDir = new VertexGDir(Rwg); + VGDir->setId(4*(maxKFid+1)); + VGDir->setFixed(false); + optimizer.addVertex(VGDir); + VertexScale* VS = new VertexScale(scale); + VS->setId(4*(maxKFid+1)+1); + VS->setFixed(false); + optimizer.addVertex(VS); + + // Graph edges + for(size_t i=0;imPrevKF && pKFi->mnId<=maxKFid) + { + if(pKFi->isBad() || pKFi->mPrevKF->mnId>maxKFid) + continue; + + g2o::HyperGraph::Vertex* VP1 = optimizer.vertex(pKFi->mPrevKF->mnId); + g2o::HyperGraph::Vertex* VV1 = optimizer.vertex((maxKFid+1)+pKFi->mPrevKF->mnId); + g2o::HyperGraph::Vertex* VP2 = optimizer.vertex(pKFi->mnId); + g2o::HyperGraph::Vertex* VV2 = optimizer.vertex((maxKFid+1)+pKFi->mnId); + g2o::HyperGraph::Vertex* VG = optimizer.vertex(2*(maxKFid+1)+pKFi->mPrevKF->mnId); + g2o::HyperGraph::Vertex* VA = optimizer.vertex(3*(maxKFid+1)+pKFi->mPrevKF->mnId); + g2o::HyperGraph::Vertex* VGDir = optimizer.vertex(4*(maxKFid+1)); + g2o::HyperGraph::Vertex* VS = optimizer.vertex(4*(maxKFid+1)+1); + if(!VP1 || !VV1 || !VG || !VA || !VP2 || !VV2 || !VGDir || !VS) + { + Verbose::PrintMess("Error" + to_string(VP1->id()) + ", " + to_string(VV1->id()) + ", " + to_string(VG->id()) + ", " + to_string(VA->id()) + ", " + to_string(VP2->id()) + ", " + to_string(VV2->id()) + ", " + to_string(VGDir->id()) + ", " + to_string(VS->id()), Verbose::VERBOSITY_NORMAL); + + continue; + } + EdgeInertialGS* ei = new EdgeInertialGS(pKFi->mpImuPreintegrated); + ei->setVertex(0,dynamic_cast(VP1)); + ei->setVertex(1,dynamic_cast(VV1)); + ei->setVertex(2,dynamic_cast(VG)); + ei->setVertex(3,dynamic_cast(VA)); + ei->setVertex(4,dynamic_cast(VP2)); + ei->setVertex(5,dynamic_cast(VV2)); + ei->setVertex(6,dynamic_cast(VGDir)); + ei->setVertex(7,dynamic_cast(VS)); + + optimizer.addEdge(ei); + } + } + + // Compute error for different scales + optimizer.setVerbose(false); + optimizer.initializeOptimization(); + optimizer.optimize(its); + + // Recover optimized data + scale = VS->estimate(); + Rwg = VGDir->estimate().Rwg; +} + + +void Optimizer::MergeBundleAdjustmentVisual(KeyFrame* pCurrentKF, vector vpWeldingKFs, vector vpFixedKFs, bool *pbStopFlag) +{ + vector vpMPs; + + g2o::SparseOptimizer optimizer; + g2o::BlockSolver_6_3::LinearSolverType * linearSolver; + + linearSolver = new g2o::LinearSolverEigen(); + + g2o::BlockSolver_6_3 * solver_ptr = new g2o::BlockSolver_6_3(linearSolver); + + g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg(solver_ptr); + optimizer.setAlgorithm(solver); + + if(pbStopFlag) + optimizer.setForceStopFlag(pbStopFlag); + + long unsigned int maxKFid = 0; + set spKeyFrameBA; + + // Set not fixed KeyFrame vertices + for(KeyFrame* pKFi : vpWeldingKFs) + { + if(pKFi->isBad()) + continue; + + pKFi->mnBALocalForKF = pCurrentKF->mnId; + + g2o::VertexSE3Expmap * vSE3 = new g2o::VertexSE3Expmap(); + vSE3->setEstimate(Converter::toSE3Quat(pKFi->GetPose())); + vSE3->setId(pKFi->mnId); + vSE3->setFixed(false); + optimizer.addVertex(vSE3); + if(pKFi->mnId>maxKFid) + maxKFid=pKFi->mnId; + + set spViewMPs = pKFi->GetMapPoints(); + for(MapPoint* pMPi : spViewMPs) + { + if(pMPi) + if(!pMPi->isBad()) + if(pMPi->mnBALocalForKF!=pCurrentKF->mnId) + { + vpMPs.push_back(pMPi); + pMPi->mnBALocalForKF=pCurrentKF->mnId; + } + } + + spKeyFrameBA.insert(pKFi); + } + + // Set fixed KeyFrame vertices + for(KeyFrame* pKFi : vpFixedKFs) + { + if(pKFi->isBad()) + continue; + + pKFi->mnBALocalForKF = pCurrentKF->mnId; + + g2o::VertexSE3Expmap * vSE3 = new g2o::VertexSE3Expmap(); + vSE3->setEstimate(Converter::toSE3Quat(pKFi->GetPose())); + vSE3->setId(pKFi->mnId); + vSE3->setFixed(true); + optimizer.addVertex(vSE3); + if(pKFi->mnId>maxKFid) + maxKFid=pKFi->mnId; + + set spViewMPs = pKFi->GetMapPoints(); + for(MapPoint* pMPi : spViewMPs) + { + if(pMPi) + if(!pMPi->isBad()) + if(pMPi->mnBALocalForKF!=pCurrentKF->mnId) + { + vpMPs.push_back(pMPi); + pMPi->mnBALocalForKF=pCurrentKF->mnId; + } + } + + spKeyFrameBA.insert(pKFi); + } + + + const int nExpectedSize = (vpWeldingKFs.size()+vpFixedKFs.size())*vpMPs.size(); + + vector vpEdgesMono; + vpEdgesMono.reserve(nExpectedSize); + + vector vpEdgeKFMono; + vpEdgeKFMono.reserve(nExpectedSize); + + vector vpMapPointEdgeMono; + vpMapPointEdgeMono.reserve(nExpectedSize); + + vector vpEdgesStereo; + vpEdgesStereo.reserve(nExpectedSize); + + vector vpEdgeKFStereo; + vpEdgeKFStereo.reserve(nExpectedSize); + + vector vpMapPointEdgeStereo; + vpMapPointEdgeStereo.reserve(nExpectedSize); + + const float thHuber2D = sqrt(5.99); + const float thHuber3D = sqrt(7.815); + + // Set MapPoint vertices + for(unsigned int i=0; i < vpMPs.size(); ++i) + { + MapPoint* pMPi = vpMPs[i]; + if(pMPi->isBad()) + continue; + + g2o::VertexSBAPointXYZ* vPoint = new g2o::VertexSBAPointXYZ(); + vPoint->setEstimate(Converter::toVector3d(pMPi->GetWorldPos())); + const int id = pMPi->mnId+maxKFid+1; + vPoint->setId(id); + vPoint->setMarginalized(true); + optimizer.addVertex(vPoint); + + + const map> observations = pMPi->GetObservations(); + int nEdges = 0; + //SET EDGES + for(map>::const_iterator mit=observations.begin(); mit!=observations.end(); mit++) + { + //cout << "--KF view init" << endl; + + KeyFrame* pKF = mit->first; + if(spKeyFrameBA.find(pKF) == spKeyFrameBA.end() || pKF->isBad() || pKF->mnId>maxKFid || pKF->mnBALocalForKF != pCurrentKF->mnId || !pKF->GetMapPoint(get<0>(mit->second))) + continue; + + //cout << "-- KF view exists" << endl; + nEdges++; + + const cv::KeyPoint &kpUn = pKF->mvKeysUn[get<0>(mit->second)]; + //cout << "-- KeyPoint loads" << endl; + + if(pKF->mvuRight[get<0>(mit->second)]<0) //Monocular + { + Eigen::Matrix obs; + obs << kpUn.pt.x, kpUn.pt.y; + + g2o::EdgeSE3ProjectXYZ* e = new g2o::EdgeSE3ProjectXYZ(); + + + e->setVertex(0, dynamic_cast(optimizer.vertex(id))); + e->setVertex(1, dynamic_cast(optimizer.vertex(pKF->mnId))); + e->setMeasurement(obs); + const float &invSigma2 = pKF->mvInvLevelSigma2[kpUn.octave]; + e->setInformation(Eigen::Matrix2d::Identity()*invSigma2); + //cout << "-- Sigma loads" << endl; + + g2o::RobustKernelHuber* rk = new g2o::RobustKernelHuber; + e->setRobustKernel(rk); + rk->setDelta(thHuber2D); + + e->fx = pKF->fx; + e->fy = pKF->fy; + e->cx = pKF->cx; + e->cy = pKF->cy; + //cout << "-- Calibration loads" << endl; + + optimizer.addEdge(e); + //cout << "-- Edge added" << endl; + + vpEdgesMono.push_back(e); + vpEdgeKFMono.push_back(pKF); + vpMapPointEdgeMono.push_back(pMPi); + //cout << "-- Added to vector" << endl; + } + else // RGBD or Stereo + { + Eigen::Matrix obs; + const float kp_ur = pKF->mvuRight[get<0>(mit->second)]; + obs << kpUn.pt.x, kpUn.pt.y, kp_ur; + + g2o::EdgeStereoSE3ProjectXYZ* e = new g2o::EdgeStereoSE3ProjectXYZ(); + + e->setVertex(0, dynamic_cast(optimizer.vertex(id))); + e->setVertex(1, dynamic_cast(optimizer.vertex(pKF->mnId))); + e->setMeasurement(obs); + const float &invSigma2 = pKF->mvInvLevelSigma2[kpUn.octave]; + Eigen::Matrix3d Info = Eigen::Matrix3d::Identity()*invSigma2; + e->setInformation(Info); + + g2o::RobustKernelHuber* rk = new g2o::RobustKernelHuber; + e->setRobustKernel(rk); + rk->setDelta(thHuber3D); + + e->fx = pKF->fx; + e->fy = pKF->fy; + e->cx = pKF->cx; + e->cy = pKF->cy; + e->bf = pKF->mbf; + + optimizer.addEdge(e); + + vpEdgesStereo.push_back(e); + vpEdgeKFStereo.push_back(pKF); + vpMapPointEdgeStereo.push_back(pMPi); + } + //cout << "-- End to load point" << endl; + } + } + + //cout << "End to load MPs" << endl; + + if(pbStopFlag) + if(*pbStopFlag) + return; + + optimizer.initializeOptimization(); + optimizer.optimize(5); + + //cout << "End the first optimization" << endl; + + bool bDoMore= true; + + if(pbStopFlag) + if(*pbStopFlag) + bDoMore = false; + + if(bDoMore) + { + + // Check inlier observations + for(size_t i=0, iend=vpEdgesMono.size(); iisBad()) + continue; + + if(e->chi2()>5.991 || !e->isDepthPositive()) + { + e->setLevel(1); + } + + e->setRobustKernel(0); + } + + for(size_t i=0, iend=vpEdgesStereo.size(); iisBad()) + continue; + + if(e->chi2()>7.815 || !e->isDepthPositive()) + { + e->setLevel(1); + } + + e->setRobustKernel(0); + } + + // Optimize again without the outliers + + optimizer.initializeOptimization(0); + optimizer.optimize(10); + + //cout << "End the second optimization (without outliers)" << endl; + } + + vector > vToErase; + vToErase.reserve(vpEdgesMono.size()+vpEdgesStereo.size()); + + // Check inlier observations + for(size_t i=0, iend=vpEdgesMono.size(); iisBad()) + continue; + + if(e->chi2()>5.991 || !e->isDepthPositive()) + { + KeyFrame* pKFi = vpEdgeKFMono[i]; + vToErase.push_back(make_pair(pKFi,pMP)); + } + } + + for(size_t i=0, iend=vpEdgesStereo.size(); iisBad()) + continue; + + if(e->chi2()>7.815 || !e->isDepthPositive()) + { + KeyFrame* pKFi = vpEdgeKFStereo[i]; + vToErase.push_back(make_pair(pKFi,pMP)); + } + } + + // Get Map Mutex + unique_lock lock(pCurrentKF->GetMap()->mMutexMapUpdate); + + if(!vToErase.empty()) + { + for(size_t i=0;iEraseMapPointMatch(pMPi); + pMPi->EraseObservation(pKFi); + } + } + //cout << "End to erase observations" << endl; + + // Recover optimized data + + //Keyframes + for(KeyFrame* pKFi : vpWeldingKFs) + { + if(pKFi->isBad()) + continue; + + g2o::VertexSE3Expmap* vSE3 = static_cast(optimizer.vertex(pKFi->mnId)); + g2o::SE3Quat SE3quat = vSE3->estimate(); + pKFi->SetPose(Converter::toCvMat(SE3quat)); + + } + //cout << "End to update the KeyFrames" << endl; + + //Points + for(MapPoint* pMPi : vpMPs) + { + if(pMPi->isBad()) + continue; + + g2o::VertexSBAPointXYZ* vPoint = static_cast(optimizer.vertex(pMPi->mnId+maxKFid+1)); + pMPi->SetWorldPos(Converter::toCvMat(vPoint->estimate())); + pMPi->UpdateNormalAndDepth(); + + } +} + +void Optimizer::LocalBundleAdjustment(KeyFrame* pMainKF,vector vpAdjustKF, vector vpFixedKF, bool *pbStopFlag) +{ + bool bShowImages = false; + + vector vpMPs; + + g2o::SparseOptimizer optimizer; + g2o::BlockSolver_6_3::LinearSolverType * linearSolver; + + linearSolver = new g2o::LinearSolverEigen(); + + g2o::BlockSolver_6_3 * solver_ptr = new g2o::BlockSolver_6_3(linearSolver); + + g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg(solver_ptr); + optimizer.setAlgorithm(solver); + + optimizer.setVerbose(false); + + if(pbStopFlag) + optimizer.setForceStopFlag(pbStopFlag); + + long unsigned int maxKFid = 0; + set spKeyFrameBA; + + Map* pCurrentMap = pMainKF->GetMap(); + + //set sNumObsMP; + + // Set fixed KeyFrame vertices + for(KeyFrame* pKFi : vpFixedKF) + { + if(pKFi->isBad() || pKFi->GetMap() != pCurrentMap) + { + Verbose::PrintMess("ERROR LBA: KF is bad or is not in the current map", Verbose::VERBOSITY_NORMAL); + continue; + } + + pKFi->mnBALocalForMerge = pMainKF->mnId; + + g2o::VertexSE3Expmap * vSE3 = new g2o::VertexSE3Expmap(); + vSE3->setEstimate(Converter::toSE3Quat(pKFi->GetPose())); + vSE3->setId(pKFi->mnId); + vSE3->setFixed(true); + optimizer.addVertex(vSE3); + if(pKFi->mnId>maxKFid) + maxKFid=pKFi->mnId; + + set spViewMPs = pKFi->GetMapPoints(); + for(MapPoint* pMPi : spViewMPs) + { + if(pMPi) + if(!pMPi->isBad() && pMPi->GetMap() == pCurrentMap) + + if(pMPi->mnBALocalForMerge!=pMainKF->mnId) + { + vpMPs.push_back(pMPi); + pMPi->mnBALocalForMerge=pMainKF->mnId; + } + /*if(sNumObsMP.find(pMPi) == sNumObsMP.end()) + { + sNumObsMP.insert(pMPi); + } + else + { + if(pMPi->mnBALocalForMerge!=pMainKF->mnId) + { + vpMPs.push_back(pMPi); + pMPi->mnBALocalForMerge=pMainKF->mnId; + } + }*/ + } + + spKeyFrameBA.insert(pKFi); + } + + //cout << "End to load Fixed KFs" << endl; + + // Set non fixed Keyframe vertices + set spAdjustKF(vpAdjustKF.begin(), vpAdjustKF.end()); + for(KeyFrame* pKFi : vpAdjustKF) + { + if(pKFi->isBad() || pKFi->GetMap() != pCurrentMap) + continue; + + pKFi->mnBALocalForKF = pMainKF->mnId; + + g2o::VertexSE3Expmap * vSE3 = new g2o::VertexSE3Expmap(); + vSE3->setEstimate(Converter::toSE3Quat(pKFi->GetPose())); + vSE3->setId(pKFi->mnId); + optimizer.addVertex(vSE3); + if(pKFi->mnId>maxKFid) + maxKFid=pKFi->mnId; + + set spViewMPs = pKFi->GetMapPoints(); + for(MapPoint* pMPi : spViewMPs) + { + if(pMPi) + { + if(!pMPi->isBad() && pMPi->GetMap() == pCurrentMap) + { + /*if(sNumObsMP.find(pMPi) == sNumObsMP.end()) + { + sNumObsMP.insert(pMPi); + }*/ + if(pMPi->mnBALocalForMerge != pMainKF->mnId) + { + vpMPs.push_back(pMPi); + pMPi->mnBALocalForMerge = pMainKF->mnId; + } + } + } + } + + spKeyFrameBA.insert(pKFi); + } + + //Verbose::PrintMess("LBA: There are " + to_string(vpMPs.size()) + " MPs to optimize", Verbose::VERBOSITY_NORMAL); + + //cout << "End to load KFs for position adjust" << endl; + + const int nExpectedSize = (vpAdjustKF.size()+vpFixedKF.size())*vpMPs.size(); + + vector vpEdgesMono; + vpEdgesMono.reserve(nExpectedSize); + + vector vpEdgeKFMono; + vpEdgeKFMono.reserve(nExpectedSize); + + vector vpMapPointEdgeMono; + vpMapPointEdgeMono.reserve(nExpectedSize); + + vector vpEdgesStereo; + vpEdgesStereo.reserve(nExpectedSize); + + vector vpEdgeKFStereo; + vpEdgeKFStereo.reserve(nExpectedSize); + + vector vpMapPointEdgeStereo; + vpMapPointEdgeStereo.reserve(nExpectedSize); + + const float thHuber2D = sqrt(5.99); + const float thHuber3D = sqrt(7.815); + + // Set MapPoint vertices + map mpObsKFs; + map mpObsFinalKFs; + map mpObsMPs; + for(unsigned int i=0; i < vpMPs.size(); ++i) + { + MapPoint* pMPi = vpMPs[i]; + if(pMPi->isBad()) + continue; + + g2o::VertexSBAPointXYZ* vPoint = new g2o::VertexSBAPointXYZ(); + vPoint->setEstimate(Converter::toVector3d(pMPi->GetWorldPos())); + const int id = pMPi->mnId+maxKFid+1; + vPoint->setId(id); + vPoint->setMarginalized(true); + optimizer.addVertex(vPoint); + + + const map> observations = pMPi->GetObservations(); + int nEdges = 0; + //SET EDGES + for(map>::const_iterator mit=observations.begin(); mit!=observations.end(); mit++) + { + //cout << "--KF view init" << endl; + + KeyFrame* pKF = mit->first; + if(pKF->isBad() || pKF->mnId>maxKFid || pKF->mnBALocalForMerge != pMainKF->mnId || !pKF->GetMapPoint(get<0>(mit->second))) + continue; + + //cout << "-- KF view exists" << endl; + nEdges++; + + const cv::KeyPoint &kpUn = pKF->mvKeysUn[get<0>(mit->second)]; + //cout << "-- KeyPoint loads" << endl; + + if(pKF->mvuRight[get<0>(mit->second)]<0) //Monocular + { + mpObsMPs[pMPi]++; + Eigen::Matrix obs; + obs << kpUn.pt.x, kpUn.pt.y; + + ORB_SLAM3::EdgeSE3ProjectXYZ* e = new ORB_SLAM3::EdgeSE3ProjectXYZ(); + + + e->setVertex(0, dynamic_cast(optimizer.vertex(id))); + e->setVertex(1, dynamic_cast(optimizer.vertex(pKF->mnId))); + e->setMeasurement(obs); + const float &invSigma2 = pKF->mvInvLevelSigma2[kpUn.octave]; + e->setInformation(Eigen::Matrix2d::Identity()*invSigma2); + //cout << "-- Sigma loads" << endl; + + g2o::RobustKernelHuber* rk = new g2o::RobustKernelHuber; + e->setRobustKernel(rk); + rk->setDelta(thHuber2D); + + e->pCamera = pKF->mpCamera; + //cout << "-- Calibration loads" << endl; + + optimizer.addEdge(e); + //cout << "-- Edge added" << endl; + + vpEdgesMono.push_back(e); + vpEdgeKFMono.push_back(pKF); + vpMapPointEdgeMono.push_back(pMPi); + //cout << "-- Added to vector" << endl; + + mpObsKFs[pKF]++; + } + else // RGBD or Stereo + { + mpObsMPs[pMPi]+=2; + Eigen::Matrix obs; + const float kp_ur = pKF->mvuRight[get<0>(mit->second)]; + obs << kpUn.pt.x, kpUn.pt.y, kp_ur; + + g2o::EdgeStereoSE3ProjectXYZ* e = new g2o::EdgeStereoSE3ProjectXYZ(); + + e->setVertex(0, dynamic_cast(optimizer.vertex(id))); + e->setVertex(1, dynamic_cast(optimizer.vertex(pKF->mnId))); + e->setMeasurement(obs); + const float &invSigma2 = pKF->mvInvLevelSigma2[kpUn.octave]; + Eigen::Matrix3d Info = Eigen::Matrix3d::Identity()*invSigma2; + e->setInformation(Info); + + g2o::RobustKernelHuber* rk = new g2o::RobustKernelHuber; + e->setRobustKernel(rk); + rk->setDelta(thHuber3D); + + e->fx = pKF->fx; + e->fy = pKF->fy; + e->cx = pKF->cx; + e->cy = pKF->cy; + e->bf = pKF->mbf; + + optimizer.addEdge(e); + + vpEdgesStereo.push_back(e); + vpEdgeKFStereo.push_back(pKF); + vpMapPointEdgeStereo.push_back(pMPi); + + mpObsKFs[pKF]++; + } + //cout << "-- End to load point" << endl; + } + } + //Verbose::PrintMess("LBA: number total of edged -> " + to_string(vpEdgeKFMono.size() + vpEdgeKFStereo.size()), Verbose::VERBOSITY_NORMAL); + + map mStatsObs; + for(map::iterator it = mpObsMPs.begin(); it != mpObsMPs.end(); ++it) + { + MapPoint* pMPi = it->first; + int numObs = it->second; + + mStatsObs[numObs]++; + /*if(numObs < 5) + { + cout << "LBA: MP " << pMPi->mnId << " has " << numObs << " observations" << endl; + }*/ + } + + /*for(map::iterator it = mStatsObs.begin(); it != mStatsObs.end(); ++it) + { + cout << "LBA: There are " << it->second << " MPs with " << it->first << " observations" << endl; + }*/ + + //cout << "End to load MPs" << endl; + + if(pbStopFlag) + if(*pbStopFlag) + return; + + optimizer.initializeOptimization(); + optimizer.optimize(5); + + //cout << "End the first optimization" << endl; + + bool bDoMore= true; + + if(pbStopFlag) + if(*pbStopFlag) + bDoMore = false; + + map mWrongObsKF; + if(bDoMore) + { + + // Check inlier observations + int badMonoMP = 0, badStereoMP = 0; + for(size_t i=0, iend=vpEdgesMono.size(); iisBad()) + continue; + + if(e->chi2()>5.991 || !e->isDepthPositive()) + { + e->setLevel(1); + badMonoMP++; + } + + e->setRobustKernel(0); + } + + for(size_t i=0, iend=vpEdgesStereo.size(); iisBad()) + continue; + + if(e->chi2()>7.815 || !e->isDepthPositive()) + { + e->setLevel(1); + badStereoMP++; + } + + e->setRobustKernel(0); + } + Verbose::PrintMess("LBA: First optimization, there are " + to_string(badMonoMP) + " monocular and " + to_string(badStereoMP) + " sterero bad edges", Verbose::VERBOSITY_DEBUG); + + // Optimize again without the outliers + + optimizer.initializeOptimization(0); + optimizer.optimize(10); + + //cout << "End the second optimization (without outliers)" << endl; + } + + vector > vToErase; + vToErase.reserve(vpEdgesMono.size()+vpEdgesStereo.size()); + set spErasedMPs; + set spErasedKFs; + + // Check inlier observations + int badMonoMP = 0, badStereoMP = 0; + for(size_t i=0, iend=vpEdgesMono.size(); iisBad()) + continue; + + if(e->chi2()>5.991 || !e->isDepthPositive()) + { + KeyFrame* pKFi = vpEdgeKFMono[i]; + vToErase.push_back(make_pair(pKFi,pMP)); + mWrongObsKF[pKFi->mnId]++; + badMonoMP++; + + spErasedMPs.insert(pMP); + spErasedKFs.insert(pKFi); + } + } + + for(size_t i=0, iend=vpEdgesStereo.size(); iisBad()) + continue; + + if(e->chi2()>7.815 || !e->isDepthPositive()) + { + KeyFrame* pKFi = vpEdgeKFStereo[i]; + vToErase.push_back(make_pair(pKFi,pMP)); + mWrongObsKF[pKFi->mnId]++; + badStereoMP++; + + spErasedMPs.insert(pMP); + spErasedKFs.insert(pKFi); + } + } + Verbose::PrintMess("LBA: Second optimization, there are " + to_string(badMonoMP) + " monocular and " + to_string(badStereoMP) + " sterero bad edges", Verbose::VERBOSITY_DEBUG); + + // Get Map Mutex + unique_lock lock(pMainKF->GetMap()->mMutexMapUpdate); + + if(!vToErase.empty()) + { + map mpMPs_in_KF; + for(KeyFrame* pKFi : spErasedKFs) + { + int num_MPs = pKFi->GetMapPoints().size(); + mpMPs_in_KF[pKFi] = num_MPs; + } + + Verbose::PrintMess("LBA: There are " + to_string(vToErase.size()) + " observations whose will be deleted from the map", Verbose::VERBOSITY_DEBUG); + for(size_t i=0;iEraseMapPointMatch(pMPi); + pMPi->EraseObservation(pKFi); + } + + Verbose::PrintMess("LBA: " + to_string(spErasedMPs.size()) + " MPs had deleted observations", Verbose::VERBOSITY_DEBUG); + Verbose::PrintMess("LBA: Current map is " + to_string(pMainKF->GetMap()->GetId()), Verbose::VERBOSITY_DEBUG); + int numErasedMP = 0; + for(MapPoint* pMPi : spErasedMPs) + { + if(pMPi->isBad()) + { + Verbose::PrintMess("LBA: MP " + to_string(pMPi->mnId) + " has lost almost all the observations, its origin map is " + to_string(pMPi->mnOriginMapId), Verbose::VERBOSITY_DEBUG); + numErasedMP++; + } + } + Verbose::PrintMess("LBA: " + to_string(numErasedMP) + " MPs had deleted from the map", Verbose::VERBOSITY_DEBUG); + + for(KeyFrame* pKFi : spErasedKFs) + { + int num_MPs = pKFi->GetMapPoints().size(); + int num_init_MPs = mpMPs_in_KF[pKFi]; + Verbose::PrintMess("LBA: Initially KF " + to_string(pKFi->mnId) + " had " + to_string(num_init_MPs) + ", at the end has " + to_string(num_MPs), Verbose::VERBOSITY_DEBUG); + } + } + for(unsigned int i=0; i < vpMPs.size(); ++i) + { + MapPoint* pMPi = vpMPs[i]; + if(pMPi->isBad()) + continue; + + const map> observations = pMPi->GetObservations(); + for(map>::const_iterator mit=observations.begin(); mit!=observations.end(); mit++) + { + //cout << "--KF view init" << endl; + + KeyFrame* pKF = mit->first; + if(pKF->isBad() || pKF->mnId>maxKFid || pKF->mnBALocalForKF != pMainKF->mnId || !pKF->GetMapPoint(get<0>(mit->second))) + continue; + + const cv::KeyPoint &kpUn = pKF->mvKeysUn[get<0>(mit->second)]; + //cout << "-- KeyPoint loads" << endl; + + if(pKF->mvuRight[get<0>(mit->second)]<0) //Monocular + { + mpObsFinalKFs[pKF]++; + } + else // RGBD or Stereo + { + + mpObsFinalKFs[pKF]++; + } + //cout << "-- End to load point" << endl; + } + } + + //cout << "End to erase observations" << endl; + + // Recover optimized data + + //Keyframes + for(KeyFrame* pKFi : vpAdjustKF) + { + if(pKFi->isBad()) + continue; + + g2o::VertexSE3Expmap* vSE3 = static_cast(optimizer.vertex(pKFi->mnId)); + g2o::SE3Quat SE3quat = vSE3->estimate(); + cv::Mat Tiw = Converter::toCvMat(SE3quat); + cv::Mat Tco_cn = pKFi->GetPose() * Tiw.inv(); + cv::Vec3d trasl = Tco_cn.rowRange(0,3).col(3); + double dist = cv::norm(trasl); + + int numMonoBadPoints = 0, numMonoOptPoints = 0; + int numStereoBadPoints = 0, numStereoOptPoints = 0; + vector vpMonoMPsOpt, vpStereoMPsOpt; + vector vpMonoMPsBad, vpStereoMPsBad; + + for(size_t i=0, iend=vpEdgesMono.size(); iisBad()) + continue; + + if(e->chi2()>5.991 || !e->isDepthPositive()) + { + numMonoBadPoints++; + vpMonoMPsBad.push_back(pMP); + + } + else + { + numMonoOptPoints++; + vpMonoMPsOpt.push_back(pMP); + } + + } + + for(size_t i=0, iend=vpEdgesStereo.size(); iisBad()) + continue; + + if(e->chi2()>7.815 || !e->isDepthPositive()) + { + numStereoBadPoints++; + vpStereoMPsBad.push_back(pMP); + } + else + { + numStereoOptPoints++; + vpStereoMPsOpt.push_back(pMP); + } + } + + + if(numMonoOptPoints + numStereoOptPoints < 50) + { + Verbose::PrintMess("LBA ERROR: KF " + to_string(pKFi->mnId) + " has only " + to_string(numMonoOptPoints) + " monocular and " + to_string(numStereoOptPoints) + " stereo points", Verbose::VERBOSITY_DEBUG); + } + if(dist > 1.0) + { + if(bShowImages) + { + string strNameFile = pKFi->mNameFile; + cv::Mat imLeft = cv::imread(strNameFile, cv::IMREAD_UNCHANGED); + + cv::cvtColor(imLeft, imLeft, CV_GRAY2BGR); + + int numPointsMono = 0, numPointsStereo = 0; + int numPointsMonoBad = 0, numPointsStereoBad = 0; + for(int i=0; iisBad()) + { + continue; + } + int index = get<0>(vpMonoMPsOpt[i]->GetIndexInKeyFrame(pKFi)); + if(index < 0) + { + //cout << "LBA ERROR: KF has a monocular observation which is not recognized by the MP" << endl; + //cout << "LBA: KF " << pKFi->mnId << " and MP " << vpMonoMPsOpt[i]->mnId << " with index " << endl; + continue; + } + + //string strNumOBs = to_string(vpMapPointsKF[i]->Observations()); + cv::circle(imLeft, pKFi->mvKeys[index].pt, 2, cv::Scalar(255, 0, 0)); + //cv::putText(imLeft, strNumOBs, pKF->mvKeys[i].pt, CV_FONT_HERSHEY_DUPLEX, 1, cv::Scalar(255, 0, 0)); + numPointsMono++; + } + + for(int i=0; iisBad()) + { + continue; + } + int index = get<0>(vpStereoMPsOpt[i]->GetIndexInKeyFrame(pKFi)); + if(index < 0) + { + //cout << "LBA: KF has a stereo observation which is not recognized by the MP" << endl; + //cout << "LBA: KF " << pKFi->mnId << " and MP " << vpStereoMPsOpt[i]->mnId << endl; + continue; + } + + //string strNumOBs = to_string(vpMapPointsKF[i]->Observations()); + cv::circle(imLeft, pKFi->mvKeys[index].pt, 2, cv::Scalar(0, 255, 0)); + //cv::putText(imLeft, strNumOBs, pKF->mvKeys[i].pt, CV_FONT_HERSHEY_DUPLEX, 1, cv::Scalar(255, 0, 0)); + numPointsStereo++; + } + + for(int i=0; iisBad()) + { + continue; + } + int index = get<0>(vpMonoMPsBad[i]->GetIndexInKeyFrame(pKFi)); + if(index < 0) + { + //cout << "LBA ERROR: KF has a monocular observation which is not recognized by the MP" << endl; + //cout << "LBA: KF " << pKFi->mnId << " and MP " << vpMonoMPsOpt[i]->mnId << " with index " << endl; + continue; + } + + //string strNumOBs = to_string(vpMapPointsKF[i]->Observations()); + cv::circle(imLeft, pKFi->mvKeys[index].pt, 2, cv::Scalar(0, 0, 255)); + //cv::putText(imLeft, strNumOBs, pKF->mvKeys[i].pt, CV_FONT_HERSHEY_DUPLEX, 1, cv::Scalar(255, 0, 0)); + numPointsMonoBad++; + } + for(int i=0; iisBad()) + { + continue; + } + int index = get<0>(vpStereoMPsBad[i]->GetIndexInKeyFrame(pKFi)); + if(index < 0) + { + //cout << "LBA: KF has a stereo observation which is not recognized by the MP" << endl; + //cout << "LBA: KF " << pKFi->mnId << " and MP " << vpStereoMPsOpt[i]->mnId << endl; + continue; + } + + //string strNumOBs = to_string(vpMapPointsKF[i]->Observations()); + cv::circle(imLeft, pKFi->mvKeys[index].pt, 2, cv::Scalar(0, 0, 255)); + //cv::putText(imLeft, strNumOBs, pKF->mvKeys[i].pt, CV_FONT_HERSHEY_DUPLEX, 1, cv::Scalar(255, 0, 0)); + numPointsStereoBad++; + } + + string namefile = "./test_LBA/LBA_KF" + to_string(pKFi->mnId) + "_" + to_string(numPointsMono + numPointsStereo) +"_D" + to_string(dist) +".png"; + cv::imwrite(namefile, imLeft); + + Verbose::PrintMess("--LBA in KF " + to_string(pKFi->mnId), Verbose::VERBOSITY_DEBUG); + Verbose::PrintMess("--Distance: " + to_string(dist) + " meters", Verbose::VERBOSITY_DEBUG); + Verbose::PrintMess("--Number of observations: " + to_string(numMonoOptPoints) + " in mono and " + to_string(numStereoOptPoints) + " in stereo", Verbose::VERBOSITY_DEBUG); + Verbose::PrintMess("--Number of discarded observations: " + to_string(numMonoBadPoints) + " in mono and " + to_string(numStereoBadPoints) + " in stereo", Verbose::VERBOSITY_DEBUG); + Verbose::PrintMess("--To much distance correction in LBA: It has " + to_string(mpObsKFs[pKFi]) + " observated MPs", Verbose::VERBOSITY_DEBUG); + Verbose::PrintMess("--To much distance correction in LBA: It has " + to_string(mpObsFinalKFs[pKFi]) + " deleted observations", Verbose::VERBOSITY_DEBUG); + Verbose::PrintMess("--------", Verbose::VERBOSITY_DEBUG); + } + } + pKFi->SetPose(Tiw); + + } + //cout << "End to update the KeyFrames" << endl; + + //Points + for(MapPoint* pMPi : vpMPs) + { + if(pMPi->isBad()) + continue; + + g2o::VertexSBAPointXYZ* vPoint = static_cast(optimizer.vertex(pMPi->mnId+maxKFid+1)); + pMPi->SetWorldPos(Converter::toCvMat(vPoint->estimate())); + pMPi->UpdateNormalAndDepth(); + + } + //cout << "End to update MapPoint" << endl; +} + + +void Optimizer::MergeInertialBA(KeyFrame* pCurrKF, KeyFrame* pMergeKF, bool *pbStopFlag, Map *pMap, LoopClosing::KeyFrameAndPose &corrPoses) +{ + const int Nd = 6; + const unsigned long maxKFid = pCurrKF->mnId; + + vector vpOptimizableKFs; + vpOptimizableKFs.reserve(2*Nd); + + // For cov KFS, inertial parameters are not optimized + const int maxCovKF=30; + vector vpOptimizableCovKFs; + vpOptimizableCovKFs.reserve(maxCovKF); + + // Add sliding window for current KF + vpOptimizableKFs.push_back(pCurrKF); + pCurrKF->mnBALocalForKF = pCurrKF->mnId; + for(int i=1; imPrevKF) + { + vpOptimizableKFs.push_back(vpOptimizableKFs.back()->mPrevKF); + vpOptimizableKFs.back()->mnBALocalForKF = pCurrKF->mnId; + } + else + break; + } + + list lFixedKeyFrames; + if(vpOptimizableKFs.back()->mPrevKF) + { + vpOptimizableCovKFs.push_back(vpOptimizableKFs.back()->mPrevKF); + vpOptimizableKFs.back()->mPrevKF->mnBALocalForKF=pCurrKF->mnId; + } + else + { + vpOptimizableCovKFs.push_back(vpOptimizableKFs.back()); + vpOptimizableKFs.pop_back(); + } + + KeyFrame* pKF0 = vpOptimizableCovKFs.back(); + cv::Mat Twc0 = pKF0->GetPoseInverse(); + + // Add temporal neighbours to merge KF (previous and next KFs) + vpOptimizableKFs.push_back(pMergeKF); + pMergeKF->mnBALocalForKF = pCurrKF->mnId; + + // Previous KFs + for(int i=1; i<(Nd/2); i++) + { + if(vpOptimizableKFs.back()->mPrevKF) + { + vpOptimizableKFs.push_back(vpOptimizableKFs.back()->mPrevKF); + vpOptimizableKFs.back()->mnBALocalForKF = pCurrKF->mnId; + } + else + break; + } + + // We fix just once the old map + if(vpOptimizableKFs.back()->mPrevKF) + { + lFixedKeyFrames.push_back(vpOptimizableKFs.back()->mPrevKF); + vpOptimizableKFs.back()->mPrevKF->mnBAFixedForKF=pCurrKF->mnId; + } + else + { + vpOptimizableKFs.back()->mnBALocalForKF=0; + vpOptimizableKFs.back()->mnBAFixedForKF=pCurrKF->mnId; + lFixedKeyFrames.push_back(vpOptimizableKFs.back()); + vpOptimizableKFs.pop_back(); + } + + // Next KFs + if(pMergeKF->mNextKF) + { + vpOptimizableKFs.push_back(pMergeKF->mNextKF); + vpOptimizableKFs.back()->mnBALocalForKF = pCurrKF->mnId; + } + + while(vpOptimizableKFs.size()<(2*Nd)) + { + if(vpOptimizableKFs.back()->mNextKF) + { + vpOptimizableKFs.push_back(vpOptimizableKFs.back()->mNextKF); + vpOptimizableKFs.back()->mnBALocalForKF = pCurrKF->mnId; + } + else + break; + } + + int N = vpOptimizableKFs.size(); + + // Optimizable points seen by optimizable keyframes + list lLocalMapPoints; + map mLocalObs; + for(int i=0; i vpMPs = vpOptimizableKFs[i]->GetMapPointMatches(); + for(vector::iterator vit=vpMPs.begin(), vend=vpMPs.end(); vit!=vend; vit++) + { + // Using mnBALocalForKF we avoid redundance here, one MP can not be added several times to lLocalMapPoints + MapPoint* pMP = *vit; + if(pMP) + if(!pMP->isBad()) + if(pMP->mnBALocalForKF!=pCurrKF->mnId) + { + mLocalObs[pMP]=1; + lLocalMapPoints.push_back(pMP); + pMP->mnBALocalForKF=pCurrKF->mnId; + } + else + mLocalObs[pMP]++; + } + } + + std::vector> pairs; + pairs.reserve(mLocalObs.size()); + for (auto itr = mLocalObs.begin(); itr != mLocalObs.end(); ++itr) + pairs.push_back(*itr); + sort(pairs.begin(), pairs.end(),sortByVal); + + // Fixed Keyframes. Keyframes that see Local MapPoints but that are not Local Keyframes + int i=0; + for(vector>::iterator lit=pairs.begin(), lend=pairs.end(); lit!=lend; lit++, i++) + { + map> observations = lit->first->GetObservations(); + if(i>=maxCovKF) + break; + for(map>::iterator mit=observations.begin(), mend=observations.end(); mit!=mend; mit++) + { + KeyFrame* pKFi = mit->first; + + if(pKFi->mnBALocalForKF!=pCurrKF->mnId && pKFi->mnBAFixedForKF!=pCurrKF->mnId) // If optimizable or already included... + { + pKFi->mnBALocalForKF=pCurrKF->mnId; + if(!pKFi->isBad()) + { + vpOptimizableCovKFs.push_back(pKFi); + break; + } + } + } + } + + g2o::SparseOptimizer optimizer; + g2o::BlockSolverX::LinearSolverType * linearSolver; + linearSolver = new g2o::LinearSolverEigen(); + + g2o::BlockSolverX * solver_ptr = new g2o::BlockSolverX(linearSolver); + + g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg(solver_ptr); + + solver->setUserLambdaInit(1e3); // TODO uncomment + + optimizer.setAlgorithm(solver); + optimizer.setVerbose(false); + + // Set Local KeyFrame vertices + N=vpOptimizableKFs.size(); + for(int i=0; isetId(pKFi->mnId); + VP->setFixed(false); + optimizer.addVertex(VP); + + if(pKFi->bImu) + { + VertexVelocity* VV = new VertexVelocity(pKFi); + VV->setId(maxKFid+3*(pKFi->mnId)+1); + VV->setFixed(false); + optimizer.addVertex(VV); + VertexGyroBias* VG = new VertexGyroBias(pKFi); + VG->setId(maxKFid+3*(pKFi->mnId)+2); + VG->setFixed(false); + optimizer.addVertex(VG); + VertexAccBias* VA = new VertexAccBias(pKFi); + VA->setId(maxKFid+3*(pKFi->mnId)+3); + VA->setFixed(false); + optimizer.addVertex(VA); + } + } + + // Set Local cov keyframes vertices + int Ncov=vpOptimizableCovKFs.size(); + for(int i=0; isetId(pKFi->mnId); + VP->setFixed(false); + optimizer.addVertex(VP); + + if(pKFi->bImu) + { + VertexVelocity* VV = new VertexVelocity(pKFi); + VV->setId(maxKFid+3*(pKFi->mnId)+1); + VV->setFixed(false); + optimizer.addVertex(VV); + VertexGyroBias* VG = new VertexGyroBias(pKFi); + VG->setId(maxKFid+3*(pKFi->mnId)+2); + VG->setFixed(false); + optimizer.addVertex(VG); + VertexAccBias* VA = new VertexAccBias(pKFi); + VA->setId(maxKFid+3*(pKFi->mnId)+3); + VA->setFixed(false); + optimizer.addVertex(VA); + } + } + + // Set Fixed KeyFrame vertices + for(list::iterator lit=lFixedKeyFrames.begin(), lend=lFixedKeyFrames.end(); lit!=lend; lit++) + { + KeyFrame* pKFi = *lit; + VertexPose * VP = new VertexPose(pKFi); + VP->setId(pKFi->mnId); + VP->setFixed(true); + optimizer.addVertex(VP); + + if(pKFi->bImu) + { + VertexVelocity* VV = new VertexVelocity(pKFi); + VV->setId(maxKFid+3*(pKFi->mnId)+1); + VV->setFixed(true); + optimizer.addVertex(VV); + VertexGyroBias* VG = new VertexGyroBias(pKFi); + VG->setId(maxKFid+3*(pKFi->mnId)+2); + VG->setFixed(true); + optimizer.addVertex(VG); + VertexAccBias* VA = new VertexAccBias(pKFi); + VA->setId(maxKFid+3*(pKFi->mnId)+3); + VA->setFixed(true); + optimizer.addVertex(VA); + } + } + + // Create intertial constraints + vector vei(N,(EdgeInertial*)NULL); + vector vegr(N,(EdgeGyroRW*)NULL); + vector vear(N,(EdgeAccRW*)NULL); + for(int i=0;imPrevKF) + { + Verbose::PrintMess("NOT INERTIAL LINK TO PREVIOUS FRAME!!!!", Verbose::VERBOSITY_NORMAL); + continue; + } + if(pKFi->bImu && pKFi->mPrevKF->bImu && pKFi->mpImuPreintegrated) + { + pKFi->mpImuPreintegrated->SetNewBias(pKFi->mPrevKF->GetImuBias()); + g2o::HyperGraph::Vertex* VP1 = optimizer.vertex(pKFi->mPrevKF->mnId); + g2o::HyperGraph::Vertex* VV1 = optimizer.vertex(maxKFid+3*(pKFi->mPrevKF->mnId)+1); + g2o::HyperGraph::Vertex* VG1 = optimizer.vertex(maxKFid+3*(pKFi->mPrevKF->mnId)+2); + g2o::HyperGraph::Vertex* VA1 = optimizer.vertex(maxKFid+3*(pKFi->mPrevKF->mnId)+3); + g2o::HyperGraph::Vertex* VP2 = optimizer.vertex(pKFi->mnId); + g2o::HyperGraph::Vertex* VV2 = optimizer.vertex(maxKFid+3*(pKFi->mnId)+1); + g2o::HyperGraph::Vertex* VG2 = optimizer.vertex(maxKFid+3*(pKFi->mnId)+2); + g2o::HyperGraph::Vertex* VA2 = optimizer.vertex(maxKFid+3*(pKFi->mnId)+3); + + if(!VP1 || !VV1 || !VG1 || !VA1 || !VP2 || !VV2 || !VG2 || !VA2) + { + cerr << "Error " << VP1 << ", "<< VV1 << ", "<< VG1 << ", "<< VA1 << ", " << VP2 << ", " << VV2 << ", "<< VG2 << ", "<< VA2 <mpImuPreintegrated); + + vei[i]->setVertex(0,dynamic_cast(VP1)); + vei[i]->setVertex(1,dynamic_cast(VV1)); + vei[i]->setVertex(2,dynamic_cast(VG1)); + vei[i]->setVertex(3,dynamic_cast(VA1)); + vei[i]->setVertex(4,dynamic_cast(VP2)); + vei[i]->setVertex(5,dynamic_cast(VV2)); + + // TODO Uncomment + g2o::RobustKernelHuber* rki = new g2o::RobustKernelHuber; + vei[i]->setRobustKernel(rki); + rki->setDelta(sqrt(16.92)); + optimizer.addEdge(vei[i]); + + vegr[i] = new EdgeGyroRW(); + vegr[i]->setVertex(0,VG1); + vegr[i]->setVertex(1,VG2); + cv::Mat cvInfoG = pKFi->mpImuPreintegrated->C.rowRange(9,12).colRange(9,12).inv(cv::DECOMP_SVD); + Eigen::Matrix3d InfoG; + + for(int r=0;r<3;r++) + for(int c=0;c<3;c++) + InfoG(r,c)=cvInfoG.at(r,c); + vegr[i]->setInformation(InfoG); + optimizer.addEdge(vegr[i]); + + vear[i] = new EdgeAccRW(); + vear[i]->setVertex(0,VA1); + vear[i]->setVertex(1,VA2); + cv::Mat cvInfoA = pKFi->mpImuPreintegrated->C.rowRange(12,15).colRange(12,15).inv(cv::DECOMP_SVD); + Eigen::Matrix3d InfoA; + for(int r=0;r<3;r++) + for(int c=0;c<3;c++) + InfoA(r,c)=cvInfoA.at(r,c); + vear[i]->setInformation(InfoA); + optimizer.addEdge(vear[i]); + } + else + Verbose::PrintMess("ERROR building inertial edge", Verbose::VERBOSITY_NORMAL); + } + + Verbose::PrintMess("end inserting inertial edges", Verbose::VERBOSITY_NORMAL); + + + // Set MapPoint vertices + const int nExpectedSize = (N+Ncov+lFixedKeyFrames.size())*lLocalMapPoints.size(); + + // Mono + vector vpEdgesMono; + vpEdgesMono.reserve(nExpectedSize); + + vector vpEdgeKFMono; + vpEdgeKFMono.reserve(nExpectedSize); + + vector vpMapPointEdgeMono; + vpMapPointEdgeMono.reserve(nExpectedSize); + + // Stereo + vector vpEdgesStereo; + vpEdgesStereo.reserve(nExpectedSize); + + vector vpEdgeKFStereo; + vpEdgeKFStereo.reserve(nExpectedSize); + + vector vpMapPointEdgeStereo; + vpMapPointEdgeStereo.reserve(nExpectedSize); + + const float thHuberMono = sqrt(5.991); + const float chi2Mono2 = 5.991; + const float thHuberStereo = sqrt(7.815); + const float chi2Stereo2 = 7.815; + + + + + const unsigned long iniMPid = maxKFid*5; // TODO: should be maxKFid*4; + + + Verbose::PrintMess("start inserting MPs", Verbose::VERBOSITY_NORMAL); + for(list::iterator lit=lLocalMapPoints.begin(), lend=lLocalMapPoints.end(); lit!=lend; lit++) + { + MapPoint* pMP = *lit; + if (!pMP) + continue; + + g2o::VertexSBAPointXYZ* vPoint = new g2o::VertexSBAPointXYZ(); + vPoint->setEstimate(Converter::toVector3d(pMP->GetWorldPos())); + + unsigned long id = pMP->mnId+iniMPid+1; + vPoint->setId(id); + vPoint->setMarginalized(true); + optimizer.addVertex(vPoint); + + const map> observations = pMP->GetObservations(); + + // Create visual constraints + for(map>::const_iterator mit=observations.begin(), mend=observations.end(); mit!=mend; mit++) + { + KeyFrame* pKFi = mit->first; + + if (!pKFi) + continue; + + if ((pKFi->mnBALocalForKF!=pCurrKF->mnId) && (pKFi->mnBAFixedForKF!=pCurrKF->mnId)) + continue; + + if (pKFi->mnId>maxKFid){ + Verbose::PrintMess("ID greater than current KF is", Verbose::VERBOSITY_NORMAL); + continue; + } + + + if(optimizer.vertex(id)==NULL || optimizer.vertex(pKFi->mnId)==NULL) + continue; + + if(!pKFi->isBad()) + { + const cv::KeyPoint &kpUn = pKFi->mvKeysUn[get<0>(mit->second)]; + + if(pKFi->mvuRight[get<0>(mit->second)]<0) // Monocular observation + { + Eigen::Matrix obs; + obs << kpUn.pt.x, kpUn.pt.y; + + EdgeMono* e = new EdgeMono(); + e->setVertex(0, dynamic_cast(optimizer.vertex(id))); + e->setVertex(1, dynamic_cast(optimizer.vertex(pKFi->mnId))); + e->setMeasurement(obs); + const float &invSigma2 = pKFi->mvInvLevelSigma2[kpUn.octave]; + e->setInformation(Eigen::Matrix2d::Identity()*invSigma2); + + g2o::RobustKernelHuber* rk = new g2o::RobustKernelHuber; + e->setRobustKernel(rk); + rk->setDelta(thHuberMono); + optimizer.addEdge(e); + vpEdgesMono.push_back(e); + vpEdgeKFMono.push_back(pKFi); + vpMapPointEdgeMono.push_back(pMP); + } + else // stereo observation + { + const float kp_ur = pKFi->mvuRight[get<0>(mit->second)]; + Eigen::Matrix obs; + obs << kpUn.pt.x, kpUn.pt.y, kp_ur; + + EdgeStereo* e = new EdgeStereo(); + + e->setVertex(0, dynamic_cast(optimizer.vertex(id))); + e->setVertex(1, dynamic_cast(optimizer.vertex(pKFi->mnId))); + e->setMeasurement(obs); + const float &invSigma2 = pKFi->mvInvLevelSigma2[kpUn.octave]; + e->setInformation(Eigen::Matrix3d::Identity()*invSigma2); + + g2o::RobustKernelHuber* rk = new g2o::RobustKernelHuber; + e->setRobustKernel(rk); + rk->setDelta(thHuberStereo); + + optimizer.addEdge(e); + vpEdgesStereo.push_back(e); + vpEdgeKFStereo.push_back(pKFi); + vpMapPointEdgeStereo.push_back(pMP); + } + } + } + } + + if(pbStopFlag) + if(*pbStopFlag) + return; + optimizer.initializeOptimization(); + optimizer.optimize(3); + if(pbStopFlag) + if(!*pbStopFlag) + optimizer.optimize(5); + + optimizer.setForceStopFlag(pbStopFlag); + + vector > vToErase; + vToErase.reserve(vpEdgesMono.size()+vpEdgesStereo.size()); + + // Check inlier observations + // Mono + for(size_t i=0, iend=vpEdgesMono.size(); iisBad()) + continue; + + if(e->chi2()>chi2Mono2) + { + KeyFrame* pKFi = vpEdgeKFMono[i]; + vToErase.push_back(make_pair(pKFi,pMP)); + } + } + + + // Stereo + for(size_t i=0, iend=vpEdgesStereo.size(); iisBad()) + continue; + + if(e->chi2()>chi2Stereo2) + { + KeyFrame* pKFi = vpEdgeKFStereo[i]; + vToErase.push_back(make_pair(pKFi,pMP)); + } + } + + // Get Map Mutex and erase outliers + unique_lock lock(pMap->mMutexMapUpdate); + if(!vToErase.empty()) + { + for(size_t i=0;iEraseMapPointMatch(pMPi); + pMPi->EraseObservation(pKFi); + } + } + + + // Recover optimized data + //Keyframes + for(int i=0; i(optimizer.vertex(pKFi->mnId)); + cv::Mat Tcw = Converter::toCvSE3(VP->estimate().Rcw[0], VP->estimate().tcw[0]); + pKFi->SetPose(Tcw); + + cv::Mat Tiw=pKFi->GetPose(); + cv::Mat Riw = Tiw.rowRange(0,3).colRange(0,3); + cv::Mat tiw = Tiw.rowRange(0,3).col(3); + g2o::Sim3 g2oSiw(Converter::toMatrix3d(Riw),Converter::toVector3d(tiw),1.0); + corrPoses[pKFi] = g2oSiw; + + + if(pKFi->bImu) + { + VertexVelocity* VV = static_cast(optimizer.vertex(maxKFid+3*(pKFi->mnId)+1)); + pKFi->SetVelocity(Converter::toCvMat(VV->estimate())); + VertexGyroBias* VG = static_cast(optimizer.vertex(maxKFid+3*(pKFi->mnId)+2)); + VertexAccBias* VA = static_cast(optimizer.vertex(maxKFid+3*(pKFi->mnId)+3)); + Vector6d b; + b << VG->estimate(), VA->estimate(); + pKFi->SetNewBias(IMU::Bias(b[3],b[4],b[5],b[0],b[1],b[2])); + } + } + + for(int i=0; i(optimizer.vertex(pKFi->mnId)); + cv::Mat Tcw = Converter::toCvSE3(VP->estimate().Rcw[0], VP->estimate().tcw[0]); + pKFi->SetPose(Tcw); + + cv::Mat Tiw=pKFi->GetPose(); + cv::Mat Riw = Tiw.rowRange(0,3).colRange(0,3); + cv::Mat tiw = Tiw.rowRange(0,3).col(3); + g2o::Sim3 g2oSiw(Converter::toMatrix3d(Riw),Converter::toVector3d(tiw),1.0); + corrPoses[pKFi] = g2oSiw; + + if(pKFi->bImu) + { + VertexVelocity* VV = static_cast(optimizer.vertex(maxKFid+3*(pKFi->mnId)+1)); + pKFi->SetVelocity(Converter::toCvMat(VV->estimate())); + VertexGyroBias* VG = static_cast(optimizer.vertex(maxKFid+3*(pKFi->mnId)+2)); + VertexAccBias* VA = static_cast(optimizer.vertex(maxKFid+3*(pKFi->mnId)+3)); + Vector6d b; + b << VG->estimate(), VA->estimate(); + pKFi->SetNewBias(IMU::Bias(b[3],b[4],b[5],b[0],b[1],b[2])); + } + } + + //Points + for(list::iterator lit=lLocalMapPoints.begin(), lend=lLocalMapPoints.end(); lit!=lend; lit++) + { + MapPoint* pMP = *lit; + g2o::VertexSBAPointXYZ* vPoint = static_cast(optimizer.vertex(pMP->mnId+iniMPid+1)); + pMP->SetWorldPos(Converter::toCvMat(vPoint->estimate())); + pMP->UpdateNormalAndDepth(); + } + + pMap->IncreaseChangeIndex(); +} + +int Optimizer::PoseInertialOptimizationLastKeyFrame(Frame *pFrame, bool bRecInit) +{ + g2o::SparseOptimizer optimizer; + g2o::BlockSolverX::LinearSolverType * linearSolver; + + linearSolver = new g2o::LinearSolverDense(); + + g2o::BlockSolverX * solver_ptr = new g2o::BlockSolverX(linearSolver); + + g2o::OptimizationAlgorithmGaussNewton* solver = new g2o::OptimizationAlgorithmGaussNewton(solver_ptr); + optimizer.setVerbose(false); + optimizer.setAlgorithm(solver); + + int nInitialMonoCorrespondences=0; + int nInitialStereoCorrespondences=0; + int nInitialCorrespondences=0; + + // Set Frame vertex + VertexPose* VP = new VertexPose(pFrame); + VP->setId(0); + VP->setFixed(false); + optimizer.addVertex(VP); + VertexVelocity* VV = new VertexVelocity(pFrame); + VV->setId(1); + VV->setFixed(false); + optimizer.addVertex(VV); + VertexGyroBias* VG = new VertexGyroBias(pFrame); + VG->setId(2); + VG->setFixed(false); + optimizer.addVertex(VG); + VertexAccBias* VA = new VertexAccBias(pFrame); + VA->setId(3); + VA->setFixed(false); + optimizer.addVertex(VA); + + // Set MapPoint vertices + const int N = pFrame->N; + const int Nleft = pFrame->Nleft; + const bool bRight = (Nleft!=-1); + + vector vpEdgesMono; + vector vpEdgesStereo; + vector vnIndexEdgeMono; + vector vnIndexEdgeStereo; + vpEdgesMono.reserve(N); + vpEdgesStereo.reserve(N); + vnIndexEdgeMono.reserve(N); + vnIndexEdgeStereo.reserve(N); + + const float thHuberMono = sqrt(5.991); + const float thHuberStereo = sqrt(7.815); + + + { + unique_lock lock(MapPoint::mGlobalMutex); + + for(int i=0; imvpMapPoints[i]; + if(pMP) + { + cv::KeyPoint kpUn; + + // Left monocular observation + if((!bRight && pFrame->mvuRight[i]<0) || i < Nleft) + { + if(i < Nleft) // pair left-right + kpUn = pFrame->mvKeys[i]; + else + kpUn = pFrame->mvKeysUn[i]; + + nInitialMonoCorrespondences++; + pFrame->mvbOutlier[i] = false; + + Eigen::Matrix obs; + obs << kpUn.pt.x, kpUn.pt.y; + + EdgeMonoOnlyPose* e = new EdgeMonoOnlyPose(pMP->GetWorldPos(),0); + + e->setVertex(0,VP); + e->setMeasurement(obs); + + // Add here uncerteinty + const float unc2 = pFrame->mpCamera->uncertainty2(obs); + + const float invSigma2 = pFrame->mvInvLevelSigma2[kpUn.octave]/unc2; + e->setInformation(Eigen::Matrix2d::Identity()*invSigma2); + + g2o::RobustKernelHuber* rk = new g2o::RobustKernelHuber; + e->setRobustKernel(rk); + rk->setDelta(thHuberMono); + + optimizer.addEdge(e); + + vpEdgesMono.push_back(e); + vnIndexEdgeMono.push_back(i); + } + // Stereo observation + else if(!bRight) + { + nInitialStereoCorrespondences++; + pFrame->mvbOutlier[i] = false; + + kpUn = pFrame->mvKeysUn[i]; + const float kp_ur = pFrame->mvuRight[i]; + Eigen::Matrix obs; + obs << kpUn.pt.x, kpUn.pt.y, kp_ur; + + EdgeStereoOnlyPose* e = new EdgeStereoOnlyPose(pMP->GetWorldPos()); + + e->setVertex(0, VP); + e->setMeasurement(obs); + + // Add here uncerteinty + const float unc2 = pFrame->mpCamera->uncertainty2(obs.head(2)); + + const float &invSigma2 = pFrame->mvInvLevelSigma2[kpUn.octave]/unc2; + e->setInformation(Eigen::Matrix3d::Identity()*invSigma2); + + g2o::RobustKernelHuber* rk = new g2o::RobustKernelHuber; + e->setRobustKernel(rk); + rk->setDelta(thHuberStereo); + + optimizer.addEdge(e); + + vpEdgesStereo.push_back(e); + vnIndexEdgeStereo.push_back(i); + } + + // Right monocular observation + if(bRight && i >= Nleft) + { + nInitialMonoCorrespondences++; + pFrame->mvbOutlier[i] = false; + + kpUn = pFrame->mvKeysRight[i - Nleft]; + Eigen::Matrix obs; + obs << kpUn.pt.x, kpUn.pt.y; + + EdgeMonoOnlyPose* e = new EdgeMonoOnlyPose(pMP->GetWorldPos(),1); + + e->setVertex(0,VP); + e->setMeasurement(obs); + + // Add here uncerteinty + const float unc2 = pFrame->mpCamera->uncertainty2(obs); + + const float invSigma2 = pFrame->mvInvLevelSigma2[kpUn.octave]/unc2; + e->setInformation(Eigen::Matrix2d::Identity()*invSigma2); + + g2o::RobustKernelHuber* rk = new g2o::RobustKernelHuber; + e->setRobustKernel(rk); + rk->setDelta(thHuberMono); + + optimizer.addEdge(e); + + vpEdgesMono.push_back(e); + vnIndexEdgeMono.push_back(i); + } + } + } + } + nInitialCorrespondences = nInitialMonoCorrespondences + nInitialStereoCorrespondences; + + KeyFrame* pKF = pFrame->mpLastKeyFrame; + VertexPose* VPk = new VertexPose(pKF); + VPk->setId(4); + VPk->setFixed(true); + optimizer.addVertex(VPk); + VertexVelocity* VVk = new VertexVelocity(pKF); + VVk->setId(5); + VVk->setFixed(true); + optimizer.addVertex(VVk); + VertexGyroBias* VGk = new VertexGyroBias(pKF); + VGk->setId(6); + VGk->setFixed(true); + optimizer.addVertex(VGk); + VertexAccBias* VAk = new VertexAccBias(pKF); + VAk->setId(7); + VAk->setFixed(true); + optimizer.addVertex(VAk); + + EdgeInertial* ei = new EdgeInertial(pFrame->mpImuPreintegrated); + + ei->setVertex(0, VPk); + ei->setVertex(1, VVk); + ei->setVertex(2, VGk); + ei->setVertex(3, VAk); + ei->setVertex(4, VP); + ei->setVertex(5, VV); + optimizer.addEdge(ei); + + EdgeGyroRW* egr = new EdgeGyroRW(); + egr->setVertex(0,VGk); + egr->setVertex(1,VG); + cv::Mat cvInfoG = pFrame->mpImuPreintegrated->C.rowRange(9,12).colRange(9,12).inv(cv::DECOMP_SVD); + Eigen::Matrix3d InfoG; + for(int r=0;r<3;r++) + for(int c=0;c<3;c++) + InfoG(r,c)=cvInfoG.at(r,c); + egr->setInformation(InfoG); + optimizer.addEdge(egr); + + EdgeAccRW* ear = new EdgeAccRW(); + ear->setVertex(0,VAk); + ear->setVertex(1,VA); + cv::Mat cvInfoA = pFrame->mpImuPreintegrated->C.rowRange(12,15).colRange(12,15).inv(cv::DECOMP_SVD); + Eigen::Matrix3d InfoA; + for(int r=0;r<3;r++) + for(int c=0;c<3;c++) + InfoA(r,c)=cvInfoA.at(r,c); + ear->setInformation(InfoA); + optimizer.addEdge(ear); + + // We perform 4 optimizations, after each optimization we classify observation as inlier/outlier + // At the next optimization, outliers are not included, but at the end they can be classified as inliers again. + float chi2Mono[4]={12,7.5,5.991,5.991}; + float chi2Stereo[4]={15.6,9.8,7.815,7.815}; + + int its[4]={10,10,10,10}; + + int nBad=0; + int nBadMono = 0; + int nBadStereo = 0; + int nInliersMono = 0; + int nInliersStereo = 0; + int nInliers=0; + bool bOut = false; + for(size_t it=0; it<4; it++) + { + optimizer.initializeOptimization(0); + optimizer.optimize(its[it]); + + nBad=0; + nBadMono = 0; + nBadStereo = 0; + nInliers=0; + nInliersMono=0; + nInliersStereo=0; + float chi2close = 1.5*chi2Mono[it]; + + // For monocular observations + for(size_t i=0, iend=vpEdgesMono.size(); imvbOutlier[idx]) + { + e->computeError(); + } + + const float chi2 = e->chi2(); + bool bClose = pFrame->mvpMapPoints[idx]->mTrackDepth<10.f; + + if((chi2>chi2Mono[it]&&!bClose)||(bClose && chi2>chi2close)||!e->isDepthPositive()) + { + pFrame->mvbOutlier[idx]=true; + e->setLevel(1); + nBadMono++; + } + else + { + pFrame->mvbOutlier[idx]=false; + e->setLevel(0); + nInliersMono++; + } + + if (it==2) + e->setRobustKernel(0); + } + + // For stereo observations + for(size_t i=0, iend=vpEdgesStereo.size(); imvbOutlier[idx]) + { + e->computeError(); + } + + const float chi2 = e->chi2(); + + if(chi2>chi2Stereo[it]) + { + pFrame->mvbOutlier[idx]=true; + e->setLevel(1); // not included in next optimization + nBadStereo++; + } + else + { + pFrame->mvbOutlier[idx]=false; + e->setLevel(0); + nInliersStereo++; + } + + if(it==2) + e->setRobustKernel(0); + } + + nInliers = nInliersMono + nInliersStereo; + nBad = nBadMono + nBadStereo; + + if(optimizer.edges().size()<10) + { + cout << "PIOLKF: NOT ENOUGH EDGES" << endl; + break; + } + + } + + // If not too much tracks, recover not too bad points + if ((nInliers<30) && !bRecInit) + { + nBad=0; + const float chi2MonoOut = 18.f; + const float chi2StereoOut = 24.f; + EdgeMonoOnlyPose* e1; + EdgeStereoOnlyPose* e2; + for(size_t i=0, iend=vnIndexEdgeMono.size(); icomputeError(); + if (e1->chi2()mvbOutlier[idx]=false; + else + nBad++; + } + for(size_t i=0, iend=vnIndexEdgeStereo.size(); icomputeError(); + if (e2->chi2()mvbOutlier[idx]=false; + else + nBad++; + } + } + + // Recover optimized pose, velocity and biases + pFrame->SetImuPoseVelocity(Converter::toCvMat(VP->estimate().Rwb),Converter::toCvMat(VP->estimate().twb),Converter::toCvMat(VV->estimate())); + Vector6d b; + b << VG->estimate(), VA->estimate(); + pFrame->mImuBias = IMU::Bias(b[3],b[4],b[5],b[0],b[1],b[2]); + + // Recover Hessian, marginalize keyFframe states and generate new prior for frame + Eigen::Matrix H; + H.setZero(); + + H.block<9,9>(0,0)+= ei->GetHessian2(); + H.block<3,3>(9,9) += egr->GetHessian2(); + H.block<3,3>(12,12) += ear->GetHessian2(); + + int tot_in = 0, tot_out = 0; + for(size_t i=0, iend=vpEdgesMono.size(); imvbOutlier[idx]) + { + H.block<6,6>(0,0) += e->GetHessian(); + tot_in++; + } + else + tot_out++; + } + + for(size_t i=0, iend=vpEdgesStereo.size(); imvbOutlier[idx]) + { + H.block<6,6>(0,0) += e->GetHessian(); + tot_in++; + } + else + tot_out++; + } + + pFrame->mpcpi = new ConstraintPoseImu(VP->estimate().Rwb,VP->estimate().twb,VV->estimate(),VG->estimate(),VA->estimate(),H); + + return nInitialCorrespondences-nBad; +} + +int Optimizer::PoseInertialOptimizationLastFrame(Frame *pFrame, bool bRecInit) +{ + g2o::SparseOptimizer optimizer; + g2o::BlockSolverX::LinearSolverType * linearSolver; + + linearSolver = new g2o::LinearSolverDense(); + + g2o::BlockSolverX * solver_ptr = new g2o::BlockSolverX(linearSolver); + + g2o::OptimizationAlgorithmGaussNewton* solver = new g2o::OptimizationAlgorithmGaussNewton(solver_ptr); + optimizer.setAlgorithm(solver); + optimizer.setVerbose(false); + + int nInitialMonoCorrespondences=0; + int nInitialStereoCorrespondences=0; + int nInitialCorrespondences=0; + + // Set Current Frame vertex + VertexPose* VP = new VertexPose(pFrame); + VP->setId(0); + VP->setFixed(false); + optimizer.addVertex(VP); + VertexVelocity* VV = new VertexVelocity(pFrame); + VV->setId(1); + VV->setFixed(false); + optimizer.addVertex(VV); + VertexGyroBias* VG = new VertexGyroBias(pFrame); + VG->setId(2); + VG->setFixed(false); + optimizer.addVertex(VG); + VertexAccBias* VA = new VertexAccBias(pFrame); + VA->setId(3); + VA->setFixed(false); + optimizer.addVertex(VA); + + // Set MapPoint vertices + const int N = pFrame->N; + const int Nleft = pFrame->Nleft; + const bool bRight = (Nleft!=-1); + + vector vpEdgesMono; + vector vpEdgesStereo; + vector vnIndexEdgeMono; + vector vnIndexEdgeStereo; + vpEdgesMono.reserve(N); + vpEdgesStereo.reserve(N); + vnIndexEdgeMono.reserve(N); + vnIndexEdgeStereo.reserve(N); + + const float thHuberMono = sqrt(5.991); + const float thHuberStereo = sqrt(7.815); + + { + unique_lock lock(MapPoint::mGlobalMutex); + + for(int i=0; imvpMapPoints[i]; + if(pMP) + { + cv::KeyPoint kpUn; + // Left monocular observation + if((!bRight && pFrame->mvuRight[i]<0) || i < Nleft) + { + if(i < Nleft) // pair left-right + kpUn = pFrame->mvKeys[i]; + else + kpUn = pFrame->mvKeysUn[i]; + + nInitialMonoCorrespondences++; + pFrame->mvbOutlier[i] = false; + + Eigen::Matrix obs; + obs << kpUn.pt.x, kpUn.pt.y; + + EdgeMonoOnlyPose* e = new EdgeMonoOnlyPose(pMP->GetWorldPos(),0); + + e->setVertex(0,VP); + e->setMeasurement(obs); + + // Add here uncerteinty + const float unc2 = pFrame->mpCamera->uncertainty2(obs); + + const float invSigma2 = pFrame->mvInvLevelSigma2[kpUn.octave]/unc2; + e->setInformation(Eigen::Matrix2d::Identity()*invSigma2); + + g2o::RobustKernelHuber* rk = new g2o::RobustKernelHuber; + e->setRobustKernel(rk); + rk->setDelta(thHuberMono); + + optimizer.addEdge(e); + + vpEdgesMono.push_back(e); + vnIndexEdgeMono.push_back(i); + } + // Stereo observation + else if(!bRight) + { + nInitialStereoCorrespondences++; + pFrame->mvbOutlier[i] = false; + + kpUn = pFrame->mvKeysUn[i]; + const float kp_ur = pFrame->mvuRight[i]; + Eigen::Matrix obs; + obs << kpUn.pt.x, kpUn.pt.y, kp_ur; + + EdgeStereoOnlyPose* e = new EdgeStereoOnlyPose(pMP->GetWorldPos()); + + e->setVertex(0, VP); + e->setMeasurement(obs); + + // Add here uncerteinty + const float unc2 = pFrame->mpCamera->uncertainty2(obs.head(2)); + + const float &invSigma2 = pFrame->mvInvLevelSigma2[kpUn.octave]/unc2; + e->setInformation(Eigen::Matrix3d::Identity()*invSigma2); + + g2o::RobustKernelHuber* rk = new g2o::RobustKernelHuber; + e->setRobustKernel(rk); + rk->setDelta(thHuberStereo); + + optimizer.addEdge(e); + + vpEdgesStereo.push_back(e); + vnIndexEdgeStereo.push_back(i); + } + + // Right monocular observation + if(bRight && i >= Nleft) + { + nInitialMonoCorrespondences++; + pFrame->mvbOutlier[i] = false; + + kpUn = pFrame->mvKeysRight[i - Nleft]; + Eigen::Matrix obs; + obs << kpUn.pt.x, kpUn.pt.y; + + EdgeMonoOnlyPose* e = new EdgeMonoOnlyPose(pMP->GetWorldPos(),1); + + e->setVertex(0,VP); + e->setMeasurement(obs); + + // Add here uncerteinty + const float unc2 = pFrame->mpCamera->uncertainty2(obs); + + const float invSigma2 = pFrame->mvInvLevelSigma2[kpUn.octave]/unc2; + e->setInformation(Eigen::Matrix2d::Identity()*invSigma2); + + g2o::RobustKernelHuber* rk = new g2o::RobustKernelHuber; + e->setRobustKernel(rk); + rk->setDelta(thHuberMono); + + optimizer.addEdge(e); + + vpEdgesMono.push_back(e); + vnIndexEdgeMono.push_back(i); + } + } + } + } + + nInitialCorrespondences = nInitialMonoCorrespondences + nInitialStereoCorrespondences; + + // Set Previous Frame Vertex + Frame* pFp = pFrame->mpPrevFrame; + + VertexPose* VPk = new VertexPose(pFp); + VPk->setId(4); + VPk->setFixed(false); + optimizer.addVertex(VPk); + VertexVelocity* VVk = new VertexVelocity(pFp); + VVk->setId(5); + VVk->setFixed(false); + optimizer.addVertex(VVk); + VertexGyroBias* VGk = new VertexGyroBias(pFp); + VGk->setId(6); + VGk->setFixed(false); + optimizer.addVertex(VGk); + VertexAccBias* VAk = new VertexAccBias(pFp); + VAk->setId(7); + VAk->setFixed(false); + optimizer.addVertex(VAk); + + EdgeInertial* ei = new EdgeInertial(pFrame->mpImuPreintegratedFrame); + + ei->setVertex(0, VPk); + ei->setVertex(1, VVk); + ei->setVertex(2, VGk); + ei->setVertex(3, VAk); + ei->setVertex(4, VP); + ei->setVertex(5, VV); + optimizer.addEdge(ei); + + EdgeGyroRW* egr = new EdgeGyroRW(); + egr->setVertex(0,VGk); + egr->setVertex(1,VG); + cv::Mat cvInfoG = pFrame->mpImuPreintegratedFrame->C.rowRange(9,12).colRange(9,12).inv(cv::DECOMP_SVD); + Eigen::Matrix3d InfoG; + for(int r=0;r<3;r++) + for(int c=0;c<3;c++) + InfoG(r,c)=cvInfoG.at(r,c); + egr->setInformation(InfoG); + optimizer.addEdge(egr); + + EdgeAccRW* ear = new EdgeAccRW(); + ear->setVertex(0,VAk); + ear->setVertex(1,VA); + cv::Mat cvInfoA = pFrame->mpImuPreintegratedFrame->C.rowRange(12,15).colRange(12,15).inv(cv::DECOMP_SVD); + Eigen::Matrix3d InfoA; + for(int r=0;r<3;r++) + for(int c=0;c<3;c++) + InfoA(r,c)=cvInfoA.at(r,c); + ear->setInformation(InfoA); + optimizer.addEdge(ear); + + if (!pFp->mpcpi) + Verbose::PrintMess("pFp->mpcpi does not exist!!!\nPrevious Frame " + to_string(pFp->mnId), Verbose::VERBOSITY_NORMAL); + + EdgePriorPoseImu* ep = new EdgePriorPoseImu(pFp->mpcpi); + + ep->setVertex(0,VPk); + ep->setVertex(1,VVk); + ep->setVertex(2,VGk); + ep->setVertex(3,VAk); + g2o::RobustKernelHuber* rkp = new g2o::RobustKernelHuber; + ep->setRobustKernel(rkp); + rkp->setDelta(5); + optimizer.addEdge(ep); + + // We perform 4 optimizations, after each optimization we classify observation as inlier/outlier + // At the next optimization, outliers are not included, but at the end they can be classified as inliers again. + + const float chi2Mono[4]={5.991,5.991,5.991,5.991}; + const float chi2Stereo[4]={15.6f,9.8f,7.815f,7.815f}; + const int its[4]={10,10,10,10}; + + int nBad=0; + int nBadMono = 0; + int nBadStereo = 0; + int nInliersMono = 0; + int nInliersStereo = 0; + int nInliers=0; + for(size_t it=0; it<4; it++) + { + optimizer.initializeOptimization(0); + optimizer.optimize(its[it]); + + nBad=0; + nBadMono = 0; + nBadStereo = 0; + nInliers=0; + nInliersMono=0; + nInliersStereo=0; + float chi2close = 1.5*chi2Mono[it]; + + for(size_t i=0, iend=vpEdgesMono.size(); imvpMapPoints[idx]->mTrackDepth<10.f; + + if(pFrame->mvbOutlier[idx]) + { + e->computeError(); + } + + const float chi2 = e->chi2(); + + if((chi2>chi2Mono[it]&&!bClose)||(bClose && chi2>chi2close)||!e->isDepthPositive()) + { + pFrame->mvbOutlier[idx]=true; + e->setLevel(1); + nBadMono++; + } + else + { + pFrame->mvbOutlier[idx]=false; + e->setLevel(0); + nInliersMono++; + } + + if (it==2) + e->setRobustKernel(0); + + } + + for(size_t i=0, iend=vpEdgesStereo.size(); imvbOutlier[idx]) + { + e->computeError(); + } + + const float chi2 = e->chi2(); + + if(chi2>chi2Stereo[it]) + { + pFrame->mvbOutlier[idx]=true; + e->setLevel(1); + nBadStereo++; + } + else + { + pFrame->mvbOutlier[idx]=false; + e->setLevel(0); + nInliersStereo++; + } + + if(it==2) + e->setRobustKernel(0); + } + + nInliers = nInliersMono + nInliersStereo; + nBad = nBadMono + nBadStereo; + + if(optimizer.edges().size()<10) + { + cout << "PIOLF: NOT ENOUGH EDGES" << endl; + break; + } + } + + + if ((nInliers<30) && !bRecInit) + { + nBad=0; + const float chi2MonoOut = 18.f; + const float chi2StereoOut = 24.f; + EdgeMonoOnlyPose* e1; + EdgeStereoOnlyPose* e2; + for(size_t i=0, iend=vnIndexEdgeMono.size(); icomputeError(); + if (e1->chi2()mvbOutlier[idx]=false; + else + nBad++; + + } + for(size_t i=0, iend=vnIndexEdgeStereo.size(); icomputeError(); + if (e2->chi2()mvbOutlier[idx]=false; + else + nBad++; + } + } + + nInliers = nInliersMono + nInliersStereo; + + + // Recover optimized pose, velocity and biases + pFrame->SetImuPoseVelocity(Converter::toCvMat(VP->estimate().Rwb),Converter::toCvMat(VP->estimate().twb),Converter::toCvMat(VV->estimate())); + Vector6d b; + b << VG->estimate(), VA->estimate(); + pFrame->mImuBias = IMU::Bias(b[3],b[4],b[5],b[0],b[1],b[2]); + + // Recover Hessian, marginalize previous frame states and generate new prior for frame + Eigen::Matrix H; + H.setZero(); + + H.block<24,24>(0,0)+= ei->GetHessian(); + + Eigen::Matrix Hgr = egr->GetHessian(); + H.block<3,3>(9,9) += Hgr.block<3,3>(0,0); + H.block<3,3>(9,24) += Hgr.block<3,3>(0,3); + H.block<3,3>(24,9) += Hgr.block<3,3>(3,0); + H.block<3,3>(24,24) += Hgr.block<3,3>(3,3); + + Eigen::Matrix Har = ear->GetHessian(); + H.block<3,3>(12,12) += Har.block<3,3>(0,0); + H.block<3,3>(12,27) += Har.block<3,3>(0,3); + H.block<3,3>(27,12) += Har.block<3,3>(3,0); + H.block<3,3>(27,27) += Har.block<3,3>(3,3); + + H.block<15,15>(0,0) += ep->GetHessian(); + + int tot_in = 0, tot_out = 0; + for(size_t i=0, iend=vpEdgesMono.size(); imvbOutlier[idx]) + { + H.block<6,6>(15,15) += e->GetHessian(); + tot_in++; + } + else + tot_out++; + } + + for(size_t i=0, iend=vpEdgesStereo.size(); imvbOutlier[idx]) + { + H.block<6,6>(15,15) += e->GetHessian(); + tot_in++; + } + else + tot_out++; + } + + H = Marginalize(H,0,14); + + pFrame->mpcpi = new ConstraintPoseImu(VP->estimate().Rwb,VP->estimate().twb,VV->estimate(),VG->estimate(),VA->estimate(),H.block<15,15>(15,15)); + delete pFp->mpcpi; + pFp->mpcpi = NULL; + + return nInitialCorrespondences-nBad; +} + + + + + +void Optimizer::OptimizeEssentialGraph4DoF(Map* pMap, KeyFrame* pLoopKF, KeyFrame* pCurKF, + const LoopClosing::KeyFrameAndPose &NonCorrectedSim3, + const LoopClosing::KeyFrameAndPose &CorrectedSim3, + const map > &LoopConnections) +{ + typedef g2o::BlockSolver< g2o::BlockSolverTraits<4, 4> > BlockSolver_4_4; + + // Setup optimizer + g2o::SparseOptimizer optimizer; + optimizer.setVerbose(false); + g2o::BlockSolverX::LinearSolverType * linearSolver = + new g2o::LinearSolverEigen(); + g2o::BlockSolverX * solver_ptr = new g2o::BlockSolverX(linearSolver); + + g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg(solver_ptr); + + optimizer.setAlgorithm(solver); + + const vector vpKFs = pMap->GetAllKeyFrames(); + const vector vpMPs = pMap->GetAllMapPoints(); + + const unsigned int nMaxKFid = pMap->GetMaxKFid(); + + vector > vScw(nMaxKFid+1); + vector > vCorrectedSwc(nMaxKFid+1); + + vector vpVertices(nMaxKFid+1); + + const int minFeat = 100; + // Set KeyFrame vertices + for(size_t i=0, iend=vpKFs.size(); iisBad()) + continue; + + VertexPose4DoF* V4DoF; + + const int nIDi = pKF->mnId; + + LoopClosing::KeyFrameAndPose::const_iterator it = CorrectedSim3.find(pKF); + + if(it!=CorrectedSim3.end()) + { + vScw[nIDi] = it->second; + const g2o::Sim3 Swc = it->second.inverse(); + Eigen::Matrix3d Rwc = Swc.rotation().toRotationMatrix(); + Eigen::Vector3d twc = Swc.translation(); + V4DoF = new VertexPose4DoF(Rwc, twc, pKF); + } + else + { + Eigen::Matrix Rcw = Converter::toMatrix3d(pKF->GetRotation()); + Eigen::Matrix tcw = Converter::toVector3d(pKF->GetTranslation()); + g2o::Sim3 Siw(Rcw,tcw,1.0); + vScw[nIDi] = Siw; + V4DoF = new VertexPose4DoF(pKF); + } + + if(pKF==pLoopKF) + V4DoF->setFixed(true); + + V4DoF->setId(nIDi); + V4DoF->setMarginalized(false); + + optimizer.addVertex(V4DoF); + vpVertices[nIDi]=V4DoF; + } + cout << "PoseGraph4DoF: KFs loaded" << endl; + + set > sInsertedEdges; + + // Edge used in posegraph has still 6Dof, even if updates of camera poses are just in 4DoF + Eigen::Matrix matLambda = Eigen::Matrix::Identity(); + matLambda(0,0) = 1e3; + matLambda(1,1) = 1e3; + matLambda(0,0) = 1e3; + + // Set Loop edges + Edge4DoF* e_loop; + for(map >::const_iterator mit = LoopConnections.begin(), mend=LoopConnections.end(); mit!=mend; mit++) + { + KeyFrame* pKF = mit->first; + const long unsigned int nIDi = pKF->mnId; + const set &spConnections = mit->second; + const g2o::Sim3 Siw = vScw[nIDi]; + const g2o::Sim3 Swi = Siw.inverse(); + + for(set::const_iterator sit=spConnections.begin(), send=spConnections.end(); sit!=send; sit++) + { + const long unsigned int nIDj = (*sit)->mnId; + if((nIDi!=pCurKF->mnId || nIDj!=pLoopKF->mnId) && pKF->GetWeight(*sit)(0,0) = Sij.rotation().toRotationMatrix(); + Tij.block<3,1>(0,3) = Sij.translation(); + Tij(3,3) = 1.; + + Edge4DoF* e = new Edge4DoF(Tij); + e->setVertex(1, dynamic_cast(optimizer.vertex(nIDj))); + e->setVertex(0, dynamic_cast(optimizer.vertex(nIDi))); + + e->information() = matLambda; + e_loop = e; + optimizer.addEdge(e); + + sInsertedEdges.insert(make_pair(min(nIDi,nIDj),max(nIDi,nIDj))); + } + } + cout << "PoseGraph4DoF: Loop edges loaded" << endl; + + // 1. Set normal edges + for(size_t i=0, iend=vpKFs.size(); imnId; + + g2o::Sim3 Siw; + + // Use noncorrected poses for posegraph edges + LoopClosing::KeyFrameAndPose::const_iterator iti = NonCorrectedSim3.find(pKF); + + if(iti!=NonCorrectedSim3.end()) + Siw = iti->second; + else + Siw = vScw[nIDi]; + + + // 1.1.0 Spanning tree edge + KeyFrame* pParentKF = static_cast(NULL); + if(pParentKF) + { + int nIDj = pParentKF->mnId; + + g2o::Sim3 Swj; + + LoopClosing::KeyFrameAndPose::const_iterator itj = NonCorrectedSim3.find(pParentKF); + + if(itj!=NonCorrectedSim3.end()) + Swj = (itj->second).inverse(); + else + Swj = vScw[nIDj].inverse(); + + g2o::Sim3 Sij = Siw * Swj; + Eigen::Matrix4d Tij; + Tij.block<3,3>(0,0) = Sij.rotation().toRotationMatrix(); + Tij.block<3,1>(0,3) = Sij.translation(); + Tij(3,3)=1.; + + Edge4DoF* e = new Edge4DoF(Tij); + e->setVertex(0, dynamic_cast(optimizer.vertex(nIDi))); + e->setVertex(1, dynamic_cast(optimizer.vertex(nIDj))); + e->information() = matLambda; + optimizer.addEdge(e); + } + + // 1.1.1 Inertial edges + KeyFrame* prevKF = pKF->mPrevKF; + if(prevKF) + { + int nIDj = prevKF->mnId; + + g2o::Sim3 Swj; + + LoopClosing::KeyFrameAndPose::const_iterator itj = NonCorrectedSim3.find(prevKF); + + if(itj!=NonCorrectedSim3.end()) + Swj = (itj->second).inverse(); + else + Swj = vScw[nIDj].inverse(); + + g2o::Sim3 Sij = Siw * Swj; + Eigen::Matrix4d Tij; + Tij.block<3,3>(0,0) = Sij.rotation().toRotationMatrix(); + Tij.block<3,1>(0,3) = Sij.translation(); + Tij(3,3)=1.; + + Edge4DoF* e = new Edge4DoF(Tij); + e->setVertex(0, dynamic_cast(optimizer.vertex(nIDi))); + e->setVertex(1, dynamic_cast(optimizer.vertex(nIDj))); + e->information() = matLambda; + optimizer.addEdge(e); + } + + // 1.2 Loop edges + const set sLoopEdges = pKF->GetLoopEdges(); + for(set::const_iterator sit=sLoopEdges.begin(), send=sLoopEdges.end(); sit!=send; sit++) + { + KeyFrame* pLKF = *sit; + if(pLKF->mnIdmnId) + { + g2o::Sim3 Swl; + + LoopClosing::KeyFrameAndPose::const_iterator itl = NonCorrectedSim3.find(pLKF); + + if(itl!=NonCorrectedSim3.end()) + Swl = itl->second.inverse(); + else + Swl = vScw[pLKF->mnId].inverse(); + + g2o::Sim3 Sil = Siw * Swl; + Eigen::Matrix4d Til; + Til.block<3,3>(0,0) = Sil.rotation().toRotationMatrix(); + Til.block<3,1>(0,3) = Sil.translation(); + Til(3,3) = 1.; + + Edge4DoF* e = new Edge4DoF(Til); + e->setVertex(0, dynamic_cast(optimizer.vertex(nIDi))); + e->setVertex(1, dynamic_cast(optimizer.vertex(pLKF->mnId))); + e->information() = matLambda; + optimizer.addEdge(e); + } + } + + // 1.3 Covisibility graph edges + const vector vpConnectedKFs = pKF->GetCovisiblesByWeight(minFeat); + for(vector::const_iterator vit=vpConnectedKFs.begin(); vit!=vpConnectedKFs.end(); vit++) + { + KeyFrame* pKFn = *vit; + if(pKFn && pKFn!=pParentKF && pKFn!=prevKF && pKFn!=pKF->mNextKF && !pKF->hasChild(pKFn) && !sLoopEdges.count(pKFn)) + { + if(!pKFn->isBad() && pKFn->mnIdmnId) + { + if(sInsertedEdges.count(make_pair(min(pKF->mnId,pKFn->mnId),max(pKF->mnId,pKFn->mnId)))) + continue; + + g2o::Sim3 Swn; + + LoopClosing::KeyFrameAndPose::const_iterator itn = NonCorrectedSim3.find(pKFn); + + if(itn!=NonCorrectedSim3.end()) + Swn = itn->second.inverse(); + else + Swn = vScw[pKFn->mnId].inverse(); + + g2o::Sim3 Sin = Siw * Swn; + Eigen::Matrix4d Tin; + Tin.block<3,3>(0,0) = Sin.rotation().toRotationMatrix(); + Tin.block<3,1>(0,3) = Sin.translation(); + Tin(3,3) = 1.; + Edge4DoF* e = new Edge4DoF(Tin); + e->setVertex(0, dynamic_cast(optimizer.vertex(nIDi))); + e->setVertex(1, dynamic_cast(optimizer.vertex(pKFn->mnId))); + e->information() = matLambda; + optimizer.addEdge(e); + } + } + } + } + cout << "PoseGraph4DoF: Covisibility edges loaded" << endl; + + optimizer.initializeOptimization(); + optimizer.computeActiveErrors(); + optimizer.optimize(20); + + unique_lock lock(pMap->mMutexMapUpdate); + + // SE3 Pose Recovering. Sim3:[sR t;0 1] -> SE3:[R t/s;0 1] + for(size_t i=0;imnId; + + VertexPose4DoF* Vi = static_cast(optimizer.vertex(nIDi)); + Eigen::Matrix3d Ri = Vi->estimate().Rcw[0]; + Eigen::Vector3d ti = Vi->estimate().tcw[0]; + + g2o::Sim3 CorrectedSiw = g2o::Sim3(Ri,ti,1.); + vCorrectedSwc[nIDi]=CorrectedSiw.inverse(); + + cv::Mat Tiw = Converter::toCvSE3(Ri,ti); + pKFi->SetPose(Tiw); + } + + // Correct points. Transform to "non-optimized" reference keyframe pose and transform back with optimized pose + for(size_t i=0, iend=vpMPs.size(); iisBad()) + continue; + + int nIDr; + + KeyFrame* pRefKF = pMP->GetReferenceKeyFrame(); + nIDr = pRefKF->mnId; + + g2o::Sim3 Srw = vScw[nIDr]; + g2o::Sim3 correctedSwr = vCorrectedSwc[nIDr]; + + cv::Mat P3Dw = pMP->GetWorldPos(); + Eigen::Matrix eigP3Dw = Converter::toVector3d(P3Dw); + Eigen::Matrix eigCorrectedP3Dw = correctedSwr.map(Srw.map(eigP3Dw)); + + cv::Mat cvCorrectedP3Dw = Converter::toCvMat(eigCorrectedP3Dw); + pMP->SetWorldPos(cvCorrectedP3Dw); + + pMP->UpdateNormalAndDepth(); + } + pMap->IncreaseChangeIndex(); +} + +} //namespace ORB_SLAM diff --git a/third_party/ORB_SLAM3/src/PnPsolver.cc b/third_party/ORB_SLAM3/src/PnPsolver.cc new file mode 100644 index 0000000..1bbebfc --- /dev/null +++ b/third_party/ORB_SLAM3/src/PnPsolver.cc @@ -0,0 +1,1019 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + +/** +* Copyright (c) 2009, V. Lepetit, EPFL +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* 1. Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* 2. Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR +* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +* +* The views and conclusions contained in the software and documentation are those +* of the authors and should not be interpreted as representing official policies, +* either expressed or implied, of the FreeBSD Project +*/ + +#include + +#include "PnPsolver.h" + +#include +#include +#include +#include "Thirdparty/DBoW2/DUtils/Random.h" +#include + +using namespace std; + +namespace ORB_SLAM3 +{ + + +PnPsolver::PnPsolver(const Frame &F, const vector &vpMapPointMatches): + pws(0), us(0), alphas(0), pcs(0), maximum_number_of_correspondences(0), number_of_correspondences(0), mnInliersi(0), + mnIterations(0), mnBestInliers(0), N(0) +{ + mvpMapPointMatches = vpMapPointMatches; + mvP2D.reserve(F.mvpMapPoints.size()); + mvSigma2.reserve(F.mvpMapPoints.size()); + mvP3Dw.reserve(F.mvpMapPoints.size()); + mvKeyPointIndices.reserve(F.mvpMapPoints.size()); + mvAllIndices.reserve(F.mvpMapPoints.size()); + + int idx=0; + for(size_t i=0, iend=vpMapPointMatches.size(); iisBad()) + { + const cv::KeyPoint &kp = F.mvKeysUn[i]; + + mvP2D.push_back(kp.pt); + mvSigma2.push_back(F.mvLevelSigma2[kp.octave]); + + cv::Mat Pos = pMP->GetWorldPos(); + mvP3Dw.push_back(cv::Point3f(Pos.at(0),Pos.at(1), Pos.at(2))); + + mvKeyPointIndices.push_back(i); + mvAllIndices.push_back(idx); + + idx++; + } + } + } + + // Set camera calibration parameters + fu = F.fx; + fv = F.fy; + uc = F.cx; + vc = F.cy; + + SetRansacParameters(); +} + +PnPsolver::~PnPsolver() +{ + delete [] pws; + delete [] us; + delete [] alphas; + delete [] pcs; +} + + +void PnPsolver::SetRansacParameters(double probability, int minInliers, int maxIterations, int minSet, float epsilon, float th2) +{ + mRansacProb = probability; + mRansacMinInliers = minInliers; + mRansacMaxIts = maxIterations; + mRansacEpsilon = epsilon; + mRansacMinSet = minSet; + + N = mvP2D.size(); // number of correspondences + + mvbInliersi.resize(N); + + // Adjust Parameters according to number of correspondences + int nMinInliers = N*mRansacEpsilon; + if(nMinInliers &vbInliers, int &nInliers) +{ + bool bFlag; + return iterate(mRansacMaxIts,bFlag,vbInliers,nInliers); +} + +cv::Mat PnPsolver::iterate(int nIterations, bool &bNoMore, vector &vbInliers, int &nInliers) +{ + bNoMore = false; + vbInliers.clear(); + nInliers=0; + + set_maximum_number_of_correspondences(mRansacMinSet); + + if(N vAvailableIndices; + + int nCurrentIterations = 0; + while(mnIterations=mRansacMinInliers) + { + // If it is the best solution so far, save it + if(mnInliersi>mnBestInliers) + { + mvbBestInliers = mvbInliersi; + mnBestInliers = mnInliersi; + + cv::Mat Rcw(3,3,CV_64F,mRi); + cv::Mat tcw(3,1,CV_64F,mti); + Rcw.convertTo(Rcw,CV_32F); + tcw.convertTo(tcw,CV_32F); + mBestTcw = cv::Mat::eye(4,4,CV_32F); + Rcw.copyTo(mBestTcw.rowRange(0,3).colRange(0,3)); + tcw.copyTo(mBestTcw.rowRange(0,3).col(3)); + } + + if(Refine()) + { + nInliers = mnRefinedInliers; + vbInliers = vector(mvpMapPointMatches.size(),false); + for(int i=0; i=mRansacMaxIts) + { + bNoMore=true; + if(mnBestInliers>=mRansacMinInliers) + { + nInliers=mnBestInliers; + vbInliers = vector(mvpMapPointMatches.size(),false); + for(int i=0; i vIndices; + vIndices.reserve(mvbBestInliers.size()); + + for(size_t i=0; imRansacMinInliers) + { + cv::Mat Rcw(3,3,CV_64F,mRi); + cv::Mat tcw(3,1,CV_64F,mti); + Rcw.convertTo(Rcw,CV_32F); + tcw.convertTo(tcw,CV_32F); + mRefinedTcw = cv::Mat::eye(4,4,CV_32F); + Rcw.copyTo(mRefinedTcw.rowRange(0,3).colRange(0,3)); + tcw.copyTo(mRefinedTcw.rowRange(0,3).col(3)); + return true; + } + + return false; +} + + +void PnPsolver::CheckInliers() +{ + mnInliersi=0; + + for(int i=0; idata.db[3 * i + j] = pws[3 * i + j] - cws[0][j]; + + cvMulTransposed(PW0, &PW0tPW0, 1); + cvSVD(&PW0tPW0, &DC, &UCt, 0, CV_SVD_MODIFY_A | CV_SVD_U_T); + + cvReleaseMat(&PW0); + + for(int i = 1; i < 4; i++) { + double k = sqrt(dc[i - 1] / number_of_correspondences); + for(int j = 0; j < 3; j++) + cws[i][j] = cws[0][j] + k * uct[3 * (i - 1) + j]; + } +} + +void PnPsolver::compute_barycentric_coordinates(void) +{ + double cc[3 * 3], cc_inv[3 * 3]; + CvMat CC = cvMat(3, 3, CV_64F, cc); + CvMat CC_inv = cvMat(3, 3, CV_64F, cc_inv); + + for(int i = 0; i < 3; i++) + for(int j = 1; j < 4; j++) + cc[3 * i + j - 1] = cws[j][i] - cws[0][i]; + + cvInvert(&CC, &CC_inv, CV_SVD); + double * ci = cc_inv; + for(int i = 0; i < number_of_correspondences; i++) { + double * pi = pws + 3 * i; + double * a = alphas + 4 * i; + + for(int j = 0; j < 3; j++) + a[1 + j] = + ci[3 * j ] * (pi[0] - cws[0][0]) + + ci[3 * j + 1] * (pi[1] - cws[0][1]) + + ci[3 * j + 2] * (pi[2] - cws[0][2]); + a[0] = 1.0f - a[1] - a[2] - a[3]; + } +} + +void PnPsolver::fill_M(CvMat * M, + const int row, const double * as, const double u, const double v) +{ + double * M1 = M->data.db + row * 12; + double * M2 = M1 + 12; + + for(int i = 0; i < 4; i++) { + M1[3 * i ] = as[i] * fu; + M1[3 * i + 1] = 0.0; + M1[3 * i + 2] = as[i] * (uc - u); + + M2[3 * i ] = 0.0; + M2[3 * i + 1] = as[i] * fv; + M2[3 * i + 2] = as[i] * (vc - v); + } +} + +void PnPsolver::compute_ccs(const double * betas, const double * ut) +{ + for(int i = 0; i < 4; i++) + ccs[i][0] = ccs[i][1] = ccs[i][2] = 0.0f; + + for(int i = 0; i < 4; i++) { + const double * v = ut + 12 * (11 - i); + for(int j = 0; j < 4; j++) + for(int k = 0; k < 3; k++) + ccs[j][k] += betas[i] * v[3 * j + k]; + } +} + +void PnPsolver::compute_pcs(void) +{ + for(int i = 0; i < number_of_correspondences; i++) { + double * a = alphas + 4 * i; + double * pc = pcs + 3 * i; + + for(int j = 0; j < 3; j++) + pc[j] = a[0] * ccs[0][j] + a[1] * ccs[1][j] + a[2] * ccs[2][j] + a[3] * ccs[3][j]; + } +} + +double PnPsolver::compute_pose(double R[3][3], double t[3]) +{ + choose_control_points(); + compute_barycentric_coordinates(); + + CvMat * M = cvCreateMat(2 * number_of_correspondences, 12, CV_64F); + + for(int i = 0; i < number_of_correspondences; i++) + fill_M(M, 2 * i, alphas + 4 * i, us[2 * i], us[2 * i + 1]); + + double mtm[12 * 12], d[12], ut[12 * 12]; + CvMat MtM = cvMat(12, 12, CV_64F, mtm); + CvMat D = cvMat(12, 1, CV_64F, d); + CvMat Ut = cvMat(12, 12, CV_64F, ut); + + cvMulTransposed(M, &MtM, 1); + cvSVD(&MtM, &D, &Ut, 0, CV_SVD_MODIFY_A | CV_SVD_U_T); + cvReleaseMat(&M); + + double l_6x10[6 * 10], rho[6]; + CvMat L_6x10 = cvMat(6, 10, CV_64F, l_6x10); + CvMat Rho = cvMat(6, 1, CV_64F, rho); + + compute_L_6x10(ut, l_6x10); + compute_rho(rho); + + double Betas[4][4], rep_errors[4]; + double Rs[4][3][3], ts[4][3]; + + find_betas_approx_1(&L_6x10, &Rho, Betas[1]); + gauss_newton(&L_6x10, &Rho, Betas[1]); + rep_errors[1] = compute_R_and_t(ut, Betas[1], Rs[1], ts[1]); + + find_betas_approx_2(&L_6x10, &Rho, Betas[2]); + gauss_newton(&L_6x10, &Rho, Betas[2]); + rep_errors[2] = compute_R_and_t(ut, Betas[2], Rs[2], ts[2]); + + find_betas_approx_3(&L_6x10, &Rho, Betas[3]); + gauss_newton(&L_6x10, &Rho, Betas[3]); + rep_errors[3] = compute_R_and_t(ut, Betas[3], Rs[3], ts[3]); + + int N = 1; + if (rep_errors[2] < rep_errors[1]) N = 2; + if (rep_errors[3] < rep_errors[N]) N = 3; + + copy_R_and_t(Rs[N], ts[N], R, t); + + return rep_errors[N]; +} + +void PnPsolver::copy_R_and_t(const double R_src[3][3], const double t_src[3], + double R_dst[3][3], double t_dst[3]) +{ + for(int i = 0; i < 3; i++) { + for(int j = 0; j < 3; j++) + R_dst[i][j] = R_src[i][j]; + t_dst[i] = t_src[i]; + } +} + +double PnPsolver::dist2(const double * p1, const double * p2) +{ + return + (p1[0] - p2[0]) * (p1[0] - p2[0]) + + (p1[1] - p2[1]) * (p1[1] - p2[1]) + + (p1[2] - p2[2]) * (p1[2] - p2[2]); +} + +double PnPsolver::dot(const double * v1, const double * v2) +{ + return v1[0] * v2[0] + v1[1] * v2[1] + v1[2] * v2[2]; +} + +double PnPsolver::reprojection_error(const double R[3][3], const double t[3]) +{ + double sum2 = 0.0; + + for(int i = 0; i < number_of_correspondences; i++) { + double * pw = pws + 3 * i; + double Xc = dot(R[0], pw) + t[0]; + double Yc = dot(R[1], pw) + t[1]; + double inv_Zc = 1.0 / (dot(R[2], pw) + t[2]); + double ue = uc + fu * Xc * inv_Zc; + double ve = vc + fv * Yc * inv_Zc; + double u = us[2 * i], v = us[2 * i + 1]; + + sum2 += sqrt( (u - ue) * (u - ue) + (v - ve) * (v - ve) ); + } + + return sum2 / number_of_correspondences; +} + +void PnPsolver::estimate_R_and_t(double R[3][3], double t[3]) +{ + double pc0[3], pw0[3]; + + pc0[0] = pc0[1] = pc0[2] = 0.0; + pw0[0] = pw0[1] = pw0[2] = 0.0; + + for(int i = 0; i < number_of_correspondences; i++) { + const double * pc = pcs + 3 * i; + const double * pw = pws + 3 * i; + + for(int j = 0; j < 3; j++) { + pc0[j] += pc[j]; + pw0[j] += pw[j]; + } + } + for(int j = 0; j < 3; j++) { + pc0[j] /= number_of_correspondences; + pw0[j] /= number_of_correspondences; + } + + double abt[3 * 3], abt_d[3], abt_u[3 * 3], abt_v[3 * 3]; + CvMat ABt = cvMat(3, 3, CV_64F, abt); + CvMat ABt_D = cvMat(3, 1, CV_64F, abt_d); + CvMat ABt_U = cvMat(3, 3, CV_64F, abt_u); + CvMat ABt_V = cvMat(3, 3, CV_64F, abt_v); + + cvSetZero(&ABt); + for(int i = 0; i < number_of_correspondences; i++) { + double * pc = pcs + 3 * i; + double * pw = pws + 3 * i; + + for(int j = 0; j < 3; j++) { + abt[3 * j ] += (pc[j] - pc0[j]) * (pw[0] - pw0[0]); + abt[3 * j + 1] += (pc[j] - pc0[j]) * (pw[1] - pw0[1]); + abt[3 * j + 2] += (pc[j] - pc0[j]) * (pw[2] - pw0[2]); + } + } + + cvSVD(&ABt, &ABt_D, &ABt_U, &ABt_V, CV_SVD_MODIFY_A); + + for(int i = 0; i < 3; i++) + for(int j = 0; j < 3; j++) + R[i][j] = dot(abt_u + 3 * i, abt_v + 3 * j); + + const double det = + R[0][0] * R[1][1] * R[2][2] + R[0][1] * R[1][2] * R[2][0] + R[0][2] * R[1][0] * R[2][1] - + R[0][2] * R[1][1] * R[2][0] - R[0][1] * R[1][0] * R[2][2] - R[0][0] * R[1][2] * R[2][1]; + + if (det < 0) { + R[2][0] = -R[2][0]; + R[2][1] = -R[2][1]; + R[2][2] = -R[2][2]; + } + + t[0] = pc0[0] - dot(R[0], pw0); + t[1] = pc0[1] - dot(R[1], pw0); + t[2] = pc0[2] - dot(R[2], pw0); +} + +void PnPsolver::print_pose(const double R[3][3], const double t[3]) +{ + cout << R[0][0] << " " << R[0][1] << " " << R[0][2] << " " << t[0] << endl; + cout << R[1][0] << " " << R[1][1] << " " << R[1][2] << " " << t[1] << endl; + cout << R[2][0] << " " << R[2][1] << " " << R[2][2] << " " << t[2] << endl; +} + +void PnPsolver::solve_for_sign(void) +{ + if (pcs[2] < 0.0) { + for(int i = 0; i < 4; i++) + for(int j = 0; j < 3; j++) + ccs[i][j] = -ccs[i][j]; + + for(int i = 0; i < number_of_correspondences; i++) { + pcs[3 * i ] = -pcs[3 * i]; + pcs[3 * i + 1] = -pcs[3 * i + 1]; + pcs[3 * i + 2] = -pcs[3 * i + 2]; + } + } +} + +double PnPsolver::compute_R_and_t(const double * ut, const double * betas, + double R[3][3], double t[3]) +{ + compute_ccs(betas, ut); + compute_pcs(); + + solve_for_sign(); + + estimate_R_and_t(R, t); + + return reprojection_error(R, t); +} + +// betas10 = [B11 B12 B22 B13 B23 B33 B14 B24 B34 B44] +// betas_approx_1 = [B11 B12 B13 B14] + +void PnPsolver::find_betas_approx_1(const CvMat * L_6x10, const CvMat * Rho, + double * betas) +{ + double l_6x4[6 * 4], b4[4]; + CvMat L_6x4 = cvMat(6, 4, CV_64F, l_6x4); + CvMat B4 = cvMat(4, 1, CV_64F, b4); + + for(int i = 0; i < 6; i++) { + cvmSet(&L_6x4, i, 0, cvmGet(L_6x10, i, 0)); + cvmSet(&L_6x4, i, 1, cvmGet(L_6x10, i, 1)); + cvmSet(&L_6x4, i, 2, cvmGet(L_6x10, i, 3)); + cvmSet(&L_6x4, i, 3, cvmGet(L_6x10, i, 6)); + } + + cvSolve(&L_6x4, Rho, &B4, CV_SVD); + + if (b4[0] < 0) { + betas[0] = sqrt(-b4[0]); + betas[1] = -b4[1] / betas[0]; + betas[2] = -b4[2] / betas[0]; + betas[3] = -b4[3] / betas[0]; + } else { + betas[0] = sqrt(b4[0]); + betas[1] = b4[1] / betas[0]; + betas[2] = b4[2] / betas[0]; + betas[3] = b4[3] / betas[0]; + } +} + +// betas10 = [B11 B12 B22 B13 B23 B33 B14 B24 B34 B44] +// betas_approx_2 = [B11 B12 B22 ] + +void PnPsolver::find_betas_approx_2(const CvMat * L_6x10, const CvMat * Rho, + double * betas) +{ + double l_6x3[6 * 3], b3[3]; + CvMat L_6x3 = cvMat(6, 3, CV_64F, l_6x3); + CvMat B3 = cvMat(3, 1, CV_64F, b3); + + for(int i = 0; i < 6; i++) { + cvmSet(&L_6x3, i, 0, cvmGet(L_6x10, i, 0)); + cvmSet(&L_6x3, i, 1, cvmGet(L_6x10, i, 1)); + cvmSet(&L_6x3, i, 2, cvmGet(L_6x10, i, 2)); + } + + cvSolve(&L_6x3, Rho, &B3, CV_SVD); + + if (b3[0] < 0) { + betas[0] = sqrt(-b3[0]); + betas[1] = (b3[2] < 0) ? sqrt(-b3[2]) : 0.0; + } else { + betas[0] = sqrt(b3[0]); + betas[1] = (b3[2] > 0) ? sqrt(b3[2]) : 0.0; + } + + if (b3[1] < 0) betas[0] = -betas[0]; + + betas[2] = 0.0; + betas[3] = 0.0; +} + +// betas10 = [B11 B12 B22 B13 B23 B33 B14 B24 B34 B44] +// betas_approx_3 = [B11 B12 B22 B13 B23 ] + +void PnPsolver::find_betas_approx_3(const CvMat * L_6x10, const CvMat * Rho, + double * betas) +{ + double l_6x5[6 * 5], b5[5]; + CvMat L_6x5 = cvMat(6, 5, CV_64F, l_6x5); + CvMat B5 = cvMat(5, 1, CV_64F, b5); + + for(int i = 0; i < 6; i++) { + cvmSet(&L_6x5, i, 0, cvmGet(L_6x10, i, 0)); + cvmSet(&L_6x5, i, 1, cvmGet(L_6x10, i, 1)); + cvmSet(&L_6x5, i, 2, cvmGet(L_6x10, i, 2)); + cvmSet(&L_6x5, i, 3, cvmGet(L_6x10, i, 3)); + cvmSet(&L_6x5, i, 4, cvmGet(L_6x10, i, 4)); + } + + cvSolve(&L_6x5, Rho, &B5, CV_SVD); + + if (b5[0] < 0) { + betas[0] = sqrt(-b5[0]); + betas[1] = (b5[2] < 0) ? sqrt(-b5[2]) : 0.0; + } else { + betas[0] = sqrt(b5[0]); + betas[1] = (b5[2] > 0) ? sqrt(b5[2]) : 0.0; + } + if (b5[1] < 0) betas[0] = -betas[0]; + betas[2] = b5[3] / betas[0]; + betas[3] = 0.0; +} + +void PnPsolver::compute_L_6x10(const double * ut, double * l_6x10) +{ + const double * v[4]; + + v[0] = ut + 12 * 11; + v[1] = ut + 12 * 10; + v[2] = ut + 12 * 9; + v[3] = ut + 12 * 8; + + double dv[4][6][3]; + + for(int i = 0; i < 4; i++) { + int a = 0, b = 1; + for(int j = 0; j < 6; j++) { + dv[i][j][0] = v[i][3 * a ] - v[i][3 * b]; + dv[i][j][1] = v[i][3 * a + 1] - v[i][3 * b + 1]; + dv[i][j][2] = v[i][3 * a + 2] - v[i][3 * b + 2]; + + b++; + if (b > 3) { + a++; + b = a + 1; + } + } + } + + for(int i = 0; i < 6; i++) { + double * row = l_6x10 + 10 * i; + + row[0] = dot(dv[0][i], dv[0][i]); + row[1] = 2.0f * dot(dv[0][i], dv[1][i]); + row[2] = dot(dv[1][i], dv[1][i]); + row[3] = 2.0f * dot(dv[0][i], dv[2][i]); + row[4] = 2.0f * dot(dv[1][i], dv[2][i]); + row[5] = dot(dv[2][i], dv[2][i]); + row[6] = 2.0f * dot(dv[0][i], dv[3][i]); + row[7] = 2.0f * dot(dv[1][i], dv[3][i]); + row[8] = 2.0f * dot(dv[2][i], dv[3][i]); + row[9] = dot(dv[3][i], dv[3][i]); + } +} + +void PnPsolver::compute_rho(double * rho) +{ + rho[0] = dist2(cws[0], cws[1]); + rho[1] = dist2(cws[0], cws[2]); + rho[2] = dist2(cws[0], cws[3]); + rho[3] = dist2(cws[1], cws[2]); + rho[4] = dist2(cws[1], cws[3]); + rho[5] = dist2(cws[2], cws[3]); +} + +void PnPsolver::compute_A_and_b_gauss_newton(const double * l_6x10, const double * rho, + double betas[4], CvMat * A, CvMat * b) +{ + for(int i = 0; i < 6; i++) { + const double * rowL = l_6x10 + i * 10; + double * rowA = A->data.db + i * 4; + + rowA[0] = 2 * rowL[0] * betas[0] + rowL[1] * betas[1] + rowL[3] * betas[2] + rowL[6] * betas[3]; + rowA[1] = rowL[1] * betas[0] + 2 * rowL[2] * betas[1] + rowL[4] * betas[2] + rowL[7] * betas[3]; + rowA[2] = rowL[3] * betas[0] + rowL[4] * betas[1] + 2 * rowL[5] * betas[2] + rowL[8] * betas[3]; + rowA[3] = rowL[6] * betas[0] + rowL[7] * betas[1] + rowL[8] * betas[2] + 2 * rowL[9] * betas[3]; + + cvmSet(b, i, 0, rho[i] - + ( + rowL[0] * betas[0] * betas[0] + + rowL[1] * betas[0] * betas[1] + + rowL[2] * betas[1] * betas[1] + + rowL[3] * betas[0] * betas[2] + + rowL[4] * betas[1] * betas[2] + + rowL[5] * betas[2] * betas[2] + + rowL[6] * betas[0] * betas[3] + + rowL[7] * betas[1] * betas[3] + + rowL[8] * betas[2] * betas[3] + + rowL[9] * betas[3] * betas[3] + )); + } +} + +void PnPsolver::gauss_newton(const CvMat * L_6x10, const CvMat * Rho, + double betas[4]) +{ + const int iterations_number = 5; + + double a[6*4], b[6], x[4]; + CvMat A = cvMat(6, 4, CV_64F, a); + CvMat B = cvMat(6, 1, CV_64F, b); + CvMat X = cvMat(4, 1, CV_64F, x); + + for(int k = 0; k < iterations_number; k++) { + compute_A_and_b_gauss_newton(L_6x10->data.db, Rho->data.db, + betas, &A, &B); + qr_solve(&A, &B, &X); + + for(int i = 0; i < 4; i++) + betas[i] += x[i]; + } +} + +void PnPsolver::qr_solve(CvMat * A, CvMat * b, CvMat * X) +{ + static int max_nr = 0; + static double * A1, * A2; + + const int nr = A->rows; + const int nc = A->cols; + + if (max_nr != 0 && max_nr < nr) { + delete [] A1; + delete [] A2; + } + if (max_nr < nr) { + max_nr = nr; + A1 = new double[nr]; + A2 = new double[nr]; + } + + double * pA = A->data.db, * ppAkk = pA; + for(int k = 0; k < nc; k++) { + double * ppAik = ppAkk, eta = fabs(*ppAik); + for(int i = k + 1; i < nr; i++) { + double elt = fabs(*ppAik); + if (eta < elt) eta = elt; + ppAik += nc; + } + + if (eta == 0) { + A1[k] = A2[k] = 0.0; + cerr << "God damnit, A is singular, this shouldn't happen." << endl; + return; + } else { + double * ppAik = ppAkk, sum = 0.0, inv_eta = 1. / eta; + for(int i = k; i < nr; i++) { + *ppAik *= inv_eta; + sum += *ppAik * *ppAik; + ppAik += nc; + } + double sigma = sqrt(sum); + if (*ppAkk < 0) + sigma = -sigma; + *ppAkk += sigma; + A1[k] = sigma * *ppAkk; + A2[k] = -eta * sigma; + for(int j = k + 1; j < nc; j++) { + double * ppAik = ppAkk, sum = 0; + for(int i = k; i < nr; i++) { + sum += *ppAik * ppAik[j - k]; + ppAik += nc; + } + double tau = sum / A1[k]; + ppAik = ppAkk; + for(int i = k; i < nr; i++) { + ppAik[j - k] -= tau * *ppAik; + ppAik += nc; + } + } + } + ppAkk += nc + 1; + } + + // b <- Qt b + double * ppAjj = pA, * pb = b->data.db; + for(int j = 0; j < nc; j++) { + double * ppAij = ppAjj, tau = 0; + for(int i = j; i < nr; i++) { + tau += *ppAij * pb[i]; + ppAij += nc; + } + tau /= A1[j]; + ppAij = ppAjj; + for(int i = j; i < nr; i++) { + pb[i] -= tau * *ppAij; + ppAij += nc; + } + ppAjj += nc + 1; + } + + // X = R-1 b + double * pX = X->data.db; + pX[nc - 1] = pb[nc - 1] / A2[nc - 1]; + for(int i = nc - 2; i >= 0; i--) { + double * ppAij = pA + i * nc + (i + 1), sum = 0; + + for(int j = i + 1; j < nc; j++) { + sum += *ppAij * pX[j]; + ppAij++; + } + pX[i] = (pb[i] - sum) / A2[i]; + } +} + + + +void PnPsolver::relative_error(double & rot_err, double & transl_err, + const double Rtrue[3][3], const double ttrue[3], + const double Rest[3][3], const double test[3]) +{ + double qtrue[4], qest[4]; + + mat_to_quat(Rtrue, qtrue); + mat_to_quat(Rest, qest); + + double rot_err1 = sqrt((qtrue[0] - qest[0]) * (qtrue[0] - qest[0]) + + (qtrue[1] - qest[1]) * (qtrue[1] - qest[1]) + + (qtrue[2] - qest[2]) * (qtrue[2] - qest[2]) + + (qtrue[3] - qest[3]) * (qtrue[3] - qest[3]) ) / + sqrt(qtrue[0] * qtrue[0] + qtrue[1] * qtrue[1] + qtrue[2] * qtrue[2] + qtrue[3] * qtrue[3]); + + double rot_err2 = sqrt((qtrue[0] + qest[0]) * (qtrue[0] + qest[0]) + + (qtrue[1] + qest[1]) * (qtrue[1] + qest[1]) + + (qtrue[2] + qest[2]) * (qtrue[2] + qest[2]) + + (qtrue[3] + qest[3]) * (qtrue[3] + qest[3]) ) / + sqrt(qtrue[0] * qtrue[0] + qtrue[1] * qtrue[1] + qtrue[2] * qtrue[2] + qtrue[3] * qtrue[3]); + + rot_err = min(rot_err1, rot_err2); + + transl_err = + sqrt((ttrue[0] - test[0]) * (ttrue[0] - test[0]) + + (ttrue[1] - test[1]) * (ttrue[1] - test[1]) + + (ttrue[2] - test[2]) * (ttrue[2] - test[2])) / + sqrt(ttrue[0] * ttrue[0] + ttrue[1] * ttrue[1] + ttrue[2] * ttrue[2]); +} + +void PnPsolver::mat_to_quat(const double R[3][3], double q[4]) +{ + double tr = R[0][0] + R[1][1] + R[2][2]; + double n4; + + if (tr > 0.0f) { + q[0] = R[1][2] - R[2][1]; + q[1] = R[2][0] - R[0][2]; + q[2] = R[0][1] - R[1][0]; + q[3] = tr + 1.0f; + n4 = q[3]; + } else if ( (R[0][0] > R[1][1]) && (R[0][0] > R[2][2]) ) { + q[0] = 1.0f + R[0][0] - R[1][1] - R[2][2]; + q[1] = R[1][0] + R[0][1]; + q[2] = R[2][0] + R[0][2]; + q[3] = R[1][2] - R[2][1]; + n4 = q[0]; + } else if (R[1][1] > R[2][2]) { + q[0] = R[1][0] + R[0][1]; + q[1] = 1.0f + R[1][1] - R[0][0] - R[2][2]; + q[2] = R[2][1] + R[1][2]; + q[3] = R[2][0] - R[0][2]; + n4 = q[1]; + } else { + q[0] = R[2][0] + R[0][2]; + q[1] = R[2][1] + R[1][2]; + q[2] = 1.0f + R[2][2] - R[0][0] - R[1][1]; + q[3] = R[0][1] - R[1][0]; + n4 = q[2]; + } + double scale = 0.5f / double(sqrt(n4)); + + q[0] *= scale; + q[1] *= scale; + q[2] *= scale; + q[3] *= scale; +} + +} //namespace ORB_SLAM diff --git a/third_party/ORB_SLAM3/src/Sim3Solver.cc b/third_party/ORB_SLAM3/src/Sim3Solver.cc new file mode 100644 index 0000000..fc92cbf --- /dev/null +++ b/third_party/ORB_SLAM3/src/Sim3Solver.cc @@ -0,0 +1,508 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + + +#include "Sim3Solver.h" + +#include +#include +#include + +#include "KeyFrame.h" +#include "ORBmatcher.h" + +#include "Thirdparty/DBoW2/DUtils/Random.h" + +namespace ORB_SLAM3 +{ + + +Sim3Solver::Sim3Solver(KeyFrame *pKF1, KeyFrame *pKF2, const vector &vpMatched12, const bool bFixScale, + vector vpKeyFrameMatchedMP): + mnIterations(0), mnBestInliers(0), mbFixScale(bFixScale), + pCamera1(pKF1->mpCamera), pCamera2(pKF2->mpCamera) +{ + bool bDifferentKFs = false; + if(vpKeyFrameMatchedMP.empty()) + { + bDifferentKFs = true; + vpKeyFrameMatchedMP = vector(vpMatched12.size(), pKF2); + } + + mpKF1 = pKF1; + mpKF2 = pKF2; + + vector vpKeyFrameMP1 = pKF1->GetMapPointMatches(); + + mN1 = vpMatched12.size(); + + mvpMapPoints1.reserve(mN1); + mvpMapPoints2.reserve(mN1); + mvpMatches12 = vpMatched12; + mvnIndices1.reserve(mN1); + mvX3Dc1.reserve(mN1); + mvX3Dc2.reserve(mN1); + + cv::Mat Rcw1 = pKF1->GetRotation(); + cv::Mat tcw1 = pKF1->GetTranslation(); + cv::Mat Rcw2 = pKF2->GetRotation(); + cv::Mat tcw2 = pKF2->GetTranslation(); + + mvAllIndices.reserve(mN1); + + size_t idx=0; + + KeyFrame* pKFm = pKF2; //Default variable + for(int i1=0; i1isBad() || pMP2->isBad()) + continue; + + if(bDifferentKFs) + pKFm = vpKeyFrameMatchedMP[i1]; + + int indexKF1 = get<0>(pMP1->GetIndexInKeyFrame(pKF1)); + int indexKF2 = get<0>(pMP2->GetIndexInKeyFrame(pKFm)); + + if(indexKF1<0 || indexKF2<0) + continue; + + const cv::KeyPoint &kp1 = pKF1->mvKeysUn[indexKF1]; + const cv::KeyPoint &kp2 = pKFm->mvKeysUn[indexKF2]; + + const float sigmaSquare1 = pKF1->mvLevelSigma2[kp1.octave]; + const float sigmaSquare2 = pKFm->mvLevelSigma2[kp2.octave]; + + mvnMaxError1.push_back(9.210*sigmaSquare1); + mvnMaxError2.push_back(9.210*sigmaSquare2); + + mvpMapPoints1.push_back(pMP1); + mvpMapPoints2.push_back(pMP2); + mvnIndices1.push_back(i1); + + cv::Mat X3D1w = pMP1->GetWorldPos(); + mvX3Dc1.push_back(Rcw1*X3D1w+tcw1); + + cv::Mat X3D2w = pMP2->GetWorldPos(); + mvX3Dc2.push_back(Rcw2*X3D2w+tcw2); + + mvAllIndices.push_back(idx); + idx++; + } + } + + mK1 = pKF1->mK; + mK2 = pKF2->mK; + + FromCameraToImage(mvX3Dc1,mvP1im1,pCamera1); + FromCameraToImage(mvX3Dc2,mvP2im2,pCamera2); + + SetRansacParameters(); +} + +void Sim3Solver::SetRansacParameters(double probability, int minInliers, int maxIterations) +{ + mRansacProb = probability; + mRansacMinInliers = minInliers; + mRansacMaxIts = maxIterations; + + N = mvpMapPoints1.size(); // number of correspondences + + mvbInliersi.resize(N); + + // Adjust Parameters according to number of correspondences + float epsilon = (float)mRansacMinInliers/N; + + // Set RANSAC iterations according to probability, epsilon, and max iterations + int nIterations; + + if(mRansacMinInliers==N) + nIterations=1; + else + nIterations = ceil(log(1-mRansacProb)/log(1-pow(epsilon,3))); + + mRansacMaxIts = max(1,min(nIterations,mRansacMaxIts)); + + mnIterations = 0; +} + +cv::Mat Sim3Solver::iterate(int nIterations, bool &bNoMore, vector &vbInliers, int &nInliers) +{ + bNoMore = false; + vbInliers = vector(mN1,false); + nInliers=0; + + if(N vAvailableIndices; + + cv::Mat P3Dc1i(3,3,CV_32F); + cv::Mat P3Dc2i(3,3,CV_32F); + + int nCurrentIterations = 0; + while(mnIterations=mnBestInliers) + { + mvbBestInliers = mvbInliersi; + mnBestInliers = mnInliersi; + mBestT12 = mT12i.clone(); + mBestRotation = mR12i.clone(); + mBestTranslation = mt12i.clone(); + mBestScale = ms12i; + + if(mnInliersi>mRansacMinInliers) + { + nInliers = mnInliersi; + for(int i=0; i=mRansacMaxIts) + bNoMore=true; + + return cv::Mat(); +} + +cv::Mat Sim3Solver::iterate(int nIterations, bool &bNoMore, vector &vbInliers, int &nInliers, bool &bConverge) +{ + bNoMore = false; + bConverge = false; + vbInliers = vector(mN1,false); + nInliers=0; + + if(N vAvailableIndices; + + cv::Mat P3Dc1i(3,3,CV_32F); + cv::Mat P3Dc2i(3,3,CV_32F); + + int nCurrentIterations = 0; + + cv::Mat bestSim3; + + while(mnIterations=mnBestInliers) + { + mvbBestInliers = mvbInliersi; + mnBestInliers = mnInliersi; + mBestT12 = mT12i.clone(); + mBestRotation = mR12i.clone(); + mBestTranslation = mt12i.clone(); + mBestScale = ms12i; + + if(mnInliersi>mRansacMinInliers) + { + nInliers = mnInliersi; + for(int i=0; i=mRansacMaxIts) + bNoMore=true; + + return bestSim3; +} + +cv::Mat Sim3Solver::find(vector &vbInliers12, int &nInliers) +{ + bool bFlag; + return iterate(mRansacMaxIts,bFlag,vbInliers12,nInliers); +} + +void Sim3Solver::ComputeCentroid(cv::Mat &P, cv::Mat &Pr, cv::Mat &C) +{ + cv::reduce(P,C,1,cv::REDUCE_SUM); + C = C/P.cols; + + for(int i=0; i(0,0)+M.at(1,1)+M.at(2,2); + N12 = M.at(1,2)-M.at(2,1); + N13 = M.at(2,0)-M.at(0,2); + N14 = M.at(0,1)-M.at(1,0); + N22 = M.at(0,0)-M.at(1,1)-M.at(2,2); + N23 = M.at(0,1)+M.at(1,0); + N24 = M.at(2,0)+M.at(0,2); + N33 = -M.at(0,0)+M.at(1,1)-M.at(2,2); + N34 = M.at(1,2)+M.at(2,1); + N44 = -M.at(0,0)-M.at(1,1)+M.at(2,2); + + N = (cv::Mat_(4,4) << N11, N12, N13, N14, + N12, N22, N23, N24, + N13, N23, N33, N34, + N14, N24, N34, N44); + + + // Step 4: Eigenvector of the highest eigenvalue + + cv::Mat eval, evec; + + cv::eigen(N,eval,evec); //evec[0] is the quaternion of the desired rotation + + cv::Mat vec(1,3,evec.type()); + (evec.row(0).colRange(1,4)).copyTo(vec); //extract imaginary part of the quaternion (sin*axis) + + // Rotation angle. sin is the norm of the imaginary part, cos is the real part + double ang=atan2(norm(vec),evec.at(0,0)); + + vec = 2*ang*vec/norm(vec); //Angle-axis representation. quaternion angle is the half + + mR12i.create(3,3,P1.type()); + + cv::Rodrigues(vec,mR12i); // computes the rotation matrix from angle-axis + + // Step 5: Rotate set 2 + + cv::Mat P3 = mR12i*Pr2; + + // Step 6: Scale + + if(!mbFixScale) + { + double nom = Pr1.dot(P3); + cv::Mat aux_P3(P3.size(),P3.type()); + aux_P3=P3; + cv::pow(P3,2,aux_P3); + double den = 0; + + for(int i=0; i(i,j); + } + } + + ms12i = nom/den; + } + else + ms12i = 1.0f; + + // Step 7: Translation + + mt12i.create(1,3,P1.type()); + mt12i = O1 - ms12i*mR12i*O2; + + // Step 8: Transformation + + // Step 8.1 T12 + mT12i = cv::Mat::eye(4,4,P1.type()); + + cv::Mat sR = ms12i*mR12i; + + sR.copyTo(mT12i.rowRange(0,3).colRange(0,3)); + mt12i.copyTo(mT12i.rowRange(0,3).col(3)); + + // Step 8.2 T21 + + mT21i = cv::Mat::eye(4,4,P1.type()); + + cv::Mat sRinv = (1.0/ms12i)*mR12i.t(); + + sRinv.copyTo(mT21i.rowRange(0,3).colRange(0,3)); + cv::Mat tinv = -sRinv*mt12i; + tinv.copyTo(mT21i.rowRange(0,3).col(3)); +} + + +void Sim3Solver::CheckInliers() +{ + vector vP1im2, vP2im1; + Project(mvX3Dc2,vP2im1,mT12i,pCamera1); + Project(mvX3Dc1,vP1im2,mT21i,pCamera2); + + mnInliersi=0; + + for(size_t i=0; i &vP3Dw, vector &vP2D, cv::Mat Tcw, GeometricCamera* pCamera) +{ + cv::Mat Rcw = Tcw.rowRange(0,3).colRange(0,3); + cv::Mat tcw = Tcw.rowRange(0,3).col(3); + + vP2D.clear(); + vP2D.reserve(vP3Dw.size()); + + for(size_t i=0, iend=vP3Dw.size(); i(2)); + const float x = P3Dc.at(0); + const float y = P3Dc.at(1); + const float z = P3Dc.at(2); + + vP2D.push_back(pCamera->projectMat(cv::Point3f(x,y,z))); + } +} + +void Sim3Solver::FromCameraToImage(const vector &vP3Dc, vector &vP2D, GeometricCamera* pCamera) +{ + vP2D.clear(); + vP2D.reserve(vP3Dc.size()); + + for(size_t i=0, iend=vP3Dc.size(); i(2)); + const float x = vP3Dc[i].at(0); + const float y = vP3Dc[i].at(1); + const float z = vP3Dc[i].at(2); + + vP2D.push_back(pCamera->projectMat(cv::Point3f(x,y,z))); + } +} + +} //namespace ORB_SLAM diff --git a/third_party/ORB_SLAM3/src/System.cc b/third_party/ORB_SLAM3/src/System.cc new file mode 100644 index 0000000..ab66b7c --- /dev/null +++ b/third_party/ORB_SLAM3/src/System.cc @@ -0,0 +1,1069 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + + + +#include "System.h" +#include "Converter.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace ORB_SLAM3 +{ + +Verbose::eLevel Verbose::th = Verbose::VERBOSITY_NORMAL; + +System::System(const string &strVocFile, const string &strSettingsFile, const eSensor sensor, + const bool bUseViewer, const int initFr, const string &strSequence, const string &strLoadingFile): + mSensor(sensor), mpViewer(static_cast(NULL)), mbReset(false), mbResetActiveMap(false), + mbActivateLocalizationMode(false), mbDeactivateLocalizationMode(false) +{ + // Output welcome message + cout << endl << + "ORB-SLAM3 Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza." << endl << + "ORB-SLAM2 Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza." << endl << + "This program comes with ABSOLUTELY NO WARRANTY;" << endl << + "This is free software, and you are welcome to redistribute it" << endl << + "under certain conditions. See LICENSE.txt." << endl << endl; + + cout << "Input sensor was set to: "; + + if(mSensor==MONOCULAR) + cout << "Monocular" << endl; + else if(mSensor==STEREO) + cout << "Stereo" << endl; + else if(mSensor==RGBD) + cout << "RGB-D" << endl; + else if(mSensor==IMU_MONOCULAR) + cout << "Monocular-Inertial" << endl; + else if(mSensor==IMU_STEREO) + cout << "Stereo-Inertial" << endl; + + //Check settings file + cv::FileStorage fsSettings(strSettingsFile.c_str(), cv::FileStorage::READ); + if(!fsSettings.isOpened()) + { + cerr << "Failed to open settings file at: " << strSettingsFile << endl; + exit(-1); + } + + bool loadedAtlas = false; + + //---- + //Load ORB Vocabulary + cout << endl << "Loading ORB Vocabulary. This could take a while..." << endl; + + mpVocabulary = new ORBVocabulary(); + bool bVocLoad = mpVocabulary->loadFromTextFile(strVocFile); + if(!bVocLoad) + { + cerr << "Wrong path to vocabulary. " << endl; + cerr << "Falied to open at: " << strVocFile << endl; + exit(-1); + } + cout << "Vocabulary loaded!" << endl << endl; + + //Create KeyFrame Database + mpKeyFrameDatabase = new KeyFrameDatabase(*mpVocabulary); + + //Create the Atlas + //mpMap = new Map(); + mpAtlas = new Atlas(0); + //---- + + /*if(strLoadingFile.empty()) + { + //Load ORB Vocabulary + cout << endl << "Loading ORB Vocabulary. This could take a while..." << endl; + + mpVocabulary = new ORBVocabulary(); + bool bVocLoad = mpVocabulary->loadFromTextFile(strVocFile); + if(!bVocLoad) + { + cerr << "Wrong path to vocabulary. " << endl; + cerr << "Falied to open at: " << strVocFile << endl; + exit(-1); + } + cout << "Vocabulary loaded!" << endl << endl; + + //Create KeyFrame Database + mpKeyFrameDatabase = new KeyFrameDatabase(*mpVocabulary); + + //Create the Atlas + //mpMap = new Map(); + mpAtlas = new Atlas(0); + } + else + { + //Load ORB Vocabulary + cout << endl << "Loading ORB Vocabulary. This could take a while..." << endl; + + mpVocabulary = new ORBVocabulary(); + bool bVocLoad = mpVocabulary->loadFromTextFile(strVocFile); + if(!bVocLoad) + { + cerr << "Wrong path to vocabulary. " << endl; + cerr << "Falied to open at: " << strVocFile << endl; + exit(-1); + } + cout << "Vocabulary loaded!" << endl << endl; + + cout << "Load File" << endl; + + // Load the file with an earlier session + //clock_t start = clock(); + bool isRead = LoadAtlas(strLoadingFile,BINARY_FILE); + + if(!isRead) + { + cout << "Error to load the file, please try with other session file or vocabulary file" << endl; + exit(-1); + } + mpKeyFrameDatabase = new KeyFrameDatabase(*mpVocabulary); + + mpAtlas->SetKeyFrameDababase(mpKeyFrameDatabase); + mpAtlas->SetORBVocabulary(mpVocabulary); + mpAtlas->PostLoad(); + //cout << "KF in DB: " << mpKeyFrameDatabase->mnNumKFs << "; words: " << mpKeyFrameDatabase->mnNumWords << endl; + + loadedAtlas = true; + + mpAtlas->CreateNewMap(); + + //clock_t timeElapsed = clock() - start; + //unsigned msElapsed = timeElapsed / (CLOCKS_PER_SEC / 1000); + //cout << "Binary file read in " << msElapsed << " ms" << endl; + + //usleep(10*1000*1000); + }*/ + + + if (mSensor==IMU_STEREO || mSensor==IMU_MONOCULAR) + mpAtlas->SetInertialSensor(); + + //Create Drawers. These are used by the Viewer + mpFrameDrawer = new FrameDrawer(mpAtlas); + mpMapDrawer = new MapDrawer(mpAtlas, strSettingsFile); + + //Initialize the Tracking thread + //(it will live in the main thread of execution, the one that called this constructor) + cout << "Seq. Name: " << strSequence << endl; + mpTracker = new Tracking(this, mpVocabulary, mpFrameDrawer, mpMapDrawer, + mpAtlas, mpKeyFrameDatabase, strSettingsFile, mSensor, strSequence); + + //Initialize the Local Mapping thread and launch + mpLocalMapper = new LocalMapping(this, mpAtlas, mSensor==MONOCULAR || mSensor==IMU_MONOCULAR, mSensor==IMU_MONOCULAR || mSensor==IMU_STEREO, strSequence); + mptLocalMapping = new thread(&ORB_SLAM3::LocalMapping::Run,mpLocalMapper); + mpLocalMapper->mInitFr = initFr; + mpLocalMapper->mThFarPoints = fsSettings["thFarPoints"]; + if(mpLocalMapper->mThFarPoints!=0) + { + cout << "Discard points further than " << mpLocalMapper->mThFarPoints << " m from current camera" << endl; + mpLocalMapper->mbFarPoints = true; + } + else + mpLocalMapper->mbFarPoints = false; + + //Initialize the Loop Closing thread and launch + // mSensor!=MONOCULAR && mSensor!=IMU_MONOCULAR + mpLoopCloser = new LoopClosing(mpAtlas, mpKeyFrameDatabase, mpVocabulary, mSensor!=MONOCULAR); // mSensor!=MONOCULAR); + mptLoopClosing = new thread(&ORB_SLAM3::LoopClosing::Run, mpLoopCloser); + + //Initialize the Viewer thread and launch + if(bUseViewer) + { + mpViewer = new Viewer(this, mpFrameDrawer,mpMapDrawer,mpTracker,strSettingsFile); + mptViewer = new thread(&Viewer::Run, mpViewer); + mpTracker->SetViewer(mpViewer); + mpLoopCloser->mpViewer = mpViewer; + mpViewer->both = mpFrameDrawer->both; + } + + //Set pointers between threads + mpTracker->SetLocalMapper(mpLocalMapper); + mpTracker->SetLoopClosing(mpLoopCloser); + + mpLocalMapper->SetTracker(mpTracker); + mpLocalMapper->SetLoopCloser(mpLoopCloser); + + mpLoopCloser->SetTracker(mpTracker); + mpLoopCloser->SetLocalMapper(mpLocalMapper); + + // Fix verbosity + Verbose::SetTh(Verbose::VERBOSITY_QUIET); + +} + +cv::Mat System::TrackStereo(const cv::Mat &imLeft, const cv::Mat &imRight, const double ×tamp, const vector& vImuMeas, string filename) +{ + if(mSensor!=STEREO && mSensor!=IMU_STEREO) + { + cerr << "ERROR: you called TrackStereo but input sensor was not set to Stereo nor Stereo-Inertial." << endl; + exit(-1); + } + + // Check mode change + { + unique_lock lock(mMutexMode); + if(mbActivateLocalizationMode) + { + mpLocalMapper->RequestStop(); + + // Wait until Local Mapping has effectively stopped + while(!mpLocalMapper->isStopped()) + { + usleep(1000); + } + + mpTracker->InformOnlyTracking(true); + mbActivateLocalizationMode = false; + } + if(mbDeactivateLocalizationMode) + { + mpTracker->InformOnlyTracking(false); + mpLocalMapper->Release(); + mbDeactivateLocalizationMode = false; + } + } + + // Check reset + { + unique_lock lock(mMutexReset); + if(mbReset) + { + mpTracker->Reset(); + cout << "Reset stereo..." << endl; + mbReset = false; + mbResetActiveMap = false; + } + else if(mbResetActiveMap) + { + mpTracker->ResetActiveMap(); + mbResetActiveMap = false; + } + } + + if (mSensor == System::IMU_STEREO) + for(size_t i_imu = 0; i_imu < vImuMeas.size(); i_imu++) + mpTracker->GrabImuData(vImuMeas[i_imu]); + + // std::cout << "start GrabImageStereo" << std::endl; + cv::Mat Tcw = mpTracker->GrabImageStereo(imLeft,imRight,timestamp,filename); + + // std::cout << "out grabber" << std::endl; + + unique_lock lock2(mMutexState); + mTrackingState = mpTracker->mState; + mTrackedMapPoints = mpTracker->mCurrentFrame.mvpMapPoints; + mTrackedKeyPointsUn = mpTracker->mCurrentFrame.mvKeysUn; + + return Tcw; +} + +cv::Mat System::TrackRGBD(const cv::Mat &im, const cv::Mat &depthmap, const double ×tamp, string filename) +{ + if(mSensor!=RGBD) + { + cerr << "ERROR: you called TrackRGBD but input sensor was not set to RGBD." << endl; + exit(-1); + } + + // Check mode change + { + unique_lock lock(mMutexMode); + if(mbActivateLocalizationMode) + { + mpLocalMapper->RequestStop(); + + // Wait until Local Mapping has effectively stopped + while(!mpLocalMapper->isStopped()) + { + usleep(1000); + } + + mpTracker->InformOnlyTracking(true); + mbActivateLocalizationMode = false; + } + if(mbDeactivateLocalizationMode) + { + mpTracker->InformOnlyTracking(false); + mpLocalMapper->Release(); + mbDeactivateLocalizationMode = false; + } + } + + // Check reset + { + unique_lock lock(mMutexReset); + if(mbReset) + { + mpTracker->Reset(); + mbReset = false; + mbResetActiveMap = false; + } + else if(mbResetActiveMap) + { + mpTracker->ResetActiveMap(); + mbResetActiveMap = false; + } + } + + + cv::Mat Tcw = mpTracker->GrabImageRGBD(im,depthmap,timestamp,filename); + + unique_lock lock2(mMutexState); + mTrackingState = mpTracker->mState; + mTrackedMapPoints = mpTracker->mCurrentFrame.mvpMapPoints; + mTrackedKeyPointsUn = mpTracker->mCurrentFrame.mvKeysUn; + return Tcw; +} + +cv::Mat System::TrackMonocular(const cv::Mat &im, const double ×tamp, const vector& vImuMeas, string filename) +{ + if(mSensor!=MONOCULAR && mSensor!=IMU_MONOCULAR) + { + cerr << "ERROR: you called TrackMonocular but input sensor was not set to Monocular nor Monocular-Inertial." << endl; + exit(-1); + } + + // Check mode change + { + unique_lock lock(mMutexMode); + if(mbActivateLocalizationMode) + { + mpLocalMapper->RequestStop(); + + // Wait until Local Mapping has effectively stopped + while(!mpLocalMapper->isStopped()) + { + usleep(1000); + } + + mpTracker->InformOnlyTracking(true); + mbActivateLocalizationMode = false; + } + if(mbDeactivateLocalizationMode) + { + mpTracker->InformOnlyTracking(false); + mpLocalMapper->Release(); + mbDeactivateLocalizationMode = false; + } + } + + // Check reset + { + unique_lock lock(mMutexReset); + if(mbReset) + { + mpTracker->Reset(); + mbReset = false; + mbResetActiveMap = false; + } + else if(mbResetActiveMap) + { + cout << "SYSTEM-> Reseting active map in monocular case" << endl; + mpTracker->ResetActiveMap(); + mbResetActiveMap = false; + } + } + + if (mSensor == System::IMU_MONOCULAR) + for(size_t i_imu = 0; i_imu < vImuMeas.size(); i_imu++) + mpTracker->GrabImuData(vImuMeas[i_imu]); + + cv::Mat Tcw = mpTracker->GrabImageMonocular(im,timestamp,filename); + + unique_lock lock2(mMutexState); + mTrackingState = mpTracker->mState; + mTrackedMapPoints = mpTracker->mCurrentFrame.mvpMapPoints; + mTrackedKeyPointsUn = mpTracker->mCurrentFrame.mvKeysUn; + + return Tcw; +} + + + +void System::ActivateLocalizationMode() +{ + unique_lock lock(mMutexMode); + mbActivateLocalizationMode = true; +} + +void System::DeactivateLocalizationMode() +{ + unique_lock lock(mMutexMode); + mbDeactivateLocalizationMode = true; +} + +bool System::MapChanged() +{ + static int n=0; + int curn = mpAtlas->GetLastBigChangeIdx(); + if(n lock(mMutexReset); + mbReset = true; +} + +void System::ResetActiveMap() +{ + unique_lock lock(mMutexReset); + mbResetActiveMap = true; +} + +void System::Shutdown() +{ + mpLocalMapper->RequestFinish(); + mpLoopCloser->RequestFinish(); + if(mpViewer) + { + mpViewer->RequestFinish(); + while(!mpViewer->isFinished()) + usleep(5000); + } + + // Wait until all thread have effectively stopped + while(!mpLocalMapper->isFinished() || !mpLoopCloser->isFinished() || mpLoopCloser->isRunningGBA()) + { + if(!mpLocalMapper->isFinished()) + cout << "mpLocalMapper is not finished" << endl; + if(!mpLoopCloser->isFinished()) + cout << "mpLoopCloser is not finished" << endl; + if(mpLoopCloser->isRunningGBA()){ + cout << "mpLoopCloser is running GBA" << endl; + cout << "break anyway..." << endl; + break; + } + usleep(5000); + } + + if(mpViewer) + pangolin::BindToContext("ORB-SLAM2: Map Viewer"); +} + + + +void System::SaveTrajectoryTUM(const string &filename) +{ + cout << endl << "Saving camera trajectory to " << filename << " ..." << endl; + if(mSensor==MONOCULAR) + { + cerr << "ERROR: SaveTrajectoryTUM cannot be used for monocular." << endl; + return; + } + + vector vpKFs = mpAtlas->GetAllKeyFrames(); + sort(vpKFs.begin(),vpKFs.end(),KeyFrame::lId); + + // Transform all keyframes so that the first keyframe is at the origin. + // After a loop closure the first keyframe might not be at the origin. + cv::Mat Two = vpKFs[0]->GetPoseInverse(); + + ofstream f; + f.open(filename.c_str()); + f << fixed; + + // Frame pose is stored relative to its reference keyframe (which is optimized by BA and pose graph). + // We need to get first the keyframe pose and then concatenate the relative transformation. + // Frames not localized (tracking failure) are not saved. + + // For each frame we have a reference keyframe (lRit), the timestamp (lT) and a flag + // which is true when tracking failed (lbL). + list::iterator lRit = mpTracker->mlpReferences.begin(); + list::iterator lT = mpTracker->mlFrameTimes.begin(); + list::iterator lbL = mpTracker->mlbLost.begin(); + for(list::iterator lit=mpTracker->mlRelativeFramePoses.begin(), + lend=mpTracker->mlRelativeFramePoses.end();lit!=lend;lit++, lRit++, lT++, lbL++) + { + if(*lbL) + continue; + + KeyFrame* pKF = *lRit; + + cv::Mat Trw = cv::Mat::eye(4,4,CV_32F); + + // If the reference keyframe was culled, traverse the spanning tree to get a suitable keyframe. + while(pKF->isBad()) + { + Trw = Trw*pKF->mTcp; + pKF = pKF->GetParent(); + } + + Trw = Trw*pKF->GetPose()*Two; + + cv::Mat Tcw = (*lit)*Trw; + cv::Mat Rwc = Tcw.rowRange(0,3).colRange(0,3).t(); + cv::Mat twc = -Rwc*Tcw.rowRange(0,3).col(3); + + vector q = Converter::toQuaternion(Rwc); + + f << setprecision(6) << *lT << " " << setprecision(9) << twc.at(0) << " " << twc.at(1) << " " << twc.at(2) << " " << q[0] << " " << q[1] << " " << q[2] << " " << q[3] << endl; + } + f.close(); + // cout << endl << "trajectory saved!" << endl; +} + +void System::SaveKeyFrameTrajectoryTUM(const string &filename) +{ + cout << endl << "Saving keyframe trajectory to " << filename << " ..." << endl; + + vector vpKFs = mpAtlas->GetAllKeyFrames(); + sort(vpKFs.begin(),vpKFs.end(),KeyFrame::lId); + + // Transform all keyframes so that the first keyframe is at the origin. + // After a loop closure the first keyframe might not be at the origin. + ofstream f; + f.open(filename.c_str()); + f << fixed; + + for(size_t i=0; iSetPose(pKF->GetPose()*Two); + + if(pKF->isBad()) + continue; + + cv::Mat R = pKF->GetRotation().t(); + vector q = Converter::toQuaternion(R); + cv::Mat t = pKF->GetCameraCenter(); + f << setprecision(6) << pKF->mTimeStamp << setprecision(7) << " " << t.at(0) << " " << t.at(1) << " " << t.at(2) + << " " << q[0] << " " << q[1] << " " << q[2] << " " << q[3] << endl; + + } + + f.close(); +} + +void System::SaveTrajectoryEuRoC(const string &filename) +{ + + cout << endl << "Saving trajectory to " << filename << " ..." << endl; + /*if(mSensor==MONOCULAR) + { + cerr << "ERROR: SaveTrajectoryEuRoC cannot be used for monocular." << endl; + return; + }*/ + + vector vpMaps = mpAtlas->GetAllMaps(); + Map* pBiggerMap; + int numMaxKFs = 0; + for(Map* pMap :vpMaps) + { + if(pMap->GetAllKeyFrames().size() > numMaxKFs) + { + numMaxKFs = pMap->GetAllKeyFrames().size(); + pBiggerMap = pMap; + } + } + + vector vpKFs = pBiggerMap->GetAllKeyFrames(); + sort(vpKFs.begin(),vpKFs.end(),KeyFrame::lId); + + // Transform all keyframes so that the first keyframe is at the origin. + // After a loop closure the first keyframe might not be at the origin. + cv::Mat Twb; // Can be word to cam0 or world to b dependingo on IMU or not. + if (mSensor==IMU_MONOCULAR || mSensor==IMU_STEREO) + Twb = vpKFs[0]->GetImuPose(); + else + Twb = vpKFs[0]->GetPoseInverse(); + + ofstream f; + f.open(filename.c_str()); + // cout << "file open" << endl; + f << fixed; + + // Frame pose is stored relative to its reference keyframe (which is optimized by BA and pose graph). + // We need to get first the keyframe pose and then concatenate the relative transformation. + // Frames not localized (tracking failure) are not saved. + + // For each frame we have a reference keyframe (lRit), the timestamp (lT) and a flag + // which is true when tracking failed (lbL). + list::iterator lRit = mpTracker->mlpReferences.begin(); + list::iterator lT = mpTracker->mlFrameTimes.begin(); + list::iterator lbL = mpTracker->mlbLost.begin(); + + //cout << "size mlpReferences: " << mpTracker->mlpReferences.size() << endl; + //cout << "size mlRelativeFramePoses: " << mpTracker->mlRelativeFramePoses.size() << endl; + //cout << "size mpTracker->mlFrameTimes: " << mpTracker->mlFrameTimes.size() << endl; + //cout << "size mpTracker->mlbLost: " << mpTracker->mlbLost.size() << endl; + + + for(list::iterator lit=mpTracker->mlRelativeFramePoses.begin(), + lend=mpTracker->mlRelativeFramePoses.end();lit!=lend;lit++, lRit++, lT++, lbL++) + { + //cout << "1" << endl; + if(*lbL) + continue; + + + KeyFrame* pKF = *lRit; + //cout << "KF: " << pKF->mnId << endl; + + cv::Mat Trw = cv::Mat::eye(4,4,CV_32F); + + /*cout << "2" << endl; + cout << "KF id: " << pKF->mnId << endl;*/ + + // If the reference keyframe was culled, traverse the spanning tree to get a suitable keyframe. + if (!pKF) + continue; + + //cout << "2.5" << endl; + + while(pKF->isBad()) + { + //cout << " 2.bad" << endl; + Trw = Trw*pKF->mTcp; + pKF = pKF->GetParent(); + //cout << "--Parent KF: " << pKF->mnId << endl; + } + + if(!pKF || pKF->GetMap() != pBiggerMap) + { + //cout << "--Parent KF is from another map" << endl; + /*if(pKF) + cout << "--Parent KF " << pKF->mnId << " is from another map " << pKF->GetMap()->GetId() << endl;*/ + continue; + } + + //cout << "3" << endl; + + Trw = Trw*pKF->GetPose()*Twb; // Tcp*Tpw*Twb0=Tcb0 where b0 is the new world reference + + // cout << "4" << endl; + + if (mSensor == IMU_MONOCULAR || mSensor == IMU_STEREO) + { + cv::Mat Tbw = pKF->mImuCalib.Tbc*(*lit)*Trw; + cv::Mat Rwb = Tbw.rowRange(0,3).colRange(0,3).t(); + cv::Mat twb = -Rwb*Tbw.rowRange(0,3).col(3); + vector q = Converter::toQuaternion(Rwb); + f << setprecision(6) << 1e9*(*lT) << " " << setprecision(9) << twb.at(0) << " " << twb.at(1) << " " << twb.at(2) << " " << q[0] << " " << q[1] << " " << q[2] << " " << q[3] << endl; + } + else + { + cv::Mat Tcw = (*lit)*Trw; + cv::Mat Rwc = Tcw.rowRange(0,3).colRange(0,3).t(); + cv::Mat twc = -Rwc*Tcw.rowRange(0,3).col(3); + vector q = Converter::toQuaternion(Rwc); + f << setprecision(6) << 1e9*(*lT) << " " << setprecision(9) << twc.at(0) << " " << twc.at(1) << " " << twc.at(2) << " " << q[0] << " " << q[1] << " " << q[2] << " " << q[3] << endl; + } + + // cout << "5" << endl; + } + //cout << "end saving trajectory" << endl; + f.close(); + cout << endl << "End of saving trajectory to " << filename << " ..." << endl; +} + + +void System::SaveKeyFrameTrajectoryEuRoC(const string &filename) +{ + cout << endl << "Saving keyframe trajectory to " << filename << " ..." << endl; + + vector vpMaps = mpAtlas->GetAllMaps(); + Map* pBiggerMap; + int numMaxKFs = 0; + for(Map* pMap :vpMaps) + { + if(pMap->GetAllKeyFrames().size() > numMaxKFs) + { + numMaxKFs = pMap->GetAllKeyFrames().size(); + pBiggerMap = pMap; + } + } + + vector vpKFs = pBiggerMap->GetAllKeyFrames(); + sort(vpKFs.begin(),vpKFs.end(),KeyFrame::lId); + + // Transform all keyframes so that the first keyframe is at the origin. + // After a loop closure the first keyframe might not be at the origin. + ofstream f; + f.open(filename.c_str()); + f << fixed; + + for(size_t i=0; iSetPose(pKF->GetPose()*Two); + + if(pKF->isBad()) + continue; + if (mSensor == IMU_MONOCULAR || mSensor == IMU_STEREO) + { + cv::Mat R = pKF->GetImuRotation().t(); + vector q = Converter::toQuaternion(R); + cv::Mat twb = pKF->GetImuPosition(); + f << setprecision(6) << 1e9*pKF->mTimeStamp << " " << setprecision(9) << twb.at(0) << " " << twb.at(1) << " " << twb.at(2) << " " << q[0] << " " << q[1] << " " << q[2] << " " << q[3] << endl; + + } + else + { + cv::Mat R = pKF->GetRotation(); + vector q = Converter::toQuaternion(R); + cv::Mat t = pKF->GetCameraCenter(); + f << setprecision(6) << 1e9*pKF->mTimeStamp << " " << setprecision(9) << t.at(0) << " " << t.at(1) << " " << t.at(2) << " " << q[0] << " " << q[1] << " " << q[2] << " " << q[3] << endl; + } + } + f.close(); +} + +void System::SaveTrajectoryKITTI(const string &filename) +{ + cout << endl << "Saving camera trajectory to " << filename << " ..." << endl; + if(mSensor==MONOCULAR) + { + cerr << "ERROR: SaveTrajectoryKITTI cannot be used for monocular." << endl; + return; + } + + vector vpKFs = mpAtlas->GetAllKeyFrames(); + sort(vpKFs.begin(),vpKFs.end(),KeyFrame::lId); + + // Transform all keyframes so that the first keyframe is at the origin. + // After a loop closure the first keyframe might not be at the origin. + cv::Mat Two = vpKFs[0]->GetPoseInverse(); + + ofstream f; + f.open(filename.c_str()); + f << fixed; + + // Frame pose is stored relative to its reference keyframe (which is optimized by BA and pose graph). + // We need to get first the keyframe pose and then concatenate the relative transformation. + // Frames not localized (tracking failure) are not saved. + + // For each frame we have a reference keyframe (lRit), the timestamp (lT) and a flag + // which is true when tracking failed (lbL). + list::iterator lRit = mpTracker->mlpReferences.begin(); + list::iterator lT = mpTracker->mlFrameTimes.begin(); + for(list::iterator lit=mpTracker->mlRelativeFramePoses.begin(), lend=mpTracker->mlRelativeFramePoses.end();lit!=lend;lit++, lRit++, lT++) + { + ORB_SLAM3::KeyFrame* pKF = *lRit; + + cv::Mat Trw = cv::Mat::eye(4,4,CV_32F); + + while(pKF->isBad()) + { + Trw = Trw*pKF->mTcp; + pKF = pKF->GetParent(); + } + + Trw = Trw*pKF->GetPose()*Two; + + cv::Mat Tcw = (*lit)*Trw; + cv::Mat Rwc = Tcw.rowRange(0,3).colRange(0,3).t(); + cv::Mat twc = -Rwc*Tcw.rowRange(0,3).col(3); + + f << setprecision(9) << Rwc.at(0,0) << " " << Rwc.at(0,1) << " " << Rwc.at(0,2) << " " << twc.at(0) << " " << + Rwc.at(1,0) << " " << Rwc.at(1,1) << " " << Rwc.at(1,2) << " " << twc.at(1) << " " << + Rwc.at(2,0) << " " << Rwc.at(2,1) << " " << Rwc.at(2,2) << " " << twc.at(2) << endl; + } + f.close(); +} + + +void System::SaveDebugData(const int &initIdx) +{ + // 0. Save initialization trajectory + SaveTrajectoryEuRoC("init_FrameTrajectoy_" +to_string(mpLocalMapper->mInitSect)+ "_" + to_string(initIdx)+".txt"); + + // 1. Save scale + ofstream f; + f.open("init_Scale_" + to_string(mpLocalMapper->mInitSect) + ".txt", ios_base::app); + f << fixed; + f << mpLocalMapper->mScale << endl; + f.close(); + + // 2. Save gravity direction + f.open("init_GDir_" +to_string(mpLocalMapper->mInitSect)+ ".txt", ios_base::app); + f << fixed; + f << mpLocalMapper->mRwg(0,0) << "," << mpLocalMapper->mRwg(0,1) << "," << mpLocalMapper->mRwg(0,2) << endl; + f << mpLocalMapper->mRwg(1,0) << "," << mpLocalMapper->mRwg(1,1) << "," << mpLocalMapper->mRwg(1,2) << endl; + f << mpLocalMapper->mRwg(2,0) << "," << mpLocalMapper->mRwg(2,1) << "," << mpLocalMapper->mRwg(2,2) << endl; + f.close(); + + // 3. Save computational cost + f.open("init_CompCost_" +to_string(mpLocalMapper->mInitSect)+ ".txt", ios_base::app); + f << fixed; + f << mpLocalMapper->mCostTime << endl; + f.close(); + + // 4. Save biases + f.open("init_Biases_" +to_string(mpLocalMapper->mInitSect)+ ".txt", ios_base::app); + f << fixed; + f << mpLocalMapper->mbg(0) << "," << mpLocalMapper->mbg(1) << "," << mpLocalMapper->mbg(2) << endl; + f << mpLocalMapper->mba(0) << "," << mpLocalMapper->mba(1) << "," << mpLocalMapper->mba(2) << endl; + f.close(); + + // 5. Save covariance matrix + f.open("init_CovMatrix_" +to_string(mpLocalMapper->mInitSect)+ "_" +to_string(initIdx)+".txt", ios_base::app); + f << fixed; + for(int i=0; imcovInertial.rows(); i++) + { + for(int j=0; jmcovInertial.cols(); j++) + { + if(j!=0) + f << ","; + f << setprecision(15) << mpLocalMapper->mcovInertial(i,j); + } + f << endl; + } + f.close(); + + // 6. Save initialization time + f.open("init_Time_" +to_string(mpLocalMapper->mInitSect)+ ".txt", ios_base::app); + f << fixed; + f << mpLocalMapper->mInitTime << endl; + f.close(); +} + + +int System::GetTrackingState() +{ + unique_lock lock(mMutexState); + return mTrackingState; +} + +vector System::GetTrackedMapPoints() +{ + unique_lock lock(mMutexState); + return mTrackedMapPoints; +} + +vector System::GetTrackedKeyPointsUn() +{ + unique_lock lock(mMutexState); + return mTrackedKeyPointsUn; +} + +double System::GetTimeFromIMUInit() +{ + double aux = mpLocalMapper->GetCurrKFTime()-mpLocalMapper->mFirstTs; + if ((aux>0.) && mpAtlas->isImuInitialized()) + return mpLocalMapper->GetCurrKFTime()-mpLocalMapper->mFirstTs; + else + return 0.f; +} + +bool System::isLost() +{ + if (!mpAtlas->isImuInitialized()) + return false; + else + { + if ((mpTracker->mState==Tracking::LOST)) //||(mpTracker->mState==Tracking::RECENTLY_LOST)) + return true; + else + return false; + } +} + + +bool System::isFinished() +{ + return (GetTimeFromIMUInit()>0.1); +} + +void System::ChangeDataset() +{ + if(mpAtlas->GetCurrentMap()->KeyFramesInMap() < 12) + { + mpTracker->ResetActiveMap(); + } + else + { + mpTracker->CreateMapInAtlas(); + } + + mpTracker->NewDataset(); +} + +/*void System::SaveAtlas(int type){ + cout << endl << "Enter the name of the file if you want to save the current Atlas session. To exit press ENTER: "; + string saveFileName; + getline(cin,saveFileName); + if(!saveFileName.empty()) + { + //clock_t start = clock(); + + // Save the current session + mpAtlas->PreSave(); + mpKeyFrameDatabase->PreSave(); + + string pathSaveFileName = "./"; + pathSaveFileName = pathSaveFileName.append(saveFileName); + pathSaveFileName = pathSaveFileName.append(".osa"); + + string strVocabularyChecksum = CalculateCheckSum(mStrVocabularyFilePath,TEXT_FILE); + std::size_t found = mStrVocabularyFilePath.find_last_of("/\\"); + string strVocabularyName = mStrVocabularyFilePath.substr(found+1); + + if(type == TEXT_FILE) // File text + { + cout << "Starting to write the save text file " << endl; + std::remove(pathSaveFileName.c_str()); + std::ofstream ofs(pathSaveFileName, std::ios::binary); + boost::archive::text_oarchive oa(ofs); + + oa << strVocabularyName; + oa << strVocabularyChecksum; + oa << mpAtlas; + oa << mpKeyFrameDatabase; + cout << "End to write the save text file" << endl; + } + else if(type == BINARY_FILE) // File binary + { + cout << "Starting to write the save binary file" << endl; + std::remove(pathSaveFileName.c_str()); + std::ofstream ofs(pathSaveFileName, std::ios::binary); + boost::archive::binary_oarchive oa(ofs); + oa << strVocabularyName; + oa << strVocabularyChecksum; + oa << mpAtlas; + oa << mpKeyFrameDatabase; + cout << "End to write save binary file" << endl; + } + + //clock_t timeElapsed = clock() - start; + //unsigned msElapsed = timeElapsed / (CLOCKS_PER_SEC / 1000); + //cout << "Binary file saved in " << msElapsed << " ms" << endl; + } +} + +bool System::LoadAtlas(string filename, int type) +{ + string strFileVoc, strVocChecksum; + bool isRead = false; + + if(type == TEXT_FILE) // File text + { + cout << "Starting to read the save text file " << endl; + std::ifstream ifs(filename, std::ios::binary); + if(!ifs.good()) + { + cout << "Load file not found" << endl; + return false; + } + boost::archive::text_iarchive ia(ifs); + ia >> strFileVoc; + ia >> strVocChecksum; + ia >> mpAtlas; + //ia >> mpKeyFrameDatabase; + cout << "End to load the save text file " << endl; + isRead = true; + } + else if(type == BINARY_FILE) // File binary + { + cout << "Starting to read the save binary file" << endl; + std::ifstream ifs(filename, std::ios::binary); + if(!ifs.good()) + { + cout << "Load file not found" << endl; + return false; + } + boost::archive::binary_iarchive ia(ifs); + ia >> strFileVoc; + ia >> strVocChecksum; + ia >> mpAtlas; + //ia >> mpKeyFrameDatabase; + cout << "End to load the save binary file" << endl; + isRead = true; + } + + if(isRead) + { + //Check if the vocabulary is the same + string strInputVocabularyChecksum = CalculateCheckSum(mStrVocabularyFilePath,TEXT_FILE); + + if(strInputVocabularyChecksum.compare(strVocChecksum) != 0) + { + cout << "The vocabulary load isn't the same which the load session was created " << endl; + cout << "-Vocabulary name: " << strFileVoc << endl; + return false; // Both are differents + } + + return true; + } + return false; +} + +string System::CalculateCheckSum(string filename, int type) +{ + string checksum = ""; + + unsigned char c[MD5_DIGEST_LENGTH]; + + std::ios_base::openmode flags = std::ios::in; + if(type == BINARY_FILE) // Binary file + flags = std::ios::in | std::ios::binary; + + ifstream f(filename.c_str(), flags); + if ( !f.is_open() ) + { + cout << "[E] Unable to open the in file " << filename << " for Md5 hash." << endl; + return checksum; + } + + MD5_CTX md5Context; + char buffer[1024]; + + MD5_Init (&md5Context); + while ( int count = f.readsome(buffer, sizeof(buffer))) + { + MD5_Update(&md5Context, buffer, count); + } + + f.close(); + + MD5_Final(c, &md5Context ); + + for(int i = 0; i < MD5_DIGEST_LENGTH; i++) + { + char aux[10]; + sprintf(aux,"%02x", c[i]); + checksum = checksum + aux; + } + + return checksum; +}*/ + +} //namespace ORB_SLAM + + diff --git a/third_party/ORB_SLAM3/src/Tracking.cc b/third_party/ORB_SLAM3/src/Tracking.cc new file mode 100644 index 0000000..ff8b3a7 --- /dev/null +++ b/third_party/ORB_SLAM3/src/Tracking.cc @@ -0,0 +1,3901 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + + +#include "Tracking.h" + +#include +#include + +#include"ORBmatcher.h" +#include"FrameDrawer.h" +#include"Converter.h" +#include"Initializer.h" +#include"G2oTypes.h" +#include"Optimizer.h" +#include"PnPsolver.h" + +#include + +#include +#include +#include +#include +#include + + +using namespace std; + +namespace ORB_SLAM3 +{ + + +Tracking::Tracking(System *pSys, ORBVocabulary* pVoc, FrameDrawer *pFrameDrawer, MapDrawer *pMapDrawer, Atlas *pAtlas, KeyFrameDatabase* pKFDB, const string &strSettingPath, const int sensor, const string &_nameSeq): + mState(NO_IMAGES_YET), mSensor(sensor), mTrackedFr(0), mbStep(false), + mbOnlyTracking(false), mbMapUpdated(false), mbVO(false), mpORBVocabulary(pVoc), mpKeyFrameDB(pKFDB), + mpInitializer(static_cast(NULL)), mpSystem(pSys), mpViewer(NULL), + mpFrameDrawer(pFrameDrawer), mpMapDrawer(pMapDrawer), mpAtlas(pAtlas), mnLastRelocFrameId(0), time_recently_lost(5.0), + mnInitialFrameId(0), mbCreatedMap(false), mnFirstFrameId(0), mpCamera2(nullptr) +{ + // Load camera parameters from settings file + cv::FileStorage fSettings(strSettingPath, cv::FileStorage::READ); + + bool b_parse_cam = ParseCamParamFile(fSettings); + if(!b_parse_cam) + { + std::cout << "*Error with the camera parameters in the config file*" << std::endl; + } + + // Load ORB parameters + bool b_parse_orb = ParseORBParamFile(fSettings); + if(!b_parse_orb) + { + std::cout << "*Error with the ORB parameters in the config file*" << std::endl; + } + + initID = 0; lastID = 0; + + // Load IMU parameters + bool b_parse_imu = true; + if(sensor==System::IMU_MONOCULAR || sensor==System::IMU_STEREO) + { + b_parse_imu = ParseIMUParamFile(fSettings); + if(!b_parse_imu) + { + std::cout << "*Error with the IMU parameters in the config file*" << std::endl; + } + + mnFramesToResetIMU = mMaxFrames; + } + + mbInitWith3KFs = false; + + + //Rectification parameters + /*mbNeedRectify = false; + if((mSensor == System::STEREO || mSensor == System::IMU_STEREO) && sCameraName == "PinHole") + { + cv::Mat K_l, K_r, P_l, P_r, R_l, R_r, D_l, D_r; + fSettings["LEFT.K"] >> K_l; + fSettings["RIGHT.K"] >> K_r; + + fSettings["LEFT.P"] >> P_l; + fSettings["RIGHT.P"] >> P_r; + + fSettings["LEFT.R"] >> R_l; + fSettings["RIGHT.R"] >> R_r; + + fSettings["LEFT.D"] >> D_l; + fSettings["RIGHT.D"] >> D_r; + + int rows_l = fSettings["LEFT.height"]; + int cols_l = fSettings["LEFT.width"]; + int rows_r = fSettings["RIGHT.height"]; + int cols_r = fSettings["RIGHT.width"]; + + if(K_l.empty() || K_r.empty() || P_l.empty() || P_r.empty() || R_l.empty() || R_r.empty() || D_l.empty() || D_r.empty() + || rows_l==0 || cols_l==0 || rows_r==0 || cols_r==0) + { + mbNeedRectify = false; + } + else + { + mbNeedRectify = true; + // M1r y M2r son los outputs (igual para l) + // M1r y M2r son las matrices relativas al mapeo correspondiente a la rectificación de mapa en el eje X e Y respectivamente + //cv::initUndistortRectifyMap(K_l,D_l,R_l,P_l.rowRange(0,3).colRange(0,3),cv::Size(cols_l,rows_l),CV_32F,M1l,M2l); + //cv::initUndistortRectifyMap(K_r,D_r,R_r,P_r.rowRange(0,3).colRange(0,3),cv::Size(cols_r,rows_r),CV_32F,M1r,M2r); + } + + + } + else + { + int cols = 752; + int rows = 480; + cv::Mat R_l = cv::Mat::eye(3, 3, CV_32F); + }*/ + + mnNumDataset = 0; + + if(!b_parse_cam || !b_parse_orb || !b_parse_imu) + { + std::cerr << "**ERROR in the config file, the format is not correct**" << std::endl; + try + { + throw -1; + } + catch(exception &e) + { + + } + } + + //f_track_stats.open("tracking_stats"+ _nameSeq + ".txt"); + /*f_track_stats.open("tracking_stats.txt"); + f_track_stats << "# timestamp, Num KF local, Num MP local, time" << endl; + f_track_stats << fixed ;*/ + +#ifdef SAVE_TIMES + f_track_times.open("tracking_times.txt"); + f_track_times << "# ORB_Ext(ms), Stereo matching(ms), Preintegrate_IMU(ms), Pose pred(ms), LocalMap_track(ms), NewKF_dec(ms)" << endl; + f_track_times << fixed ; +#endif +} + +Tracking::~Tracking() +{ + //f_track_stats.close(); +#ifdef SAVE_TIMES + f_track_times.close(); +#endif +} + +bool Tracking::ParseCamParamFile(cv::FileStorage &fSettings) +{ + mDistCoef = cv::Mat::zeros(4,1,CV_32F); + cout << endl << "Camera Parameters: " << endl; + bool b_miss_params = false; + + string sCameraName = fSettings["Camera.type"]; + if(sCameraName == "PinHole") + { + float fx, fy, cx, cy; + + // Camera calibration parameters + cv::FileNode node = fSettings["Camera.fx"]; + if(!node.empty() && node.isReal()) + { + fx = node.real(); + } + else + { + std::cerr << "*Camera.fx parameter doesn't exist or is not a real number*" << std::endl; + b_miss_params = true; + } + + node = fSettings["Camera.fy"]; + if(!node.empty() && node.isReal()) + { + fy = node.real(); + } + else + { + std::cerr << "*Camera.fy parameter doesn't exist or is not a real number*" << std::endl; + b_miss_params = true; + } + + node = fSettings["Camera.cx"]; + if(!node.empty() && node.isReal()) + { + cx = node.real(); + } + else + { + std::cerr << "*Camera.cx parameter doesn't exist or is not a real number*" << std::endl; + b_miss_params = true; + } + + node = fSettings["Camera.cy"]; + if(!node.empty() && node.isReal()) + { + cy = node.real(); + } + else + { + std::cerr << "*Camera.cy parameter doesn't exist or is not a real number*" << std::endl; + b_miss_params = true; + } + + // Distortion parameters + node = fSettings["Camera.k1"]; + if(!node.empty() && node.isReal()) + { + mDistCoef.at(0) = node.real(); + } + else + { + std::cerr << "*Camera.k1 parameter doesn't exist or is not a real number*" << std::endl; + b_miss_params = true; + } + + node = fSettings["Camera.k2"]; + if(!node.empty() && node.isReal()) + { + mDistCoef.at(1) = node.real(); + } + else + { + std::cerr << "*Camera.k2 parameter doesn't exist or is not a real number*" << std::endl; + b_miss_params = true; + } + + node = fSettings["Camera.p1"]; + if(!node.empty() && node.isReal()) + { + mDistCoef.at(2) = node.real(); + } + else + { + std::cerr << "*Camera.p1 parameter doesn't exist or is not a real number*" << std::endl; + b_miss_params = true; + } + + node = fSettings["Camera.p2"]; + if(!node.empty() && node.isReal()) + { + mDistCoef.at(3) = node.real(); + } + else + { + std::cerr << "*Camera.p2 parameter doesn't exist or is not a real number*" << std::endl; + b_miss_params = true; + } + + node = fSettings["Camera.k3"]; + if(!node.empty() && node.isReal()) + { + mDistCoef.resize(5); + mDistCoef.at(4) = node.real(); + } + + if(b_miss_params) + { + return false; + } + + vector vCamCalib{fx,fy,cx,cy}; + + mpCamera = new Pinhole(vCamCalib); + + mpAtlas->AddCamera(mpCamera); + + + std::cout << "- Camera: Pinhole" << std::endl; + std::cout << "- fx: " << fx << std::endl; + std::cout << "- fy: " << fy << std::endl; + std::cout << "- cx: " << cx << std::endl; + std::cout << "- cy: " << cy << std::endl; + std::cout << "- k1: " << mDistCoef.at(0) << std::endl; + std::cout << "- k2: " << mDistCoef.at(1) << std::endl; + + + std::cout << "- p1: " << mDistCoef.at(2) << std::endl; + std::cout << "- p2: " << mDistCoef.at(3) << std::endl; + + if(mDistCoef.rows==5) + std::cout << "- k3: " << mDistCoef.at(4) << std::endl; + + mK = cv::Mat::eye(3,3,CV_32F); + mK.at(0,0) = fx; + mK.at(1,1) = fy; + mK.at(0,2) = cx; + mK.at(1,2) = cy; + + } + else if(sCameraName == "KannalaBrandt8") + { + float fx, fy, cx, cy; + float k1, k2, k3, k4; + + // Camera calibration parameters + cv::FileNode node = fSettings["Camera.fx"]; + if(!node.empty() && node.isReal()) + { + fx = node.real(); + } + else + { + std::cerr << "*Camera.fx parameter doesn't exist or is not a real number*" << std::endl; + b_miss_params = true; + } + node = fSettings["Camera.fy"]; + if(!node.empty() && node.isReal()) + { + fy = node.real(); + } + else + { + std::cerr << "*Camera.fy parameter doesn't exist or is not a real number*" << std::endl; + b_miss_params = true; + } + + node = fSettings["Camera.cx"]; + if(!node.empty() && node.isReal()) + { + cx = node.real(); + } + else + { + std::cerr << "*Camera.cx parameter doesn't exist or is not a real number*" << std::endl; + b_miss_params = true; + } + + node = fSettings["Camera.cy"]; + if(!node.empty() && node.isReal()) + { + cy = node.real(); + } + else + { + std::cerr << "*Camera.cy parameter doesn't exist or is not a real number*" << std::endl; + b_miss_params = true; + } + + // Distortion parameters + node = fSettings["Camera.k1"]; + if(!node.empty() && node.isReal()) + { + k1 = node.real(); + } + else + { + std::cerr << "*Camera.k1 parameter doesn't exist or is not a real number*" << std::endl; + b_miss_params = true; + } + node = fSettings["Camera.k2"]; + if(!node.empty() && node.isReal()) + { + k2 = node.real(); + } + else + { + std::cerr << "*Camera.k2 parameter doesn't exist or is not a real number*" << std::endl; + b_miss_params = true; + } + + node = fSettings["Camera.k3"]; + if(!node.empty() && node.isReal()) + { + k3 = node.real(); + } + else + { + std::cerr << "*Camera.k3 parameter doesn't exist or is not a real number*" << std::endl; + b_miss_params = true; + } + + node = fSettings["Camera.k4"]; + if(!node.empty() && node.isReal()) + { + k4 = node.real(); + } + else + { + std::cerr << "*Camera.k4 parameter doesn't exist or is not a real number*" << std::endl; + b_miss_params = true; + } + + if(!b_miss_params) + { + vector vCamCalib{fx,fy,cx,cy,k1,k2,k3,k4}; + mpCamera = new KannalaBrandt8(vCamCalib); + + std::cout << "- Camera: Fisheye" << std::endl; + std::cout << "- fx: " << fx << std::endl; + std::cout << "- fy: " << fy << std::endl; + std::cout << "- cx: " << cx << std::endl; + std::cout << "- cy: " << cy << std::endl; + std::cout << "- k1: " << k1 << std::endl; + std::cout << "- k2: " << k2 << std::endl; + std::cout << "- k3: " << k3 << std::endl; + std::cout << "- k4: " << k4 << std::endl; + + mK = cv::Mat::eye(3,3,CV_32F); + mK.at(0,0) = fx; + mK.at(1,1) = fy; + mK.at(0,2) = cx; + mK.at(1,2) = cy; + } + + if(mSensor==System::STEREO || mSensor==System::IMU_STEREO){ + // Right camera + // Camera calibration parameters + cv::FileNode node = fSettings["Camera2.fx"]; + if(!node.empty() && node.isReal()) + { + fx = node.real(); + } + else + { + std::cerr << "*Camera2.fx parameter doesn't exist or is not a real number*" << std::endl; + b_miss_params = true; + } + node = fSettings["Camera2.fy"]; + if(!node.empty() && node.isReal()) + { + fy = node.real(); + } + else + { + std::cerr << "*Camera2.fy parameter doesn't exist or is not a real number*" << std::endl; + b_miss_params = true; + } + + node = fSettings["Camera2.cx"]; + if(!node.empty() && node.isReal()) + { + cx = node.real(); + } + else + { + std::cerr << "*Camera2.cx parameter doesn't exist or is not a real number*" << std::endl; + b_miss_params = true; + } + + node = fSettings["Camera2.cy"]; + if(!node.empty() && node.isReal()) + { + cy = node.real(); + } + else + { + std::cerr << "*Camera2.cy parameter doesn't exist or is not a real number*" << std::endl; + b_miss_params = true; + } + + // Distortion parameters + node = fSettings["Camera2.k1"]; + if(!node.empty() && node.isReal()) + { + k1 = node.real(); + } + else + { + std::cerr << "*Camera2.k1 parameter doesn't exist or is not a real number*" << std::endl; + b_miss_params = true; + } + node = fSettings["Camera2.k2"]; + if(!node.empty() && node.isReal()) + { + k2 = node.real(); + } + else + { + std::cerr << "*Camera2.k2 parameter doesn't exist or is not a real number*" << std::endl; + b_miss_params = true; + } + + node = fSettings["Camera2.k3"]; + if(!node.empty() && node.isReal()) + { + k3 = node.real(); + } + else + { + std::cerr << "*Camera2.k3 parameter doesn't exist or is not a real number*" << std::endl; + b_miss_params = true; + } + + node = fSettings["Camera2.k4"]; + if(!node.empty() && node.isReal()) + { + k4 = node.real(); + } + else + { + std::cerr << "*Camera2.k4 parameter doesn't exist or is not a real number*" << std::endl; + b_miss_params = true; + } + + + int leftLappingBegin = -1; + int leftLappingEnd = -1; + + int rightLappingBegin = -1; + int rightLappingEnd = -1; + + node = fSettings["Camera.lappingBegin"]; + if(!node.empty() && node.isInt()) + { + leftLappingBegin = node.operator int(); + } + else + { + std::cout << "WARNING: Camera.lappingBegin not correctly defined" << std::endl; + } + node = fSettings["Camera.lappingEnd"]; + if(!node.empty() && node.isInt()) + { + leftLappingEnd = node.operator int(); + } + else + { + std::cout << "WARNING: Camera.lappingEnd not correctly defined" << std::endl; + } + node = fSettings["Camera2.lappingBegin"]; + if(!node.empty() && node.isInt()) + { + rightLappingBegin = node.operator int(); + } + else + { + std::cout << "WARNING: Camera2.lappingBegin not correctly defined" << std::endl; + } + node = fSettings["Camera2.lappingEnd"]; + if(!node.empty() && node.isInt()) + { + rightLappingEnd = node.operator int(); + } + else + { + std::cout << "WARNING: Camera2.lappingEnd not correctly defined" << std::endl; + } + + node = fSettings["Tlr"]; + if(!node.empty()) + { + mTlr = node.mat(); + if(mTlr.rows != 3 || mTlr.cols != 4) + { + std::cerr << "*Tlr matrix have to be a 3x4 transformation matrix*" << std::endl; + b_miss_params = true; + } + } + else + { + std::cerr << "*Tlr matrix doesn't exist*" << std::endl; + b_miss_params = true; + } + + if(!b_miss_params) + { + static_cast(mpCamera)->mvLappingArea[0] = leftLappingBegin; + static_cast(mpCamera)->mvLappingArea[1] = leftLappingEnd; + + mpFrameDrawer->both = true; + + vector vCamCalib2{fx,fy,cx,cy,k1,k2,k3,k4}; + mpCamera2 = new KannalaBrandt8(vCamCalib2); + + static_cast(mpCamera2)->mvLappingArea[0] = rightLappingBegin; + static_cast(mpCamera2)->mvLappingArea[1] = rightLappingEnd; + + std::cout << "- Camera1 Lapping: " << leftLappingBegin << ", " << leftLappingEnd << std::endl; + + std::cout << std::endl << "Camera2 Parameters:" << std::endl; + std::cout << "- Camera: Fisheye" << std::endl; + std::cout << "- fx: " << fx << std::endl; + std::cout << "- fy: " << fy << std::endl; + std::cout << "- cx: " << cx << std::endl; + std::cout << "- cy: " << cy << std::endl; + std::cout << "- k1: " << k1 << std::endl; + std::cout << "- k2: " << k2 << std::endl; + std::cout << "- k3: " << k3 << std::endl; + std::cout << "- k4: " << k4 << std::endl; + + std::cout << "- mTlr: \n" << mTlr << std::endl; + + std::cout << "- Camera2 Lapping: " << rightLappingBegin << ", " << rightLappingEnd << std::endl; + } + } + + if(b_miss_params) + { + return false; + } + + mpAtlas->AddCamera(mpCamera); + mpAtlas->AddCamera(mpCamera2); + } + else + { + std::cerr << "*Not Supported Camera Sensor*" << std::endl; + std::cerr << "Check an example configuration file with the desired sensor" << std::endl; + } + + if(mSensor==System::STEREO || mSensor==System::IMU_STEREO) + { + cv::FileNode node = fSettings["Camera.bf"]; + if(!node.empty() && node.isReal()) + { + mbf = node.real(); + } + else + { + std::cerr << "*Camera.bf parameter doesn't exist or is not a real number*" << std::endl; + b_miss_params = true; + } + + } + + float fps = fSettings["Camera.fps"]; + if(fps==0) + fps=30; + + // Max/Min Frames to insert keyframes and to check relocalisation + mMinFrames = 0; + mMaxFrames = fps; + + cout << "- fps: " << fps << endl; + + + int nRGB = fSettings["Camera.RGB"]; + mbRGB = nRGB; + + if(mbRGB) + cout << "- color order: RGB (ignored if grayscale)" << endl; + else + cout << "- color order: BGR (ignored if grayscale)" << endl; + + if(mSensor==System::STEREO || mSensor==System::RGBD || mSensor==System::IMU_STEREO) + { + float fx = mpCamera->getParameter(0); + cv::FileNode node = fSettings["ThDepth"]; + if(!node.empty() && node.isReal()) + { + mThDepth = node.real(); + mThDepth = mbf*mThDepth/fx; + cout << endl << "Depth Threshold (Close/Far Points): " << mThDepth << endl; + } + else + { + std::cerr << "*ThDepth parameter doesn't exist or is not a real number*" << std::endl; + b_miss_params = true; + } + + + } + + if(mSensor==System::RGBD) + { + cv::FileNode node = fSettings["DepthMapFactor"]; + if(!node.empty() && node.isReal()) + { + mDepthMapFactor = node.real(); + if(fabs(mDepthMapFactor)<1e-5) + mDepthMapFactor=1; + else + mDepthMapFactor = 1.0f/mDepthMapFactor; + } + else + { + std::cerr << "*DepthMapFactor parameter doesn't exist or is not a real number*" << std::endl; + b_miss_params = true; + } + + } + + if(b_miss_params) + { + return false; + } + + return true; +} + +bool Tracking::ParseORBParamFile(cv::FileStorage &fSettings) +{ + bool b_miss_params = false; + int nFeatures, nLevels, fIniThFAST, fMinThFAST; + float fScaleFactor; + + cv::FileNode node = fSettings["ORBextractor.nFeatures"]; + if(!node.empty() && node.isInt()) + { + nFeatures = node.operator int(); + } + else + { + std::cerr << "*ORBextractor.nFeatures parameter doesn't exist or is not an integer*" << std::endl; + b_miss_params = true; + } + + node = fSettings["ORBextractor.scaleFactor"]; + if(!node.empty() && node.isReal()) + { + fScaleFactor = node.real(); + } + else + { + std::cerr << "*ORBextractor.scaleFactor parameter doesn't exist or is not a real number*" << std::endl; + b_miss_params = true; + } + + node = fSettings["ORBextractor.nLevels"]; + if(!node.empty() && node.isInt()) + { + nLevels = node.operator int(); + } + else + { + std::cerr << "*ORBextractor.nLevels parameter doesn't exist or is not an integer*" << std::endl; + b_miss_params = true; + } + + node = fSettings["ORBextractor.iniThFAST"]; + if(!node.empty() && node.isInt()) + { + fIniThFAST = node.operator int(); + } + else + { + std::cerr << "*ORBextractor.iniThFAST parameter doesn't exist or is not an integer*" << std::endl; + b_miss_params = true; + } + + node = fSettings["ORBextractor.minThFAST"]; + if(!node.empty() && node.isInt()) + { + fMinThFAST = node.operator int(); + } + else + { + std::cerr << "*ORBextractor.minThFAST parameter doesn't exist or is not an integer*" << std::endl; + b_miss_params = true; + } + + if(b_miss_params) + { + return false; + } + + mpORBextractorLeft = new ORBextractor(nFeatures,fScaleFactor,nLevels,fIniThFAST,fMinThFAST); + + if(mSensor==System::STEREO || mSensor==System::IMU_STEREO) + mpORBextractorRight = new ORBextractor(nFeatures,fScaleFactor,nLevels,fIniThFAST,fMinThFAST); + + if(mSensor==System::MONOCULAR || mSensor==System::IMU_MONOCULAR) + mpIniORBextractor = new ORBextractor(5*nFeatures,fScaleFactor,nLevels,fIniThFAST,fMinThFAST); + + cout << endl << "ORB Extractor Parameters: " << endl; + cout << "- Number of Features: " << nFeatures << endl; + cout << "- Scale Levels: " << nLevels << endl; + cout << "- Scale Factor: " << fScaleFactor << endl; + cout << "- Initial Fast Threshold: " << fIniThFAST << endl; + cout << "- Minimum Fast Threshold: " << fMinThFAST << endl; + + return true; +} + +bool Tracking::ParseIMUParamFile(cv::FileStorage &fSettings) +{ + bool b_miss_params = false; + + cv::Mat Tbc; + cv::FileNode node = fSettings["Tbc"]; + if(!node.empty()) + { + Tbc = node.mat(); + if(Tbc.rows != 4 || Tbc.cols != 4) + { + std::cerr << "*Tbc matrix have to be a 4x4 transformation matrix*" << std::endl; + b_miss_params = true; + } + } + else + { + std::cerr << "*Tbc matrix doesn't exist*" << std::endl; + b_miss_params = true; + } + + cout << endl; + + cout << "Left camera to Imu Transform (Tbc): " << endl << Tbc << endl; + + float freq, Ng, Na, Ngw, Naw; + + node = fSettings["IMU.Frequency"]; + if(!node.empty() && node.isInt()) + { + freq = node.operator int(); + } + else + { + std::cerr << "*IMU.Frequency parameter doesn't exist or is not an integer*" << std::endl; + b_miss_params = true; + } + + node = fSettings["IMU.NoiseGyro"]; + if(!node.empty() && node.isReal()) + { + Ng = node.real(); + } + else + { + std::cerr << "*IMU.NoiseGyro parameter doesn't exist or is not a real number*" << std::endl; + b_miss_params = true; + } + + node = fSettings["IMU.NoiseAcc"]; + if(!node.empty() && node.isReal()) + { + Na = node.real(); + } + else + { + std::cerr << "*IMU.NoiseAcc parameter doesn't exist or is not a real number*" << std::endl; + b_miss_params = true; + } + + node = fSettings["IMU.GyroWalk"]; + if(!node.empty() && node.isReal()) + { + Ngw = node.real(); + } + else + { + std::cerr << "*IMU.GyroWalk parameter doesn't exist or is not a real number*" << std::endl; + b_miss_params = true; + } + + node = fSettings["IMU.AccWalk"]; + if(!node.empty() && node.isReal()) + { + Naw = node.real(); + } + else + { + std::cerr << "*IMU.AccWalk parameter doesn't exist or is not a real number*" << std::endl; + b_miss_params = true; + } + + if(b_miss_params) + { + return false; + } + + const float sf = sqrt(freq); + cout << endl; + cout << "IMU frequency: " << freq << " Hz" << endl; + cout << "IMU gyro noise: " << Ng << " rad/s/sqrt(Hz)" << endl; + cout << "IMU gyro walk: " << Ngw << " rad/s^2/sqrt(Hz)" << endl; + cout << "IMU accelerometer noise: " << Na << " m/s^2/sqrt(Hz)" << endl; + cout << "IMU accelerometer walk: " << Naw << " m/s^3/sqrt(Hz)" << endl; + + mpImuCalib = new IMU::Calib(Tbc,Ng*sf,Na*sf,Ngw/sf,Naw/sf); + + mpImuPreintegratedFromLastKF = new IMU::Preintegrated(IMU::Bias(),*mpImuCalib); + + + return true; +} + +void Tracking::SetLocalMapper(LocalMapping *pLocalMapper) +{ + mpLocalMapper=pLocalMapper; +} + +void Tracking::SetLoopClosing(LoopClosing *pLoopClosing) +{ + mpLoopClosing=pLoopClosing; +} + +void Tracking::SetViewer(Viewer *pViewer) +{ + mpViewer=pViewer; +} + +void Tracking::SetStepByStep(bool bSet) +{ + bStepByStep = bSet; +} + + + +cv::Mat Tracking::GrabImageStereo(const cv::Mat &imRectLeft, const cv::Mat &imRectRight, const double ×tamp, string filename) +{ + mImGray = imRectLeft; + cv::Mat imGrayRight = imRectRight; + mImRight = imRectRight; + + if(mImGray.channels()==3) + { + if(mbRGB) + { + cvtColor(mImGray,mImGray,CV_RGB2GRAY); + cvtColor(imGrayRight,imGrayRight,CV_RGB2GRAY); + } + else + { + cvtColor(mImGray,mImGray,CV_BGR2GRAY); + cvtColor(imGrayRight,imGrayRight,CV_BGR2GRAY); + } + } + else if(mImGray.channels()==4) + { + if(mbRGB) + { + cvtColor(mImGray,mImGray,CV_RGBA2GRAY); + cvtColor(imGrayRight,imGrayRight,CV_RGBA2GRAY); + } + else + { + cvtColor(mImGray,mImGray,CV_BGRA2GRAY); + cvtColor(imGrayRight,imGrayRight,CV_BGRA2GRAY); + } + } + + if (mSensor == System::STEREO && !mpCamera2) + mCurrentFrame = Frame(mImGray,imGrayRight,timestamp,mpORBextractorLeft,mpORBextractorRight,mpORBVocabulary,mK,mDistCoef,mbf,mThDepth,mpCamera); + else if(mSensor == System::STEREO && mpCamera2) + mCurrentFrame = Frame(mImGray,imGrayRight,timestamp,mpORBextractorLeft,mpORBextractorRight,mpORBVocabulary,mK,mDistCoef,mbf,mThDepth,mpCamera,mpCamera2,mTlr); + else if(mSensor == System::IMU_STEREO && !mpCamera2) + mCurrentFrame = Frame(mImGray,imGrayRight,timestamp,mpORBextractorLeft,mpORBextractorRight,mpORBVocabulary,mK,mDistCoef,mbf,mThDepth,mpCamera,&mLastFrame,*mpImuCalib); + else if(mSensor == System::IMU_STEREO && mpCamera2) + mCurrentFrame = Frame(mImGray,imGrayRight,timestamp,mpORBextractorLeft,mpORBextractorRight,mpORBVocabulary,mK,mDistCoef,mbf,mThDepth,mpCamera,mpCamera2,mTlr,&mLastFrame,*mpImuCalib); + + std::chrono::steady_clock::time_point t0 = std::chrono::steady_clock::now(); + mCurrentFrame.mNameFile = filename; + mCurrentFrame.mnDataset = mnNumDataset; + + Track(); + + std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now(); + + double t_track = std::chrono::duration_cast >(t1 - t0).count(); + + /*cout << "trracking time: " << t_track << endl; + f_track_stats << setprecision(0) << mCurrentFrame.mTimeStamp*1e9 << ","; + f_track_stats << mvpLocalKeyFrames.size() << ","; + f_track_stats << mvpLocalMapPoints.size() << ","; + f_track_stats << setprecision(6) << t_track << endl;*/ + +#ifdef SAVE_TIMES + f_track_times << mCurrentFrame.mTimeORB_Ext << ","; + f_track_times << mCurrentFrame.mTimeStereoMatch << ","; + f_track_times << mTime_PreIntIMU << ","; + f_track_times << mTime_PosePred << ","; + f_track_times << mTime_LocalMapTrack << ","; + f_track_times << mTime_NewKF_Dec << ","; + f_track_times << t_track << endl; +#endif + + return mCurrentFrame.mTcw.clone(); +} + + +cv::Mat Tracking::GrabImageRGBD(const cv::Mat &imRGB,const cv::Mat &imD, const double ×tamp, string filename) +{ + mImGray = imRGB; + cv::Mat imDepth = imD; + + if(mImGray.channels()==3) + { + if(mbRGB) + cvtColor(mImGray,mImGray,CV_RGB2GRAY); + else + cvtColor(mImGray,mImGray,CV_BGR2GRAY); + } + else if(mImGray.channels()==4) + { + if(mbRGB) + cvtColor(mImGray,mImGray,CV_RGBA2GRAY); + else + cvtColor(mImGray,mImGray,CV_BGRA2GRAY); + } + + if((fabs(mDepthMapFactor-1.0f)>1e-5) || imDepth.type()!=CV_32F) + imDepth.convertTo(imDepth,CV_32F,mDepthMapFactor); + + std::chrono::steady_clock::time_point t0 = std::chrono::steady_clock::now(); + mCurrentFrame = Frame(mImGray,imDepth,timestamp,mpORBextractorLeft,mpORBVocabulary,mK,mDistCoef,mbf,mThDepth,mpCamera); + + mCurrentFrame.mNameFile = filename; + mCurrentFrame.mnDataset = mnNumDataset; + + + Track(); + + std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now(); + + double t_track = std::chrono::duration_cast >(t1 - t0).count(); + + /*f_track_stats << setprecision(0) << mCurrentFrame.mTimeStamp*1e9 << ","; + f_track_stats << mvpLocalKeyFrames.size() << ","; + f_track_stats << mvpLocalMapPoints.size() << ","; + f_track_stats << setprecision(6) << t_track << endl;*/ + +#ifdef SAVE_TIMES + f_track_times << mCurrentFrame.mTimeORB_Ext << ","; + f_track_times << mCurrentFrame.mTimeStereoMatch << ","; + f_track_times << mTime_PreIntIMU << ","; + f_track_times << mTime_PosePred << ","; + f_track_times << mTime_LocalMapTrack << ","; + f_track_times << mTime_NewKF_Dec << ","; + f_track_times << t_track << endl; +#endif + + return mCurrentFrame.mTcw.clone(); +} + + +cv::Mat Tracking::GrabImageMonocular(const cv::Mat &im, const double ×tamp, string filename) +{ + mImGray = im; + + if(mImGray.channels()==3) + { + if(mbRGB) + cvtColor(mImGray,mImGray,CV_RGB2GRAY); + else + cvtColor(mImGray,mImGray,CV_BGR2GRAY); + } + else if(mImGray.channels()==4) + { + if(mbRGB) + cvtColor(mImGray,mImGray,CV_RGBA2GRAY); + else + cvtColor(mImGray,mImGray,CV_BGRA2GRAY); + } + + if (mSensor == System::MONOCULAR) + { + if(mState==NOT_INITIALIZED || mState==NO_IMAGES_YET ||(lastID - initID) < mMaxFrames) + mCurrentFrame = Frame(mImGray,timestamp,mpIniORBextractor,mpORBVocabulary,mpCamera,mDistCoef,mbf,mThDepth); + else + mCurrentFrame = Frame(mImGray,timestamp,mpORBextractorLeft,mpORBVocabulary,mpCamera,mDistCoef,mbf,mThDepth); + } + else if(mSensor == System::IMU_MONOCULAR) + { + if(mState==NOT_INITIALIZED || mState==NO_IMAGES_YET) + { + mCurrentFrame = Frame(mImGray,timestamp,mpIniORBextractor,mpORBVocabulary,mpCamera,mDistCoef,mbf,mThDepth,&mLastFrame,*mpImuCalib); + } + else + mCurrentFrame = Frame(mImGray,timestamp,mpORBextractorLeft,mpORBVocabulary,mpCamera,mDistCoef,mbf,mThDepth,&mLastFrame,*mpImuCalib); + } + + if (mState==NO_IMAGES_YET) + t0=timestamp; + + std::chrono::steady_clock::time_point t0 = std::chrono::steady_clock::now(); + + mCurrentFrame.mNameFile = filename; + mCurrentFrame.mnDataset = mnNumDataset; + + lastID = mCurrentFrame.mnId; + Track(); + + std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now(); + + double t_track = std::chrono::duration_cast >(t1 - t0).count(); + + /*f_track_stats << setprecision(0) << mCurrentFrame.mTimeStamp*1e9 << ","; + f_track_stats << mvpLocalKeyFrames.size() << ","; + f_track_stats << mvpLocalMapPoints.size() << ","; + f_track_stats << setprecision(6) << t_track << endl;*/ + +#ifdef SAVE_TIMES + f_track_times << mCurrentFrame.mTimeORB_Ext << ","; + f_track_times << mCurrentFrame.mTimeStereoMatch << ","; + f_track_times << mTime_PreIntIMU << ","; + f_track_times << mTime_PosePred << ","; + f_track_times << mTime_LocalMapTrack << ","; + f_track_times << mTime_NewKF_Dec << ","; + f_track_times << t_track << endl; +#endif + + return mCurrentFrame.mTcw.clone(); +} + + +void Tracking::GrabImuData(const IMU::Point &imuMeasurement) +{ + unique_lock lock(mMutexImuQueue); + mlQueueImuData.push_back(imuMeasurement); +} + +void Tracking::PreintegrateIMU() +{ + //cout << "start preintegration" << endl; + + if(!mCurrentFrame.mpPrevFrame) + { + Verbose::PrintMess("non prev frame ", Verbose::VERBOSITY_NORMAL); + mCurrentFrame.setIntegrated(); + return; + } + + // cout << "start loop. Total meas:" << mlQueueImuData.size() << endl; + + mvImuFromLastFrame.clear(); + mvImuFromLastFrame.reserve(mlQueueImuData.size()); + if(mlQueueImuData.size() == 0) + { + Verbose::PrintMess("Not IMU data in mlQueueImuData!!", Verbose::VERBOSITY_NORMAL); + mCurrentFrame.setIntegrated(); + return; + } + + while(true) + { + bool bSleep = false; + { + unique_lock lock(mMutexImuQueue); + if(!mlQueueImuData.empty()) + { + IMU::Point* m = &mlQueueImuData.front(); + cout.precision(17); + if(m->tmTimeStamp-0.001l) + { + mlQueueImuData.pop_front(); + } + else if(m->tmTimeStamp; + acc = (mvImuFromLastFrame[i].a+mvImuFromLastFrame[i+1].a- + (mvImuFromLastFrame[i+1].a-mvImuFromLastFrame[i].a)*(tini/tab))*0.5f; + angVel = (mvImuFromLastFrame[i].w+mvImuFromLastFrame[i+1].w- + (mvImuFromLastFrame[i+1].w-mvImuFromLastFrame[i].w)*(tini/tab))*0.5f; + tstep = mvImuFromLastFrame[i+1].t-mCurrentFrame.mpPrevFrame->mTimeStamp; + } + else if(i<(n-1)) + { + acc = (mvImuFromLastFrame[i].a+mvImuFromLastFrame[i+1].a)*0.5f; + angVel = (mvImuFromLastFrame[i].w+mvImuFromLastFrame[i+1].w)*0.5f; + tstep = mvImuFromLastFrame[i+1].t-mvImuFromLastFrame[i].t; + } + else if((i>0) && (i==(n-1))) + { + float tab = mvImuFromLastFrame[i+1].t-mvImuFromLastFrame[i].t; + float tend = mvImuFromLastFrame[i+1].t-mCurrentFrame.mTimeStamp; + acc = (mvImuFromLastFrame[i].a+mvImuFromLastFrame[i+1].a- + (mvImuFromLastFrame[i+1].a-mvImuFromLastFrame[i].a)*(tend/tab))*0.5f; + angVel = (mvImuFromLastFrame[i].w+mvImuFromLastFrame[i+1].w- + (mvImuFromLastFrame[i+1].w-mvImuFromLastFrame[i].w)*(tend/tab))*0.5f; + tstep = mCurrentFrame.mTimeStamp-mvImuFromLastFrame[i].t; + } + else if((i==0) && (i==(n-1))) + { + acc = mvImuFromLastFrame[i].a; + angVel = mvImuFromLastFrame[i].w; + tstep = mCurrentFrame.mTimeStamp-mCurrentFrame.mpPrevFrame->mTimeStamp; + } + + if (!mpImuPreintegratedFromLastKF) + cout << "mpImuPreintegratedFromLastKF does not exist" << endl; + mpImuPreintegratedFromLastKF->IntegrateNewMeasurement(acc,angVel,tstep); + pImuPreintegratedFromLastFrame->IntegrateNewMeasurement(acc,angVel,tstep); + } + + mCurrentFrame.mpImuPreintegratedFrame = pImuPreintegratedFromLastFrame; + mCurrentFrame.mpImuPreintegrated = mpImuPreintegratedFromLastKF; + mCurrentFrame.mpLastKeyFrame = mpLastKeyFrame; + + mCurrentFrame.setIntegrated(); + + Verbose::PrintMess("Preintegration is finished!! ", Verbose::VERBOSITY_DEBUG); +} + + +bool Tracking::PredictStateIMU() +{ + if(!mCurrentFrame.mpPrevFrame) + { + Verbose::PrintMess("No last frame", Verbose::VERBOSITY_NORMAL); + return false; + } + + if(mbMapUpdated && mpLastKeyFrame) + { + const cv::Mat twb1 = mpLastKeyFrame->GetImuPosition(); + const cv::Mat Rwb1 = mpLastKeyFrame->GetImuRotation(); + const cv::Mat Vwb1 = mpLastKeyFrame->GetVelocity(); + + const cv::Mat Gz = (cv::Mat_(3,1) << 0,0,-IMU::GRAVITY_VALUE); + const float t12 = mpImuPreintegratedFromLastKF->dT; + + cv::Mat Rwb2 = IMU::NormalizeRotation(Rwb1*mpImuPreintegratedFromLastKF->GetDeltaRotation(mpLastKeyFrame->GetImuBias())); + cv::Mat twb2 = twb1 + Vwb1*t12 + 0.5f*t12*t12*Gz+ Rwb1*mpImuPreintegratedFromLastKF->GetDeltaPosition(mpLastKeyFrame->GetImuBias()); + cv::Mat Vwb2 = Vwb1 + t12*Gz + Rwb1*mpImuPreintegratedFromLastKF->GetDeltaVelocity(mpLastKeyFrame->GetImuBias()); + mCurrentFrame.SetImuPoseVelocity(Rwb2,twb2,Vwb2); + mCurrentFrame.mPredRwb = Rwb2.clone(); + mCurrentFrame.mPredtwb = twb2.clone(); + mCurrentFrame.mPredVwb = Vwb2.clone(); + mCurrentFrame.mImuBias = mpLastKeyFrame->GetImuBias(); + mCurrentFrame.mPredBias = mCurrentFrame.mImuBias; + return true; + } + else if(!mbMapUpdated) + { + const cv::Mat twb1 = mLastFrame.GetImuPosition(); + const cv::Mat Rwb1 = mLastFrame.GetImuRotation(); + const cv::Mat Vwb1 = mLastFrame.mVw; + const cv::Mat Gz = (cv::Mat_(3,1) << 0,0,-IMU::GRAVITY_VALUE); + const float t12 = mCurrentFrame.mpImuPreintegratedFrame->dT; + + cv::Mat Rwb2 = IMU::NormalizeRotation(Rwb1*mCurrentFrame.mpImuPreintegratedFrame->GetDeltaRotation(mLastFrame.mImuBias)); + cv::Mat twb2 = twb1 + Vwb1*t12 + 0.5f*t12*t12*Gz+ Rwb1*mCurrentFrame.mpImuPreintegratedFrame->GetDeltaPosition(mLastFrame.mImuBias); + cv::Mat Vwb2 = Vwb1 + t12*Gz + Rwb1*mCurrentFrame.mpImuPreintegratedFrame->GetDeltaVelocity(mLastFrame.mImuBias); + + mCurrentFrame.SetImuPoseVelocity(Rwb2,twb2,Vwb2); + mCurrentFrame.mPredRwb = Rwb2.clone(); + mCurrentFrame.mPredtwb = twb2.clone(); + mCurrentFrame.mPredVwb = Vwb2.clone(); + mCurrentFrame.mImuBias =mLastFrame.mImuBias; + mCurrentFrame.mPredBias = mCurrentFrame.mImuBias; + return true; + } + else + cout << "not IMU prediction!!" << endl; + + return false; +} + + +void Tracking::ComputeGyroBias(const vector &vpFs, float &bwx, float &bwy, float &bwz) +{ + const int N = vpFs.size(); + vector vbx; + vbx.reserve(N); + vector vby; + vby.reserve(N); + vector vbz; + vbz.reserve(N); + + cv::Mat H = cv::Mat::zeros(3,3,CV_32F); + cv::Mat grad = cv::Mat::zeros(3,1,CV_32F); + for(int i=1;iGetImuRotation().t()*pF2->GetImuRotation(); + cv::Mat JRg = pF2->mpImuPreintegratedFrame->JRg; + cv::Mat E = pF2->mpImuPreintegratedFrame->GetUpdatedDeltaRotation().t()*VisionR; + cv::Mat e = IMU::LogSO3(E); + assert(fabs(pF2->mTimeStamp-pF1->mTimeStamp-pF2->mpImuPreintegratedFrame->dT)<0.01); + + cv::Mat J = -IMU::InverseRightJacobianSO3(e)*E.t()*JRg; + grad += J.t()*e; + H += J.t()*J; + } + + cv::Mat bg = -H.inv(cv::DECOMP_SVD)*grad; + bwx = bg.at(0); + bwy = bg.at(1); + bwz = bg.at(2); + + for(int i=1;imImuBias.bwx = bwx; + pF->mImuBias.bwy = bwy; + pF->mImuBias.bwz = bwz; + pF->mpImuPreintegratedFrame->SetNewBias(pF->mImuBias); + pF->mpImuPreintegratedFrame->Reintegrate(); + } +} + +void Tracking::ComputeVelocitiesAccBias(const vector &vpFs, float &bax, float &bay, float &baz) +{ + const int N = vpFs.size(); + const int nVar = 3*N +3; // 3 velocities/frame + acc bias + const int nEqs = 6*(N-1); + + cv::Mat J(nEqs,nVar,CV_32F,cv::Scalar(0)); + cv::Mat e(nEqs,1,CV_32F,cv::Scalar(0)); + cv::Mat g = (cv::Mat_(3,1)<<0,0,-IMU::GRAVITY_VALUE); + + for(int i=0;iGetImuPosition(); + cv::Mat twb2 = pF2->GetImuPosition(); + cv::Mat Rwb1 = pF1->GetImuRotation(); + cv::Mat dP12 = pF2->mpImuPreintegratedFrame->GetUpdatedDeltaPosition(); + cv::Mat dV12 = pF2->mpImuPreintegratedFrame->GetUpdatedDeltaVelocity(); + cv::Mat JP12 = pF2->mpImuPreintegratedFrame->JPa; + cv::Mat JV12 = pF2->mpImuPreintegratedFrame->JVa; + float t12 = pF2->mpImuPreintegratedFrame->dT; + // Position p2=p1+v1*t+0.5*g*t^2+R1*dP12 + J.rowRange(6*i,6*i+3).colRange(3*i,3*i+3) += cv::Mat::eye(3,3,CV_32F)*t12; + J.rowRange(6*i,6*i+3).colRange(3*N,3*N+3) += Rwb1*JP12; + e.rowRange(6*i,6*i+3) = twb2-twb1-0.5f*g*t12*t12-Rwb1*dP12; + // Velocity v2=v1+g*t+R1*dV12 + J.rowRange(6*i+3,6*i+6).colRange(3*i,3*i+3) += -cv::Mat::eye(3,3,CV_32F); + J.rowRange(6*i+3,6*i+6).colRange(3*(i+1),3*(i+1)+3) += cv::Mat::eye(3,3,CV_32F); + J.rowRange(6*i+3,6*i+6).colRange(3*N,3*N+3) -= Rwb1*JV12; + e.rowRange(6*i+3,6*i+6) = g*t12+Rwb1*dV12; + } + + cv::Mat H = J.t()*J; + cv::Mat B = J.t()*e; + cv::Mat x(nVar,1,CV_32F); + cv::solve(H,B,x); + + bax = x.at(3*N); + bay = x.at(3*N+1); + baz = x.at(3*N+2); + + for(int i=0;imVw); + if(i>0) + { + pF->mImuBias.bax = bax; + pF->mImuBias.bay = bay; + pF->mImuBias.baz = baz; + pF->mpImuPreintegratedFrame->SetNewBias(pF->mImuBias); + } + } +} + +void Tracking::ResetFrameIMU() +{ + // TODO To implement... +} + + +void Tracking::Track() +{ +#ifdef SAVE_TIMES + mTime_PreIntIMU = 0; + mTime_PosePred = 0; + mTime_LocalMapTrack = 0; + mTime_NewKF_Dec = 0; +#endif + + if (bStepByStep) + { + while(!mbStep) + usleep(500); + mbStep = false; + } + + if(mpLocalMapper->mbBadImu) + { + cout << "TRACK: Reset map because local mapper set the bad imu flag " << endl; + mpSystem->ResetActiveMap(); + return; + } + + Map* pCurrentMap = mpAtlas->GetCurrentMap(); + + if(mState!=NO_IMAGES_YET) + { + if(mLastFrame.mTimeStamp>mCurrentFrame.mTimeStamp) + { + cerr << "ERROR: Frame with a timestamp older than previous frame detected!" << endl; + unique_lock lock(mMutexImuQueue); + mlQueueImuData.clear(); + CreateMapInAtlas(); + return; + } + else if(mCurrentFrame.mTimeStamp>mLastFrame.mTimeStamp+1.0) + { + cout << "id last: " << mLastFrame.mnId << " id curr: " << mCurrentFrame.mnId << endl; + if(mpAtlas->isInertial()) + { + + if(mpAtlas->isImuInitialized()) + { + cout << "Timestamp jump detected. State set to LOST. Reseting IMU integration..." << endl; + if(!pCurrentMap->GetIniertialBA2()) + { + mpSystem->ResetActiveMap(); + } + else + { + CreateMapInAtlas(); + } + } + else + { + cout << "Timestamp jump detected, before IMU initialization. Reseting..." << endl; + mpSystem->ResetActiveMap(); + } + } + + return; + } + } + + + if ((mSensor == System::IMU_MONOCULAR || mSensor == System::IMU_STEREO) && mpLastKeyFrame) + mCurrentFrame.SetNewBias(mpLastKeyFrame->GetImuBias()); + + if(mState==NO_IMAGES_YET) + { + mState = NOT_INITIALIZED; + } + + mLastProcessedState=mState; + + if ((mSensor == System::IMU_MONOCULAR || mSensor == System::IMU_STEREO) && !mbCreatedMap) + { +#ifdef SAVE_TIMES + std::chrono::steady_clock::time_point t0 = std::chrono::steady_clock::now(); +#endif + PreintegrateIMU(); +#ifdef SAVE_TIMES + std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now(); + + mTime_PreIntIMU = std::chrono::duration_cast >(t1 - t0).count(); +#endif + + + } + mbCreatedMap = false; + + // Get Map Mutex -> Map cannot be changed + unique_lock lock(pCurrentMap->mMutexMapUpdate); + + mbMapUpdated = false; + + int nCurMapChangeIndex = pCurrentMap->GetMapChangeIndex(); + int nMapChangeIndex = pCurrentMap->GetLastMapChange(); + if(nCurMapChangeIndex>nMapChangeIndex) + { + // cout << "Map update detected" << endl; + pCurrentMap->SetLastMapChange(nCurMapChangeIndex); + mbMapUpdated = true; + } + + + if(mState==NOT_INITIALIZED) + { + if(mSensor==System::STEREO || mSensor==System::RGBD || mSensor==System::IMU_STEREO) + StereoInitialization(); + else + { + MonocularInitialization(); + } + + mpFrameDrawer->Update(this); + + if(mState!=OK) // If rightly initialized, mState=OK + { + mLastFrame = Frame(mCurrentFrame); + return; + } + + if(mpAtlas->GetAllMaps().size() == 1) + { + mnFirstFrameId = mCurrentFrame.mnId; + } + } + else + { + // System is initialized. Track Frame. + bool bOK; + + // Initial camera pose estimation using motion model or relocalization (if tracking is lost) + if(!mbOnlyTracking) + { +#ifdef SAVE_TIMES + std::chrono::steady_clock::time_point timeStartPosePredict = std::chrono::steady_clock::now(); +#endif + + // State OK + // Local Mapping is activated. This is the normal behaviour, unless + // you explicitly activate the "only tracking" mode. + if(mState==OK) + { + + // Local Mapping might have changed some MapPoints tracked in last frame + CheckReplacedInLastFrame(); + + if((mVelocity.empty() && !pCurrentMap->isImuInitialized()) || mCurrentFrame.mnIdKeyFramesInMap()>10) + { + cout << "KF in map: " << pCurrentMap->KeyFramesInMap() << endl; + mState = RECENTLY_LOST; + mTimeStampLost = mCurrentFrame.mTimeStamp; + //mCurrentFrame.SetPose(mLastFrame.mTcw); + } + else + { + mState = LOST; + } + } + } + else + { + + if (mState == RECENTLY_LOST) + { + Verbose::PrintMess("Lost for a short time", Verbose::VERBOSITY_NORMAL); + + bOK = true; + if((mSensor == System::IMU_MONOCULAR || mSensor == System::IMU_STEREO)) + { + if(pCurrentMap->isImuInitialized()) + PredictStateIMU(); + else + bOK = false; + + if (mCurrentFrame.mTimeStamp-mTimeStampLost>time_recently_lost) + { + mState = LOST; + Verbose::PrintMess("Track Lost...", Verbose::VERBOSITY_NORMAL); + bOK=false; + } + } + else + { + // TODO fix relocalization + bOK = Relocalization(); + if(!bOK) + { + mState = LOST; + Verbose::PrintMess("Track Lost...", Verbose::VERBOSITY_NORMAL); + bOK=false; + } + } + } + else if (mState == LOST) + { + + Verbose::PrintMess("A new map is started...", Verbose::VERBOSITY_NORMAL); + + if (pCurrentMap->KeyFramesInMap()<10) + { + mpSystem->ResetActiveMap(); + cout << "Reseting current map..." << endl; + }else + CreateMapInAtlas(); + + if(mpLastKeyFrame) + mpLastKeyFrame = static_cast(NULL); + + Verbose::PrintMess("done", Verbose::VERBOSITY_NORMAL); + + return; + } + } + + +#ifdef SAVE_TIMES + std::chrono::steady_clock::time_point timeEndPosePredict = std::chrono::steady_clock::now(); + + mTime_PosePred = std::chrono::duration_cast >(timeEndPosePredict - timeStartPosePredict).count(); +#endif + + } + else + { + // Localization Mode: Local Mapping is deactivated (TODO Not available in inertial mode) + if(mState==LOST) + { + if(mSensor == System::IMU_MONOCULAR || mSensor == System::IMU_STEREO) + Verbose::PrintMess("IMU. State LOST", Verbose::VERBOSITY_NORMAL); + bOK = Relocalization(); + } + else + { + if(!mbVO) + { + // In last frame we tracked enough MapPoints in the map + if(!mVelocity.empty()) + { + bOK = TrackWithMotionModel(); + } + else + { + bOK = TrackReferenceKeyFrame(); + } + } + else + { + // In last frame we tracked mainly "visual odometry" points. + + // We compute two camera poses, one from motion model and one doing relocalization. + // If relocalization is sucessfull we choose that solution, otherwise we retain + // the "visual odometry" solution. + + bool bOKMM = false; + bool bOKReloc = false; + vector vpMPsMM; + vector vbOutMM; + cv::Mat TcwMM; + if(!mVelocity.empty()) + { + bOKMM = TrackWithMotionModel(); + vpMPsMM = mCurrentFrame.mvpMapPoints; + vbOutMM = mCurrentFrame.mvbOutlier; + TcwMM = mCurrentFrame.mTcw.clone(); + } + bOKReloc = Relocalization(); + + if(bOKMM && !bOKReloc) + { + mCurrentFrame.SetPose(TcwMM); + mCurrentFrame.mvpMapPoints = vpMPsMM; + mCurrentFrame.mvbOutlier = vbOutMM; + + if(mbVO) + { + for(int i =0; iIncreaseFound(); + } + } + } + } + else if(bOKReloc) + { + mbVO = false; + } + + bOK = bOKReloc || bOKMM; + } + } + } + + if(!mCurrentFrame.mpReferenceKF) + mCurrentFrame.mpReferenceKF = mpReferenceKF; + + // If we have an initial estimation of the camera pose and matching. Track the local map. + if(!mbOnlyTracking) + { + if(bOK) + { +#ifdef SAVE_TIMES + std::chrono::steady_clock::time_point time_StartTrackLocalMap = std::chrono::steady_clock::now(); +#endif + bOK = TrackLocalMap(); +#ifdef SAVE_TIMES + std::chrono::steady_clock::time_point time_EndTrackLocalMap = std::chrono::steady_clock::now(); + + mTime_LocalMapTrack = std::chrono::duration_cast >(time_EndTrackLocalMap - time_StartTrackLocalMap).count(); +#endif + + + } + if(!bOK) + cout << "Fail to track local map!" << endl; + } + else + { + // mbVO true means that there are few matches to MapPoints in the map. We cannot retrieve + // a local map and therefore we do not perform TrackLocalMap(). Once the system relocalizes + // the camera we will use the local map again. + if(bOK && !mbVO) + bOK = TrackLocalMap(); + } + + if(bOK) + mState = OK; + else if (mState == OK) + { + if (mSensor == System::IMU_MONOCULAR || mSensor == System::IMU_STEREO) + { + Verbose::PrintMess("Track lost for less than one second...", Verbose::VERBOSITY_NORMAL); + if(!pCurrentMap->isImuInitialized() || !pCurrentMap->GetIniertialBA2()) + { + cout << "IMU is not or recently initialized. Reseting active map..." << endl; + mpSystem->ResetActiveMap(); + } + + mState=RECENTLY_LOST; + } + else + mState=LOST; // visual to lost + + if(mCurrentFrame.mnId>mnLastRelocFrameId+mMaxFrames) + { + mTimeStampLost = mCurrentFrame.mTimeStamp; + } + } + + // Save frame if recent relocalization, since they are used for IMU reset (as we are making copy, it shluld be once mCurrFrame is completely modified) + if((mCurrentFrame.mnId<(mnLastRelocFrameId+mnFramesToResetIMU)) && (mCurrentFrame.mnId > mnFramesToResetIMU) && ((mSensor == System::IMU_MONOCULAR) || (mSensor == System::IMU_STEREO)) && pCurrentMap->isImuInitialized()) + { + // TODO check this situation + Verbose::PrintMess("Saving pointer to frame. imu needs reset...", Verbose::VERBOSITY_NORMAL); + Frame* pF = new Frame(mCurrentFrame); + pF->mpPrevFrame = new Frame(mLastFrame); + + // Load preintegration + pF->mpImuPreintegratedFrame = new IMU::Preintegrated(mCurrentFrame.mpImuPreintegratedFrame); + } + + if(pCurrentMap->isImuInitialized()) + { + if(bOK) + { + if(mCurrentFrame.mnId==(mnLastRelocFrameId+mnFramesToResetIMU)) + { + cout << "RESETING FRAME!!!" << endl; + ResetFrameIMU(); + } + else if(mCurrentFrame.mnId>(mnLastRelocFrameId+30)) + mLastBias = mCurrentFrame.mImuBias; + } + } + + // Update drawer + mpFrameDrawer->Update(this); + if(!mCurrentFrame.mTcw.empty()) + mpMapDrawer->SetCurrentCameraPose(mCurrentFrame.mTcw); + + if(bOK || mState==RECENTLY_LOST) + { + // Update motion model + if(!mLastFrame.mTcw.empty() && !mCurrentFrame.mTcw.empty()) + { + cv::Mat LastTwc = cv::Mat::eye(4,4,CV_32F); + mLastFrame.GetRotationInverse().copyTo(LastTwc.rowRange(0,3).colRange(0,3)); + mLastFrame.GetCameraCenter().copyTo(LastTwc.rowRange(0,3).col(3)); + mVelocity = mCurrentFrame.mTcw*LastTwc; + } + else + mVelocity = cv::Mat(); + + if(mSensor == System::IMU_MONOCULAR || mSensor == System::IMU_STEREO) + mpMapDrawer->SetCurrentCameraPose(mCurrentFrame.mTcw); + + // Clean VO matches + for(int i=0; iObservations()<1) + { + mCurrentFrame.mvbOutlier[i] = false; + mCurrentFrame.mvpMapPoints[i]=static_cast(NULL); + } + } + + // Delete temporal MapPoints + for(list::iterator lit = mlpTemporalPoints.begin(), lend = mlpTemporalPoints.end(); lit!=lend; lit++) + { + MapPoint* pMP = *lit; + delete pMP; + } + mlpTemporalPoints.clear(); + +#ifdef SAVE_TIMES + std::chrono::steady_clock::time_point timeStartNewKF = std::chrono::steady_clock::now(); +#endif + bool bNeedKF = NeedNewKeyFrame(); +#ifdef SAVE_TIMES + std::chrono::steady_clock::time_point timeEndNewKF = std::chrono::steady_clock::now(); + + mTime_NewKF_Dec = std::chrono::duration_cast >(timeEndNewKF - timeStartNewKF).count(); +#endif + + + + // Check if we need to insert a new keyframe + if(bNeedKF && (bOK|| (mState==RECENTLY_LOST && (mSensor == System::IMU_MONOCULAR || mSensor == System::IMU_STEREO)))) + CreateNewKeyFrame(); + + // We allow points with high innovation (considererd outliers by the Huber Function) + // pass to the new keyframe, so that bundle adjustment will finally decide + // if they are outliers or not. We don't want next frame to estimate its position + // with those points so we discard them in the frame. Only has effect if lastframe is tracked + for(int i=0; i(NULL); + } + } + + // Reset if the camera get lost soon after initialization + if(mState==LOST) + { + if(pCurrentMap->KeyFramesInMap()<=5) + { + mpSystem->ResetActiveMap(); + return; + } + if ((mSensor == System::IMU_MONOCULAR) || (mSensor == System::IMU_STEREO)) + if (!pCurrentMap->isImuInitialized()) + { + Verbose::PrintMess("Track lost before IMU initialisation, reseting...", Verbose::VERBOSITY_QUIET); + mpSystem->ResetActiveMap(); + return; + } + + CreateMapInAtlas(); + } + + if(!mCurrentFrame.mpReferenceKF) + mCurrentFrame.mpReferenceKF = mpReferenceKF; + + mLastFrame = Frame(mCurrentFrame); + } + + + + + if(mState==OK || mState==RECENTLY_LOST) + { + // Store frame pose information to retrieve the complete camera trajectory afterwards. + if(!mCurrentFrame.mTcw.empty()) + { + cv::Mat Tcr = mCurrentFrame.mTcw*mCurrentFrame.mpReferenceKF->GetPoseInverse(); + mlRelativeFramePoses.push_back(Tcr); + mlpReferences.push_back(mCurrentFrame.mpReferenceKF); + mlFrameTimes.push_back(mCurrentFrame.mTimeStamp); + mlbLost.push_back(mState==LOST); + } + else + { + // This can happen if tracking is lost + mlRelativeFramePoses.push_back(mlRelativeFramePoses.back()); + mlpReferences.push_back(mlpReferences.back()); + mlFrameTimes.push_back(mlFrameTimes.back()); + mlbLost.push_back(mState==LOST); + } + + } +} + + +void Tracking::StereoInitialization() +{ + if(mCurrentFrame.N>500) + { + if (mSensor == System::IMU_STEREO) + { + if (!mCurrentFrame.mpImuPreintegrated || !mLastFrame.mpImuPreintegrated) + { + cout << "not IMU meas" << endl; + return; + } + + if (cv::norm(mCurrentFrame.mpImuPreintegratedFrame->avgA-mLastFrame.mpImuPreintegratedFrame->avgA)<0.5) + { + cout << "not enough acceleration" << endl; + return; + } + + if(mpImuPreintegratedFromLastKF) + delete mpImuPreintegratedFromLastKF; + + mpImuPreintegratedFromLastKF = new IMU::Preintegrated(IMU::Bias(),*mpImuCalib); + mCurrentFrame.mpImuPreintegrated = mpImuPreintegratedFromLastKF; + } + + // Set Frame pose to the origin (In case of inertial SLAM to imu) + if (mSensor == System::IMU_STEREO) + { + cv::Mat Rwb0 = mCurrentFrame.mImuCalib.Tcb.rowRange(0,3).colRange(0,3).clone(); + cv::Mat twb0 = mCurrentFrame.mImuCalib.Tcb.rowRange(0,3).col(3).clone(); + mCurrentFrame.SetImuPoseVelocity(Rwb0, twb0, cv::Mat::zeros(3,1,CV_32F)); + } + else + mCurrentFrame.SetPose(cv::Mat::eye(4,4,CV_32F)); + + // Create KeyFrame + KeyFrame* pKFini = new KeyFrame(mCurrentFrame,mpAtlas->GetCurrentMap(),mpKeyFrameDB); + + // Insert KeyFrame in the map + mpAtlas->AddKeyFrame(pKFini); + + // Create MapPoints and asscoiate to KeyFrame + if(!mpCamera2){ + for(int i=0; i0) + { + cv::Mat x3D = mCurrentFrame.UnprojectStereo(i); + MapPoint* pNewMP = new MapPoint(x3D,pKFini,mpAtlas->GetCurrentMap()); + pNewMP->AddObservation(pKFini,i); + pKFini->AddMapPoint(pNewMP,i); + pNewMP->ComputeDistinctiveDescriptors(); + pNewMP->UpdateNormalAndDepth(); + mpAtlas->AddMapPoint(pNewMP); + + mCurrentFrame.mvpMapPoints[i]=pNewMP; + } + } + } else{ + for(int i = 0; i < mCurrentFrame.Nleft; i++){ + int rightIndex = mCurrentFrame.mvLeftToRightMatch[i]; + if(rightIndex != -1){ + cv::Mat x3D = mCurrentFrame.mvStereo3Dpoints[i]; + + MapPoint* pNewMP = new MapPoint(x3D,pKFini,mpAtlas->GetCurrentMap()); + + pNewMP->AddObservation(pKFini,i); + pNewMP->AddObservation(pKFini,rightIndex + mCurrentFrame.Nleft); + + pKFini->AddMapPoint(pNewMP,i); + pKFini->AddMapPoint(pNewMP,rightIndex + mCurrentFrame.Nleft); + + pNewMP->ComputeDistinctiveDescriptors(); + pNewMP->UpdateNormalAndDepth(); + mpAtlas->AddMapPoint(pNewMP); + + mCurrentFrame.mvpMapPoints[i]=pNewMP; + mCurrentFrame.mvpMapPoints[rightIndex + mCurrentFrame.Nleft]=pNewMP; + } + } + } + + Verbose::PrintMess("New Map created with " + to_string(mpAtlas->MapPointsInMap()) + " points", Verbose::VERBOSITY_QUIET); + + mpLocalMapper->InsertKeyFrame(pKFini); + + mLastFrame = Frame(mCurrentFrame); + mnLastKeyFrameId=mCurrentFrame.mnId; + mpLastKeyFrame = pKFini; + mnLastRelocFrameId = mCurrentFrame.mnId; + + mvpLocalKeyFrames.push_back(pKFini); + mvpLocalMapPoints=mpAtlas->GetAllMapPoints(); + mpReferenceKF = pKFini; + mCurrentFrame.mpReferenceKF = pKFini; + + mpAtlas->SetReferenceMapPoints(mvpLocalMapPoints); + + mpAtlas->GetCurrentMap()->mvpKeyFrameOrigins.push_back(pKFini); + + mpMapDrawer->SetCurrentCameraPose(mCurrentFrame.mTcw); + + mState=OK; + } +} + + +void Tracking::MonocularInitialization() +{ + + if(!mpInitializer) + { + // Set Reference Frame + if(mCurrentFrame.mvKeys.size()>100) + { + + mInitialFrame = Frame(mCurrentFrame); + mLastFrame = Frame(mCurrentFrame); + mvbPrevMatched.resize(mCurrentFrame.mvKeysUn.size()); + for(size_t i=0; i1.0))) + { + delete mpInitializer; + mpInitializer = static_cast(NULL); + fill(mvIniMatches.begin(),mvIniMatches.end(),-1); + + return; + } + + // Find correspondences + ORBmatcher matcher(0.9,true); + int nmatches = matcher.SearchForInitialization(mInitialFrame,mCurrentFrame,mvbPrevMatched,mvIniMatches,100); + + // Check if there are enough correspondences + if(nmatches<100) + { + delete mpInitializer; + mpInitializer = static_cast(NULL); + fill(mvIniMatches.begin(),mvIniMatches.end(),-1); + return; + } + + cv::Mat Rcw; // Current Camera Rotation + cv::Mat tcw; // Current Camera Translation + vector vbTriangulated; // Triangulated Correspondences (mvIniMatches) + + if(mpCamera->ReconstructWithTwoViews(mInitialFrame.mvKeysUn,mCurrentFrame.mvKeysUn,mvIniMatches,Rcw,tcw,mvIniP3D,vbTriangulated)) + { + for(size_t i=0, iend=mvIniMatches.size(); i=0 && !vbTriangulated[i]) + { + mvIniMatches[i]=-1; + nmatches--; + } + } + + // Set Frame Poses + mInitialFrame.SetPose(cv::Mat::eye(4,4,CV_32F)); + cv::Mat Tcw = cv::Mat::eye(4,4,CV_32F); + Rcw.copyTo(Tcw.rowRange(0,3).colRange(0,3)); + tcw.copyTo(Tcw.rowRange(0,3).col(3)); + mCurrentFrame.SetPose(Tcw); + + CreateInitialMapMonocular(); + + // Just for video + // bStepByStep = true; + } + } +} + + + +void Tracking::CreateInitialMapMonocular() +{ + // Create KeyFrames + KeyFrame* pKFini = new KeyFrame(mInitialFrame,mpAtlas->GetCurrentMap(),mpKeyFrameDB); + KeyFrame* pKFcur = new KeyFrame(mCurrentFrame,mpAtlas->GetCurrentMap(),mpKeyFrameDB); + + if(mSensor == System::IMU_MONOCULAR) + pKFini->mpImuPreintegrated = (IMU::Preintegrated*)(NULL); + + + pKFini->ComputeBoW(); + pKFcur->ComputeBoW(); + + // Insert KFs in the map + mpAtlas->AddKeyFrame(pKFini); + mpAtlas->AddKeyFrame(pKFcur); + + for(size_t i=0; iGetCurrentMap()); + + pKFini->AddMapPoint(pMP,i); + pKFcur->AddMapPoint(pMP,mvIniMatches[i]); + + pMP->AddObservation(pKFini,i); + pMP->AddObservation(pKFcur,mvIniMatches[i]); + + pMP->ComputeDistinctiveDescriptors(); + pMP->UpdateNormalAndDepth(); + + //Fill Current Frame structure + mCurrentFrame.mvpMapPoints[mvIniMatches[i]] = pMP; + mCurrentFrame.mvbOutlier[mvIniMatches[i]] = false; + + //Add to Map + mpAtlas->AddMapPoint(pMP); + } + + + // Update Connections + pKFini->UpdateConnections(); + pKFcur->UpdateConnections(); + + std::set sMPs; + sMPs = pKFini->GetMapPoints(); + + // Bundle Adjustment + Verbose::PrintMess("New Map created with " + to_string(mpAtlas->MapPointsInMap()) + " points", Verbose::VERBOSITY_QUIET); + Optimizer::GlobalBundleAdjustemnt(mpAtlas->GetCurrentMap(),20); + + pKFcur->PrintPointDistribution(); + + float medianDepth = pKFini->ComputeSceneMedianDepth(2); + float invMedianDepth; + if(mSensor == System::IMU_MONOCULAR) + invMedianDepth = 4.0f/medianDepth; // 4.0f + else + invMedianDepth = 1.0f/medianDepth; + + if(medianDepth<0 || pKFcur->TrackedMapPoints(1)<50) // TODO Check, originally 100 tracks + { + Verbose::PrintMess("Wrong initialization, reseting...", Verbose::VERBOSITY_NORMAL); + mpSystem->ResetActiveMap(); + return; + } + + // Scale initial baseline + cv::Mat Tc2w = pKFcur->GetPose(); + Tc2w.col(3).rowRange(0,3) = Tc2w.col(3).rowRange(0,3)*invMedianDepth; + pKFcur->SetPose(Tc2w); + + // Scale points + vector vpAllMapPoints = pKFini->GetMapPointMatches(); + for(size_t iMP=0; iMPSetWorldPos(pMP->GetWorldPos()*invMedianDepth); + pMP->UpdateNormalAndDepth(); + } + } + + if (mSensor == System::IMU_MONOCULAR) + { + pKFcur->mPrevKF = pKFini; + pKFini->mNextKF = pKFcur; + pKFcur->mpImuPreintegrated = mpImuPreintegratedFromLastKF; + + mpImuPreintegratedFromLastKF = new IMU::Preintegrated(pKFcur->mpImuPreintegrated->GetUpdatedBias(),pKFcur->mImuCalib); + } + + + mpLocalMapper->InsertKeyFrame(pKFini); + mpLocalMapper->InsertKeyFrame(pKFcur); + mpLocalMapper->mFirstTs=pKFcur->mTimeStamp; + + mCurrentFrame.SetPose(pKFcur->GetPose()); + mnLastKeyFrameId=mCurrentFrame.mnId; + mpLastKeyFrame = pKFcur; + mnLastRelocFrameId = mInitialFrame.mnId; + + mvpLocalKeyFrames.push_back(pKFcur); + mvpLocalKeyFrames.push_back(pKFini); + mvpLocalMapPoints=mpAtlas->GetAllMapPoints(); + mpReferenceKF = pKFcur; + mCurrentFrame.mpReferenceKF = pKFcur; + + // Compute here initial velocity + vector vKFs = mpAtlas->GetAllKeyFrames(); + + cv::Mat deltaT = vKFs.back()->GetPose()*vKFs.front()->GetPoseInverse(); + mVelocity = cv::Mat(); + Eigen::Vector3d phi = LogSO3(Converter::toMatrix3d(deltaT.rowRange(0,3).colRange(0,3))); + + + double aux = (mCurrentFrame.mTimeStamp-mLastFrame.mTimeStamp)/(mCurrentFrame.mTimeStamp-mInitialFrame.mTimeStamp); + phi *= aux; + + mLastFrame = Frame(mCurrentFrame); + + mpAtlas->SetReferenceMapPoints(mvpLocalMapPoints); + + mpMapDrawer->SetCurrentCameraPose(pKFcur->GetPose()); + + mpAtlas->GetCurrentMap()->mvpKeyFrameOrigins.push_back(pKFini); + + mState=OK; + + initID = pKFcur->mnId; +} + + +void Tracking::CreateMapInAtlas() +{ + mnLastInitFrameId = mCurrentFrame.mnId; + mpAtlas->CreateNewMap(); + if (mSensor==System::IMU_STEREO || mSensor == System::IMU_MONOCULAR) + mpAtlas->SetInertialSensor(); + mbSetInit=false; + + mnInitialFrameId = mCurrentFrame.mnId+1; + mState = NO_IMAGES_YET; + + // Restart the variable with information about the last KF + mVelocity = cv::Mat(); + mnLastRelocFrameId = mnLastInitFrameId; // The last relocation KF_id is the current id, because it is the new starting point for new map + Verbose::PrintMess("First frame id in map: " + to_string(mnLastInitFrameId+1), Verbose::VERBOSITY_NORMAL); + mbVO = false; // Init value for know if there are enough MapPoints in the last KF + if(mSensor == System::MONOCULAR || mSensor == System::IMU_MONOCULAR) + { + if(mpInitializer) + delete mpInitializer; + mpInitializer = static_cast(NULL); + } + + if((mSensor == System::IMU_MONOCULAR || mSensor == System::IMU_STEREO ) && mpImuPreintegratedFromLastKF) + { + delete mpImuPreintegratedFromLastKF; + mpImuPreintegratedFromLastKF = new IMU::Preintegrated(IMU::Bias(),*mpImuCalib); + } + + if(mpLastKeyFrame) + mpLastKeyFrame = static_cast(NULL); + + if(mpReferenceKF) + mpReferenceKF = static_cast(NULL); + + mLastFrame = Frame(); + mCurrentFrame = Frame(); + mvIniMatches.clear(); + + mbCreatedMap = true; + +} + +void Tracking::CheckReplacedInLastFrame() +{ + for(int i =0; iGetReplaced(); + if(pRep) + { + mLastFrame.mvpMapPoints[i] = pRep; + } + } + } +} + + +bool Tracking::TrackReferenceKeyFrame() +{ + // Compute Bag of Words vector + mCurrentFrame.ComputeBoW(); + + // We perform first an ORB matching with the reference keyframe + // If enough matches are found we setup a PnP solver + ORBmatcher matcher(0.7,true); + vector vpMapPointMatches; + + int nmatches = matcher.SearchByBoW(mpReferenceKF,mCurrentFrame,vpMapPointMatches); + + if(nmatches<15) + { + cout << "TRACK_REF_KF: Less than 15 matches!!\n"; + return false; + } + + mCurrentFrame.mvpMapPoints = vpMapPointMatches; + mCurrentFrame.SetPose(mLastFrame.mTcw); + + //mCurrentFrame.PrintPointDistribution(); + + + // cout << " TrackReferenceKeyFrame mLastFrame.mTcw: " << mLastFrame.mTcw << endl; + Optimizer::PoseOptimization(&mCurrentFrame); + + // Discard outliers + int nmatchesMap = 0; + for(int i =0; i= mCurrentFrame.Nleft) break; + if(mCurrentFrame.mvpMapPoints[i]) + { + if(mCurrentFrame.mvbOutlier[i]) + { + MapPoint* pMP = mCurrentFrame.mvpMapPoints[i]; + + mCurrentFrame.mvpMapPoints[i]=static_cast(NULL); + mCurrentFrame.mvbOutlier[i]=false; + if(i < mCurrentFrame.Nleft){ + pMP->mbTrackInView = false; + } + else{ + pMP->mbTrackInViewR = false; + } + pMP->mbTrackInView = false; + pMP->mnLastFrameSeen = mCurrentFrame.mnId; + nmatches--; + } + else if(mCurrentFrame.mvpMapPoints[i]->Observations()>0) + nmatchesMap++; + } + } + + // TODO check these conditions + if (mSensor == System::IMU_MONOCULAR || mSensor == System::IMU_STEREO) + return true; + else + return nmatchesMap>=10; +} + +void Tracking::UpdateLastFrame() +{ + // Update pose according to reference keyframe + KeyFrame* pRef = mLastFrame.mpReferenceKF; + cv::Mat Tlr = mlRelativeFramePoses.back(); + mLastFrame.SetPose(Tlr*pRef->GetPose()); + + if(mnLastKeyFrameId==mLastFrame.mnId || mSensor==System::MONOCULAR || mSensor==System::IMU_MONOCULAR || !mbOnlyTracking) + return; + + // Create "visual odometry" MapPoints + // We sort points according to their measured depth by the stereo/RGB-D sensor + vector > vDepthIdx; + vDepthIdx.reserve(mLastFrame.N); + for(int i=0; i0) + { + vDepthIdx.push_back(make_pair(z,i)); + } + } + + if(vDepthIdx.empty()) + return; + + sort(vDepthIdx.begin(),vDepthIdx.end()); + + // We insert all close points (depthObservations()<1) + { + bCreateNew = true; + } + + if(bCreateNew) + { + cv::Mat x3D = mLastFrame.UnprojectStereo(i); + MapPoint* pNewMP = new MapPoint(x3D,mpAtlas->GetCurrentMap(),&mLastFrame,i); + + mLastFrame.mvpMapPoints[i]=pNewMP; + + mlpTemporalPoints.push_back(pNewMP); + nPoints++; + } + else + { + nPoints++; + } + + if(vDepthIdx[j].first>mThDepth && nPoints>100) + { + break; + } + } +} + +bool Tracking::TrackWithMotionModel() +{ + ORBmatcher matcher(0.9,true); + + // Update last frame pose according to its reference keyframe + // Create "visual odometry" points if in Localization Mode + UpdateLastFrame(); + + + + if (mpAtlas->isImuInitialized() && (mCurrentFrame.mnId>mnLastRelocFrameId+mnFramesToResetIMU)) + { + // Predict ste with IMU if it is initialized and it doesnt need reset + PredictStateIMU(); + return true; + } + else + { + mCurrentFrame.SetPose(mVelocity*mLastFrame.mTcw); + } + + + fill(mCurrentFrame.mvpMapPoints.begin(),mCurrentFrame.mvpMapPoints.end(),static_cast(NULL)); + + // Project points seen in previous frame + int th; + + if(mSensor==System::STEREO) + th=7; + else + th=15; + + int nmatches = matcher.SearchByProjection(mCurrentFrame,mLastFrame,th,mSensor==System::MONOCULAR || mSensor==System::IMU_MONOCULAR); + + // If few matches, uses a wider window search + if(nmatches<20) + { + Verbose::PrintMess("Not enough matches, wider window search!!", Verbose::VERBOSITY_NORMAL); + fill(mCurrentFrame.mvpMapPoints.begin(),mCurrentFrame.mvpMapPoints.end(),static_cast(NULL)); + + nmatches = matcher.SearchByProjection(mCurrentFrame,mLastFrame,2*th,mSensor==System::MONOCULAR || mSensor==System::IMU_MONOCULAR); + Verbose::PrintMess("Matches with wider search: " + to_string(nmatches), Verbose::VERBOSITY_NORMAL); + + } + + if(nmatches<20) + { + Verbose::PrintMess("Not enough matches!!", Verbose::VERBOSITY_NORMAL); + if (mSensor == System::IMU_MONOCULAR || mSensor == System::IMU_STEREO) + return true; + else + return false; + } + + // Optimize frame pose with all matches + Optimizer::PoseOptimization(&mCurrentFrame); + + // Discard outliers + int nmatchesMap = 0; + for(int i =0; i(NULL); + mCurrentFrame.mvbOutlier[i]=false; + if(i < mCurrentFrame.Nleft){ + pMP->mbTrackInView = false; + } + else{ + pMP->mbTrackInViewR = false; + } + pMP->mnLastFrameSeen = mCurrentFrame.mnId; + nmatches--; + } + else if(mCurrentFrame.mvpMapPoints[i]->Observations()>0) + nmatchesMap++; + } + } + + if(mbOnlyTracking) + { + mbVO = nmatchesMap<10; + return nmatches>20; + } + + if (mSensor == System::IMU_MONOCULAR || mSensor == System::IMU_STEREO) + return true; + else + return nmatchesMap>=10; +} + +bool Tracking::TrackLocalMap() +{ + + // We have an estimation of the camera pose and some map points tracked in the frame. + // We retrieve the local map and try to find matches to points in the local map. + mTrackedFr++; + + UpdateLocalMap(); + SearchLocalPoints(); + + // TOO check outliers before PO + int aux1 = 0, aux2=0; + for(int i=0; iisImuInitialized()) + Optimizer::PoseOptimization(&mCurrentFrame); + else + { + if(mCurrentFrame.mnId<=mnLastRelocFrameId+mnFramesToResetIMU) + { + Verbose::PrintMess("TLM: PoseOptimization ", Verbose::VERBOSITY_DEBUG); + Optimizer::PoseOptimization(&mCurrentFrame); + } + else + { + // if(!mbMapUpdated && mState == OK) // && (mnMatchesInliers>30)) + if(!mbMapUpdated) // && (mnMatchesInliers>30)) + { + Verbose::PrintMess("TLM: PoseInertialOptimizationLastFrame ", Verbose::VERBOSITY_DEBUG); + inliers = Optimizer::PoseInertialOptimizationLastFrame(&mCurrentFrame); // , !mpLastKeyFrame->GetMap()->GetIniertialBA1()); + } + else + { + Verbose::PrintMess("TLM: PoseInertialOptimizationLastKeyFrame ", Verbose::VERBOSITY_DEBUG); + inliers = Optimizer::PoseInertialOptimizationLastKeyFrame(&mCurrentFrame); // , !mpLastKeyFrame->GetMap()->GetIniertialBA1()); + } + } + } + + aux1 = 0, aux2 = 0; + for(int i=0; iIncreaseFound(); + if(!mbOnlyTracking) + { + if(mCurrentFrame.mvpMapPoints[i]->Observations()>0) + mnMatchesInliers++; + } + else + mnMatchesInliers++; + } + else if(mSensor==System::STEREO) + mCurrentFrame.mvpMapPoints[i] = static_cast(NULL); + } + } + + // Decide if the tracking was succesful + // More restrictive if there was a relocalization recently + mpLocalMapper->mnMatchesInliers=mnMatchesInliers; + if(mCurrentFrame.mnId10)&&(mState==RECENTLY_LOST)) + return true; + + + if (mSensor == System::IMU_MONOCULAR) + { + if(mnMatchesInliers<15) + { + return false; + } + else + return true; + } + else if (mSensor == System::IMU_STEREO) + { + if(mnMatchesInliers<15) + { + return false; + } + else + return true; + } + else + { + if(mnMatchesInliers<30) + return false; + else + return true; + } +} + +bool Tracking::NeedNewKeyFrame() +{ + if(((mSensor == System::IMU_MONOCULAR) || (mSensor == System::IMU_STEREO)) && !mpAtlas->GetCurrentMap()->isImuInitialized()) + { + if (mSensor == System::IMU_MONOCULAR && (mCurrentFrame.mTimeStamp-mpLastKeyFrame->mTimeStamp)>=0.25) + return true; + else if (mSensor == System::IMU_STEREO && (mCurrentFrame.mTimeStamp-mpLastKeyFrame->mTimeStamp)>=0.25) + return true; + else + return false; + } + + if(mbOnlyTracking) + return false; + + // If Local Mapping is freezed by a Loop Closure do not insert keyframes + if(mpLocalMapper->isStopped() || mpLocalMapper->stopRequested()) + { + return false; + } + + // Return false if IMU is initialazing + if (mpLocalMapper->IsInitializing()) + return false; + const int nKFs = mpAtlas->KeyFramesInMap(); + + // Do not insert keyframes if not enough frames have passed from last relocalisation + if(mCurrentFrame.mnIdmMaxFrames) + { + return false; + } + + // Tracked MapPoints in the reference keyframe + int nMinObs = 3; + if(nKFs<=2) + nMinObs=2; + int nRefMatches = mpReferenceKF->TrackedMapPoints(nMinObs); + + // Local Mapping accept keyframes? + bool bLocalMappingIdle = mpLocalMapper->AcceptKeyFrames(); + + // Check how many "close" points are being tracked and how many could be potentially created. + int nNonTrackedClose = 0; + int nTrackedClose= 0; + + if(mSensor!=System::MONOCULAR && mSensor!=System::IMU_MONOCULAR) + { + int N = (mCurrentFrame.Nleft == -1) ? mCurrentFrame.N : mCurrentFrame.Nleft; + for(int i =0; i0 && mCurrentFrame.mvDepth[i]70); + + // Thresholds + float thRefRatio = 0.75f; + if(nKFs<2) + thRefRatio = 0.4f; + + if(mSensor==System::MONOCULAR) + thRefRatio = 0.9f; + + if(mpCamera2) thRefRatio = 0.75f; + + if(mSensor==System::IMU_MONOCULAR) + { + if(mnMatchesInliers>350) // Points tracked from the local map + thRefRatio = 0.75f; + else + thRefRatio = 0.90f; + } + + // Condition 1a: More than "MaxFrames" have passed from last keyframe insertion + const bool c1a = mCurrentFrame.mnId>=mnLastKeyFrameId+mMaxFrames; + // Condition 1b: More than "MinFrames" have passed and Local Mapping is idle + const bool c1b = ((mCurrentFrame.mnId>=mnLastKeyFrameId+mMinFrames) && bLocalMappingIdle); + //Condition 1c: tracking is weak + const bool c1c = mSensor!=System::MONOCULAR && mSensor!=System::IMU_MONOCULAR && mSensor!=System::IMU_STEREO && (mnMatchesInliers15); + + // Temporal condition for Inertial cases + bool c3 = false; + if(mpLastKeyFrame) + { + if (mSensor==System::IMU_MONOCULAR) + { + if ((mCurrentFrame.mTimeStamp-mpLastKeyFrame->mTimeStamp)>=0.5) + c3 = true; + } + else if (mSensor==System::IMU_STEREO) + { + if ((mCurrentFrame.mTimeStamp-mpLastKeyFrame->mTimeStamp)>=0.5) + c3 = true; + } + } + + bool c4 = false; + if ((((mnMatchesInliers<75) && (mnMatchesInliers>15)) || mState==RECENTLY_LOST) && ((mSensor == System::IMU_MONOCULAR))) // MODIFICATION_2, originally ((((mnMatchesInliers<75) && (mnMatchesInliers>15)) || mState==RECENTLY_LOST) && ((mSensor == System::IMU_MONOCULAR))) + c4=true; + else + c4=false; + + if(((c1a||c1b||c1c) && c2)||c3 ||c4) + { + // If the mapping accepts keyframes, insert keyframe. + // Otherwise send a signal to interrupt BA + if(bLocalMappingIdle) + { + return true; + } + else + { + mpLocalMapper->InterruptBA(); + if(mSensor!=System::MONOCULAR && mSensor!=System::IMU_MONOCULAR) + { + if(mpLocalMapper->KeyframesInQueue()<3) + return true; + else + return false; + } + else + return false; + } + } + else + return false; +} + +void Tracking::CreateNewKeyFrame() +{ + if(mpLocalMapper->IsInitializing()) + return; + + if(!mpLocalMapper->SetNotStop(true)) + return; + + KeyFrame* pKF = new KeyFrame(mCurrentFrame,mpAtlas->GetCurrentMap(),mpKeyFrameDB); + + if(mpAtlas->isImuInitialized()) + pKF->bImu = true; + + pKF->SetNewBias(mCurrentFrame.mImuBias); + mpReferenceKF = pKF; + mCurrentFrame.mpReferenceKF = pKF; + + if(mpLastKeyFrame) + { + pKF->mPrevKF = mpLastKeyFrame; + mpLastKeyFrame->mNextKF = pKF; + } + else + Verbose::PrintMess("No last KF in KF creation!!", Verbose::VERBOSITY_NORMAL); + + // Reset preintegration from last KF (Create new object) + if (mSensor == System::IMU_MONOCULAR || mSensor == System::IMU_STEREO) + { + mpImuPreintegratedFromLastKF = new IMU::Preintegrated(pKF->GetImuBias(),pKF->mImuCalib); + } + + if(mSensor!=System::MONOCULAR && mSensor != System::IMU_MONOCULAR) // TODO check if incluide imu_stereo + { + mCurrentFrame.UpdatePoseMatrices(); + // cout << "create new MPs" << endl; + // We sort points by the measured depth by the stereo/RGBD sensor. + // We create all those MapPoints whose depth < mThDepth. + // If there are less than 100 close points we create the 100 closest. + int maxPoint = 100; + if(mSensor == System::IMU_STEREO) + maxPoint = 100; + + vector > vDepthIdx; + int N = (mCurrentFrame.Nleft != -1) ? mCurrentFrame.Nleft : mCurrentFrame.N; + vDepthIdx.reserve(mCurrentFrame.N); + for(int i=0; i0) + { + vDepthIdx.push_back(make_pair(z,i)); + } + } + + if(!vDepthIdx.empty()) + { + sort(vDepthIdx.begin(),vDepthIdx.end()); + + int nPoints = 0; + for(size_t j=0; jObservations()<1) + { + bCreateNew = true; + mCurrentFrame.mvpMapPoints[i] = static_cast(NULL); + } + + if(bCreateNew) + { + cv::Mat x3D; + + if(mCurrentFrame.Nleft == -1){ + x3D = mCurrentFrame.UnprojectStereo(i); + } + else{ + x3D = mCurrentFrame.UnprojectStereoFishEye(i); + } + + MapPoint* pNewMP = new MapPoint(x3D,pKF,mpAtlas->GetCurrentMap()); + pNewMP->AddObservation(pKF,i); + + //Check if it is a stereo observation in order to not + //duplicate mappoints + if(mCurrentFrame.Nleft != -1 && mCurrentFrame.mvLeftToRightMatch[i] >= 0){ + mCurrentFrame.mvpMapPoints[mCurrentFrame.Nleft + mCurrentFrame.mvLeftToRightMatch[i]]=pNewMP; + pNewMP->AddObservation(pKF,mCurrentFrame.Nleft + mCurrentFrame.mvLeftToRightMatch[i]); + pKF->AddMapPoint(pNewMP,mCurrentFrame.Nleft + mCurrentFrame.mvLeftToRightMatch[i]); + } + + pKF->AddMapPoint(pNewMP,i); + pNewMP->ComputeDistinctiveDescriptors(); + pNewMP->UpdateNormalAndDepth(); + mpAtlas->AddMapPoint(pNewMP); + + mCurrentFrame.mvpMapPoints[i]=pNewMP; + nPoints++; + } + else + { + nPoints++; // TODO check ??? + } + + if(vDepthIdx[j].first>mThDepth && nPoints>maxPoint) + { + break; + } + } + + Verbose::PrintMess("new mps for stereo KF: " + to_string(nPoints), Verbose::VERBOSITY_NORMAL); + + } + } + + + mpLocalMapper->InsertKeyFrame(pKF); + + mpLocalMapper->SetNotStop(false); + + mnLastKeyFrameId = mCurrentFrame.mnId; + mpLastKeyFrame = pKF; + //cout << "end creating new KF" << endl; +} + +void Tracking::SearchLocalPoints() +{ + // Do not search map points already matched + for(vector::iterator vit=mCurrentFrame.mvpMapPoints.begin(), vend=mCurrentFrame.mvpMapPoints.end(); vit!=vend; vit++) + { + MapPoint* pMP = *vit; + if(pMP) + { + if(pMP->isBad()) + { + *vit = static_cast(NULL); + } + else + { + pMP->IncreaseVisible(); + pMP->mnLastFrameSeen = mCurrentFrame.mnId; + pMP->mbTrackInView = false; + pMP->mbTrackInViewR = false; + } + } + } + + int nToMatch=0; + + // Project points in frame and check its visibility + for(vector::iterator vit=mvpLocalMapPoints.begin(), vend=mvpLocalMapPoints.end(); vit!=vend; vit++) + { + MapPoint* pMP = *vit; + + if(pMP->mnLastFrameSeen == mCurrentFrame.mnId) + continue; + if(pMP->isBad()) + continue; + // Project (this fills MapPoint variables for matching) + if(mCurrentFrame.isInFrustum(pMP,0.5)) + { + pMP->IncreaseVisible(); + nToMatch++; + } + if(pMP->mbTrackInView) + { + mCurrentFrame.mmProjectPoints[pMP->mnId] = cv::Point2f(pMP->mTrackProjX, pMP->mTrackProjY); + } + } + + if(nToMatch>0) + { + ORBmatcher matcher(0.8); + int th = 1; + if(mSensor==System::RGBD) + th=3; + if(mpAtlas->isImuInitialized()) + { + if(mpAtlas->GetCurrentMap()->GetIniertialBA2()) + th=2; + else + th=3; + } + else if(!mpAtlas->isImuInitialized() && (mSensor==System::IMU_MONOCULAR || mSensor==System::IMU_STEREO)) + { + th=10; + } + + // If the camera has been relocalised recently, perform a coarser search + if(mCurrentFrame.mnIdmbFarPoints, mpLocalMapper->mThFarPoints); + } +} + +void Tracking::UpdateLocalMap() +{ + // This is for visualization + mpAtlas->SetReferenceMapPoints(mvpLocalMapPoints); + + // Update + UpdateLocalKeyFrames(); + UpdateLocalPoints(); +} + +void Tracking::UpdateLocalPoints() +{ + mvpLocalMapPoints.clear(); + + int count_pts = 0; + + for(vector::const_reverse_iterator itKF=mvpLocalKeyFrames.rbegin(), itEndKF=mvpLocalKeyFrames.rend(); itKF!=itEndKF; ++itKF) + { + KeyFrame* pKF = *itKF; + const vector vpMPs = pKF->GetMapPointMatches(); + + for(vector::const_iterator itMP=vpMPs.begin(), itEndMP=vpMPs.end(); itMP!=itEndMP; itMP++) + { + + MapPoint* pMP = *itMP; + if(!pMP) + continue; + if(pMP->mnTrackReferenceForFrame==mCurrentFrame.mnId) + continue; + if(!pMP->isBad()) + { + count_pts++; + mvpLocalMapPoints.push_back(pMP); + pMP->mnTrackReferenceForFrame=mCurrentFrame.mnId; + } + } + } +} + + +void Tracking::UpdateLocalKeyFrames() +{ + // Each map point vote for the keyframes in which it has been observed + map keyframeCounter; + if(!mpAtlas->isImuInitialized() || (mCurrentFrame.mnIdisBad()) + { + const map> observations = pMP->GetObservations(); + for(map>::const_iterator it=observations.begin(), itend=observations.end(); it!=itend; it++) + keyframeCounter[it->first]++; + } + else + { + mCurrentFrame.mvpMapPoints[i]=NULL; + } + } + } + } + else + { + for(int i=0; iisBad()) + { + const map> observations = pMP->GetObservations(); + for(map>::const_iterator it=observations.begin(), itend=observations.end(); it!=itend; it++) + keyframeCounter[it->first]++; + } + else + { + // MODIFICATION + mLastFrame.mvpMapPoints[i]=NULL; + } + } + } + } + + + int max=0; + KeyFrame* pKFmax= static_cast(NULL); + + mvpLocalKeyFrames.clear(); + mvpLocalKeyFrames.reserve(3*keyframeCounter.size()); + + // All keyframes that observe a map point are included in the local map. Also check which keyframe shares most points + for(map::const_iterator it=keyframeCounter.begin(), itEnd=keyframeCounter.end(); it!=itEnd; it++) + { + KeyFrame* pKF = it->first; + + if(pKF->isBad()) + continue; + + if(it->second>max) + { + max=it->second; + pKFmax=pKF; + } + + mvpLocalKeyFrames.push_back(pKF); + pKF->mnTrackReferenceForFrame = mCurrentFrame.mnId; + } + + // Include also some not-already-included keyframes that are neighbors to already-included keyframes + for(vector::const_iterator itKF=mvpLocalKeyFrames.begin(), itEndKF=mvpLocalKeyFrames.end(); itKF!=itEndKF; itKF++) + { + // Limit the number of keyframes + if(mvpLocalKeyFrames.size()>80) // 80 + break; + + KeyFrame* pKF = *itKF; + + const vector vNeighs = pKF->GetBestCovisibilityKeyFrames(10); + + + for(vector::const_iterator itNeighKF=vNeighs.begin(), itEndNeighKF=vNeighs.end(); itNeighKF!=itEndNeighKF; itNeighKF++) + { + KeyFrame* pNeighKF = *itNeighKF; + if(!pNeighKF->isBad()) + { + if(pNeighKF->mnTrackReferenceForFrame!=mCurrentFrame.mnId) + { + mvpLocalKeyFrames.push_back(pNeighKF); + pNeighKF->mnTrackReferenceForFrame=mCurrentFrame.mnId; + break; + } + } + } + + const set spChilds = pKF->GetChilds(); + for(set::const_iterator sit=spChilds.begin(), send=spChilds.end(); sit!=send; sit++) + { + KeyFrame* pChildKF = *sit; + if(!pChildKF->isBad()) + { + if(pChildKF->mnTrackReferenceForFrame!=mCurrentFrame.mnId) + { + mvpLocalKeyFrames.push_back(pChildKF); + pChildKF->mnTrackReferenceForFrame=mCurrentFrame.mnId; + break; + } + } + } + + KeyFrame* pParent = pKF->GetParent(); + if(pParent) + { + if(pParent->mnTrackReferenceForFrame!=mCurrentFrame.mnId) + { + mvpLocalKeyFrames.push_back(pParent); + pParent->mnTrackReferenceForFrame=mCurrentFrame.mnId; + break; + } + } + } + + // Add 10 last temporal KFs (mainly for IMU) + if((mSensor == System::IMU_MONOCULAR || mSensor == System::IMU_STEREO) &&mvpLocalKeyFrames.size()<80) + { + //cout << "CurrentKF: " << mCurrentFrame.mnId << endl; + KeyFrame* tempKeyFrame = mCurrentFrame.mpLastKeyFrame; + + const int Nd = 20; + for(int i=0; imnTrackReferenceForFrame!=mCurrentFrame.mnId) + { + mvpLocalKeyFrames.push_back(tempKeyFrame); + tempKeyFrame->mnTrackReferenceForFrame=mCurrentFrame.mnId; + tempKeyFrame=tempKeyFrame->mPrevKF; + } + } + } + + if(pKFmax) + { + mpReferenceKF = pKFmax; + mCurrentFrame.mpReferenceKF = mpReferenceKF; + } +} + +bool Tracking::Relocalization() +{ + Verbose::PrintMess("Starting relocalization", Verbose::VERBOSITY_NORMAL); + // Compute Bag of Words Vector + mCurrentFrame.ComputeBoW(); + + // Relocalization is performed when tracking is lost + // Track Lost: Query KeyFrame Database for keyframe candidates for relocalisation + vector vpCandidateKFs = mpKeyFrameDB->DetectRelocalizationCandidates(&mCurrentFrame, mpAtlas->GetCurrentMap()); + + if(vpCandidateKFs.empty()) { + Verbose::PrintMess("There are not candidates", Verbose::VERBOSITY_NORMAL); + return false; + } + + const int nKFs = vpCandidateKFs.size(); + + // We perform first an ORB matching with each candidate + // If enough matches are found we setup a PnP solver + ORBmatcher matcher(0.75,true); + + vector vpMLPnPsolvers; + vpMLPnPsolvers.resize(nKFs); + + vector > vvpMapPointMatches; + vvpMapPointMatches.resize(nKFs); + + vector vbDiscarded; + vbDiscarded.resize(nKFs); + + int nCandidates=0; + + for(int i=0; iisBad()) + vbDiscarded[i] = true; + else + { + int nmatches = matcher.SearchByBoW(pKF,mCurrentFrame,vvpMapPointMatches[i]); + if(nmatches<15) + { + vbDiscarded[i] = true; + continue; + } + else + { + MLPnPsolver* pSolver = new MLPnPsolver(mCurrentFrame,vvpMapPointMatches[i]); + pSolver->SetRansacParameters(0.99,10,300,6,0.5,5.991); //This solver needs at least 6 points + vpMLPnPsolvers[i] = pSolver; + } + } + } + + // Alternatively perform some iterations of P4P RANSAC + // Until we found a camera pose supported by enough inliers + bool bMatch = false; + ORBmatcher matcher2(0.9,true); + + while(nCandidates>0 && !bMatch) + { + for(int i=0; i vbInliers; + int nInliers; + bool bNoMore; + + MLPnPsolver* pSolver = vpMLPnPsolvers[i]; + cv::Mat Tcw = pSolver->iterate(5,bNoMore,vbInliers,nInliers); + + // If Ransac reachs max. iterations discard keyframe + if(bNoMore) + { + vbDiscarded[i]=true; + nCandidates--; + } + + // If a Camera Pose is computed, optimize + if(!Tcw.empty()) + { + Tcw.copyTo(mCurrentFrame.mTcw); + + set sFound; + + const int np = vbInliers.size(); + + for(int j=0; j(NULL); + + // If few inliers, search by projection in a coarse window and optimize again + if(nGood<50) + { + int nadditional =matcher2.SearchByProjection(mCurrentFrame,vpCandidateKFs[i],sFound,10,100); + + if(nadditional+nGood>=50) + { + nGood = Optimizer::PoseOptimization(&mCurrentFrame); + + // If many inliers but still not enough, search by projection again in a narrower window + // the camera has been already optimized with many points + if(nGood>30 && nGood<50) + { + sFound.clear(); + for(int ip =0; ip=50) + { + nGood = Optimizer::PoseOptimization(&mCurrentFrame); + + for(int io =0; io=50) + { + bMatch = true; + break; + } + } + } + } + + if(!bMatch) + { + return false; + } + else + { + mnLastRelocFrameId = mCurrentFrame.mnId; + cout << "Relocalized!!" << endl; + return true; + } + +} + +void Tracking::Reset(bool bLocMap) +{ + Verbose::PrintMess("System Reseting", Verbose::VERBOSITY_NORMAL); + + if(mpViewer) + { + mpViewer->RequestStop(); + while(!mpViewer->isStopped()) + usleep(3000); + } + + // Reset Local Mapping + if (!bLocMap) + { + Verbose::PrintMess("Reseting Local Mapper...", Verbose::VERBOSITY_NORMAL); + mpLocalMapper->RequestReset(); + Verbose::PrintMess("done", Verbose::VERBOSITY_NORMAL); + } + + + // Reset Loop Closing + Verbose::PrintMess("Reseting Loop Closing...", Verbose::VERBOSITY_NORMAL); + mpLoopClosing->RequestReset(); + Verbose::PrintMess("done", Verbose::VERBOSITY_NORMAL); + + // Clear BoW Database + Verbose::PrintMess("Reseting Database...", Verbose::VERBOSITY_NORMAL); + mpKeyFrameDB->clear(); + Verbose::PrintMess("done", Verbose::VERBOSITY_NORMAL); + + // Clear Map (this erase MapPoints and KeyFrames) + mpAtlas->clearAtlas(); + mpAtlas->CreateNewMap(); + if (mSensor==System::IMU_STEREO || mSensor == System::IMU_MONOCULAR) + mpAtlas->SetInertialSensor(); + mnInitialFrameId = 0; + + KeyFrame::nNextId = 0; + Frame::nNextId = 0; + mState = NO_IMAGES_YET; + + if(mpInitializer) + { + delete mpInitializer; + mpInitializer = static_cast(NULL); + } + mbSetInit=false; + + mlRelativeFramePoses.clear(); + mlpReferences.clear(); + mlFrameTimes.clear(); + mlbLost.clear(); + mCurrentFrame = Frame(); + mnLastRelocFrameId = 0; + mLastFrame = Frame(); + mpReferenceKF = static_cast(NULL); + mpLastKeyFrame = static_cast(NULL); + mvIniMatches.clear(); + + if(mpViewer) + mpViewer->Release(); + + Verbose::PrintMess(" End reseting! ", Verbose::VERBOSITY_NORMAL); +} + +void Tracking::ResetActiveMap(bool bLocMap) +{ + Verbose::PrintMess("Active map Reseting", Verbose::VERBOSITY_NORMAL); + if(mpViewer) + { + mpViewer->RequestStop(); + while(!mpViewer->isStopped()) + usleep(3000); + } + + Map* pMap = mpAtlas->GetCurrentMap(); + + if (!bLocMap) + { + Verbose::PrintMess("Reseting Local Mapper...", Verbose::VERBOSITY_NORMAL); + mpLocalMapper->RequestResetActiveMap(pMap); + Verbose::PrintMess("done", Verbose::VERBOSITY_NORMAL); + } + + // Reset Loop Closing + Verbose::PrintMess("Reseting Loop Closing...", Verbose::VERBOSITY_NORMAL); + mpLoopClosing->RequestResetActiveMap(pMap); + Verbose::PrintMess("done", Verbose::VERBOSITY_NORMAL); + + // Clear BoW Database + Verbose::PrintMess("Reseting Database", Verbose::VERBOSITY_NORMAL); + mpKeyFrameDB->clearMap(pMap); // Only clear the active map references + Verbose::PrintMess("done", Verbose::VERBOSITY_NORMAL); + + // Clear Map (this erase MapPoints and KeyFrames) + mpAtlas->clearMap(); + + + //KeyFrame::nNextId = mpAtlas->GetLastInitKFid(); + //Frame::nNextId = mnLastInitFrameId; + mnLastInitFrameId = Frame::nNextId; + mnLastRelocFrameId = mnLastInitFrameId; + mState = NO_IMAGES_YET; //NOT_INITIALIZED; + + if(mpInitializer) + { + delete mpInitializer; + mpInitializer = static_cast(NULL); + } + + list lbLost; + // lbLost.reserve(mlbLost.size()); + unsigned int index = mnFirstFrameId; + cout << "mnFirstFrameId = " << mnFirstFrameId << endl; + for(Map* pMap : mpAtlas->GetAllMaps()) + { + if(pMap->GetAllKeyFrames().size() > 0) + { + if(index > pMap->GetLowerKFID()) + index = pMap->GetLowerKFID(); + } + } + + //cout << "First Frame id: " << index << endl; + int num_lost = 0; + cout << "mnInitialFrameId = " << mnInitialFrameId << endl; + + for(list::iterator ilbL = mlbLost.begin(); ilbL != mlbLost.end(); ilbL++) + { + if(index < mnInitialFrameId) + lbLost.push_back(*ilbL); + else + { + lbLost.push_back(true); + num_lost += 1; + } + + index++; + } + cout << num_lost << " Frames set to lost" << endl; + + mlbLost = lbLost; + + mnInitialFrameId = mCurrentFrame.mnId; + mnLastRelocFrameId = mCurrentFrame.mnId; + + mCurrentFrame = Frame(); + mLastFrame = Frame(); + mpReferenceKF = static_cast(NULL); + mpLastKeyFrame = static_cast(NULL); + mvIniMatches.clear(); + + if(mpViewer) + mpViewer->Release(); + + Verbose::PrintMess(" End reseting! ", Verbose::VERBOSITY_NORMAL); +} + +vector Tracking::GetLocalMapMPS() +{ + return mvpLocalMapPoints; +} + +void Tracking::ChangeCalibration(const string &strSettingPath) +{ + cv::FileStorage fSettings(strSettingPath, cv::FileStorage::READ); + float fx = fSettings["Camera.fx"]; + float fy = fSettings["Camera.fy"]; + float cx = fSettings["Camera.cx"]; + float cy = fSettings["Camera.cy"]; + + cv::Mat K = cv::Mat::eye(3,3,CV_32F); + K.at(0,0) = fx; + K.at(1,1) = fy; + K.at(0,2) = cx; + K.at(1,2) = cy; + K.copyTo(mK); + + cv::Mat DistCoef(4,1,CV_32F); + DistCoef.at(0) = fSettings["Camera.k1"]; + DistCoef.at(1) = fSettings["Camera.k2"]; + DistCoef.at(2) = fSettings["Camera.p1"]; + DistCoef.at(3) = fSettings["Camera.p2"]; + const float k3 = fSettings["Camera.k3"]; + if(k3!=0) + { + DistCoef.resize(5); + DistCoef.at(4) = k3; + } + DistCoef.copyTo(mDistCoef); + + mbf = fSettings["Camera.bf"]; + + Frame::mbInitialComputations = true; +} + +void Tracking::InformOnlyTracking(const bool &flag) +{ + mbOnlyTracking = flag; +} + +void Tracking::UpdateFrameIMU(const float s, const IMU::Bias &b, KeyFrame* pCurrentKeyFrame) +{ + Map * pMap = pCurrentKeyFrame->GetMap(); + unsigned int index = mnFirstFrameId; + list::iterator lRit = mlpReferences.begin(); + list::iterator lbL = mlbLost.begin(); + for(list::iterator lit=mlRelativeFramePoses.begin(),lend=mlRelativeFramePoses.end();lit!=lend;lit++, lRit++, lbL++) + { + if(*lbL) + continue; + + KeyFrame* pKF = *lRit; + + while(pKF->isBad()) + { + pKF = pKF->GetParent(); + } + + if(pKF->GetMap() == pMap) + { + (*lit).rowRange(0,3).col(3)=(*lit).rowRange(0,3).col(3)*s; + } + } + + mLastBias = b; + + mpLastKeyFrame = pCurrentKeyFrame; + + mLastFrame.SetNewBias(mLastBias); + mCurrentFrame.SetNewBias(mLastBias); + + cv::Mat Gz = (cv::Mat_(3,1) << 0, 0, -IMU::GRAVITY_VALUE); + + cv::Mat twb1; + cv::Mat Rwb1; + cv::Mat Vwb1; + float t12; + + while(!mCurrentFrame.imuIsPreintegrated()) + { + usleep(500); + } + + + if(mLastFrame.mnId == mLastFrame.mpLastKeyFrame->mnFrameId) + { + mLastFrame.SetImuPoseVelocity(mLastFrame.mpLastKeyFrame->GetImuRotation(), + mLastFrame.mpLastKeyFrame->GetImuPosition(), + mLastFrame.mpLastKeyFrame->GetVelocity()); + } + else + { + twb1 = mLastFrame.mpLastKeyFrame->GetImuPosition(); + Rwb1 = mLastFrame.mpLastKeyFrame->GetImuRotation(); + Vwb1 = mLastFrame.mpLastKeyFrame->GetVelocity(); + t12 = mLastFrame.mpImuPreintegrated->dT; + + mLastFrame.SetImuPoseVelocity(Rwb1*mLastFrame.mpImuPreintegrated->GetUpdatedDeltaRotation(), + twb1 + Vwb1*t12 + 0.5f*t12*t12*Gz+ Rwb1*mLastFrame.mpImuPreintegrated->GetUpdatedDeltaPosition(), + Vwb1 + Gz*t12 + Rwb1*mLastFrame.mpImuPreintegrated->GetUpdatedDeltaVelocity()); + } + + if (mCurrentFrame.mpImuPreintegrated) + { + twb1 = mCurrentFrame.mpLastKeyFrame->GetImuPosition(); + Rwb1 = mCurrentFrame.mpLastKeyFrame->GetImuRotation(); + Vwb1 = mCurrentFrame.mpLastKeyFrame->GetVelocity(); + t12 = mCurrentFrame.mpImuPreintegrated->dT; + + mCurrentFrame.SetImuPoseVelocity(Rwb1*mCurrentFrame.mpImuPreintegrated->GetUpdatedDeltaRotation(), + twb1 + Vwb1*t12 + 0.5f*t12*t12*Gz+ Rwb1*mCurrentFrame.mpImuPreintegrated->GetUpdatedDeltaPosition(), + Vwb1 + Gz*t12 + Rwb1*mCurrentFrame.mpImuPreintegrated->GetUpdatedDeltaVelocity()); + } + + mnFirstImuFrameId = mCurrentFrame.mnId; +} + + +cv::Mat Tracking::ComputeF12(KeyFrame *&pKF1, KeyFrame *&pKF2) +{ + cv::Mat R1w = pKF1->GetRotation(); + cv::Mat t1w = pKF1->GetTranslation(); + cv::Mat R2w = pKF2->GetRotation(); + cv::Mat t2w = pKF2->GetTranslation(); + + cv::Mat R12 = R1w*R2w.t(); + cv::Mat t12 = -R1w*R2w.t()*t2w+t1w; + + cv::Mat t12x = Converter::tocvSkewMatrix(t12); + + const cv::Mat &K1 = pKF1->mK; + const cv::Mat &K2 = pKF2->mK; + + + return K1.t().inv()*t12x*R12*K2.inv(); +} + + +void Tracking::CreateNewMapPoints() +{ + // Retrieve neighbor keyframes in covisibility graph + const vector vpKFs = mpAtlas->GetAllKeyFrames(); + + ORBmatcher matcher(0.6,false); + + cv::Mat Rcw1 = mpLastKeyFrame->GetRotation(); + cv::Mat Rwc1 = Rcw1.t(); + cv::Mat tcw1 = mpLastKeyFrame->GetTranslation(); + cv::Mat Tcw1(3,4,CV_32F); + Rcw1.copyTo(Tcw1.colRange(0,3)); + tcw1.copyTo(Tcw1.col(3)); + cv::Mat Ow1 = mpLastKeyFrame->GetCameraCenter(); + + const float &fx1 = mpLastKeyFrame->fx; + const float &fy1 = mpLastKeyFrame->fy; + const float &cx1 = mpLastKeyFrame->cx; + const float &cy1 = mpLastKeyFrame->cy; + const float &invfx1 = mpLastKeyFrame->invfx; + const float &invfy1 = mpLastKeyFrame->invfy; + + const float ratioFactor = 1.5f*mpLastKeyFrame->mfScaleFactor; + + int nnew=0; + + // Search matches with epipolar restriction and triangulate + for(size_t i=0; iGetCameraCenter(); + cv::Mat vBaseline = Ow2-Ow1; + const float baseline = cv::norm(vBaseline); + + if((mSensor!=System::MONOCULAR)||(mSensor!=System::IMU_MONOCULAR)) + { + if(baselinemb) + continue; + } + else + { + const float medianDepthKF2 = pKF2->ComputeSceneMedianDepth(2); + const float ratioBaselineDepth = baseline/medianDepthKF2; + + if(ratioBaselineDepth<0.01) + continue; + } + + // Compute Fundamental Matrix + cv::Mat F12 = ComputeF12(mpLastKeyFrame,pKF2); + + // Search matches that fullfil epipolar constraint + vector > vMatchedIndices; + matcher.SearchForTriangulation(mpLastKeyFrame,pKF2,F12,vMatchedIndices,false); + + cv::Mat Rcw2 = pKF2->GetRotation(); + cv::Mat Rwc2 = Rcw2.t(); + cv::Mat tcw2 = pKF2->GetTranslation(); + cv::Mat Tcw2(3,4,CV_32F); + Rcw2.copyTo(Tcw2.colRange(0,3)); + tcw2.copyTo(Tcw2.col(3)); + + const float &fx2 = pKF2->fx; + const float &fy2 = pKF2->fy; + const float &cx2 = pKF2->cx; + const float &cy2 = pKF2->cy; + const float &invfx2 = pKF2->invfx; + const float &invfy2 = pKF2->invfy; + + // Triangulate each match + const int nmatches = vMatchedIndices.size(); + for(int ikp=0; ikpmvKeysUn[idx1]; + const float kp1_ur=mpLastKeyFrame->mvuRight[idx1]; + bool bStereo1 = kp1_ur>=0; + + const cv::KeyPoint &kp2 = pKF2->mvKeysUn[idx2]; + const float kp2_ur = pKF2->mvuRight[idx2]; + bool bStereo2 = kp2_ur>=0; + + // Check parallax between rays + cv::Mat xn1 = (cv::Mat_(3,1) << (kp1.pt.x-cx1)*invfx1, (kp1.pt.y-cy1)*invfy1, 1.0); + cv::Mat xn2 = (cv::Mat_(3,1) << (kp2.pt.x-cx2)*invfx2, (kp2.pt.y-cy2)*invfy2, 1.0); + + cv::Mat ray1 = Rwc1*xn1; + cv::Mat ray2 = Rwc2*xn2; + const float cosParallaxRays = ray1.dot(ray2)/(cv::norm(ray1)*cv::norm(ray2)); + + float cosParallaxStereo = cosParallaxRays+1; + float cosParallaxStereo1 = cosParallaxStereo; + float cosParallaxStereo2 = cosParallaxStereo; + + if(bStereo1) + cosParallaxStereo1 = cos(2*atan2(mpLastKeyFrame->mb/2,mpLastKeyFrame->mvDepth[idx1])); + else if(bStereo2) + cosParallaxStereo2 = cos(2*atan2(pKF2->mb/2,pKF2->mvDepth[idx2])); + + cosParallaxStereo = min(cosParallaxStereo1,cosParallaxStereo2); + + cv::Mat x3D; + if(cosParallaxRays0 && (bStereo1 || bStereo2 || cosParallaxRays<0.9998)) + { + // Linear Triangulation Method + cv::Mat A(4,4,CV_32F); + A.row(0) = xn1.at(0)*Tcw1.row(2)-Tcw1.row(0); + A.row(1) = xn1.at(1)*Tcw1.row(2)-Tcw1.row(1); + A.row(2) = xn2.at(0)*Tcw2.row(2)-Tcw2.row(0); + A.row(3) = xn2.at(1)*Tcw2.row(2)-Tcw2.row(1); + + cv::Mat w,u,vt; + cv::SVD::compute(A,w,u,vt,cv::SVD::MODIFY_A| cv::SVD::FULL_UV); + + x3D = vt.row(3).t(); + + if(x3D.at(3)==0) + continue; + + // Euclidean coordinates + x3D = x3D.rowRange(0,3)/x3D.at(3); + + } + else if(bStereo1 && cosParallaxStereo1UnprojectStereo(idx1); + } + else if(bStereo2 && cosParallaxStereo2UnprojectStereo(idx2); + } + else + continue; //No stereo and very low parallax + + cv::Mat x3Dt = x3D.t(); + + //Check triangulation in front of cameras + float z1 = Rcw1.row(2).dot(x3Dt)+tcw1.at(2); + if(z1<=0) + continue; + + float z2 = Rcw2.row(2).dot(x3Dt)+tcw2.at(2); + if(z2<=0) + continue; + + //Check reprojection error in first keyframe + const float &sigmaSquare1 = mpLastKeyFrame->mvLevelSigma2[kp1.octave]; + const float x1 = Rcw1.row(0).dot(x3Dt)+tcw1.at(0); + const float y1 = Rcw1.row(1).dot(x3Dt)+tcw1.at(1); + const float invz1 = 1.0/z1; + + if(!bStereo1) + { + float u1 = fx1*x1*invz1+cx1; + float v1 = fy1*y1*invz1+cy1; + float errX1 = u1 - kp1.pt.x; + float errY1 = v1 - kp1.pt.y; + if((errX1*errX1+errY1*errY1)>5.991*sigmaSquare1) + continue; + } + else + { + float u1 = fx1*x1*invz1+cx1; + float u1_r = u1 - mpLastKeyFrame->mbf*invz1; + float v1 = fy1*y1*invz1+cy1; + float errX1 = u1 - kp1.pt.x; + float errY1 = v1 - kp1.pt.y; + float errX1_r = u1_r - kp1_ur; + if((errX1*errX1+errY1*errY1+errX1_r*errX1_r)>7.8*sigmaSquare1) + continue; + } + + //Check reprojection error in second keyframe + const float sigmaSquare2 = pKF2->mvLevelSigma2[kp2.octave]; + const float x2 = Rcw2.row(0).dot(x3Dt)+tcw2.at(0); + const float y2 = Rcw2.row(1).dot(x3Dt)+tcw2.at(1); + const float invz2 = 1.0/z2; + if(!bStereo2) + { + float u2 = fx2*x2*invz2+cx2; + float v2 = fy2*y2*invz2+cy2; + float errX2 = u2 - kp2.pt.x; + float errY2 = v2 - kp2.pt.y; + if((errX2*errX2+errY2*errY2)>5.991*sigmaSquare2) + continue; + } + else + { + float u2 = fx2*x2*invz2+cx2; + float u2_r = u2 - mpLastKeyFrame->mbf*invz2; + float v2 = fy2*y2*invz2+cy2; + float errX2 = u2 - kp2.pt.x; + float errY2 = v2 - kp2.pt.y; + float errX2_r = u2_r - kp2_ur; + if((errX2*errX2+errY2*errY2+errX2_r*errX2_r)>7.8*sigmaSquare2) + continue; + } + + //Check scale consistency + cv::Mat normal1 = x3D-Ow1; + float dist1 = cv::norm(normal1); + + cv::Mat normal2 = x3D-Ow2; + float dist2 = cv::norm(normal2); + + if(dist1==0 || dist2==0) + continue; + + const float ratioDist = dist2/dist1; + const float ratioOctave = mpLastKeyFrame->mvScaleFactors[kp1.octave]/pKF2->mvScaleFactors[kp2.octave]; + + if(ratioDist*ratioFactorratioOctave*ratioFactor) + continue; + + // Triangulation is succesfull + MapPoint* pMP = new MapPoint(x3D,mpLastKeyFrame,mpAtlas->GetCurrentMap()); + + pMP->AddObservation(mpLastKeyFrame,idx1); + pMP->AddObservation(pKF2,idx2); + + mpLastKeyFrame->AddMapPoint(pMP,idx1); + pKF2->AddMapPoint(pMP,idx2); + + pMP->ComputeDistinctiveDescriptors(); + + pMP->UpdateNormalAndDepth(); + + mpAtlas->AddMapPoint(pMP); + nnew++; + } + } + TrackReferenceKeyFrame(); +} + +void Tracking::NewDataset() +{ + mnNumDataset++; +} + +int Tracking::GetNumberDataset() +{ + return mnNumDataset; +} + +int Tracking::GetMatchesInliers() +{ + return mnMatchesInliers; +} + +} //namespace ORB_SLAM diff --git a/third_party/ORB_SLAM3/src/TwoViewReconstruction.cc b/third_party/ORB_SLAM3/src/TwoViewReconstruction.cc new file mode 100644 index 0000000..af41678 --- /dev/null +++ b/third_party/ORB_SLAM3/src/TwoViewReconstruction.cc @@ -0,0 +1,935 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + +#include "TwoViewReconstruction.h" + +#include "Thirdparty/DBoW2/DUtils/Random.h" + +#include + + +using namespace std; +namespace ORB_SLAM3 +{ + +TwoViewReconstruction::TwoViewReconstruction(cv::Mat& K, float sigma, int iterations) +{ + mK = K.clone(); + + mSigma = sigma; + mSigma2 = sigma*sigma; + mMaxIterations = iterations; +} + +bool TwoViewReconstruction::Reconstruct(const std::vector& vKeys1, const std::vector& vKeys2, const vector &vMatches12, + cv::Mat &R21, cv::Mat &t21, vector &vP3D, vector &vbTriangulated) +{ + mvKeys1.clear(); + mvKeys2.clear(); + + mvKeys1 = vKeys1; + mvKeys2 = vKeys2; + + // Fill structures with current keypoints and matches with reference frame + // Reference Frame: 1, Current Frame: 2 + mvMatches12.clear(); + mvMatches12.reserve(mvKeys2.size()); + mvbMatched1.resize(mvKeys1.size()); + for(size_t i=0, iend=vMatches12.size();i=0) + { + mvMatches12.push_back(make_pair(i,vMatches12[i])); + mvbMatched1[i]=true; + } + else + mvbMatched1[i]=false; + } + + const int N = mvMatches12.size(); + + // Indices for minimum set selection + vector vAllIndices; + vAllIndices.reserve(N); + vector vAvailableIndices; + + for(int i=0; i >(mMaxIterations,vector(8,0)); + + DUtils::Random::SeedRandOnce(0); + + for(int it=0; it vbMatchesInliersH, vbMatchesInliersF; + float SH, SF; + cv::Mat H, F; + + thread threadH(&TwoViewReconstruction::FindHomography,this,ref(vbMatchesInliersH), ref(SH), ref(H)); + thread threadF(&TwoViewReconstruction::FindFundamental,this,ref(vbMatchesInliersF), ref(SF), ref(F)); + + // Wait until both threads have finished + threadH.join(); + threadF.join(); + + // Compute ratio of scores + if(SH+SF == 0.f) return false; + float RH = SH/(SH+SF); + + float minParallax = 1.0; + + // Try to reconstruct from homography or fundamental depending on the ratio (0.40-0.45) + if(RH>0.50) // if(RH>0.40) + { + //cout << "Initialization from Homography" << endl; + return ReconstructH(vbMatchesInliersH,H, mK,R21,t21,vP3D,vbTriangulated,minParallax,50); + } + else //if(pF_HF>0.6) + { + //cout << "Initialization from Fundamental" << endl; + return ReconstructF(vbMatchesInliersF,F,mK,R21,t21,vP3D,vbTriangulated,minParallax,50); + } +} + +void TwoViewReconstruction::FindHomography(vector &vbMatchesInliers, float &score, cv::Mat &H21) +{ + // Number of putative matches + const int N = mvMatches12.size(); + + // Normalize coordinates + vector vPn1, vPn2; + cv::Mat T1, T2; + Normalize(mvKeys1,vPn1, T1); + Normalize(mvKeys2,vPn2, T2); + cv::Mat T2inv = T2.inv(); + + // Best Results variables + score = 0.0; + vbMatchesInliers = vector(N,false); + + // Iteration variables + vector vPn1i(8); + vector vPn2i(8); + cv::Mat H21i, H12i; + vector vbCurrentInliers(N,false); + float currentScore; + + // Perform all RANSAC iterations and save the solution with highest score + for(int it=0; itscore) + { + H21 = H21i.clone(); + vbMatchesInliers = vbCurrentInliers; + score = currentScore; + } + } +} + + +void TwoViewReconstruction::FindFundamental(vector &vbMatchesInliers, float &score, cv::Mat &F21) +{ + // Number of putative matches + const int N = vbMatchesInliers.size(); + + // Normalize coordinates + vector vPn1, vPn2; + cv::Mat T1, T2; + Normalize(mvKeys1,vPn1, T1); + Normalize(mvKeys2,vPn2, T2); + cv::Mat T2t = T2.t(); + + // Best Results variables + score = 0.0; + vbMatchesInliers = vector(N,false); + + // Iteration variables + vector vPn1i(8); + vector vPn2i(8); + cv::Mat F21i; + vector vbCurrentInliers(N,false); + float currentScore; + + // Perform all RANSAC iterations and save the solution with highest score + for(int it=0; itscore) + { + F21 = F21i.clone(); + vbMatchesInliers = vbCurrentInliers; + score = currentScore; + } + } +} + + +cv::Mat TwoViewReconstruction::ComputeH21(const vector &vP1, const vector &vP2) +{ + const int N = vP1.size(); + + cv::Mat A(2*N,9,CV_32F); + + for(int i=0; i(2*i,0) = 0.0; + A.at(2*i,1) = 0.0; + A.at(2*i,2) = 0.0; + A.at(2*i,3) = -u1; + A.at(2*i,4) = -v1; + A.at(2*i,5) = -1; + A.at(2*i,6) = v2*u1; + A.at(2*i,7) = v2*v1; + A.at(2*i,8) = v2; + + A.at(2*i+1,0) = u1; + A.at(2*i+1,1) = v1; + A.at(2*i+1,2) = 1; + A.at(2*i+1,3) = 0.0; + A.at(2*i+1,4) = 0.0; + A.at(2*i+1,5) = 0.0; + A.at(2*i+1,6) = -u2*u1; + A.at(2*i+1,7) = -u2*v1; + A.at(2*i+1,8) = -u2; + + } + + cv::Mat u,w,vt; + + cv::SVDecomp(A,w,u,vt,cv::SVD::MODIFY_A | cv::SVD::FULL_UV); + + return vt.row(8).reshape(0, 3); +} + +cv::Mat TwoViewReconstruction::ComputeF21(const vector &vP1,const vector &vP2) +{ + const int N = vP1.size(); + + cv::Mat A(N,9,CV_32F); + + for(int i=0; i(i,0) = u2*u1; + A.at(i,1) = u2*v1; + A.at(i,2) = u2; + A.at(i,3) = v2*u1; + A.at(i,4) = v2*v1; + A.at(i,5) = v2; + A.at(i,6) = u1; + A.at(i,7) = v1; + A.at(i,8) = 1; + } + + cv::Mat u,w,vt; + + cv::SVDecomp(A,w,u,vt,cv::SVD::MODIFY_A | cv::SVD::FULL_UV); + + cv::Mat Fpre = vt.row(8).reshape(0, 3); + + cv::SVDecomp(Fpre,w,u,vt,cv::SVD::MODIFY_A | cv::SVD::FULL_UV); + + w.at(2)=0; + + return u*cv::Mat::diag(w)*vt; +} + +float TwoViewReconstruction::CheckHomography(const cv::Mat &H21, const cv::Mat &H12, vector &vbMatchesInliers, float sigma) +{ + const int N = mvMatches12.size(); + + const float h11 = H21.at(0,0); + const float h12 = H21.at(0,1); + const float h13 = H21.at(0,2); + const float h21 = H21.at(1,0); + const float h22 = H21.at(1,1); + const float h23 = H21.at(1,2); + const float h31 = H21.at(2,0); + const float h32 = H21.at(2,1); + const float h33 = H21.at(2,2); + + const float h11inv = H12.at(0,0); + const float h12inv = H12.at(0,1); + const float h13inv = H12.at(0,2); + const float h21inv = H12.at(1,0); + const float h22inv = H12.at(1,1); + const float h23inv = H12.at(1,2); + const float h31inv = H12.at(2,0); + const float h32inv = H12.at(2,1); + const float h33inv = H12.at(2,2); + + vbMatchesInliers.resize(N); + + float score = 0; + + const float th = 5.991; + + const float invSigmaSquare = 1.0/(sigma*sigma); + + for(int i=0; ith) + bIn = false; + else + score += th - chiSquare1; + + // Reprojection error in second image + // x1in2 = H21*x1 + + const float w1in2inv = 1.0/(h31*u1+h32*v1+h33); + const float u1in2 = (h11*u1+h12*v1+h13)*w1in2inv; + const float v1in2 = (h21*u1+h22*v1+h23)*w1in2inv; + + const float squareDist2 = (u2-u1in2)*(u2-u1in2)+(v2-v1in2)*(v2-v1in2); + + const float chiSquare2 = squareDist2*invSigmaSquare; + + if(chiSquare2>th) + bIn = false; + else + score += th - chiSquare2; + + if(bIn) + vbMatchesInliers[i]=true; + else + vbMatchesInliers[i]=false; + } + + return score; +} + +float TwoViewReconstruction::CheckFundamental(const cv::Mat &F21, vector &vbMatchesInliers, float sigma) +{ + const int N = mvMatches12.size(); + + const float f11 = F21.at(0,0); + const float f12 = F21.at(0,1); + const float f13 = F21.at(0,2); + const float f21 = F21.at(1,0); + const float f22 = F21.at(1,1); + const float f23 = F21.at(1,2); + const float f31 = F21.at(2,0); + const float f32 = F21.at(2,1); + const float f33 = F21.at(2,2); + + vbMatchesInliers.resize(N); + + float score = 0; + + const float th = 3.841; + const float thScore = 5.991; + + const float invSigmaSquare = 1.0/(sigma*sigma); + + for(int i=0; ith) + bIn = false; + else + score += thScore - chiSquare1; + + // Reprojection error in second image + // l1 =x2tF21=(a1,b1,c1) + + const float a1 = f11*u2+f21*v2+f31; + const float b1 = f12*u2+f22*v2+f32; + const float c1 = f13*u2+f23*v2+f33; + + const float num1 = a1*u1+b1*v1+c1; + + const float squareDist2 = num1*num1/(a1*a1+b1*b1); + + const float chiSquare2 = squareDist2*invSigmaSquare; + + if(chiSquare2>th) + bIn = false; + else + score += thScore - chiSquare2; + + if(bIn) + vbMatchesInliers[i]=true; + else + vbMatchesInliers[i]=false; + } + + return score; +} + +bool TwoViewReconstruction::ReconstructF(vector &vbMatchesInliers, cv::Mat &F21, cv::Mat &K, + cv::Mat &R21, cv::Mat &t21, vector &vP3D, vector &vbTriangulated, float minParallax, int minTriangulated) +{ + int N=0; + for(size_t i=0, iend = vbMatchesInliers.size() ; i vP3D1, vP3D2, vP3D3, vP3D4; + vector vbTriangulated1,vbTriangulated2,vbTriangulated3, vbTriangulated4; + float parallax1,parallax2, parallax3, parallax4; + + int nGood1 = CheckRT(R1,t1,mvKeys1,mvKeys2,mvMatches12,vbMatchesInliers,K, vP3D1, 4.0*mSigma2, vbTriangulated1, parallax1); + int nGood2 = CheckRT(R2,t1,mvKeys1,mvKeys2,mvMatches12,vbMatchesInliers,K, vP3D2, 4.0*mSigma2, vbTriangulated2, parallax2); + int nGood3 = CheckRT(R1,t2,mvKeys1,mvKeys2,mvMatches12,vbMatchesInliers,K, vP3D3, 4.0*mSigma2, vbTriangulated3, parallax3); + int nGood4 = CheckRT(R2,t2,mvKeys1,mvKeys2,mvMatches12,vbMatchesInliers,K, vP3D4, 4.0*mSigma2, vbTriangulated4, parallax4); + + int maxGood = max(nGood1,max(nGood2,max(nGood3,nGood4))); + + R21 = cv::Mat(); + t21 = cv::Mat(); + + int nMinGood = max(static_cast(0.9*N),minTriangulated); + + int nsimilar = 0; + if(nGood1>0.7*maxGood) + nsimilar++; + if(nGood2>0.7*maxGood) + nsimilar++; + if(nGood3>0.7*maxGood) + nsimilar++; + if(nGood4>0.7*maxGood) + nsimilar++; + + // If there is not a clear winner or not enough triangulated points reject initialization + if(maxGood1) + { + return false; + } + + // If best reconstruction has enough parallax initialize + if(maxGood==nGood1) + { + if(parallax1>minParallax) + { + vP3D = vP3D1; + vbTriangulated = vbTriangulated1; + + R1.copyTo(R21); + t1.copyTo(t21); + return true; + } + }else if(maxGood==nGood2) + { + if(parallax2>minParallax) + { + vP3D = vP3D2; + vbTriangulated = vbTriangulated2; + + R2.copyTo(R21); + t1.copyTo(t21); + return true; + } + }else if(maxGood==nGood3) + { + if(parallax3>minParallax) + { + vP3D = vP3D3; + vbTriangulated = vbTriangulated3; + + R1.copyTo(R21); + t2.copyTo(t21); + return true; + } + }else if(maxGood==nGood4) + { + if(parallax4>minParallax) + { + vP3D = vP3D4; + vbTriangulated = vbTriangulated4; + + R2.copyTo(R21); + t2.copyTo(t21); + return true; + } + } + + return false; +} + +bool TwoViewReconstruction::ReconstructH(vector &vbMatchesInliers, cv::Mat &H21, cv::Mat &K, + cv::Mat &R21, cv::Mat &t21, vector &vP3D, vector &vbTriangulated, float minParallax, int minTriangulated) +{ + int N=0; + for(size_t i=0, iend = vbMatchesInliers.size() ; i(0); + float d2 = w.at(1); + float d3 = w.at(2); + + if(d1/d2<1.00001 || d2/d3<1.00001) + { + return false; + } + + vector vR, vt, vn; + vR.reserve(8); + vt.reserve(8); + vn.reserve(8); + + //n'=[x1 0 x3] 4 posibilities e1=e3=1, e1=1 e3=-1, e1=-1 e3=1, e1=e3=-1 + float aux1 = sqrt((d1*d1-d2*d2)/(d1*d1-d3*d3)); + float aux3 = sqrt((d2*d2-d3*d3)/(d1*d1-d3*d3)); + float x1[] = {aux1,aux1,-aux1,-aux1}; + float x3[] = {aux3,-aux3,aux3,-aux3}; + + //case d'=d2 + float aux_stheta = sqrt((d1*d1-d2*d2)*(d2*d2-d3*d3))/((d1+d3)*d2); + + float ctheta = (d2*d2+d1*d3)/((d1+d3)*d2); + float stheta[] = {aux_stheta, -aux_stheta, -aux_stheta, aux_stheta}; + + for(int i=0; i<4; i++) + { + cv::Mat Rp=cv::Mat::eye(3,3,CV_32F); + Rp.at(0,0)=ctheta; + Rp.at(0,2)=-stheta[i]; + Rp.at(2,0)=stheta[i]; + Rp.at(2,2)=ctheta; + + cv::Mat R = s*U*Rp*Vt; + vR.push_back(R); + + cv::Mat tp(3,1,CV_32F); + tp.at(0)=x1[i]; + tp.at(1)=0; + tp.at(2)=-x3[i]; + tp*=d1-d3; + + cv::Mat t = U*tp; + vt.push_back(t/cv::norm(t)); + + cv::Mat np(3,1,CV_32F); + np.at(0)=x1[i]; + np.at(1)=0; + np.at(2)=x3[i]; + + cv::Mat n = V*np; + if(n.at(2)<0) + n=-n; + vn.push_back(n); + } + + //case d'=-d2 + float aux_sphi = sqrt((d1*d1-d2*d2)*(d2*d2-d3*d3))/((d1-d3)*d2); + + float cphi = (d1*d3-d2*d2)/((d1-d3)*d2); + float sphi[] = {aux_sphi, -aux_sphi, -aux_sphi, aux_sphi}; + + for(int i=0; i<4; i++) + { + cv::Mat Rp=cv::Mat::eye(3,3,CV_32F); + Rp.at(0,0)=cphi; + Rp.at(0,2)=sphi[i]; + Rp.at(1,1)=-1; + Rp.at(2,0)=sphi[i]; + Rp.at(2,2)=-cphi; + + cv::Mat R = s*U*Rp*Vt; + vR.push_back(R); + + cv::Mat tp(3,1,CV_32F); + tp.at(0)=x1[i]; + tp.at(1)=0; + tp.at(2)=x3[i]; + tp*=d1+d3; + + cv::Mat t = U*tp; + vt.push_back(t/cv::norm(t)); + + cv::Mat np(3,1,CV_32F); + np.at(0)=x1[i]; + np.at(1)=0; + np.at(2)=x3[i]; + + cv::Mat n = V*np; + if(n.at(2)<0) + n=-n; + vn.push_back(n); + } + + + int bestGood = 0; + int secondBestGood = 0; + int bestSolutionIdx = -1; + float bestParallax = -1; + vector bestP3D; + vector bestTriangulated; + + // Instead of applying the visibility constraints proposed in the Faugeras' paper (which could fail for points seen with low parallax) + // We reconstruct all hypotheses and check in terms of triangulated points and parallax + for(size_t i=0; i<8; i++) + { + float parallaxi; + vector vP3Di; + vector vbTriangulatedi; + int nGood = CheckRT(vR[i],vt[i],mvKeys1,mvKeys2,mvMatches12,vbMatchesInliers,K,vP3Di, 4.0*mSigma2, vbTriangulatedi, parallaxi); + + if(nGood>bestGood) + { + secondBestGood = bestGood; + bestGood = nGood; + bestSolutionIdx = i; + bestParallax = parallaxi; + bestP3D = vP3Di; + bestTriangulated = vbTriangulatedi; + } + else if(nGood>secondBestGood) + { + secondBestGood = nGood; + } + } + + + if(secondBestGood<0.75*bestGood && bestParallax>=minParallax && bestGood>minTriangulated && bestGood>0.9*N) + { + vR[bestSolutionIdx].copyTo(R21); + vt[bestSolutionIdx].copyTo(t21); + vP3D = bestP3D; + vbTriangulated = bestTriangulated; + + return true; + } + + return false; +} + +void TwoViewReconstruction::Triangulate(const cv::KeyPoint &kp1, const cv::KeyPoint &kp2, const cv::Mat &P1, const cv::Mat &P2, cv::Mat &x3D) +{ + cv::Mat A(4,4,CV_32F); + + A.row(0) = kp1.pt.x*P1.row(2)-P1.row(0); + A.row(1) = kp1.pt.y*P1.row(2)-P1.row(1); + A.row(2) = kp2.pt.x*P2.row(2)-P2.row(0); + A.row(3) = kp2.pt.y*P2.row(2)-P2.row(1); + + cv::Mat u,w,vt; + cv::SVD::compute(A,w,u,vt,cv::SVD::MODIFY_A| cv::SVD::FULL_UV); + x3D = vt.row(3).t(); + x3D = x3D.rowRange(0,3)/x3D.at(3); +} + +void TwoViewReconstruction::Normalize(const vector &vKeys, vector &vNormalizedPoints, cv::Mat &T) +{ + float meanX = 0; + float meanY = 0; + const int N = vKeys.size(); + + vNormalizedPoints.resize(N); + + for(int i=0; i(0,0) = sX; + T.at(1,1) = sY; + T.at(0,2) = -meanX*sX; + T.at(1,2) = -meanY*sY; +} + + +int TwoViewReconstruction::CheckRT(const cv::Mat &R, const cv::Mat &t, const vector &vKeys1, const vector &vKeys2, + const vector &vMatches12, vector &vbMatchesInliers, + const cv::Mat &K, vector &vP3D, float th2, vector &vbGood, float ¶llax) +{ + // Calibration parameters + const float fx = K.at(0,0); + const float fy = K.at(1,1); + const float cx = K.at(0,2); + const float cy = K.at(1,2); + + vbGood = vector(vKeys1.size(),false); + vP3D.resize(vKeys1.size()); + + vector vCosParallax; + vCosParallax.reserve(vKeys1.size()); + + // Camera 1 Projection Matrix K[I|0] + cv::Mat P1(3,4,CV_32F,cv::Scalar(0)); + K.copyTo(P1.rowRange(0,3).colRange(0,3)); + + cv::Mat O1 = cv::Mat::zeros(3,1,CV_32F); + + // Camera 2 Projection Matrix K[R|t] + cv::Mat P2(3,4,CV_32F); + R.copyTo(P2.rowRange(0,3).colRange(0,3)); + t.copyTo(P2.rowRange(0,3).col(3)); + P2 = K*P2; + + cv::Mat O2 = -R.t()*t; + + int nGood=0; + + for(size_t i=0, iend=vMatches12.size();i(0)) || !isfinite(p3dC1.at(1)) || !isfinite(p3dC1.at(2))) + { + vbGood[vMatches12[i].first]=false; + continue; + } + + // Check parallax + cv::Mat normal1 = p3dC1 - O1; + float dist1 = cv::norm(normal1); + + cv::Mat normal2 = p3dC1 - O2; + float dist2 = cv::norm(normal2); + + float cosParallax = normal1.dot(normal2)/(dist1*dist2); + + // Check depth in front of first camera (only if enough parallax, as "infinite" points can easily go to negative depth) + if(p3dC1.at(2)<=0 && cosParallax<0.99998) + continue; + + // Check depth in front of second camera (only if enough parallax, as "infinite" points can easily go to negative depth) + cv::Mat p3dC2 = R*p3dC1+t; + + if(p3dC2.at(2)<=0 && cosParallax<0.99998) + continue; + + // Check reprojection error in first image + float im1x, im1y; + float invZ1 = 1.0/p3dC1.at(2); + im1x = fx*p3dC1.at(0)*invZ1+cx; + im1y = fy*p3dC1.at(1)*invZ1+cy; + + float squareError1 = (im1x-kp1.pt.x)*(im1x-kp1.pt.x)+(im1y-kp1.pt.y)*(im1y-kp1.pt.y); + + if(squareError1>th2) + continue; + + // Check reprojection error in second image + float im2x, im2y; + float invZ2 = 1.0/p3dC2.at(2); + im2x = fx*p3dC2.at(0)*invZ2+cx; + im2y = fy*p3dC2.at(1)*invZ2+cy; + + float squareError2 = (im2x-kp2.pt.x)*(im2x-kp2.pt.x)+(im2y-kp2.pt.y)*(im2y-kp2.pt.y); + + if(squareError2>th2) + continue; + + vCosParallax.push_back(cosParallax); + vP3D[vMatches12[i].first] = cv::Point3f(p3dC1.at(0),p3dC1.at(1),p3dC1.at(2)); + nGood++; + + if(cosParallax<0.99998) + vbGood[vMatches12[i].first]=true; + } + + if(nGood>0) + { + sort(vCosParallax.begin(),vCosParallax.end()); + + size_t idx = min(50,int(vCosParallax.size()-1)); + parallax = acos(vCosParallax[idx])*180/CV_PI; + } + else + parallax=0; + + return nGood; +} + +void TwoViewReconstruction::DecomposeE(const cv::Mat &E, cv::Mat &R1, cv::Mat &R2, cv::Mat &t) +{ + cv::Mat u,w,vt; + cv::SVD::compute(E,w,u,vt); + + u.col(2).copyTo(t); + t=t/cv::norm(t); + + cv::Mat W(3,3,CV_32F,cv::Scalar(0)); + W.at(0,1)=-1; + W.at(1,0)=1; + W.at(2,2)=1; + + R1 = u*W*vt; + if(cv::determinant(R1)<0) + R1=-R1; + + R2 = u*W.t()*vt; + if(cv::determinant(R2)<0) + R2=-R2; +} + +} //namespace ORB_SLAM diff --git a/third_party/ORB_SLAM3/src/Viewer.cc b/third_party/ORB_SLAM3/src/Viewer.cc new file mode 100644 index 0000000..6ac81e1 --- /dev/null +++ b/third_party/ORB_SLAM3/src/Viewer.cc @@ -0,0 +1,406 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + + +#include "Viewer.h" +#include + +#include + +namespace ORB_SLAM3 +{ + +Viewer::Viewer(System* pSystem, FrameDrawer *pFrameDrawer, MapDrawer *pMapDrawer, Tracking *pTracking, const string &strSettingPath): + both(false), mpSystem(pSystem), mpFrameDrawer(pFrameDrawer),mpMapDrawer(pMapDrawer), mpTracker(pTracking), + mbFinishRequested(false), mbFinished(true), mbStopped(true), mbStopRequested(false) +{ + cv::FileStorage fSettings(strSettingPath, cv::FileStorage::READ); + + bool is_correct = ParseViewerParamFile(fSettings); + + if(!is_correct) + { + std::cerr << "**ERROR in the config file, the format is not correct**" << std::endl; + try + { + throw -1; + } + catch(exception &e) + { + + } + } + + mbStopTrack = false; +} + +bool Viewer::ParseViewerParamFile(cv::FileStorage &fSettings) +{ + bool b_miss_params = false; + + float fps = fSettings["Camera.fps"]; + if(fps<1) + fps=30; + mT = 1e3/fps; + + cv::FileNode node = fSettings["Camera.width"]; + if(!node.empty()) + { + mImageWidth = node.real(); + } + else + { + std::cerr << "*Camera.width parameter doesn't exist or is not a real number*" << std::endl; + b_miss_params = true; + } + + node = fSettings["Camera.height"]; + if(!node.empty()) + { + mImageHeight = node.real(); + } + else + { + std::cerr << "*Camera.height parameter doesn't exist or is not a real number*" << std::endl; + b_miss_params = true; + } + + node = fSettings["Viewer.ViewpointX"]; + if(!node.empty()) + { + mViewpointX = node.real(); + } + else + { + std::cerr << "*Viewer.ViewpointX parameter doesn't exist or is not a real number*" << std::endl; + b_miss_params = true; + } + + node = fSettings["Viewer.ViewpointY"]; + if(!node.empty()) + { + mViewpointY = node.real(); + } + else + { + std::cerr << "*Viewer.ViewpointY parameter doesn't exist or is not a real number*" << std::endl; + b_miss_params = true; + } + + node = fSettings["Viewer.ViewpointZ"]; + if(!node.empty()) + { + mViewpointZ = node.real(); + } + else + { + std::cerr << "*Viewer.ViewpointZ parameter doesn't exist or is not a real number*" << std::endl; + b_miss_params = true; + } + + node = fSettings["Viewer.ViewpointF"]; + if(!node.empty()) + { + mViewpointF = node.real(); + } + else + { + std::cerr << "*Viewer.ViewpointF parameter doesn't exist or is not a real number*" << std::endl; + b_miss_params = true; + } + + return !b_miss_params; +} + +void Viewer::Run() +{ + mbFinished = false; + mbStopped = false; + + pangolin::CreateWindowAndBind("ORB-SLAM3: Map Viewer",1024,768); + + // 3D Mouse handler requires depth testing to be enabled + glEnable(GL_DEPTH_TEST); + + // Issue specific OpenGl we might need + glEnable (GL_BLEND); + glBlendFunc (GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + pangolin::CreatePanel("menu").SetBounds(0.0,1.0,0.0,pangolin::Attach::Pix(175)); + pangolin::Var menuFollowCamera("menu.Follow Camera",true,true); + pangolin::Var menuCamView("menu.Camera View",false,false); + pangolin::Var menuTopView("menu.Top View",false,false); + // pangolin::Var menuSideView("menu.Side View",false,false); + pangolin::Var menuShowPoints("menu.Show Points",true,true); + pangolin::Var menuShowKeyFrames("menu.Show KeyFrames",true,true); + pangolin::Var menuShowGraph("menu.Show Graph",false,true); + pangolin::Var menuShowInertialGraph("menu.Show Inertial Graph",true,true); + pangolin::Var menuLocalizationMode("menu.Localization Mode",false,true); + pangolin::Var menuReset("menu.Reset",false,false); + pangolin::Var menuStepByStep("menu.Step By Step",false,true); // false, true + pangolin::Var menuStep("menu.Step",false,false); + + // Define Camera Render Object (for view / scene browsing) + pangolin::OpenGlRenderState s_cam( + pangolin::ProjectionMatrix(1024,768,mViewpointF,mViewpointF,512,389,0.1,1000), + pangolin::ModelViewLookAt(mViewpointX,mViewpointY,mViewpointZ, 0,0,0,0.0,-1.0, 0.0) + ); + + // Add named OpenGL viewport to window and provide 3D Handler + pangolin::View& d_cam = pangolin::CreateDisplay() + .SetBounds(0.0, 1.0, pangolin::Attach::Pix(175), 1.0, -1024.0f/768.0f) + .SetHandler(new pangolin::Handler3D(s_cam)); + + pangolin::OpenGlMatrix Twc, Twr; + Twc.SetIdentity(); + pangolin::OpenGlMatrix Ow; // Oriented with g in the z axis + Ow.SetIdentity(); + pangolin::OpenGlMatrix Twwp; // Oriented with g in the z axis, but y and x from camera + Twwp.SetIdentity(); + cv::namedWindow("ORB-SLAM3: Current Frame"); + + bool bFollow = true; + bool bLocalizationMode = false; + bool bStepByStep = false; + bool bCameraView = true; + + if(mpTracker->mSensor == mpSystem->MONOCULAR || mpTracker->mSensor == mpSystem->STEREO || mpTracker->mSensor == mpSystem->RGBD) + { + menuShowGraph = true; + } + + while(1) + { + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + + mpMapDrawer->GetCurrentOpenGLCameraMatrix(Twc,Ow,Twwp); + + if(mbStopTrack) + { + menuStepByStep = true; + mbStopTrack = false; + } + + if(menuFollowCamera && bFollow) + { + if(bCameraView) + s_cam.Follow(Twc); + else + s_cam.Follow(Ow); + } + else if(menuFollowCamera && !bFollow) + { + if(bCameraView) + { + s_cam.SetProjectionMatrix(pangolin::ProjectionMatrix(1024,768,mViewpointF,mViewpointF,512,389,0.1,1000)); + s_cam.SetModelViewMatrix(pangolin::ModelViewLookAt(mViewpointX,mViewpointY,mViewpointZ, 0,0,0,0.0,-1.0, 0.0)); + s_cam.Follow(Twc); + } + else + { + s_cam.SetProjectionMatrix(pangolin::ProjectionMatrix(1024,768,3000,3000,512,389,0.1,1000)); + s_cam.SetModelViewMatrix(pangolin::ModelViewLookAt(0,0.01,10, 0,0,0,0.0,0.0, 1.0)); + s_cam.Follow(Ow); + } + bFollow = true; + } + else if(!menuFollowCamera && bFollow) + { + bFollow = false; + } + + if(menuCamView) + { + menuCamView = false; + bCameraView = true; + s_cam.SetProjectionMatrix(pangolin::ProjectionMatrix(1024,768,mViewpointF,mViewpointF,512,389,0.1,10000)); + s_cam.SetModelViewMatrix(pangolin::ModelViewLookAt(mViewpointX,mViewpointY,mViewpointZ, 0,0,0,0.0,-1.0, 0.0)); + s_cam.Follow(Twc); + } + + if(menuTopView && mpMapDrawer->mpAtlas->isImuInitialized()) + { + menuTopView = false; + bCameraView = false; + /*s_cam.SetProjectionMatrix(pangolin::ProjectionMatrix(1024,768,3000,3000,512,389,0.1,1000)); + s_cam.SetModelViewMatrix(pangolin::ModelViewLookAt(0,0.01,10, 0,0,0,0.0,0.0, 1.0));*/ + s_cam.SetProjectionMatrix(pangolin::ProjectionMatrix(1024,768,3000,3000,512,389,0.1,10000)); + s_cam.SetModelViewMatrix(pangolin::ModelViewLookAt(0,0.01,50, 0,0,0,0.0,0.0, 1.0)); + s_cam.Follow(Ow); + } + + /*if(menuSideView && mpMapDrawer->mpAtlas->isImuInitialized()) + { + s_cam.SetProjectionMatrix(pangolin::ProjectionMatrix(1024,768,3000,3000,512,389,0.1,10000)); + s_cam.SetModelViewMatrix(pangolin::ModelViewLookAt(0.0,0.1,30.0,0,0,0,0.0,0.0,1.0)); + s_cam.Follow(Twwp); + }*/ + + + if(menuLocalizationMode && !bLocalizationMode) + { + mpSystem->ActivateLocalizationMode(); + bLocalizationMode = true; + } + else if(!menuLocalizationMode && bLocalizationMode) + { + mpSystem->DeactivateLocalizationMode(); + bLocalizationMode = false; + } + + if(menuStepByStep && !bStepByStep) + { + mpTracker->SetStepByStep(true); + bStepByStep = true; + } + else if(!menuStepByStep && bStepByStep) + { + mpTracker->SetStepByStep(false); + bStepByStep = false; + } + + if(menuStep) + { + mpTracker->mbStep = true; + menuStep = false; + } + + + d_cam.Activate(s_cam); + glClearColor(1.0f,1.0f,1.0f,1.0f); + mpMapDrawer->DrawCurrentCamera(Twc); + if(menuShowKeyFrames || menuShowGraph || menuShowInertialGraph) + mpMapDrawer->DrawKeyFrames(menuShowKeyFrames,menuShowGraph, menuShowInertialGraph); + if(menuShowPoints) + mpMapDrawer->DrawMapPoints(); + + pangolin::FinishFrame(); + + cv::Mat toShow; + cv::Mat im = mpFrameDrawer->DrawFrame(true); + + if(both){ + cv::Mat imRight = mpFrameDrawer->DrawRightFrame(); + cv::hconcat(im,imRight,toShow); + } + else{ + toShow = im; + } + + cv::imshow("ORB-SLAM3: Current Frame",toShow); + cv::waitKey(mT); + + if(menuReset) + { + menuShowGraph = true; + menuShowInertialGraph = true; + menuShowKeyFrames = true; + menuShowPoints = true; + menuLocalizationMode = false; + if(bLocalizationMode) + mpSystem->DeactivateLocalizationMode(); + bLocalizationMode = false; + bFollow = true; + menuFollowCamera = true; + //mpSystem->Reset(); + mpSystem->ResetActiveMap(); + menuReset = false; + } + + if(Stop()) + { + while(isStopped()) + { + usleep(3000); + } + } + + if(CheckFinish()) + break; + } + + SetFinish(); +} + +void Viewer::RequestFinish() +{ + unique_lock lock(mMutexFinish); + mbFinishRequested = true; +} + +bool Viewer::CheckFinish() +{ + unique_lock lock(mMutexFinish); + return mbFinishRequested; +} + +void Viewer::SetFinish() +{ + unique_lock lock(mMutexFinish); + mbFinished = true; +} + +bool Viewer::isFinished() +{ + unique_lock lock(mMutexFinish); + return mbFinished; +} + +void Viewer::RequestStop() +{ + unique_lock lock(mMutexStop); + if(!mbStopped) + mbStopRequested = true; +} + +bool Viewer::isStopped() +{ + unique_lock lock(mMutexStop); + return mbStopped; +} + +bool Viewer::Stop() +{ + unique_lock lock(mMutexStop); + unique_lock lock2(mMutexFinish); + + if(mbFinishRequested) + return false; + else if(mbStopRequested) + { + mbStopped = true; + mbStopRequested = false; + return true; + } + + return false; + +} + +void Viewer::Release() +{ + unique_lock lock(mMutexStop); + mbStopped = false; +} + +void Viewer::SetTrackingPause() +{ + mbStopTrack = true; +} + +} diff --git a/third_party/ORB_SLAM3/tum_vi_eval_examples.sh b/third_party/ORB_SLAM3/tum_vi_eval_examples.sh new file mode 100755 index 0000000..111f658 --- /dev/null +++ b/third_party/ORB_SLAM3/tum_vi_eval_examples.sh @@ -0,0 +1,11 @@ +#!/bin/bash +pathDatasetTUM_VI='/Datasets/TUM_VI' #Example, it is necesary to change it by the dataset path + + +# Single Session Example + +echo "Launching Magistrale 1 with Stereo-Inertial sensor" +./Examples/Stereo-Inertial/stereo_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Stereo-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-magistrale1_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-magistrale1_512_16/mav0/cam1/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-magistrale1_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-magistrale1_512.txt dataset-magistrale1_512_stereoi +echo "------------------------------------" +echo "Evaluation of Magistrale 1 trajectory with Stereo-Inertial sensor" +python evaluation/evaluate_ate_scale.py "$pathDatasetTUM_VI"/magistrale1_512_16/mav0/mocap0/data.csv f_dataset-magistrale1_512_stereoi.txt --plot magistrale1_512_stereoi.pdf diff --git a/third_party/ORB_SLAM3/tum_vi_examples.sh b/third_party/ORB_SLAM3/tum_vi_examples.sh new file mode 100755 index 0000000..be06314 --- /dev/null +++ b/third_party/ORB_SLAM3/tum_vi_examples.sh @@ -0,0 +1,240 @@ +#!/bin/bash +pathDatasetTUM_VI='/Datasets/TUM_VI' #Example, it is necesary to change it by the dataset path + +#------------------------------------ +# Monocular Examples +echo "Launching Room 1 with Monocular sensor" +./Examples/Monocular/mono_tum_vi Vocabulary/ORBvoc.txt Examples/Monocular/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room1_512_16/mav0/cam0/data Examples/Monocular/TUM_TimeStamps/dataset-room1_512.txt dataset-room1_512_mono + +echo "Launching Room 2 with Monocular sensor" +./Examples/Monocular/mono_tum_vi Vocabulary/ORBvoc.txt Examples/Monocular/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room2_512_16/mav0/cam0/data Examples/Monocular/TUM_TimeStamps/dataset-room2_512.txt dataset-room2_512_mono + +echo "Launching Room 3 with Monocular sensor" +./Examples/Monocular/mono_tum_vi Vocabulary/ORBvoc.txt Examples/Monocular/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room3_512_16/mav0/cam0/data Examples/Monocular/TUM_TimeStamps/dataset-room3_512.txt dataset-room3_512_mono + +echo "Launching Room 4 with Monocular sensor" +./Examples/Monocular/mono_tum_vi Vocabulary/ORBvoc.txt Examples/Monocular/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room4_512_16/mav0/cam0/data Examples/Monocular/TUM_TimeStamps/dataset-room4_512.txt dataset-room4_512_mono + +echo "Launching Room 5 with Monocular sensor" +./Examples/Monocular/mono_tum_vi Vocabulary/ORBvoc.txt Examples/Monocular/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room5_512_16/mav0/cam0/data Examples/Monocular/TUM_TimeStamps/dataset-room5_512.txt dataset-room5_512_mono + +echo "Launching Room 6 with Monocular sensor" +./Examples/Monocular/mono_tum_vi Vocabulary/ORBvoc.txt Examples/Monocular/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room6_512_16/mav0/cam0/data Examples/Monocular/TUM_TimeStamps/dataset-room6_512.txt dataset-room6_512_mono + + +#------------------------------------ +# Stereo Examples +echo "Launching Room 1 with Stereo sensor" +./Examples/Stereo/stereo_tum_vi Vocabulary/ORBvoc.txt Examples/Stereo/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room1_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-room1_512_16/mav0/cam1/data Examples/Stereo/TUM_TimeStamps/dataset-room1_512.txt dataset-room1_512_stereo + +echo "Launching Room 2 with Stereo sensor" +./Examples/Stereo/stereo_tum_vi Vocabulary/ORBvoc.txt Examples/Stereo/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room2_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-room2_512_16/mav0/cam1/data Examples/Stereo/TUM_TimeStamps/dataset-room2_512.txt dataset-room2_512_stereo + +echo "Launching Room 3 with Stereo sensor" +./Examples/Stereo/stereo_tum_vi Vocabulary/ORBvoc.txt Examples/Stereo/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room3_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-room3_512_16/mav0/cam1/data Examples/Stereo/TUM_TimeStamps/dataset-room3_512.txt dataset-room3_512_stereo + +echo "Launching Room 4 with Stereo sensor" +./Examples/Stereo/stereo_tum_vi Vocabulary/ORBvoc.txt Examples/Stereo/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room4_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-room4_512_16/mav0/cam1/data Examples/Stereo/TUM_TimeStamps/dataset-room4_512.txt dataset-room4_512_stereo + +echo "Launching Room 5 with Stereo sensor" +./Examples/Stereo/stereo_tum_vi Vocabulary/ORBvoc.txt Examples/Stereo/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room5_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-room5_512_16/mav0/cam1/data Examples/Stereo/TUM_TimeStamps/dataset-room5_512.txt dataset-room5_512_stereo + +echo "Launching Room 6 with Stereo sensor" +./Examples/Stereo/stereo_tum_vi Vocabulary/ORBvoc.txt Examples/Stereo/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room6_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-room6_512_16/mav0/cam1/data Examples/Stereo/TUM_TimeStamps/dataset-room6_512.txt dataset-room6_512_stereo + + +#------------------------------------ +# Monocular-Inertial Examples +echo "Launching Corridor 1 with Monocular-Inertial sensor" +./Examples/Monocular-Inertial/mono_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Monocular-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-corridor1_512_16/mav0/cam0/data Examples/Monocular-Inertial/TUM_TimeStamps/dataset-corridor1_512.txt Examples/Monocular-Inertial/TUM_IMU/dataset-corridor1_512.txt dataset-corridor1_512_monoi + +echo "Launching Corridor 2 with Monocular-Inertial sensor" +./Examples/Monocular-Inertial/mono_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Monocular-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-corridor2_512_16/mav0/cam0/data Examples/Monocular-Inertial/TUM_TimeStamps/dataset-corridor2_512.txt Examples/Monocular-Inertial/TUM_IMU/dataset-corridor2_512.txt dataset-corridor2_512_monoi + +echo "Launching Corridor 3 with Monocular-Inertial sensor" +./Examples/Monocular-Inertial/mono_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Monocular-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-corridor3_512_16/mav0/cam0/data Examples/Monocular-Inertial/TUM_TimeStamps/dataset-corridor3_512.txt Examples/Monocular-Inertial/TUM_IMU/dataset-corridor3_512.txt dataset-corridor3_512_monoi + +echo "Launching Corridor 4 with Monocular-Inertial sensor" +./Examples/Monocular-Inertial/mono_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Monocular-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-corridor4_512_16/mav0/cam0/data Examples/Monocular-Inertial/TUM_TimeStamps/dataset-corridor4_512.txt Examples/Monocular-Inertial/TUM_IMU/dataset-corridor4_512.txt dataset-corridor4_512_monoi + +echo "Launching Corridor 5 with Monocular-Inertial sensor" +./Examples/Monocular-Inertial/mono_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Monocular-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-corridor5_512_16/mav0/cam0/data Examples/Monocular-Inertial/TUM_TimeStamps/dataset-corridor5_512.txt Examples/Monocular-Inertial/TUM_IMU/dataset-corridor5_512.txt dataset-corridor5_512_monoi + + +echo "Launching Magistrale 1 with Monocular-Inertial sensor" +./Examples/Monocular-Inertial/mono_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Monocular-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-magistrale1_512_16/mav0/cam0/data Examples/Monocular-Inertial/TUM_TimeStamps/dataset-magistrale1_512.txt Examples/Monocular-Inertial/TUM_IMU/dataset-magistrale1_512.txt dataset-magistrale1_512_monoi + +echo "Launching Magistrale 2 with Monocular-Inertial sensor" +./Examples/Monocular-Inertial/mono_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Monocular-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-magistrale2_512_16/mav0/cam0/data Examples/Monocular-Inertial/TUM_TimeStamps/dataset-magistrale2_512.txt Examples/Monocular-Inertial/TUM_IMU/dataset-magistrale2_512.txt dataset-magistrale2_512 + +echo "Launching Magistrale 3 with Monocular-Inertial sensor" +./Examples/Monocular-Inertial/mono_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Monocular-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-magistrale3_512_16/mav0/cam0/data Examples/Monocular-Inertial/TUM_TimeStamps/dataset-magistrale3_512.txt Examples/Monocular-Inertial/TUM_IMU/dataset-magistrale3_512.txt dataset-magistrale3_512_monoi + +echo "Launching Magistrale 4 with Monocular-Inertial sensor" +./Examples/Monocular-Inertial/mono_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Monocular-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-magistrale4_512_16/mav0/cam0/data Examples/Monocular-Inertial/TUM_TimeStamps/dataset-magistrale4_512.txt Examples/Monocular-Inertial/TUM_IMU/dataset-magistrale4_512.txt dataset-magistrale4_512_monoi + +echo "Launching Magistrale 5 with Monocular-Inertial sensor" +./Examples/Monocular-Inertial/mono_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Monocular-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-magistrale5_512_16/mav0/cam0/data Examples/Monocular-Inertial/TUM_TimeStamps/dataset-magistrale5_512.txt Examples/Monocular-Inertial/TUM_IMU/dataset-magistrale5_512.txt dataset-magistrale5_512_monoi + +echo "Launching Magistrale 6 with Monocular-Inertial sensor" +./Examples/Monocular-Inertial/mono_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Monocular-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-magistrale6_512_16/mav0/cam0/data Examples/Monocular-Inertial/TUM_TimeStamps/dataset-magistrale6_512.txt Examples/Monocular-Inertial/TUM_IMU/dataset-magistrale6_512.txt dataset-magistrale6_512_monoi + + +echo "Launching Outdoor 1 with Monocular-Inertial sensor" +./Examples/Monocular-Inertial/mono_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Monocular-Inertial/TUM_512_far.yaml "$pathDatasetTUM_VI"/dataset-outdoors1_512_16/mav0/cam0/data Examples/Monocular-Inertial/TUM_TimeStamps/dataset-outdoors1_512.txt Examples/Monocular-Inertial/TUM_IMU/dataset-outdoors1_512.txt dataset-outdoors1_512_monoi + +echo "Launching Outdoor 2 with Monocular-Inertial sensor" +./Examples/Monocular-Inertial/mono_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Monocular-Inertial/TUM_512_far.yaml "$pathDatasetTUM_VI"/dataset-outdoors2_512_16/mav0/cam0/data Examples/Monocular-Inertial/TUM_TimeStamps/dataset-outdoors2_512.txt Examples/Monocular-Inertial/TUM_IMU/dataset-outdoors2_512.txt dataset-outdoors2_512_monoi + +echo "Launching Outdoor 3 with Monocular-Inertial sensor" +./Examples/Monocular-Inertial/mono_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Monocular-Inertial/TUM_512_far.yaml "$pathDatasetTUM_VI"/dataset-outdoors3_512_16/mav0/cam0/data Examples/Monocular-Inertial/TUM_TimeStamps/dataset-outdoors3_512.txt Examples/Monocular-Inertial/TUM_IMU/dataset-outdoors3_512.txt dataset-outdoors3_512_monoi + +echo "Launching Outdoor 4 with Monocular-Inertial sensor" +./Examples/Monocular-Inertial/mono_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Monocular-Inertial/TUM_512_far.yaml "$pathDatasetTUM_VI"/dataset-outdoors4_512_16/mav0/cam0/data Examples/Monocular-Inertial/TUM_TimeStamps/dataset-outdoors4_512.txt Examples/Monocular-Inertial/TUM_IMU/dataset-outdoors4_512.txt dataset-outdoors4_512_monoi + +echo "Launching Outdoor 5 with Monocular-Inertial sensor" +./Examples/Monocular-Inertial/mono_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Monocular-Inertial/TUM_512_far.yaml "$pathDatasetTUM_VI"/dataset-outdoors5_512_16/mav0/cam0/data Examples/Monocular-Inertial/TUM_TimeStamps/dataset-outdoors5_512.txt Examples/Monocular-Inertial/TUM_IMU/dataset-outdoors5_512.txt dataset-outdoors5_512_monoi + +echo "Launching Outdoor 6 with Monocular-Inertial sensor" +./Examples/Monocular-Inertial/mono_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Monocular-Inertial/TUM_512_far.yaml "$pathDatasetTUM_VI"/dataset-outdoors6_512_16/mav0/cam0/data Examples/Monocular-Inertial/TUM_TimeStamps/dataset-outdoors6_512.txt Examples/Monocular-Inertial/TUM_IMU/dataset-outdoors6_512.txt dataset-outdoors6_512_monoi + +echo "Launching Outdoor 7 with Monocular-Inertial sensor" +./Examples/Monocular-Inertial/mono_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Monocular-Inertial/TUM_512_far.yaml "$pathDatasetTUM_VI"/dataset-outdoors7_512_16/mav0/cam0/data Examples/Monocular-Inertial/TUM_TimeStamps/dataset-outdoors7_512.txt Examples/Monocular-Inertial/TUM_IMU/dataset-outdoors7_512.txt dataset-outdoors7_512_monoi + +echo "Launching Outdoor 8 with Monocular-Inertial sensor" +./Examples/Monocular-Inertial/mono_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Monocular-Inertial/TUM_512_far.yaml "$pathDatasetTUM_VI"/dataset-outdoors8_512_16/mav0/cam0/data Examples/Monocular-Inertial/TUM_TimeStamps/dataset-outdoors8_512.txt Examples/Monocular-Inertial/TUM_IMU/dataset-outdoors8_512.txt dataset-outdoors8_512_monoi + + +echo "Launching Room 1 with Monocular-Inertial sensor" +./Examples/Monocular-Inertial/mono_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Monocular-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room1_512_16/mav0/cam0/data Examples/Monocular-Inertial/TUM_TimeStamps/dataset-room1_512.txt Examples/Monocular-Inertial/TUM_IMU/dataset-room1_512.txt dataset-room1_512_monoi + +echo "Launching Room 2 with Monocular-Inertial sensor" +./Examples/Monocular-Inertial/mono_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Monocular-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room2_512_16/mav0/cam0/data Examples/Monocular-Inertial/TUM_TimeStamps/dataset-room2_512.txt Examples/Monocular-Inertial/TUM_IMU/dataset-room2_512.txt dataset-room2_512_monoi + +echo "Launching Room 3 with Monocular-Inertial sensor" +./Examples/Monocular-Inertial/mono_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Monocular-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room3_512_16/mav0/cam0/data Examples/Monocular-Inertial/TUM_TimeStamps/dataset-room3_512.txt Examples/Monocular-Inertial/TUM_IMU/dataset-room3_512.txt dataset-room3_512_monoi + +echo "Launching Room 4 with Monocular-Inertial sensor" +./Examples/Monocular-Inertial/mono_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Monocular-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room4_512_16/mav0/cam0/data Examples/Monocular-Inertial/TUM_TimeStamps/dataset-room4_512.txt Examples/Monocular-Inertial/TUM_IMU/dataset-room4_512.txt dataset-room4_512_monoi + +echo "Launching Room 5 with Monocular-Inertial sensor" +./Examples/Monocular-Inertial/mono_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Monocular-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room5_512_16/mav0/cam0/data Examples/Monocular-Inertial/TUM_TimeStamps/dataset-room5_512.txt Examples/Monocular-Inertial/TUM_IMU/dataset-room5_512.txt dataset-room5_512_monoi + +echo "Launching Room 6 with Monocular-Inertial sensor" +./Examples/Monocular-Inertial/mono_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Monocular-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room6_512_16/mav0/cam0/data Examples/Monocular-Inertial/TUM_TimeStamps/dataset-room6_512.txt Examples/Monocular-Inertial/TUM_IMU/dataset-room6_512.txt dataset-room6_512_monoi + + +echo "Launching Slides 1 with Monocular-Inertial sensor" +./Examples/Monocular-Inertial/mono_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Monocular-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-slides1_512_16/mav0/cam0/data Examples/Monocular-Inertial/TUM_TimeStamps/dataset-slides1_512.txt Examples/Monocular-Inertial/TUM_IMU/dataset-slides1_512.txt dataset-slides1_512_monoi + +echo "Launching Slides 2 with Monocular-Inertial sensor" +./Examples/Monocular-Inertial/mono_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Monocular-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-slides2_512_16/mav0/cam0/data Examples/Monocular-Inertial/TUM_TimeStamps/dataset-slides2_512.txt Examples/Monocular-Inertial/TUM_IMU/dataset-slides2_512.txt dataset-slides2_512_monoi + +echo "Launching Slides 3 with Monocular-Inertial sensor" +./Examples/Monocular-Inertial/mono_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Monocular-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-slides3_512_16/mav0/cam0/data Examples/Monocular-Inertial/TUM_TimeStamps/dataset-slides3_512.txt Examples/Monocular-Inertial/TUM_IMU/dataset-slides3_512.txt dataset-slides3_512_monoi + + +# MultiSession Monocular Examples +echo "Launching Room 1, Magistrale 1, Magistrale 5 and Slides 1 in the same session with Stereo-Inertial sensor" +./Examples/Monocular-Inertial/mono_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Monocular-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room1_512_16/mav0/cam0/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-room1_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-room1_512.txt "$pathDatasetTUM_VI"/dataset-magistrale1_512_16/mav0/cam0/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-magistrale1_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-magistrale1_512.txt "$pathDatasetTUM_VI"/dataset-magistrale5_512_16/mav0/cam0/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-magistrale5_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-magistrale5_512.txt "$pathDatasetTUM_VI"/dataset-slides1_512_16/mav0/cam0/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-slides1_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-slides1_512.txt dataset-room1_mag1_mag5_slides1_monoi + +echo "Launching all Rooms (1-6) in the same session with Stereo-Inertial sensor" +./Examples/Monocular-Inertial/mono_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Monocular-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room1_512_16/mav0/cam0/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-room1_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-room1_512.txt "$pathDatasetTUM_VI"/dataset-room2_512_16/mav0/cam0/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-room2_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-room2_512.txt "$pathDatasetTUM_VI"/dataset-room3_512_16/mav0/cam0/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-room3_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-room3_512.txt "$pathDatasetTUM_VI"/dataset-room4_512_16/mav0/cam0/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-room4_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-room4_512.txt "$pathDatasetTUM_VI"/dataset-room5_512_16/mav0/cam0/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-room5_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-room5_512.txt "$pathDatasetTUM_VI"/dataset-room6_512_16/mav0/cam0/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-room6_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-room6_512.txt dataset-rooms123456_monoi + +#------------------------------------ +# Stereo-Inertial Examples +echo "Launching Corridor 1 with Stereo-Inertial sensor" +./Examples/Stereo-Inertial/stereo_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Stereo-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-corridor1_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-corridor1_512_16/mav0/cam1/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-corridor1_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-corridor1_512.txt dataset-corridor1_512_stereoi + +echo "Launching Corridor 2 with Stereo-Inertial sensor" +./Examples/Stereo-Inertial/stereo_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Stereo-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-corridor2_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-corridor2_512_16/mav0/cam1/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-corridor2_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-corridor2_512.txt dataset-corridor2_512_stereoi + +echo "Launching Corridor 3 with Stereo-Inertial sensor" +./Examples/Stereo-Inertial/stereo_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Stereo-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-corridor3_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-corridor3_512_16/mav0/cam1/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-corridor3_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-corridor3_512.txt dataset-corridor3_512_stereoi + +echo "Launching Corridor 4 with Stereo-Inertial sensor" +./Examples/Stereo-Inertial/stereo_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Stereo-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-corridor4_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-corridor4_512_16/mav0/cam1/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-corridor4_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-corridor4_512.txt dataset-corridor4_512_stereoi + +echo "Launching Corridor 5 with Stereo-Inertial sensor" +./Examples/Stereo-Inertial/stereo_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Stereo-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-corridor5_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-corridor5_512_16/mav0/cam1/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-corridor5_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-corridor5_512.txt dataset-corridor5_512_stereoi + + +echo "Launching Magistrale 1 with Stereo-Inertial sensor" +./Examples/Stereo-Inertial/stereo_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Stereo-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-magistrale1_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-magistrale1_512_16/mav0/cam1/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-magistrale1_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-magistrale1_512.txt dataset-magistrale1_512_stereoi + +echo "Launching Magistrale 2 with Stereo-Inertial sensor" +./Examples/Stereo-Inertial/stereo_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Stereo-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-magistrale2_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-magistrale2_512_16/mav0/cam1/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-magistrale2_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-magistrale2_512.txt dataset-magistrale2_512_stereoi + +echo "Launching Magistrale 3 with Stereo-Inertial sensor" +./Examples/Stereo-Inertial/stereo_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Stereo-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-magistrale3_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-magistrale3_512_16/mav0/cam1/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-magistrale3_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-magistrale3_512.txt dataset-magistrale3_512_stereoi + +echo "Launching Magistrale 4 with Stereo-Inertial sensor" +./Examples/Stereo-Inertial/stereo_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Stereo-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-magistrale4_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-magistrale4_512_16/mav0/cam1/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-magistrale4_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-magistrale4_512.txt dataset-magistrale4_512_stereoi + +echo "Launching Magistrale 5 with Stereo-Inertial sensor" +./Examples/Stereo-Inertial/stereo_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Stereo-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-magistrale5_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-magistrale5_512_16/mav0/cam1/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-magistrale5_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-magistrale5_512.txt dataset-magistrale5_512_stereoi + +echo "Launching Magistrale 6 with Stereo-Inertial sensor" +./Examples/Stereo-Inertial/stereo_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Stereo-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-magistrale6_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-magistrale6_512_16/mav0/cam1/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-magistrale6_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-magistrale6_512.txt dataset-magistrale6_512_stereoi + + +echo "Launching Outdoor 1 with Stereo-Inertial sensor" +./Examples/Stereo-Inertial/stereo_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Stereo-Inertial/TUM_512_outdoors.yaml "$pathDatasetTUM_VI"/dataset-outdoors1_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-outdoors1_512_16/mav0/cam1/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-outdoors1_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-outdoors1_512.txt outdoors1_512_stereoi + +echo "Launching Outdoor 2 with Stereo-Inertial sensor" +./Examples/Stereo-Inertial/stereo_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Stereo-Inertial/TUM_512_outdoors.yaml "$pathDatasetTUM_VI"/dataset-outdoors2_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-outdoors2_512_16/mav0/cam1/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-outdoors2_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-outdoors2_512.txt outdoors2_512_stereoi + +echo "Launching Outdoor 3 with Stereo-Inertial sensor" +./Examples/Stereo-Inertial/stereo_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Stereo-Inertial/TUM_512_outdoors.yaml "$pathDatasetTUM_VI"/dataset-outdoors3_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-outdoors3_512_16/mav0/cam1/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-outdoors3_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-outdoors3_512.txt outdoors3_512 + +echo "Launching Outdoor 4 with Stereo-Inertial sensor" +./Examples/Stereo-Inertial/stereo_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Stereo-Inertial/TUM_512_outdoors.yaml "$pathDatasetTUM_VI"/dataset-outdoors4_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-outdoors4_512_16/mav0/cam1/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-outdoors4_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-outdoors4_512.txt outdoors4_512 + +echo "Launching Outdoor 5 with Stereo-Inertial sensor" +./Examples/Stereo-Inertial/stereo_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Stereo-Inertial/TUM_512_outdoors.yaml "$pathDatasetTUM_VI"/dataset-outdoors5_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-outdoors5_512_16/mav0/cam1/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-outdoors5_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-outdoors5_512.txt outdoors5_512_stereoi + +echo "Launching Outdoor 6 with Stereo-Inertial sensor" +./Examples/Stereo-Inertial/stereo_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Stereo-Inertial/TUM_512_outdoors.yaml "$pathDatasetTUM_VI"/dataset-outdoors6_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-outdoors6_512_16/mav0/cam1/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-outdoors6_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-outdoors6_512.txt outdoors6_512_stereoi + +echo "Launching Outdoor 7 with Stereo-Inertial sensor" +./Examples/Stereo-Inertial/stereo_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Stereo-Inertial/TUM_512_outdoors.yaml "$pathDatasetTUM_VI"/dataset-outdoors7_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-outdoors7_512_16/mav0/cam1/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-outdoors7_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-outdoors7_512.txt outdoors7_512_stereoi + +echo "Launching Outdoor 8 with Stereo-Inertial sensor" +./Examples/Stereo-Inertial/stereo_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Stereo-Inertial/TUM_512_outdoors.yaml "$pathDatasetTUM_VI"/dataset-outdoors8_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-outdoors8_512_16/mav0/cam1/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-outdoors8_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-outdoors8_512.txt outdoors8_512_stereoi + + +echo "Launching Room 1 with Stereo-Inertial sensor" +./Examples/Stereo-Inertial/stereo_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Stereo-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room1_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-room1_512_16/mav0/cam1/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-room1_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-room1_512.txt dataset-room1_512_stereoi + +echo "Launching Room 2 with Stereo-Inertial sensor" +./Examples/Stereo-Inertial/stereo_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Stereo-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room2_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-room2_512_16/mav0/cam1/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-room2_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-room2_512.txt dataset-room2_512_stereoi + +echo "Launching Room 3 with Stereo-Inertial sensor" +./Examples/Stereo-Inertial/stereo_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Stereo-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room3_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-room3_512_16/mav0/cam1/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-room3_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-room3_512.txt dataset-room3_512_stereoi + +echo "Launching Room 4 with Stereo-Inertial sensor" +./Examples/Stereo-Inertial/stereo_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Stereo-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room4_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-room4_512_16/mav0/cam1/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-room4_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-room4_512.txt dataset-room4_512_stereoi + +echo "Launching Room 5 with Stereo-Inertial sensor" +./Examples/Stereo-Inertial/stereo_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Stereo-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room5_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-room5_512_16/mav0/cam1/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-room5_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-room5_512.txt dataset-room5_512_stereoi + +echo "Launching Room 6 with Stereo-Inertial sensor" +./Examples/Stereo-Inertial/stereo_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Stereo-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room6_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-room6_512_16/mav0/cam1/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-room6_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-room6_512.txt dataset-room6_512_stereoi + + +echo "Launching Slides 1 with Stereo-Inertial sensor" +./Examples/Stereo-Inertial/stereo_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Stereo-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-slides1_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-slides1_512_16/mav0/cam1/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-slides1_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-slides1_512.txt dataset-slides1_512_stereoi + +echo "Launching Slides 2 with Stereo-Inertial sensor" +./Examples/Stereo-Inertial/stereo_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Stereo-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-slides2_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-slides2_512_16/mav0/cam1/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-slides2_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-slides2_512.txt dataset-slides2_512_stereoi + +echo "Launching Slides 3 with Stereo-Inertial sensor" +./Examples/Stereo-Inertial/stereo_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Stereo-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-slides3_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-slides3_512_16/mav0/cam1/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-slides3_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-slides3_512.txt dataset-slides3_512_stereoi + + +# MultiSession Stereo-Inertial Examples +echo "Launching Room 1, Magistrale 1, Magistrale 5 and Slides 1 in the same session with Stereo-Inertial sensor" +./Examples/Stereo-Inertial/stereo_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Stereo-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room1_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-room1_512_16/mav0/cam1/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-room1_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-room1_512.txt "$pathDatasetTUM_VI"/dataset-magistrale1_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-magistrale1_512_16/mav0/cam1/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-magistrale1_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-magistrale1_512.txt "$pathDatasetTUM_VI"/dataset-magistrale5_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-magistrale5_512_16/mav0/cam1/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-magistrale5_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-magistrale5_512.txt "$pathDatasetTUM_VI"/dataset-slides1_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-slides1_512_16/mav0/cam1/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-slides1_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-slides1_512.txt dataset-room1_mag1_mag5_slides1_stereoi + +echo "Launching all Rooms (1-6) in the same session with Stereo-Inertial sensor" +./Examples/Stereo-Inertial/stereo_inertial_tum_vi Vocabulary/ORBvoc.txt Examples/Stereo-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room1_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-room1_512_16/mav0/cam1/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-room1_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-room1_512.txt "$pathDatasetTUM_VI"/dataset-room2_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-room2_512_16/mav0/cam1/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-room2_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-room2_512.txt "$pathDatasetTUM_VI"/dataset-room3_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-room3_512_16/mav0/cam1/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-room3_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-room3_512.txt "$pathDatasetTUM_VI"/dataset-room4_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-room4_512_16/mav0/cam1/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-room4_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-room4_512.txt "$pathDatasetTUM_VI"/dataset-room5_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-room5_512_16/mav0/cam1/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-room5_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-room5_512.txt "$pathDatasetTUM_VI"/dataset-room6_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-room6_512_16/mav0/cam1/data Examples/Stereo-Inertial/TUM_TimeStamps/dataset-room6_512.txt Examples/Stereo-Inertial/TUM_IMU/dataset-room6_512.txt dataset-rooms123456_stereoi