├── .github └── stale.yml ├── .gitignore ├── .gitmodules ├── CMakeLists.txt ├── LICENSE ├── Log ├── fast_lio_time_log_analysis.m ├── guide.md └── plot.py ├── PCD └── 1 ├── README.md ├── config ├── avia.yaml ├── horizon.yaml ├── marsim.yaml ├── mid360.yaml ├── ouster64.yaml └── velodyne.yaml ├── doc ├── Fast_LIO_2.pdf ├── avia_scan.png ├── avia_scan2.png ├── overview_fastlio2.svg ├── real_exp_2.png ├── real_experiment2.gif ├── results │ ├── HKU_HW.png │ ├── HKU_LG_Indoor.png │ ├── HKU_MB_001.png │ ├── HKU_MB_002.png │ ├── HKU_MB_map.png │ ├── Screenshot from 2020-10-15 20-33-35.png │ ├── Screenshot from 2020-10-15 20-35-46.png │ ├── Screenshot from 2020-10-15 20-37-48.png │ ├── indoor_loam.png │ ├── indoor_loam_imu.png │ ├── indoor_our.png │ ├── long_corrid.png │ ├── uav2_path.png │ ├── uav2_test_map.png │ ├── uav_lg.png │ ├── uav_lg_0.png │ └── uav_lg_2.png ├── uav01.jpg ├── uav_ground.pdf ├── uav_system.png └── ulhkwh_fastlio.gif ├── include ├── Exp_mat.h ├── IKFoM_toolkit │ ├── esekfom │ │ ├── esekfom.hpp │ │ └── util.hpp │ └── mtk │ │ ├── build_manifold.hpp │ │ ├── src │ │ ├── SubManifold.hpp │ │ ├── mtkmath.hpp │ │ └── vectview.hpp │ │ ├── startIdx.hpp │ │ └── types │ │ ├── S2.hpp │ │ ├── SOn.hpp │ │ ├── vect.hpp │ │ └── wrapped_cv_mat.hpp ├── common_lib.h ├── matplotlibcpp.h ├── so3_math.h └── use-ikfom.hpp ├── launch ├── gdb_debug_example.launch ├── mapping_avia.launch ├── mapping_horizon.launch ├── mapping_marsim.launch ├── mapping_mid360.launch ├── mapping_ouster64.launch └── mapping_velodyne.launch ├── msg └── Pose6D.msg ├── package.xml ├── rviz_cfg ├── .gitignore └── loam_livox.rviz └── src ├── IMU_Processing.hpp ├── laserMapping.cpp ├── preprocess.cpp └── preprocess.h /.github/stale.yml: -------------------------------------------------------------------------------- 1 | # Number of days of inactivity before an issue becomes stale 2 | daysUntilStale: 21 3 | # Number of days of inactivity before a stale issue is closed 4 | daysUntilClose: 1 5 | # Issues with these labels will never be considered stale 6 | exemptLabels: 7 | - pinned 8 | - security 9 | # Label to use when marking an issue as stale 10 | staleLabel: stale 11 | # Comment to post when marking an issue as stale. Set to `false` to disable 12 | markComment: > 13 | This issue has been automatically marked as stale because it has not had 14 | recent activity. It will be closed if no further activity occurs. Thank you 15 | for your contributions. 16 | # Comment to post when closing a stale issue. Set to `false` to disable 17 | closeComment: false 18 | -------------------------------------------------------------------------------- /.gitignore: -------------------------------------------------------------------------------- 1 | build 2 | Log/*.png 3 | Log/*.txt 4 | Log/*.csv 5 | Log/*.pdf 6 | .vscode/c_cpp_properties.json 7 | .vscode/settings.json 8 | PCD/*.pcd 9 | -------------------------------------------------------------------------------- /.gitmodules: -------------------------------------------------------------------------------- 1 | [submodule "include/ikd-Tree"] 2 | path = include/ikd-Tree 3 | url = https://github.com/hku-mars/ikd-Tree.git 4 | branch = fast_lio 5 | -------------------------------------------------------------------------------- /CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(fast_lio) 3 | 4 | SET(CMAKE_BUILD_TYPE "Debug") 5 | 6 | ADD_COMPILE_OPTIONS(-std=c++14 ) 7 | ADD_COMPILE_OPTIONS(-std=c++14 ) 8 | set( CMAKE_CXX_FLAGS "-std=c++14 -O3" ) 9 | 10 | add_definitions(-DROOT_DIR=\"${CMAKE_CURRENT_SOURCE_DIR}/\") 11 | 12 | set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -fexceptions" ) 13 | set(CMAKE_CXX_STANDARD 14) 14 | set(CMAKE_CXX_STANDARD_REQUIRED ON) 15 | set(CMAKE_CXX_EXTENSIONS OFF) 16 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++14 -pthread -std=c++0x -std=c++14 -fexceptions") 17 | 18 | message("Current CPU archtecture: ${CMAKE_SYSTEM_PROCESSOR}") 19 | if(CMAKE_SYSTEM_PROCESSOR MATCHES "(x86)|(X86)|(amd64)|(AMD64)" ) 20 | include(ProcessorCount) 21 | ProcessorCount(N) 22 | message("Processer number: ${N}") 23 | if(N GREATER 4) 24 | add_definitions(-DMP_EN) 25 | add_definitions(-DMP_PROC_NUM=3) 26 | message("core for MP: 3") 27 | elseif(N GREATER 3) 28 | add_definitions(-DMP_EN) 29 | add_definitions(-DMP_PROC_NUM=2) 30 | message("core for MP: 2") 31 | else() 32 | add_definitions(-DMP_PROC_NUM=1) 33 | endif() 34 | else() 35 | add_definitions(-DMP_PROC_NUM=1) 36 | endif() 37 | 38 | find_package(OpenMP QUIET) 39 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${OpenMP_CXX_FLAGS}") 40 | set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${OpenMP_C_FLAGS}") 41 | 42 | find_package(PythonLibs REQUIRED) 43 | find_path(MATPLOTLIB_CPP_INCLUDE_DIRS "matplotlibcpp.h") 44 | 45 | find_package(catkin REQUIRED COMPONENTS 46 | geometry_msgs 47 | nav_msgs 48 | sensor_msgs 49 | roscpp 50 | rospy 51 | std_msgs 52 | pcl_ros 53 | tf 54 | livox_ros_driver 55 | message_generation 56 | eigen_conversions 57 | ) 58 | 59 | find_package(Eigen3 REQUIRED) 60 | find_package(PCL 1.8 REQUIRED) 61 | 62 | message(Eigen: ${EIGEN3_INCLUDE_DIR}) 63 | 64 | include_directories( 65 | ${catkin_INCLUDE_DIRS} 66 | ${EIGEN3_INCLUDE_DIR} 67 | ${PCL_INCLUDE_DIRS} 68 | ${PYTHON_INCLUDE_DIRS} 69 | include) 70 | 71 | add_message_files( 72 | FILES 73 | Pose6D.msg 74 | ) 75 | 76 | generate_messages( 77 | DEPENDENCIES 78 | geometry_msgs 79 | ) 80 | 81 | catkin_package( 82 | CATKIN_DEPENDS geometry_msgs nav_msgs roscpp rospy std_msgs message_runtime 83 | DEPENDS EIGEN3 PCL 84 | INCLUDE_DIRS 85 | ) 86 | 87 | add_executable(fastlio_mapping src/laserMapping.cpp include/ikd-Tree/ikd_Tree.cpp src/preprocess.cpp) 88 | target_link_libraries(fastlio_mapping ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${PYTHON_LIBRARIES}) 89 | target_include_directories(fastlio_mapping PRIVATE ${PYTHON_INCLUDE_DIRS}) -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | GNU GENERAL PUBLIC LICENSE 2 | Version 2, June 1991 3 | 4 | Copyright (C) 1989, 1991 Free Software Foundation, Inc., 5 | 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA 6 | Everyone is permitted to copy and distribute verbatim copies 7 | of this license document, but changing it is not allowed. 8 | 9 | Preamble 10 | 11 | The licenses for most software are designed to take away your 12 | freedom to share and change it. By contrast, the GNU General Public 13 | License is intended to guarantee your freedom to share and change free 14 | software--to make sure the software is free for all its users. This 15 | General Public License applies to most of the Free Software 16 | Foundation's software and to any other program whose authors commit to 17 | using it. (Some other Free Software Foundation software is covered by 18 | the GNU Lesser General Public License instead.) You can apply it to 19 | your programs, too. 20 | 21 | When we speak of free software, we are referring to freedom, not 22 | price. Our General Public Licenses are designed to make sure that you 23 | have the freedom to distribute copies of free software (and charge for 24 | this service if you wish), that you receive source code or can get it 25 | if you want it, that you can change the software or use pieces of it 26 | in new free programs; and that you know you can do these things. 27 | 28 | To protect your rights, we need to make restrictions that forbid 29 | anyone to deny you these rights or to ask you to surrender the rights. 30 | These restrictions translate to certain responsibilities for you if you 31 | distribute copies of the software, or if you modify it. 32 | 33 | For example, if you distribute copies of such a program, whether 34 | gratis or for a fee, you must give the recipients all the rights that 35 | you have. You must make sure that they, too, receive or can get the 36 | source code. And you must show them these terms so they know their 37 | rights. 38 | 39 | We protect your rights with two steps: (1) copyright the software, and 40 | (2) offer you this license which gives you legal permission to copy, 41 | distribute and/or modify the software. 42 | 43 | Also, for each author's protection and ours, we want to make certain 44 | that everyone understands that there is no warranty for this free 45 | software. If the software is modified by someone else and passed on, we 46 | want its recipients to know that what they have is not the original, so 47 | that any problems introduced by others will not reflect on the original 48 | authors' reputations. 49 | 50 | Finally, any free program is threatened constantly by software 51 | patents. We wish to avoid the danger that redistributors of a free 52 | program will individually obtain patent licenses, in effect making the 53 | program proprietary. To prevent this, we have made it clear that any 54 | patent must be licensed for everyone's free use or not licensed at all. 55 | 56 | The precise terms and conditions for copying, distribution and 57 | modification follow. 58 | 59 | GNU GENERAL PUBLIC LICENSE 60 | TERMS AND CONDITIONS FOR COPYING, DISTRIBUTION AND MODIFICATION 61 | 62 | 0. This License applies to any program or other work which contains 63 | a notice placed by the copyright holder saying it may be distributed 64 | under the terms of this General Public License. The "Program", below, 65 | refers to any such program or work, and a "work based on the Program" 66 | means either the Program or any derivative work under copyright law: 67 | that is to say, a work containing the Program or a portion of it, 68 | either verbatim or with modifications and/or translated into another 69 | language. (Hereinafter, translation is included without limitation in 70 | the term "modification".) Each licensee is addressed as "you". 71 | 72 | Activities other than copying, distribution and modification are not 73 | covered by this License; they are outside its scope. The act of 74 | running the Program is not restricted, and the output from the Program 75 | is covered only if its contents constitute a work based on the 76 | Program (independent of having been made by running the Program). 77 | Whether that is true depends on what the Program does. 78 | 79 | 1. You may copy and distribute verbatim copies of the Program's 80 | source code as you receive it, in any medium, provided that you 81 | conspicuously and appropriately publish on each copy an appropriate 82 | copyright notice and disclaimer of warranty; keep intact all the 83 | notices that refer to this License and to the absence of any warranty; 84 | and give any other recipients of the Program a copy of this License 85 | along with the Program. 86 | 87 | You may charge a fee for the physical act of transferring a copy, and 88 | you may at your option offer warranty protection in exchange for a fee. 89 | 90 | 2. You may modify your copy or copies of the Program or any portion 91 | of it, thus forming a work based on the Program, and copy and 92 | distribute such modifications or work under the terms of Section 1 93 | above, provided that you also meet all of these conditions: 94 | 95 | a) You must cause the modified files to carry prominent notices 96 | stating that you changed the files and the date of any change. 97 | 98 | b) You must cause any work that you distribute or publish, that in 99 | whole or in part contains or is derived from the Program or any 100 | part thereof, to be licensed as a whole at no charge to all third 101 | parties under the terms of this License. 102 | 103 | c) If the modified program normally reads commands interactively 104 | when run, you must cause it, when started running for such 105 | interactive use in the most ordinary way, to print or display an 106 | announcement including an appropriate copyright notice and a 107 | notice that there is no warranty (or else, saying that you provide 108 | a warranty) and that users may redistribute the program under 109 | these conditions, and telling the user how to view a copy of this 110 | License. (Exception: if the Program itself is interactive but 111 | does not normally print such an announcement, your work based on 112 | the Program is not required to print an announcement.) 113 | 114 | These requirements apply to the modified work as a whole. If 115 | identifiable sections of that work are not derived from the Program, 116 | and can be reasonably considered independent and separate works in 117 | themselves, then this License, and its terms, do not apply to those 118 | sections when you distribute them as separate works. But when you 119 | distribute the same sections as part of a whole which is a work based 120 | on the Program, the distribution of the whole must be on the terms of 121 | this License, whose permissions for other licensees extend to the 122 | entire whole, and thus to each and every part regardless of who wrote it. 123 | 124 | Thus, it is not the intent of this section to claim rights or contest 125 | your rights to work written entirely by you; rather, the intent is to 126 | exercise the right to control the distribution of derivative or 127 | collective works based on the Program. 128 | 129 | In addition, mere aggregation of another work not based on the Program 130 | with the Program (or with a work based on the Program) on a volume of 131 | a storage or distribution medium does not bring the other work under 132 | the scope of this License. 133 | 134 | 3. You may copy and distribute the Program (or a work based on it, 135 | under Section 2) in object code or executable form under the terms of 136 | Sections 1 and 2 above provided that you also do one of the following: 137 | 138 | a) Accompany it with the complete corresponding machine-readable 139 | source code, which must be distributed under the terms of Sections 140 | 1 and 2 above on a medium customarily used for software interchange; or, 141 | 142 | b) Accompany it with a written offer, valid for at least three 143 | years, to give any third party, for a charge no more than your 144 | cost of physically performing source distribution, a complete 145 | machine-readable copy of the corresponding source code, to be 146 | distributed under the terms of Sections 1 and 2 above on a medium 147 | customarily used for software interchange; or, 148 | 149 | c) Accompany it with the information you received as to the offer 150 | to distribute corresponding source code. (This alternative is 151 | allowed only for noncommercial distribution and only if you 152 | received the program in object code or executable form with such 153 | an offer, in accord with Subsection b above.) 154 | 155 | The source code for a work means the preferred form of the work for 156 | making modifications to it. For an executable work, complete source 157 | code means all the source code for all modules it contains, plus any 158 | associated interface definition files, plus the scripts used to 159 | control compilation and installation of the executable. However, as a 160 | special exception, the source code distributed need not include 161 | anything that is normally distributed (in either source or binary 162 | form) with the major components (compiler, kernel, and so on) of the 163 | operating system on which the executable runs, unless that component 164 | itself accompanies the executable. 165 | 166 | If distribution of executable or object code is made by offering 167 | access to copy from a designated place, then offering equivalent 168 | access to copy the source code from the same place counts as 169 | distribution of the source code, even though third parties are not 170 | compelled to copy the source along with the object code. 171 | 172 | 4. You may not copy, modify, sublicense, or distribute the Program 173 | except as expressly provided under this License. Any attempt 174 | otherwise to copy, modify, sublicense or distribute the Program is 175 | void, and will automatically terminate your rights under this License. 176 | However, parties who have received copies, or rights, from you under 177 | this License will not have their licenses terminated so long as such 178 | parties remain in full compliance. 179 | 180 | 5. You are not required to accept this License, since you have not 181 | signed it. However, nothing else grants you permission to modify or 182 | distribute the Program or its derivative works. These actions are 183 | prohibited by law if you do not accept this License. Therefore, by 184 | modifying or distributing the Program (or any work based on the 185 | Program), you indicate your acceptance of this License to do so, and 186 | all its terms and conditions for copying, distributing or modifying 187 | the Program or works based on it. 188 | 189 | 6. Each time you redistribute the Program (or any work based on the 190 | Program), the recipient automatically receives a license from the 191 | original licensor to copy, distribute or modify the Program subject to 192 | these terms and conditions. You may not impose any further 193 | restrictions on the recipients' exercise of the rights granted herein. 194 | You are not responsible for enforcing compliance by third parties to 195 | this License. 196 | 197 | 7. If, as a consequence of a court judgment or allegation of patent 198 | infringement or for any other reason (not limited to patent issues), 199 | conditions are imposed on you (whether by court order, agreement or 200 | otherwise) that contradict the conditions of this License, they do not 201 | excuse you from the conditions of this License. If you cannot 202 | distribute so as to satisfy simultaneously your obligations under this 203 | License and any other pertinent obligations, then as a consequence you 204 | may not distribute the Program at all. For example, if a patent 205 | license would not permit royalty-free redistribution of the Program by 206 | all those who receive copies directly or indirectly through you, then 207 | the only way you could satisfy both it and this License would be to 208 | refrain entirely from distribution of the Program. 209 | 210 | If any portion of this section is held invalid or unenforceable under 211 | any particular circumstance, the balance of the section is intended to 212 | apply and the section as a whole is intended to apply in other 213 | circumstances. 214 | 215 | It is not the purpose of this section to induce you to infringe any 216 | patents or other property right claims or to contest validity of any 217 | such claims; this section has the sole purpose of protecting the 218 | integrity of the free software distribution system, which is 219 | implemented by public license practices. Many people have made 220 | generous contributions to the wide range of software distributed 221 | through that system in reliance on consistent application of that 222 | system; it is up to the author/donor to decide if he or she is willing 223 | to distribute software through any other system and a licensee cannot 224 | impose that choice. 225 | 226 | This section is intended to make thoroughly clear what is believed to 227 | be a consequence of the rest of this License. 228 | 229 | 8. If the distribution and/or use of the Program is restricted in 230 | certain countries either by patents or by copyrighted interfaces, the 231 | original copyright holder who places the Program under this License 232 | may add an explicit geographical distribution limitation excluding 233 | those countries, so that distribution is permitted only in or among 234 | countries not thus excluded. In such case, this License incorporates 235 | the limitation as if written in the body of this License. 236 | 237 | 9. The Free Software Foundation may publish revised and/or new versions 238 | of the General Public License from time to time. Such new versions will 239 | be similar in spirit to the present version, but may differ in detail to 240 | address new problems or concerns. 241 | 242 | Each version is given a distinguishing version number. If the Program 243 | specifies a version number of this License which applies to it and "any 244 | later version", you have the option of following the terms and conditions 245 | either of that version or of any later version published by the Free 246 | Software Foundation. If the Program does not specify a version number of 247 | this License, you may choose any version ever published by the Free Software 248 | Foundation. 249 | 250 | 10. If you wish to incorporate parts of the Program into other free 251 | programs whose distribution conditions are different, write to the author 252 | to ask for permission. For software which is copyrighted by the Free 253 | Software Foundation, write to the Free Software Foundation; we sometimes 254 | make exceptions for this. Our decision will be guided by the two goals 255 | of preserving the free status of all derivatives of our free software and 256 | of promoting the sharing and reuse of software generally. 257 | 258 | NO WARRANTY 259 | 260 | 11. BECAUSE THE PROGRAM IS LICENSED FREE OF CHARGE, THERE IS NO WARRANTY 261 | FOR THE PROGRAM, TO THE EXTENT PERMITTED BY APPLICABLE LAW. EXCEPT WHEN 262 | OTHERWISE STATED IN WRITING THE COPYRIGHT HOLDERS AND/OR OTHER PARTIES 263 | PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY OF ANY KIND, EITHER EXPRESSED 264 | OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF 265 | MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. THE ENTIRE RISK AS 266 | TO THE QUALITY AND PERFORMANCE OF THE PROGRAM IS WITH YOU. SHOULD THE 267 | PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF ALL NECESSARY SERVICING, 268 | REPAIR OR CORRECTION. 269 | 270 | 12. IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING 271 | WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MAY MODIFY AND/OR 272 | REDISTRIBUTE THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, 273 | INCLUDING ANY GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING 274 | OUT OF THE USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED 275 | TO LOSS OF DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY 276 | YOU OR THIRD PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER 277 | PROGRAMS), EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE 278 | POSSIBILITY OF SUCH DAMAGES. 279 | 280 | END OF TERMS AND CONDITIONS 281 | 282 | How to Apply These Terms to Your New Programs 283 | 284 | If you develop a new program, and you want it to be of the greatest 285 | possible use to the public, the best way to achieve this is to make it 286 | free software which everyone can redistribute and change under these terms. 287 | 288 | To do so, attach the following notices to the program. It is safest 289 | to attach them to the start of each source file to most effectively 290 | convey the exclusion of warranty; and each file should have at least 291 | the "copyright" line and a pointer to where the full notice is found. 292 | 293 | 294 | Copyright (C) 295 | 296 | This program is free software; you can redistribute it and/or modify 297 | it under the terms of the GNU General Public License as published by 298 | the Free Software Foundation; either version 2 of the License, or 299 | (at your option) any later version. 300 | 301 | This program is distributed in the hope that it will be useful, 302 | but WITHOUT ANY WARRANTY; without even the implied warranty of 303 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 304 | GNU General Public License for more details. 305 | 306 | You should have received a copy of the GNU General Public License along 307 | with this program; if not, write to the Free Software Foundation, Inc., 308 | 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA. 309 | 310 | Also add information on how to contact you by electronic and paper mail. 311 | 312 | If the program is interactive, make it output a short notice like this 313 | when it starts in an interactive mode: 314 | 315 | Gnomovision version 69, Copyright (C) year name of author 316 | Gnomovision comes with ABSOLUTELY NO WARRANTY; for details type `show w'. 317 | This is free software, and you are welcome to redistribute it 318 | under certain conditions; type `show c' for details. 319 | 320 | The hypothetical commands `show w' and `show c' should show the appropriate 321 | parts of the General Public License. Of course, the commands you use may 322 | be called something other than `show w' and `show c'; they could even be 323 | mouse-clicks or menu items--whatever suits your program. 324 | 325 | You should also get your employer (if you work as a programmer) or your 326 | school, if any, to sign a "copyright disclaimer" for the program, if 327 | necessary. Here is a sample; alter the names: 328 | 329 | Yoyodyne, Inc., hereby disclaims all copyright interest in the program 330 | `Gnomovision' (which makes passes at compilers) written by James Hacker. 331 | 332 | , 1 April 1989 333 | Ty Coon, President of Vice 334 | 335 | This General Public License does not permit incorporating your program into 336 | proprietary programs. If your program is a subroutine library, you may 337 | consider it more useful to permit linking proprietary applications with the 338 | library. If this is what you want to do, use the GNU Lesser General 339 | Public License instead of this License. 340 | -------------------------------------------------------------------------------- /Log/fast_lio_time_log_analysis.m: -------------------------------------------------------------------------------- 1 | clear 2 | close all 3 | 4 | Color_red = [0.6350 0.0780 0.1840]; 5 | Color_blue = [0 0.4470 0.7410]; 6 | Color_orange = [0.8500 0.3250 0.0980]; 7 | Color_green = [0.4660 0.6740 0.1880]; 8 | Color_lightblue = [0.3010 0.7450 0.9330]; 9 | Color_purple = [0.4940 0.1840 0.5560]; 10 | Color_yellow = [0.9290 0.6940 0.1250]; 11 | 12 | fast_lio_ikdtree = csvread("./fast_lio_time_log.csv",1,0); 13 | timestamp_ikd = fast_lio_ikdtree(:,1); 14 | timestamp_ikd = timestamp_ikd - min(timestamp_ikd); 15 | total_time_ikd = fast_lio_ikdtree(:,2)*1e3; 16 | scan_num = fast_lio_ikdtree(:,3); 17 | incremental_time_ikd = fast_lio_ikdtree(:,4)*1e3; 18 | search_time_ikd = fast_lio_ikdtree(:,5)*1e3; 19 | delete_size_ikd = fast_lio_ikdtree(:,6); 20 | delete_time_ikd = fast_lio_ikdtree(:,7) * 1e3; 21 | tree_size_ikd_st = fast_lio_ikdtree(:,8); 22 | tree_size_ikd = fast_lio_ikdtree(:,9); 23 | add_points = fast_lio_ikdtree(:,10); 24 | 25 | fast_lio_forest = csvread("fast_lio_time_log.csv",1,0); 26 | fov_check_time_forest = fast_lio_forest(:,5)*1e3; 27 | average_time_forest = fast_lio_forest(:,2)*1e3; 28 | total_time_forest = fast_lio_forest(:,6)*1e3; 29 | incremental_time_forest = fast_lio_forest(:,3)*1e3; 30 | search_time_forest = fast_lio_forest(:,4)*1e3; 31 | timestamp_forest = fast_lio_forest(:,1); 32 | 33 | % Use slide window to calculate average 34 | L = 1; % Length of slide window 35 | for i = 1:length(timestamp_ikd) 36 | if (i 0); 78 | search_time_ikd = search_time_ikd(index_ikd); 79 | index_forest = find(search_time_forest > 0); 80 | search_time_forest = search_time_forest(index_forest); 81 | 82 | t = nexttile; 83 | hold on; 84 | boxplot_data_ikd = [incremental_time_ikd,total_time_ikd]; 85 | boxplot_data_forest = [incremental_time_forest,total_time_forest]; 86 | Colors_ikd = [Color_blue;Color_blue;Color_blue]; 87 | Colors_forest = [Color_orange;Color_orange;Color_orange]; 88 | % xticks([3,8,13]) 89 | h_search_ikd = boxplot(search_time_ikd,'Whisker',50,'Positions',1,'Colors',Color_blue,'Widths',0.3); 90 | h_search_forest = boxplot(search_time_forest,'Whisker',50,'Positions',1.5,'Colors',Color_orange,'Widths',0.3); 91 | h_ikd = boxplot(boxplot_data_ikd,'Whisker',50,'Positions',[3,5],'Colors',Color_blue,'Widths',0.3); 92 | h_forest = boxplot(boxplot_data_forest,'Whisker',50,'Positions',[3.5,5.5],'Colors',Color_orange,'Widths',0.3); 93 | ax2 = gca; 94 | ax2.YAxis.Scale = 'log'; 95 | xlim([0.5,6.0]) 96 | ylim([0.0008,100]) 97 | xticks([1.25 3.25 5.25]) 98 | xticklabels({'Nearest Search',' Incremental Updates','Total Time'}); 99 | yticks([1e-3,1e-2,1e-1,1e0,1e1,1e2]) 100 | ax2.YAxis.FontSize = 12; 101 | ax2.XAxis.FontSize = 14.5; 102 | % ax.XAxis.FontWeight = 'bold'; 103 | ylabel('Run Time/ms','FontSize',14,'FontName','Times New Roman') 104 | box_vars = [findall(h_search_ikd,'Tag','Box');findall(h_ikd,'Tag','Box');findall(h_search_forest,'Tag','Box');findall(h_forest,'Tag','Box')]; 105 | for j=1:length(box_vars) 106 | if (j<=3) 107 | Color = Color_blue; 108 | else 109 | Color = Color_orange; 110 | end 111 | patch(get(box_vars(j),'XData'),get(box_vars(j),'YData'),Color,'FaceAlpha',0.25,'EdgeColor',Color); 112 | end 113 | Lg = legend(box_vars([1,4]), {'ikd-Tree','ikd-Forest'},'Location',[0.6707 0.4305 0.265 0.07891],'fontsize',14,'fontname','Times New Roman'); 114 | grid on 115 | set(gca,'YMinorGrid','off') 116 | nexttile; 117 | hold on; 118 | grid on; 119 | box on; 120 | set(gca,'FontSize',12,'FontName','Times New Roman') 121 | plot(timestamp_ikd, alpha_bal_ikd,'-','Color',Color_blue,'LineWidth',1.2); 122 | plot(timestamp_ikd, alpha_del_ikd,'--','Color',Color_orange, 'LineWidth', 1.2); 123 | plot(timestamp_ikd, 0.6*ones(size(alpha_bal_ikd)), ':','Color','black','LineWidth',1.2); 124 | lg = legend("\alpha_{bal}", "\alpha_{del}",'location',[0.7871 0.1131 0.1433 0.069],'fontsize',14,'fontname','Times New Roman') 125 | title("Re-balancing Criterion",'FontSize',16,'FontName','Times New Roman') 126 | xlabel("time/s",'FontSize',16,'FontName','Times New Roman') 127 | yl = ylabel("\alpha",'FontSize',15, 'Position',[285.7 0.4250 -1]) 128 | xlim([32,390]); 129 | ylim([0,0.85]); 130 | ax3 = gca; 131 | ax3.YAxis.FontSize = 12; 132 | ax3.XAxis.FontSize = 12; 133 | % print('./Figures/fastlio_exp_combine','-depsc','-r1200') 134 | % exportgraphics(f,'./Figures/fastlio_exp_combine_1.pdf','ContentType','vector') 135 | 136 | -------------------------------------------------------------------------------- /Log/guide.md: -------------------------------------------------------------------------------- 1 | Here saved the debug records which can be drew by the ../Log/plot.py. The record function can be found frm the MACRO: DEBUG_FILE_DIR(name) in common_lib.h. 2 | -------------------------------------------------------------------------------- /Log/plot.py: -------------------------------------------------------------------------------- 1 | # import matplotlib 2 | # matplotlib.use('Agg') 3 | import numpy as np 4 | import matplotlib.pyplot as plt 5 | 6 | 7 | #######for ikfom 8 | fig, axs = plt.subplots(4,2) 9 | lab_pre = ['', 'pre-x', 'pre-y', 'pre-z'] 10 | lab_out = ['', 'out-x', 'out-y', 'out-z'] 11 | plot_ind = range(7,10) 12 | a_pre=np.loadtxt('mat_pre.txt') 13 | a_out=np.loadtxt('mat_out.txt') 14 | time=a_pre[:,0] 15 | axs[0,0].set_title('Attitude') 16 | axs[1,0].set_title('Translation') 17 | axs[2,0].set_title('Extrins-R') 18 | axs[3,0].set_title('Extrins-T') 19 | axs[0,1].set_title('Velocity') 20 | axs[1,1].set_title('bg') 21 | axs[2,1].set_title('ba') 22 | axs[3,1].set_title('Gravity') 23 | for i in range(1,4): 24 | for j in range(8): 25 | axs[j%4, j/4].plot(time, a_pre[:,i+j*3],'.-', label=lab_pre[i]) 26 | axs[j%4, j/4].plot(time, a_out[:,i+j*3],'.-', label=lab_out[i]) 27 | for j in range(8): 28 | # axs[j].set_xlim(386,389) 29 | axs[j%4, j/4].grid() 30 | axs[j%4, j/4].legend() 31 | plt.grid() 32 | #######for ikfom####### 33 | 34 | 35 | #### Draw IMU data 36 | # fig, axs = plt.subplots(2) 37 | # imu=np.loadtxt('imu.txt') 38 | # time=imu[:,0] 39 | # axs[0].set_title('Gyroscope') 40 | # axs[1].set_title('Accelerameter') 41 | # lab_1 = ['gyr-x', 'gyr-y', 'gyr-z'] 42 | # lab_2 = ['acc-x', 'acc-y', 'acc-z'] 43 | # for i in range(3): 44 | # # if i==1: 45 | # axs[0].plot(time, imu[:,i+1],'.-', label=lab_1[i]) 46 | # axs[1].plot(time, imu[:,i+4],'.-', label=lab_2[i]) 47 | # for i in range(2): 48 | # # axs[i].set_xlim(386,389) 49 | # axs[i].grid() 50 | # axs[i].legend() 51 | # plt.grid() 52 | 53 | # #### Draw time calculation 54 | # plt.figure(3) 55 | # fig = plt.figure() 56 | # font1 = {'family' : 'Times New Roman', 57 | # 'weight' : 'normal', 58 | # 'size' : 12, 59 | # } 60 | # c="red" 61 | # a_out1=np.loadtxt('Log/mat_out_time_indoor1.txt') 62 | # a_out2=np.loadtxt('Log/mat_out_time_indoor2.txt') 63 | # a_out3=np.loadtxt('Log/mat_out_time_outdoor.txt') 64 | # # n = a_out[:,1].size 65 | # # time_mean = a_out[:,1].mean() 66 | # # time_se = a_out[:,1].std() / np.sqrt(n) 67 | # # time_err = a_out[:,1] - time_mean 68 | # # feat_mean = a_out[:,2].mean() 69 | # # feat_err = a_out[:,2] - feat_mean 70 | # # feat_se = a_out[:,2].std() / np.sqrt(n) 71 | # ax1 = fig.add_subplot(111) 72 | # ax1.set_ylabel('Effective Feature Numbers',font1) 73 | # ax1.boxplot(a_out1[:,2], showfliers=False, positions=[0.9]) 74 | # ax1.boxplot(a_out2[:,2], showfliers=False, positions=[1.9]) 75 | # ax1.boxplot(a_out3[:,2], showfliers=False, positions=[2.9]) 76 | # ax1.set_ylim([0, 3000]) 77 | 78 | # ax2 = ax1.twinx() 79 | # ax2.spines['right'].set_color('red') 80 | # ax2.set_ylabel('Compute Time (ms)',font1) 81 | # ax2.yaxis.label.set_color('red') 82 | # ax2.tick_params(axis='y', colors='red') 83 | # ax2.boxplot(a_out1[:,1]*1000, showfliers=False, positions=[1.1],boxprops=dict(color=c),capprops=dict(color=c),whiskerprops=dict(color=c)) 84 | # ax2.boxplot(a_out2[:,1]*1000, showfliers=False, positions=[2.1],boxprops=dict(color=c),capprops=dict(color=c),whiskerprops=dict(color=c)) 85 | # ax2.boxplot(a_out3[:,1]*1000, showfliers=False, positions=[3.1],boxprops=dict(color=c),capprops=dict(color=c),whiskerprops=dict(color=c)) 86 | # ax2.set_xlim([0.5, 3.5]) 87 | # ax2.set_ylim([0, 100]) 88 | 89 | # plt.xticks([1,2,3], ('Outdoor Scene', 'Indoor Scene 1', 'Indoor Scene 2')) 90 | # # # print(time_se) 91 | # # # print(a_out3[:,2]) 92 | # plt.grid() 93 | # plt.savefig("time.pdf", dpi=1200) 94 | plt.show() 95 | -------------------------------------------------------------------------------- /PCD/1: -------------------------------------------------------------------------------- 1 | 1 2 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | ## Related Works and Extended Application 2 | 3 | **SLAM:** 4 | 5 | 1. [ikd-Tree](https://github.com/hku-mars/ikd-Tree): A state-of-art dynamic KD-Tree for 3D kNN search. 6 | 2. [R2LIVE](https://github.com/hku-mars/r2live): A high-precision LiDAR-inertial-Vision fusion work using FAST-LIO as LiDAR-inertial front-end. 7 | 3. [LI_Init](https://github.com/hku-mars/LiDAR_IMU_Init): A robust, real-time LiDAR-IMU extrinsic initialization and synchronization package.. 8 | 4. [FAST-LIO-LOCALIZATION](https://github.com/HViktorTsoi/FAST_LIO_LOCALIZATION): The integration of FAST-LIO with **Re-localization** function module. 9 | 5. [FAST-LIVO](https://github.com/hku-mars/FAST-LIVO) | [FAST-LIVO2](https://github.com/hku-mars/FAST-LIVO2): A state-of-art LiDAR-inertial-visual odometry (LIVO) system with high computational efficiency, robustness, and pixel-level accuracy. 10 | 11 | **Control and Plan:** 12 | 13 | 1. [IKFOM](https://github.com/hku-mars/IKFoM): A Toolbox for fast and high-precision on-manifold Kalman filter. 14 | 2. [UAV Avoiding Dynamic Obstacles](https://github.com/hku-mars/dyn_small_obs_avoidance): One of the implementation of FAST-LIO in robot's planning. 15 | 3. [UGV Demo](https://www.youtube.com/watch?v=wikgrQbE6Cs): Model Predictive Control for Trajectory Tracking on Differentiable Manifolds. 16 | 4. [Bubble Planner](https://arxiv.org/abs/2202.12177): Planning High-speed Smooth Quadrotor Trajectories using Receding Corridors. 17 | 18 | 19 | 20 | ## FAST-LIO 21 | **FAST-LIO** (Fast LiDAR-Inertial Odometry) is a computationally efficient and robust LiDAR-inertial odometry package. It fuses LiDAR feature points with IMU data using a tightly-coupled iterated extended Kalman filter to allow robust navigation in fast-motion, noisy or cluttered environments where degeneration occurs. Our package address many key issues: 22 | 1. Fast iterated Kalman filter for odometry optimization; 23 | 2. Automaticaly initialized at most steady environments; 24 | 3. Parallel KD-Tree Search to decrease the computation; 25 | 26 | ## FAST-LIO 2.0 (2021-07-05 Update) 27 | 28 | 29 |
30 | 31 | 32 |
33 | 34 | **Related video:** [FAST-LIO2](https://youtu.be/2OvjGnxszf8), [FAST-LIO1](https://youtu.be/iYCY6T79oNU) 35 | 36 | **Pipeline:** 37 |
38 | 39 |
40 | 41 | **New Features:** 42 | 1. Incremental mapping using [ikd-Tree](https://github.com/hku-mars/ikd-Tree), achieve faster speed and over 100Hz LiDAR rate. 43 | 2. Direct odometry (scan to map) on Raw LiDAR points (feature extraction can be disabled), achieving better accuracy. 44 | 3. Since no requirements for feature extraction, FAST-LIO2 can support many types of LiDAR including spinning (Velodyne, Ouster) and solid-state (Livox Avia, Horizon, MID-70) LiDARs, and can be easily extended to support more LiDARs. 45 | 4. Support external IMU. 46 | 5. Support ARM-based platforms including Khadas VIM3, Nivida TX2, Raspberry Pi 4B(8G RAM). 47 | 48 | **Related papers**: 49 | 50 | [FAST-LIO2: Fast Direct LiDAR-inertial Odometry](doc/Fast_LIO_2.pdf) 51 | 52 | [FAST-LIO: A Fast, Robust LiDAR-inertial Odometry Package by Tightly-Coupled Iterated Kalman Filter](https://arxiv.org/abs/2010.08196) 53 | 54 | **Contributors** 55 | 56 | [Wei Xu 徐威](https://github.com/XW-HKU),[Yixi Cai 蔡逸熙](https://github.com/Ecstasy-EC),[Dongjiao He 贺东娇](https://github.com/Joanna-HE),[Fangcheng Zhu 朱方程](https://github.com/zfc-zfc),[Jiarong Lin 林家荣](https://github.com/ziv-lin),[Zheng Liu 刘政](https://github.com/Zale-Liu), [Borong Yuan](https://github.com/borongyuan) 57 | 58 | 62 | 63 | ## 1. Prerequisites 64 | ### 1.1 **Ubuntu** and **ROS** 65 | **Ubuntu >= 16.04** 66 | 67 | For **Ubuntu 18.04 or higher**, the **default** PCL and Eigen is enough for FAST-LIO to work normally. 68 | 69 | ROS >= Melodic. [ROS Installation](http://wiki.ros.org/ROS/Installation) 70 | 71 | ### 1.2. **PCL && Eigen** 72 | PCL >= 1.8, Follow [PCL Installation](http://www.pointclouds.org/downloads/linux.html). 73 | 74 | Eigen >= 3.3.4, Follow [Eigen Installation](http://eigen.tuxfamily.org/index.php?title=Main_Page). 75 | 76 | ### 1.3. **livox_ros_driver** 77 | Follow [livox_ros_driver Installation](https://github.com/Livox-SDK/livox_ros_driver). 78 | 79 | *Remarks:* 80 | - Since the FAST-LIO must support Livox serials LiDAR firstly, so the **livox_ros_driver** must be installed and **sourced** before run any FAST-LIO luanch file. 81 | - How to source? The easiest way is add the line ``` source $Livox_ros_driver_dir$/devel/setup.bash ``` to the end of file ``` ~/.bashrc ```, where ``` $Livox_ros_driver_dir$ ``` is the directory of the livox ros driver workspace (should be the ``` ws_livox ``` directory if you completely followed the livox official document). 82 | 83 | 84 | ## 2. Build 85 | If you want to use docker conatiner to run fastlio2, please install the docker on you machine. 86 | Follow [Docker Installation](https://docs.docker.com/engine/install/ubuntu/). 87 | ### 2.1 Docker Container 88 | User can create a new script with anyname by the following command in linux: 89 | ``` 90 | touch .sh 91 | ``` 92 | Place the following code inside the ``` .sh ``` script. 93 | ``` 94 | #!/bin/bash 95 | mkdir docker_ws 96 | # Script to run ROS Kinetic with GUI support in Docker 97 | 98 | # Allow X server to be accessed from the local machine 99 | xhost +local: 100 | 101 | # Container name 102 | CONTAINER_NAME="fastlio2" 103 | 104 | # Run the Docker container 105 | docker run -itd \ 106 | --name=$CONTAINER_NAME \ 107 | --user mars_ugv \ 108 | --network host \ 109 | --ipc=host \ 110 | -v /home/$USER/docker_ws:/home/mars_ugv/docker_ws \ 111 | --privileged \ 112 | --env="QT_X11_NO_MITSHM=1" \ 113 | --volume="/etc/localtime:/etc/localtime:ro" \ 114 | -v /dev/bus/usb:/dev/bus/usb \ 115 | --device=/dev/dri \ 116 | --group-add video \ 117 | -v /tmp/.X11-unix:/tmp/.X11-unix \ 118 | --env="DISPLAY=$DISPLAY" \ 119 | kenny0407/marslab_fastlio2:latest \ 120 | /bin/bash 121 | ``` 122 | execute the following command to grant execute permissions to the script, making it runnable: 123 | ``` 124 | sudo chmod +x .sh 125 | ``` 126 | execute the following command to download the image and create the container. 127 | ``` 128 | ./.sh 129 | ``` 130 | 131 | *Script explanation:* 132 | - The docker run command provided below creates a container with a tag, using an image from Docker Hub. The download duration for this image can differ depending on the user's network speed. 133 | - This command also establishes a new workspace called ``` docker_ws ```, which serves as a shared folder between the Docker container and the host machine. This means that if users wish to run the rosbag example, they need to download the rosbag file and place it in the ``` docker_ws ``` directory on their host machine. 134 | - Subsequently, a folder with the same name inside the Docker container will receive this file. Users can then easily play the file within Docker. 135 | - In this example, we've shared the network of the host machine with the Docker container. Consequently, if users execute the ``` rostopic list ``` command, they will observe identical output whether they run it on the host machine or inside the Docker container." 136 | ### 2.2 Build from source 137 | Clone the repository and catkin_make: 138 | 139 | ``` 140 | cd ~/$A_ROS_DIR$/src 141 | git clone https://github.com/hku-mars/FAST_LIO.git 142 | cd FAST_LIO 143 | git submodule update --init 144 | cd ../.. 145 | catkin_make 146 | source devel/setup.bash 147 | ``` 148 | - Remember to source the livox_ros_driver before build (follow 1.3 **livox_ros_driver**) 149 | - If you want to use a custom build of PCL, add the following line to ~/.bashrc 150 | ```export PCL_ROOT={CUSTOM_PCL_PATH}``` 151 | ## 3. Directly run 152 | Noted: 153 | 154 | A. Please make sure the IMU and LiDAR are **Synchronized**, that's important. 155 | 156 | B. The warning message "Failed to find match for field 'time'." means the timestamps of each LiDAR points are missed in the rosbag file. That is important for the forward propagation and backwark propagation. 157 | 158 | C. We recommend to set the **extrinsic_est_en** to false if the extrinsic is give. As for the extrinsic initiallization, please refer to our recent work: [**Robust Real-time LiDAR-inertial Initialization**](https://github.com/hku-mars/LiDAR_IMU_Init). 159 | 160 | ### 3.1 For Avia 161 | Connect to your PC to Livox Avia LiDAR by following [Livox-ros-driver installation](https://github.com/Livox-SDK/livox_ros_driver), then 162 | ``` 163 | cd ~/$FAST_LIO_ROS_DIR$ 164 | source devel/setup.bash 165 | roslaunch fast_lio mapping_avia.launch 166 | roslaunch livox_ros_driver livox_lidar_msg.launch 167 | ``` 168 | - For livox serials, FAST-LIO only support the data collected by the ``` livox_lidar_msg.launch ``` since only its ``` livox_ros_driver/CustomMsg ``` data structure produces the timestamp of each LiDAR point which is very important for the motion undistortion. ``` livox_lidar.launch ``` can not produce it right now. 169 | - If you want to change the frame rate, please modify the **publish_freq** parameter in the [livox_lidar_msg.launch](https://github.com/Livox-SDK/livox_ros_driver/blob/master/livox_ros_driver/launch/livox_lidar_msg.launch) of [Livox-ros-driver](https://github.com/Livox-SDK/livox_ros_driver) before make the livox_ros_driver pakage. 170 | 171 | ### 3.2 For Livox serials with external IMU 172 | 173 | mapping_avia.launch theratically supports mid-70, mid-40 or other livox serial LiDAR, but need to setup some parameters befor run: 174 | 175 | Edit ``` config/avia.yaml ``` to set the below parameters: 176 | 177 | 1. LiDAR point cloud topic name: ``` lid_topic ``` 178 | 2. IMU topic name: ``` imu_topic ``` 179 | 3. Translational extrinsic: ``` extrinsic_T ``` 180 | 4. Rotational extrinsic: ``` extrinsic_R ``` (only support rotation matrix) 181 | - The extrinsic parameters in FAST-LIO is defined as the LiDAR's pose (position and rotation matrix) in IMU body frame (i.e. the IMU is the base frame). They can be found in the official manual. 182 | - FAST-LIO produces a very simple software time sync for livox LiDAR, set parameter ```time_sync_en``` to ture to turn on. But turn on **ONLY IF external time synchronization is really not possible**, since the software time sync cannot make sure accuracy. 183 | 184 | ### 3.3 For Velodyne or Ouster (Velodyne as an example) 185 | 186 | Step A: Setup before run 187 | 188 | Edit ``` config/velodyne.yaml ``` to set the below parameters: 189 | 190 | 1. LiDAR point cloud topic name: ``` lid_topic ``` 191 | 2. IMU topic name: ``` imu_topic ``` (both internal and external, 6-aixes or 9-axies are fine) 192 | 3. Set the parameter ```timestamp_unit``` based on the unit of **time** (Velodyne) or **t** (Ouster) field in PoindCloud2 rostopic 193 | 4. Line number (we tested 16, 32 and 64 line, but not tested 128 or above): ``` scan_line ``` 194 | 5. Translational extrinsic: ``` extrinsic_T ``` 195 | 6. Rotational extrinsic: ``` extrinsic_R ``` (only support rotation matrix) 196 | - The extrinsic parameters in FAST-LIO is defined as the LiDAR's pose (position and rotation matrix) in IMU body frame (i.e. the IMU is the base frame). 197 | 198 | Step B: Run below 199 | ``` 200 | cd ~/$FAST_LIO_ROS_DIR$ 201 | source devel/setup.bash 202 | roslaunch fast_lio mapping_velodyne.launch 203 | ``` 204 | 205 | Step C: Run LiDAR's ros driver or play rosbag. 206 | 207 | ### 3.4 For MARSIM Simulator 208 | 209 | Install MARSIM: https://github.com/hku-mars/MARSIM and run MARSIM as below 210 | 211 | ``` 212 | cd ~/$MARSIM_ROS_DIR$ 213 | roslaunch test_interface single_drone_avia.launch 214 | ``` 215 | 216 | Then Run FAST-LIO: 217 | 218 | ``` 219 | roslaunch fast_lio mapping_marsim.launch 220 | ``` 221 | 222 | ### 3.5 PCD file save 223 | 224 | Set ``` pcd_save_enable ``` in launchfile to ``` 1 ```. All the scans (in global frame) will be accumulated and saved to the file ``` FAST_LIO/PCD/scans.pcd ``` after the FAST-LIO is terminated. ```pcl_viewer scans.pcd``` can visualize the point clouds. 225 | 226 | *Tips for pcl_viewer:* 227 | - change what to visualize/color by pressing keyboard 1,2,3,4,5 when pcl_viewer is running. 228 | ``` 229 | 1 is all random 230 | 2 is X values 231 | 3 is Y values 232 | 4 is Z values 233 | 5 is intensity 234 | ``` 235 | 236 | ## 4. Rosbag Example 237 | ### 4.1 Livox Avia Rosbag 238 |
239 | 240 | 241 | 242 | Files: Can be downloaded from [google drive](https://drive.google.com/drive/folders/1CGYEJ9-wWjr8INyan6q1BZz_5VtGB-fP?usp=sharing) 243 | 244 | Run: 245 | ``` 246 | roslaunch fast_lio mapping_avia.launch 247 | rosbag play YOUR_DOWNLOADED.bag 248 | 249 | ``` 250 | 251 | ### 4.2 Velodyne HDL-32E Rosbag 252 | 253 | **NCLT Dataset**: Original bin file can be found [here](http://robots.engin.umich.edu/nclt/). 254 | 255 | We produce [Rosbag Files](https://drive.google.com/drive/folders/1blQJuAB4S80NwZmpM6oALyHWvBljPSOE?usp=sharing) and [a python script](https://drive.google.com/file/d/1QC9IRBv2_-cgo_AEvL62E1ml1IL9ht6J/view?usp=sharing) to generate Rosbag files: ```python3 sensordata_to_rosbag_fastlio.py bin_file_dir bag_name.bag``` 256 | 257 | Run: 258 | ``` 259 | roslaunch fast_lio mapping_velodyne.launch 260 | rosbag play YOUR_DOWNLOADED.bag 261 | ``` 262 | 263 | ## 5.Implementation on UAV 264 | In order to validate the robustness and computational efficiency of FAST-LIO in actual mobile robots, we build a small-scale quadrotor which can carry a Livox Avia LiDAR with 70 degree FoV and a DJI Manifold 2-C onboard computer with a 1.8 GHz Intel i7-8550U CPU and 8 G RAM, as shown in below. 265 | 266 | The main structure of this UAV is 3d printed (Aluminum or PLA), the .stl file will be open-sourced in the future. 267 | 268 |
269 | 270 | 271 |
272 | 273 | ## 6.Acknowledgments 274 | 275 | Thanks for LOAM(J. Zhang and S. Singh. LOAM: Lidar Odometry and Mapping in Real-time), [Livox_Mapping](https://github.com/Livox-SDK/livox_mapping), [LINS](https://github.com/ChaoqinRobotics/LINS---LiDAR-inertial-SLAM) and [Loam_Livox](https://github.com/hku-mars/loam_livox). 276 | -------------------------------------------------------------------------------- /config/avia.yaml: -------------------------------------------------------------------------------- 1 | common: 2 | lid_topic: "/livox/lidar" 3 | imu_topic: "/livox/imu" 4 | time_sync_en: false # ONLY turn on when external time synchronization is really not possible 5 | time_offset_lidar_to_imu: 0.0 # Time offset between lidar and IMU calibrated by other algorithms, e.g. LI-Init (can be found in README). 6 | # This param will take effect no matter what time_sync_en is. So if the time offset is not known exactly, please set as 0.0 7 | 8 | preprocess: 9 | lidar_type: 1 # 1 for Livox serials LiDAR, 2 for Velodyne LiDAR, 3 for ouster LiDAR, 10 | scan_line: 6 11 | blind: 4 12 | 13 | mapping: 14 | acc_cov: 0.1 15 | gyr_cov: 0.1 16 | b_acc_cov: 0.0001 17 | b_gyr_cov: 0.0001 18 | fov_degree: 90 19 | det_range: 450.0 20 | extrinsic_est_en: false # true: enable the online estimation of IMU-LiDAR extrinsic 21 | extrinsic_T: [ 0.04165, 0.02326, -0.0284 ] 22 | extrinsic_R: [ 1, 0, 0, 23 | 0, 1, 0, 24 | 0, 0, 1] 25 | 26 | publish: 27 | path_en: false 28 | scan_publish_en: true # false: close all the point cloud output 29 | dense_publish_en: true # false: low down the points number in a global-frame point clouds scan. 30 | scan_bodyframe_pub_en: true # true: output the point cloud scans in IMU-body-frame 31 | 32 | pcd_save: 33 | pcd_save_en: true 34 | interval: -1 # how many LiDAR frames saved in each pcd file; 35 | # -1 : all frames will be saved in ONE pcd file, may lead to memory crash when having too much frames. 36 | -------------------------------------------------------------------------------- /config/horizon.yaml: -------------------------------------------------------------------------------- 1 | common: 2 | lid_topic: "/livox/lidar" 3 | imu_topic: "/livox/imu" 4 | time_sync_en: false # ONLY turn on when external time synchronization is really not possible 5 | time_offset_lidar_to_imu: 0.0 # Time offset between lidar and IMU calibrated by other algorithms, e.g. LI-Init (can be found in README). 6 | # This param will take effect no matter what time_sync_en is. So if the time offset is not known exactly, please set as 0.0 7 | 8 | preprocess: 9 | lidar_type: 1 # 1 for Livox serials LiDAR, 2 for Velodyne LiDAR, 3 for ouster LiDAR, 10 | scan_line: 6 11 | blind: 4 12 | 13 | mapping: 14 | acc_cov: 0.1 15 | gyr_cov: 0.1 16 | b_acc_cov: 0.0001 17 | b_gyr_cov: 0.0001 18 | fov_degree: 100 19 | det_range: 260.0 20 | extrinsic_est_en: true # true: enable the online estimation of IMU-LiDAR extrinsic 21 | extrinsic_T: [ 0.05512, 0.02226, -0.0297 ] 22 | extrinsic_R: [ 1, 0, 0, 23 | 0, 1, 0, 24 | 0, 0, 1] 25 | 26 | publish: 27 | path_en: false 28 | scan_publish_en: true # false: close all the point cloud output 29 | dense_publish_en: true # false: low down the points number in a global-frame point clouds scan. 30 | scan_bodyframe_pub_en: true # true: output the point cloud scans in IMU-body-frame 31 | 32 | pcd_save: 33 | pcd_save_en: true 34 | interval: -1 # how many LiDAR frames saved in each pcd file; 35 | # -1 : all frames will be saved in ONE pcd file, may lead to memory crash when having too much frames. 36 | -------------------------------------------------------------------------------- /config/marsim.yaml: -------------------------------------------------------------------------------- 1 | common: 2 | lid_topic: "/quad0_pcl_render_node/sensor_cloud" 3 | imu_topic: "/quad_0/imu" 4 | time_sync_en: false # ONLY turn on when external time synchronization is really not possible 5 | time_offset_lidar_to_imu: 0.0 # Time offset between lidar and IMU calibrated by other algorithms, e.g. LI-Init (can be found in README). 6 | # This param will take effect no matter what time_sync_en is. So if the time offset is not known exactly, please set as 0.0 7 | 8 | preprocess: 9 | lidar_type: 4 # 1 for Livox serials LiDAR, 2 for Velodyne LiDAR, 3 for ouster LiDAR, 10 | scan_line: 4 11 | blind: 0.5 12 | 13 | mapping: 14 | acc_cov: 0.1 15 | gyr_cov: 0.1 16 | b_acc_cov: 0.0001 17 | b_gyr_cov: 0.0001 18 | fov_degree: 90 19 | det_range: 50.0 20 | extrinsic_est_en: false # true: enable the online estimation of IMU-LiDAR extrinsic 21 | extrinsic_T: [ -0.0, -0.0, 0.0 ] 22 | extrinsic_R: [ 1, 0, 0, 23 | 0, 1, 0, 24 | 0, 0, 1] 25 | 26 | publish: 27 | path_en: false 28 | scan_publish_en: true # false: close all the point cloud output 29 | dense_publish_en: true # false: low down the points number in a global-frame point clouds scan. 30 | scan_bodyframe_pub_en: true # true: output the point cloud scans in IMU-body-frame 31 | 32 | pcd_save: 33 | pcd_save_en: true 34 | interval: -1 # how many LiDAR frames saved in each pcd file; 35 | # -1 : all frames will be saved in ONE pcd file, may lead to memory crash when having too much frames. 36 | -------------------------------------------------------------------------------- /config/mid360.yaml: -------------------------------------------------------------------------------- 1 | common: 2 | lid_topic: "/livox/lidar" 3 | imu_topic: "/livox/imu" 4 | time_sync_en: false # ONLY turn on when external time synchronization is really not possible 5 | time_offset_lidar_to_imu: 0.0 # Time offset between lidar and IMU calibrated by other algorithms, e.g. LI-Init (can be found in README). 6 | # This param will take effect no matter what time_sync_en is. So if the time offset is not known exactly, please set as 0.0 7 | 8 | preprocess: 9 | lidar_type: 1 # 1 for Livox serials LiDAR, 2 for Velodyne LiDAR, 3 for ouster LiDAR, 10 | scan_line: 4 11 | blind: 0.5 12 | 13 | mapping: 14 | acc_cov: 0.1 15 | gyr_cov: 0.1 16 | b_acc_cov: 0.0001 17 | b_gyr_cov: 0.0001 18 | fov_degree: 360 19 | det_range: 100.0 20 | extrinsic_est_en: false # true: enable the online estimation of IMU-LiDAR extrinsic 21 | extrinsic_T: [ -0.011, -0.02329, 0.04412 ] 22 | extrinsic_R: [ 1, 0, 0, 23 | 0, 1, 0, 24 | 0, 0, 1] 25 | 26 | publish: 27 | path_en: false 28 | scan_publish_en: true # false: close all the point cloud output 29 | dense_publish_en: true # false: low down the points number in a global-frame point clouds scan. 30 | scan_bodyframe_pub_en: true # true: output the point cloud scans in IMU-body-frame 31 | 32 | pcd_save: 33 | pcd_save_en: true 34 | interval: -1 # how many LiDAR frames saved in each pcd file; 35 | # -1 : all frames will be saved in ONE pcd file, may lead to memory crash when having too much frames. 36 | -------------------------------------------------------------------------------- /config/ouster64.yaml: -------------------------------------------------------------------------------- 1 | common: 2 | lid_topic: "/os_cloud_node/points" 3 | imu_topic: "/os_cloud_node/imu" 4 | time_sync_en: false # ONLY turn on when external time synchronization is really not possible 5 | time_offset_lidar_to_imu: 0.0 # Time offset between lidar and IMU calibrated by other algorithms, e.g. LI-Init (can be found in README). 6 | # This param will take effect no matter what time_sync_en is. So if the time offset is not known exactly, please set as 0.0 7 | 8 | preprocess: 9 | lidar_type: 3 # 1 for Livox serials LiDAR, 2 for Velodyne LiDAR, 3 for ouster LiDAR, 10 | scan_line: 64 11 | timestamp_unit: 3 # 0-second, 1-milisecond, 2-microsecond, 3-nanosecond. 12 | blind: 4 13 | 14 | mapping: 15 | acc_cov: 0.1 16 | gyr_cov: 0.1 17 | b_acc_cov: 0.0001 18 | b_gyr_cov: 0.0001 19 | fov_degree: 180 20 | det_range: 150.0 21 | extrinsic_est_en: false # true: enable the online estimation of IMU-LiDAR extrinsic 22 | extrinsic_T: [ 0.0, 0.0, 0.0 ] 23 | extrinsic_R: [1, 0, 0, 24 | 0, 1, 0, 25 | 0, 0, 1] 26 | 27 | publish: 28 | path_en: false 29 | scan_publish_en: true # false: close all the point cloud output 30 | dense_publish_en: true # false: low down the points number in a global-frame point clouds scan. 31 | scan_bodyframe_pub_en: true # true: output the point cloud scans in IMU-body-frame 32 | 33 | pcd_save: 34 | pcd_save_en: true 35 | interval: -1 # how many LiDAR frames saved in each pcd file; 36 | # -1 : all frames will be saved in ONE pcd file, may lead to memory crash when having too much frames. 37 | -------------------------------------------------------------------------------- /config/velodyne.yaml: -------------------------------------------------------------------------------- 1 | common: 2 | lid_topic: "/velodyne_points" 3 | imu_topic: "/imu/data" 4 | time_sync_en: false # ONLY turn on when external time synchronization is really not possible 5 | time_offset_lidar_to_imu: 0.0 # Time offset between lidar and IMU calibrated by other algorithms, e.g. LI-Init (can be found in README). 6 | # This param will take effect no matter what time_sync_en is. So if the time offset is not known exactly, please set as 0.0 7 | 8 | preprocess: 9 | lidar_type: 2 # 1 for Livox serials LiDAR, 2 for Velodyne LiDAR, 3 for ouster LiDAR, 10 | scan_line: 32 11 | scan_rate: 10 # only need to be set for velodyne, unit: Hz, 12 | timestamp_unit: 2 # the unit of time/t field in the PointCloud2 rostopic: 0-second, 1-milisecond, 2-microsecond, 3-nanosecond. 13 | blind: 2 14 | 15 | mapping: 16 | acc_cov: 0.1 17 | gyr_cov: 0.1 18 | b_acc_cov: 0.0001 19 | b_gyr_cov: 0.0001 20 | fov_degree: 180 21 | det_range: 100.0 22 | extrinsic_est_en: false # true: enable the online estimation of IMU-LiDAR extrinsic, 23 | extrinsic_T: [ 0, 0, 0.28] 24 | extrinsic_R: [ 1, 0, 0, 25 | 0, 1, 0, 26 | 0, 0, 1] 27 | 28 | publish: 29 | path_en: false 30 | scan_publish_en: true # false: close all the point cloud output 31 | dense_publish_en: true # false: low down the points number in a global-frame point clouds scan. 32 | scan_bodyframe_pub_en: true # true: output the point cloud scans in IMU-body-frame 33 | 34 | pcd_save: 35 | pcd_save_en: true 36 | interval: -1 # how many LiDAR frames saved in each pcd file; 37 | # -1 : all frames will be saved in ONE pcd file, may lead to memory crash when having too much frames. 38 | -------------------------------------------------------------------------------- /doc/Fast_LIO_2.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/FAST_LIO/7cc4175de6f8ba2edf34bab02a42195b141027e9/doc/Fast_LIO_2.pdf -------------------------------------------------------------------------------- /doc/avia_scan.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/FAST_LIO/7cc4175de6f8ba2edf34bab02a42195b141027e9/doc/avia_scan.png -------------------------------------------------------------------------------- /doc/avia_scan2.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/FAST_LIO/7cc4175de6f8ba2edf34bab02a42195b141027e9/doc/avia_scan2.png -------------------------------------------------------------------------------- /doc/real_exp_2.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/FAST_LIO/7cc4175de6f8ba2edf34bab02a42195b141027e9/doc/real_exp_2.png -------------------------------------------------------------------------------- /doc/real_experiment2.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/FAST_LIO/7cc4175de6f8ba2edf34bab02a42195b141027e9/doc/real_experiment2.gif -------------------------------------------------------------------------------- /doc/results/HKU_HW.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/FAST_LIO/7cc4175de6f8ba2edf34bab02a42195b141027e9/doc/results/HKU_HW.png -------------------------------------------------------------------------------- /doc/results/HKU_LG_Indoor.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/FAST_LIO/7cc4175de6f8ba2edf34bab02a42195b141027e9/doc/results/HKU_LG_Indoor.png -------------------------------------------------------------------------------- /doc/results/HKU_MB_001.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/FAST_LIO/7cc4175de6f8ba2edf34bab02a42195b141027e9/doc/results/HKU_MB_001.png -------------------------------------------------------------------------------- /doc/results/HKU_MB_002.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/FAST_LIO/7cc4175de6f8ba2edf34bab02a42195b141027e9/doc/results/HKU_MB_002.png -------------------------------------------------------------------------------- /doc/results/HKU_MB_map.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/FAST_LIO/7cc4175de6f8ba2edf34bab02a42195b141027e9/doc/results/HKU_MB_map.png -------------------------------------------------------------------------------- /doc/results/Screenshot from 2020-10-15 20-33-35.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/FAST_LIO/7cc4175de6f8ba2edf34bab02a42195b141027e9/doc/results/Screenshot from 2020-10-15 20-33-35.png -------------------------------------------------------------------------------- /doc/results/Screenshot from 2020-10-15 20-35-46.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/FAST_LIO/7cc4175de6f8ba2edf34bab02a42195b141027e9/doc/results/Screenshot from 2020-10-15 20-35-46.png -------------------------------------------------------------------------------- /doc/results/Screenshot from 2020-10-15 20-37-48.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/FAST_LIO/7cc4175de6f8ba2edf34bab02a42195b141027e9/doc/results/Screenshot from 2020-10-15 20-37-48.png -------------------------------------------------------------------------------- /doc/results/indoor_loam.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/FAST_LIO/7cc4175de6f8ba2edf34bab02a42195b141027e9/doc/results/indoor_loam.png -------------------------------------------------------------------------------- /doc/results/indoor_loam_imu.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/FAST_LIO/7cc4175de6f8ba2edf34bab02a42195b141027e9/doc/results/indoor_loam_imu.png -------------------------------------------------------------------------------- /doc/results/indoor_our.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/FAST_LIO/7cc4175de6f8ba2edf34bab02a42195b141027e9/doc/results/indoor_our.png -------------------------------------------------------------------------------- /doc/results/long_corrid.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/FAST_LIO/7cc4175de6f8ba2edf34bab02a42195b141027e9/doc/results/long_corrid.png -------------------------------------------------------------------------------- /doc/results/uav2_path.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/FAST_LIO/7cc4175de6f8ba2edf34bab02a42195b141027e9/doc/results/uav2_path.png -------------------------------------------------------------------------------- /doc/results/uav2_test_map.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/FAST_LIO/7cc4175de6f8ba2edf34bab02a42195b141027e9/doc/results/uav2_test_map.png -------------------------------------------------------------------------------- /doc/results/uav_lg.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/FAST_LIO/7cc4175de6f8ba2edf34bab02a42195b141027e9/doc/results/uav_lg.png -------------------------------------------------------------------------------- /doc/results/uav_lg_0.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/FAST_LIO/7cc4175de6f8ba2edf34bab02a42195b141027e9/doc/results/uav_lg_0.png -------------------------------------------------------------------------------- /doc/results/uav_lg_2.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/FAST_LIO/7cc4175de6f8ba2edf34bab02a42195b141027e9/doc/results/uav_lg_2.png -------------------------------------------------------------------------------- /doc/uav01.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/FAST_LIO/7cc4175de6f8ba2edf34bab02a42195b141027e9/doc/uav01.jpg -------------------------------------------------------------------------------- /doc/uav_ground.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/FAST_LIO/7cc4175de6f8ba2edf34bab02a42195b141027e9/doc/uav_ground.pdf -------------------------------------------------------------------------------- /doc/uav_system.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/FAST_LIO/7cc4175de6f8ba2edf34bab02a42195b141027e9/doc/uav_system.png -------------------------------------------------------------------------------- /doc/ulhkwh_fastlio.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/FAST_LIO/7cc4175de6f8ba2edf34bab02a42195b141027e9/doc/ulhkwh_fastlio.gif -------------------------------------------------------------------------------- /include/Exp_mat.h: -------------------------------------------------------------------------------- 1 | #ifndef EXP_MAT_H 2 | #define EXP_MAT_H 3 | 4 | #include 5 | #include 6 | #include 7 | // #include 8 | 9 | #define SKEW_SYM_MATRX(v) 0.0,-v[2],v[1],v[2],0.0,-v[0],-v[1],v[0],0.0 10 | 11 | template 12 | Eigen::Matrix Exp(const Eigen::Matrix &&ang) 13 | { 14 | T ang_norm = ang.norm(); 15 | Eigen::Matrix Eye3 = Eigen::Matrix::Identity(); 16 | if (ang_norm > 0.0000001) 17 | { 18 | Eigen::Matrix r_axis = ang / ang_norm; 19 | Eigen::Matrix K; 20 | K << SKEW_SYM_MATRX(r_axis); 21 | /// Roderigous Tranformation 22 | return Eye3 + std::sin(ang_norm) * K + (1.0 - std::cos(ang_norm)) * K * K; 23 | } 24 | else 25 | { 26 | return Eye3; 27 | } 28 | } 29 | 30 | template 31 | Eigen::Matrix Exp(const Eigen::Matrix &ang_vel, const Ts &dt) 32 | { 33 | T ang_vel_norm = ang_vel.norm(); 34 | Eigen::Matrix Eye3 = Eigen::Matrix::Identity(); 35 | 36 | if (ang_vel_norm > 0.0000001) 37 | { 38 | Eigen::Matrix r_axis = ang_vel / ang_vel_norm; 39 | Eigen::Matrix K; 40 | 41 | K << SKEW_SYM_MATRX(r_axis); 42 | 43 | T r_ang = ang_vel_norm * dt; 44 | 45 | /// Roderigous Tranformation 46 | return Eye3 + std::sin(r_ang) * K + (1.0 - std::cos(r_ang)) * K * K; 47 | } 48 | else 49 | { 50 | return Eye3; 51 | } 52 | } 53 | 54 | template 55 | Eigen::Matrix Exp(const T &v1, const T &v2, const T &v3) 56 | { 57 | T &&norm = sqrt(v1 * v1 + v2 * v2 + v3 * v3); 58 | Eigen::Matrix Eye3 = Eigen::Matrix::Identity(); 59 | if (norm > 0.00001) 60 | { 61 | T r_ang[3] = {v1 / norm, v2 / norm, v3 / norm}; 62 | Eigen::Matrix K; 63 | K << SKEW_SYM_MATRX(r_ang); 64 | 65 | /// Roderigous Tranformation 66 | return Eye3 + std::sin(norm) * K + (1.0 - std::cos(norm)) * K * K; 67 | } 68 | else 69 | { 70 | return Eye3; 71 | } 72 | } 73 | 74 | /* Logrithm of a Rotation Matrix */ 75 | template 76 | Eigen::Matrix Log(const Eigen::Matrix &R) 77 | { 78 | T &&theta = std::acos(0.5 * (R.trace() - 1)); 79 | Eigen::Matrix K(R(2,1) - R(1,2), R(0,2) - R(2,0), R(1,0) - R(0,1)); 80 | return (std::abs(theta) < 0.001) ? (0.5 * K) : (0.5 * theta / std::sin(theta) * K); 81 | } 82 | 83 | // template 84 | // cv::Mat Exp(const T &v1, const T &v2, const T &v3) 85 | // { 86 | 87 | // T norm = sqrt(v1 * v1 + v2 * v2 + v3 * v3); 88 | // cv::Mat Eye3 = cv::Mat::eye(3, 3, CV_32F); 89 | // if (norm > 0.0000001) 90 | // { 91 | // T r_ang[3] = {v1 / norm, v2 / norm, v3 / norm}; 92 | // cv::Mat K = (cv::Mat_(3,3) << SKEW_SYM_MATRX(r_ang)); 93 | 94 | // /// Roderigous Tranformation 95 | // return Eye3 + std::sin(norm) * K + (1.0 - std::cos(norm)) * K * K; 96 | // } 97 | // else 98 | // { 99 | // return Eye3; 100 | // } 101 | // } 102 | 103 | #endif 104 | -------------------------------------------------------------------------------- /include/IKFoM_toolkit/esekfom/util.hpp: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (c) 2019--2023, The University of Hong Kong 3 | * All rights reserved. 4 | * 5 | * Author: Dongjiao HE 6 | * 7 | * Redistribution and use in source and binary forms, with or without 8 | * modification, are permitted provided that the following conditions 9 | * are met: 10 | * 11 | * * Redistributions of source code must retain the above copyright 12 | * notice, this list of conditions and the following disclaimer. 13 | * * Redistributions in binary form must reproduce the above 14 | * copyright notice, this list of conditions and the following 15 | * disclaimer in the documentation and/or other materials provided 16 | * with the distribution. 17 | * * Neither the name of the Universitaet Bremen nor the names of its 18 | * contributors may be used to endorse or promote products derived 19 | * from this software without specific prior written permission. 20 | * 21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 22 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 23 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 24 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 25 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 26 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 27 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 28 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 29 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 30 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 31 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 32 | * POSSIBILITY OF SUCH DAMAGE. 33 | */ 34 | 35 | #ifndef __MEKFOM_UTIL_HPP__ 36 | #define __MEKFOM_UTIL_HPP__ 37 | 38 | #include 39 | #include "../mtk/src/mtkmath.hpp" 40 | namespace esekfom { 41 | 42 | template 43 | class is_same { 44 | public: 45 | operator bool() { 46 | return false; 47 | } 48 | }; 49 | template 50 | class is_same { 51 | public: 52 | operator bool() { 53 | return true; 54 | } 55 | }; 56 | 57 | template 58 | class is_double { 59 | public: 60 | operator bool() { 61 | return false; 62 | } 63 | }; 64 | 65 | template<> 66 | class is_double { 67 | public: 68 | operator bool() { 69 | return true; 70 | } 71 | }; 72 | 73 | template 74 | static T 75 | id(const T &x) 76 | { 77 | return x; 78 | } 79 | 80 | } // namespace esekfom 81 | 82 | #endif // __MEKFOM_UTIL_HPP__ 83 | -------------------------------------------------------------------------------- /include/IKFoM_toolkit/mtk/build_manifold.hpp: -------------------------------------------------------------------------------- 1 | // This is an advanced implementation of the algorithm described in the 2 | // following paper: 3 | // C. Hertzberg, R. Wagner, U. Frese, and L. Schroder. Integratinggeneric sensor fusion algorithms with sound state representationsthrough encapsulation of manifolds. 4 | // CoRR, vol. abs/1107.1119, 2011.[Online]. Available: http://arxiv.org/abs/1107.1119 5 | 6 | /* 7 | * Copyright (c) 2019--2023, The University of Hong Kong 8 | * All rights reserved. 9 | * 10 | * Modifier: Dongjiao HE 11 | * 12 | * Redistribution and use in source and binary forms, with or without 13 | * modification, are permitted provided that the following conditions 14 | * are met: 15 | * 16 | * * Redistributions of source code must retain the above copyright 17 | * notice, this list of conditions and the following disclaimer. 18 | * * Redistributions in binary form must reproduce the above 19 | * copyright notice, this list of conditions and the following 20 | * disclaimer in the documentation and/or other materials provided 21 | * with the distribution. 22 | * * Neither the name of the Universitaet Bremen nor the names of its 23 | * contributors may be used to endorse or promote products derived 24 | * from this software without specific prior written permission. 25 | * 26 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 27 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 28 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 29 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 30 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 31 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 32 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 33 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 34 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 35 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 36 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 37 | * POSSIBILITY OF SUCH DAMAGE. 38 | */ 39 | 40 | /* 41 | * Copyright (c) 2008--2011, Universitaet Bremen 42 | * All rights reserved. 43 | * 44 | * Author: Christoph Hertzberg 45 | * 46 | * Redistribution and use in source and binary forms, with or without 47 | * modification, are permitted provided that the following conditions 48 | * are met: 49 | * 50 | * * Redistributions of source code must retain the above copyright 51 | * notice, this list of conditions and the following disclaimer. 52 | * * Redistributions in binary form must reproduce the above 53 | * copyright notice, this list of conditions and the following 54 | * disclaimer in the documentation and/or other materials provided 55 | * with the distribution. 56 | * * Neither the name of the Universitaet Bremen nor the names of its 57 | * contributors may be used to endorse or promote products derived 58 | * from this software without specific prior written permission. 59 | * 60 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 61 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 62 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 63 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 64 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 65 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 66 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 67 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 68 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 69 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 70 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 71 | * POSSIBILITY OF SUCH DAMAGE. 72 | */ 73 | /** 74 | * @file mtk/build_manifold.hpp 75 | * @brief Macro to automatically construct compound manifolds. 76 | * 77 | */ 78 | #ifndef MTK_AUTOCONSTRUCT_HPP_ 79 | #define MTK_AUTOCONSTRUCT_HPP_ 80 | 81 | #include 82 | 83 | #include 84 | #include 85 | #include 86 | 87 | #include "src/SubManifold.hpp" 88 | #include "startIdx.hpp" 89 | 90 | #ifndef PARSED_BY_DOXYGEN 91 | //////// internals ////// 92 | 93 | #define MTK_APPLY_MACRO_ON_TUPLE(r, macro, tuple) macro tuple 94 | 95 | #define MTK_TRANSFORM_COMMA(macro, entries) BOOST_PP_SEQ_ENUM(BOOST_PP_SEQ_TRANSFORM_S(1, MTK_APPLY_MACRO_ON_TUPLE, macro, entries)) 96 | 97 | #define MTK_TRANSFORM(macro, entries) BOOST_PP_SEQ_FOR_EACH_R(1, MTK_APPLY_MACRO_ON_TUPLE, macro, entries) 98 | 99 | #define MTK_CONSTRUCTOR_ARG( type, id) const type& id = type() 100 | #define MTK_CONSTRUCTOR_COPY( type, id) id(id) 101 | #define MTK_BOXPLUS( type, id) id.boxplus(MTK::subvector(__vec, &self::id), __scale); 102 | #define MTK_OPLUS( type, id) id.oplus(MTK::subvector_(__vec, &self::id), __scale); 103 | #define MTK_BOXMINUS( type, id) id.boxminus(MTK::subvector(__res, &self::id), __oth.id); 104 | #define MTK_S2_hat( type, id) if(id.IDX == idx){id.S2_hat(res);} 105 | #define MTK_S2_Nx_yy( type, id) if(id.IDX == idx){id.S2_Nx_yy(res);} 106 | #define MTK_S2_Mx( type, id) if(id.IDX == idx){id.S2_Mx(res, dx);} 107 | #define MTK_OSTREAM( type, id) << __var.id << " " 108 | #define MTK_ISTREAM( type, id) >> __var.id 109 | #define MTK_S2_state( type, id) if(id.TYP == 1){S2_state.push_back(std::make_pair(id.IDX, id.DIM));} 110 | #define MTK_SO3_state( type, id) if(id.TYP == 2){(SO3_state).push_back(std::make_pair(id.IDX, id.DIM));} 111 | #define MTK_vect_state( type, id) if(id.TYP == 0){(vect_state).push_back(std::make_pair(std::make_pair(id.IDX, id.DIM), type::DOF));} 112 | 113 | #define MTK_SUBVARLIST(seq, S2state, SO3state) \ 114 | BOOST_PP_FOR_1( \ 115 | ( \ 116 | BOOST_PP_SEQ_SIZE(seq), \ 117 | BOOST_PP_SEQ_HEAD(seq), \ 118 | BOOST_PP_SEQ_TAIL(seq) (~), \ 119 | 0,\ 120 | 0,\ 121 | S2state,\ 122 | SO3state ),\ 123 | MTK_ENTRIES_TEST, MTK_ENTRIES_NEXT, MTK_ENTRIES_OUTPUT) 124 | 125 | #define MTK_PUT_TYPE(type, id, dof, dim, S2state, SO3state) \ 126 | MTK::SubManifold id; 127 | #define MTK_PUT_TYPE_AND_ENUM(type, id, dof, dim, S2state, SO3state) \ 128 | MTK_PUT_TYPE(type, id, dof, dim, S2state, SO3state) \ 129 | enum {DOF = type::DOF + dof}; \ 130 | enum {DIM = type::DIM+dim}; \ 131 | typedef type::scalar scalar; 132 | 133 | #define MTK_ENTRIES_OUTPUT(r, state) MTK_ENTRIES_OUTPUT_I state 134 | #define MTK_ENTRIES_OUTPUT_I(s, head, seq, dof, dim, S2state, SO3state) \ 135 | MTK_APPLY_MACRO_ON_TUPLE(~, \ 136 | BOOST_PP_IF(BOOST_PP_DEC(s), MTK_PUT_TYPE, MTK_PUT_TYPE_AND_ENUM), \ 137 | ( BOOST_PP_TUPLE_REM_2 head, dof, dim, S2state, SO3state)) 138 | 139 | #define MTK_ENTRIES_TEST(r, state) MTK_TUPLE_ELEM_4_0 state 140 | 141 | //! this used to be BOOST_PP_TUPLE_ELEM_4_0: 142 | #define MTK_TUPLE_ELEM_4_0(a,b,c,d,e,f, g) a 143 | 144 | #define MTK_ENTRIES_NEXT(r, state) MTK_ENTRIES_NEXT_I state 145 | #define MTK_ENTRIES_NEXT_I(len, head, seq, dof, dim, S2state, SO3state) ( \ 146 | BOOST_PP_DEC(len), \ 147 | BOOST_PP_SEQ_HEAD(seq), \ 148 | BOOST_PP_SEQ_TAIL(seq), \ 149 | dof + BOOST_PP_TUPLE_ELEM_2_0 head::DOF,\ 150 | dim + BOOST_PP_TUPLE_ELEM_2_0 head::DIM,\ 151 | S2state,\ 152 | SO3state) 153 | 154 | #endif /* not PARSED_BY_DOXYGEN */ 155 | 156 | 157 | /** 158 | * Construct a manifold. 159 | * @param name is the class-name of the manifold, 160 | * @param entries is the list of sub manifolds 161 | * 162 | * Entries must be given in a list like this: 163 | * @code 164 | * typedef MTK::trafo > Pose; 165 | * typedef MTK::vect Vec3; 166 | * MTK_BUILD_MANIFOLD(imu_state, 167 | * ((Pose, pose)) 168 | * ((Vec3, vel)) 169 | * ((Vec3, acc_bias)) 170 | * ) 171 | * @endcode 172 | * Whitespace is optional, but the double parentheses are necessary. 173 | * Construction is done entirely in preprocessor. 174 | * After construction @a name is also a manifold. Its members can be 175 | * accessed by names given in @a entries. 176 | * 177 | * @note Variable types are not allowed to have commas, thus types like 178 | * @c vect need to be typedef'ed ahead. 179 | */ 180 | #define MTK_BUILD_MANIFOLD(name, entries) \ 181 | struct name { \ 182 | typedef name self; \ 183 | std::vector > S2_state;\ 184 | std::vector > SO3_state;\ 185 | std::vector, int> > vect_state;\ 186 | MTK_SUBVARLIST(entries, S2_state, SO3_state) \ 187 | name ( \ 188 | MTK_TRANSFORM_COMMA(MTK_CONSTRUCTOR_ARG, entries) \ 189 | ) : \ 190 | MTK_TRANSFORM_COMMA(MTK_CONSTRUCTOR_COPY, entries) {}\ 191 | int getDOF() const { return DOF; } \ 192 | void boxplus(const MTK::vectview & __vec, scalar __scale = 1 ) { \ 193 | MTK_TRANSFORM(MTK_BOXPLUS, entries)\ 194 | } \ 195 | void oplus(const MTK::vectview & __vec, scalar __scale = 1 ) { \ 196 | MTK_TRANSFORM(MTK_OPLUS, entries)\ 197 | } \ 198 | void boxminus(MTK::vectview __res, const name& __oth) const { \ 199 | MTK_TRANSFORM(MTK_BOXMINUS, entries)\ 200 | } \ 201 | friend std::ostream& operator<<(std::ostream& __os, const name& __var){ \ 202 | return __os MTK_TRANSFORM(MTK_OSTREAM, entries); \ 203 | } \ 204 | void build_S2_state(){\ 205 | MTK_TRANSFORM(MTK_S2_state, entries)\ 206 | }\ 207 | void build_vect_state(){\ 208 | MTK_TRANSFORM(MTK_vect_state, entries)\ 209 | }\ 210 | void build_SO3_state(){\ 211 | MTK_TRANSFORM(MTK_SO3_state, entries)\ 212 | }\ 213 | void S2_hat(Eigen::Matrix &res, int idx) {\ 214 | MTK_TRANSFORM(MTK_S2_hat, entries)\ 215 | }\ 216 | void S2_Nx_yy(Eigen::Matrix &res, int idx) {\ 217 | MTK_TRANSFORM(MTK_S2_Nx_yy, entries)\ 218 | }\ 219 | void S2_Mx(Eigen::Matrix &res, Eigen::Matrix dx, int idx) {\ 220 | MTK_TRANSFORM(MTK_S2_Mx, entries)\ 221 | }\ 222 | friend std::istream& operator>>(std::istream& __is, name& __var){ \ 223 | return __is MTK_TRANSFORM(MTK_ISTREAM, entries); \ 224 | } \ 225 | }; 226 | 227 | 228 | 229 | #endif /*MTK_AUTOCONSTRUCT_HPP_*/ 230 | -------------------------------------------------------------------------------- /include/IKFoM_toolkit/mtk/src/SubManifold.hpp: -------------------------------------------------------------------------------- 1 | // This is an advanced implementation of the algorithm described in the 2 | // following paper: 3 | // C. Hertzberg, R. Wagner, U. Frese, and L. Schroder. Integratinggeneric sensor fusion algorithms with sound state representationsthrough encapsulation of manifolds. 4 | // CoRR, vol. abs/1107.1119, 2011.[Online]. Available: http://arxiv.org/abs/1107.1119 5 | 6 | /* 7 | * Copyright (c) 2019--2023, The University of Hong Kong 8 | * All rights reserved. 9 | * 10 | * Modifier: Dongjiao HE 11 | * 12 | * Redistribution and use in source and binary forms, with or without 13 | * modification, are permitted provided that the following conditions 14 | * are met: 15 | * 16 | * * Redistributions of source code must retain the above copyright 17 | * notice, this list of conditions and the following disclaimer. 18 | * * Redistributions in binary form must reproduce the above 19 | * copyright notice, this list of conditions and the following 20 | * disclaimer in the documentation and/or other materials provided 21 | * with the distribution. 22 | * * Neither the name of the Universitaet Bremen nor the names of its 23 | * contributors may be used to endorse or promote products derived 24 | * from this software without specific prior written permission. 25 | * 26 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 27 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 28 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 29 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 30 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 31 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 32 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 33 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 34 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 35 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 36 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 37 | * POSSIBILITY OF SUCH DAMAGE. 38 | */ 39 | 40 | /* 41 | * Copyright (c) 2008--2011, Universitaet Bremen 42 | * All rights reserved. 43 | * 44 | * Author: Christoph Hertzberg 45 | * 46 | * Redistribution and use in source and binary forms, with or without 47 | * modification, are permitted provided that the following conditions 48 | * are met: 49 | * 50 | * * Redistributions of source code must retain the above copyright 51 | * notice, this list of conditions and the following disclaimer. 52 | * * Redistributions in binary form must reproduce the above 53 | * copyright notice, this list of conditions and the following 54 | * disclaimer in the documentation and/or other materials provided 55 | * with the distribution. 56 | * * Neither the name of the Universitaet Bremen nor the names of its 57 | * contributors may be used to endorse or promote products derived 58 | * from this software without specific prior written permission. 59 | * 60 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 61 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 62 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 63 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 64 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 65 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 66 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 67 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 68 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 69 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 70 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 71 | * POSSIBILITY OF SUCH DAMAGE. 72 | */ 73 | /** 74 | * @file mtk/src/SubManifold.hpp 75 | * @brief Defines the SubManifold class 76 | */ 77 | 78 | 79 | #ifndef SUBMANIFOLD_HPP_ 80 | #define SUBMANIFOLD_HPP_ 81 | 82 | 83 | #include "vectview.hpp" 84 | 85 | 86 | namespace MTK { 87 | 88 | /** 89 | * @ingroup SubManifolds 90 | * Helper class for compound manifolds. 91 | * This class wraps a manifold T and provides an enum IDX refering to the 92 | * index of the SubManifold within the compound manifold. 93 | * 94 | * Memberpointers to a submanifold can be used for @ref SubManifolds "functions accessing submanifolds". 95 | * 96 | * @tparam T The manifold type of the sub-type 97 | * @tparam idx The index of the sub-type within the compound manifold 98 | */ 99 | template 100 | struct SubManifold : public T 101 | { 102 | enum {IDX = idx, DIM = dim /*!< index of the sub-type within the compound manifold */ }; 103 | //! manifold type 104 | typedef T type; 105 | 106 | //! Construct from derived type 107 | template 108 | explicit 109 | SubManifold(const X& t) : T(t) {}; 110 | 111 | //! Construct from internal type 112 | //explicit 113 | SubManifold(const T& t) : T(t) {}; 114 | 115 | //! inherit assignment operator 116 | using T::operator=; 117 | 118 | }; 119 | 120 | } // namespace MTK 121 | 122 | 123 | #endif /* SUBMANIFOLD_HPP_ */ 124 | -------------------------------------------------------------------------------- /include/IKFoM_toolkit/mtk/src/mtkmath.hpp: -------------------------------------------------------------------------------- 1 | // This is an advanced implementation of the algorithm described in the 2 | // following paper: 3 | // C. Hertzberg, R. Wagner, U. Frese, and L. Schroder. Integratinggeneric sensor fusion algorithms with sound state representationsthrough encapsulation of manifolds. 4 | // CoRR, vol. abs/1107.1119, 2011.[Online]. Available: http://arxiv.org/abs/1107.1119 5 | 6 | /* 7 | * Copyright (c) 2019--2023, The University of Hong Kong 8 | * All rights reserved. 9 | * 10 | * Modifier: Dongjiao HE 11 | * 12 | * Redistribution and use in source and binary forms, with or without 13 | * modification, are permitted provided that the following conditions 14 | * are met: 15 | * 16 | * * Redistributions of source code must retain the above copyright 17 | * notice, this list of conditions and the following disclaimer. 18 | * * Redistributions in binary form must reproduce the above 19 | * copyright notice, this list of conditions and the following 20 | * disclaimer in the documentation and/or other materials provided 21 | * with the distribution. 22 | * * Neither the name of the Universitaet Bremen nor the names of its 23 | * contributors may be used to endorse or promote products derived 24 | * from this software without specific prior written permission. 25 | * 26 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 27 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 28 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 29 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 30 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 31 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 32 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 33 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 34 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 35 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 36 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 37 | * POSSIBILITY OF SUCH DAMAGE. 38 | */ 39 | 40 | /* 41 | * Copyright (c) 2008--2011, Universitaet Bremen 42 | * All rights reserved. 43 | * 44 | * Author: Christoph Hertzberg 45 | * 46 | * Redistribution and use in source and binary forms, with or without 47 | * modification, are permitted provided that the following conditions 48 | * are met: 49 | * 50 | * * Redistributions of source code must retain the above copyright 51 | * notice, this list of conditions and the following disclaimer. 52 | * * Redistributions in binary form must reproduce the above 53 | * copyright notice, this list of conditions and the following 54 | * disclaimer in the documentation and/or other materials provided 55 | * with the distribution. 56 | * * Neither the name of the Universitaet Bremen nor the names of its 57 | * contributors may be used to endorse or promote products derived 58 | * from this software without specific prior written permission. 59 | * 60 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 61 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 62 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 63 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 64 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 65 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 66 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 67 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 68 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 69 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 70 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 71 | * POSSIBILITY OF SUCH DAMAGE. 72 | */ 73 | /** 74 | * @file mtk/src/mtkmath.hpp 75 | * @brief several math utility functions. 76 | */ 77 | 78 | #ifndef MTKMATH_H_ 79 | #define MTKMATH_H_ 80 | 81 | #include 82 | 83 | #include 84 | 85 | #include "../types/vect.hpp" 86 | 87 | #ifndef M_PI 88 | #define M_PI 3.1415926535897932384626433832795 89 | #endif 90 | 91 | 92 | namespace MTK { 93 | 94 | namespace internal { 95 | 96 | template 97 | struct traits { 98 | typedef typename Manifold::scalar scalar; 99 | enum {DOF = Manifold::DOF}; 100 | typedef vect vectorized_type; 101 | typedef Eigen::Matrix matrix_type; 102 | }; 103 | 104 | template<> 105 | struct traits : traits > {}; 106 | template<> 107 | struct traits : traits > {}; 108 | 109 | } // namespace internal 110 | 111 | /** 112 | * \defgroup MTKMath Mathematical helper functions 113 | */ 114 | //@{ 115 | 116 | //! constant @f$ \pi @f$ 117 | const double pi = M_PI; 118 | 119 | template inline scalar tolerance(); 120 | 121 | template<> inline float tolerance() { return 1e-5f; } 122 | template<> inline double tolerance() { return 1e-11; } 123 | 124 | 125 | /** 126 | * normalize @a x to @f$[-bound, bound] @f$. 127 | * 128 | * result for @f$ x = bound + 2\cdot n\cdot bound @f$ is arbitrary @f$\pm bound @f$. 129 | */ 130 | template 131 | inline scalar normalize(scalar x, scalar bound){ //not used 132 | if(std::fabs(x) <= bound) return x; 133 | int r = (int)(x *(scalar(1.0)/ bound)); 134 | return x - ((r + (r>>31) + 1) & ~1)*bound; 135 | } 136 | 137 | /** 138 | * Calculate cosine and sinc of sqrt(x2). 139 | * @param x2 the squared angle must be non-negative 140 | * @return a pair containing cos and sinc of sqrt(x2) 141 | */ 142 | template 143 | std::pair cos_sinc_sqrt(const scalar &x2){ 144 | using std::sqrt; 145 | using std::cos; 146 | using std::sin; 147 | static scalar const taylor_0_bound = boost::math::tools::epsilon(); 148 | static scalar const taylor_2_bound = sqrt(taylor_0_bound); 149 | static scalar const taylor_n_bound = sqrt(taylor_2_bound); 150 | 151 | assert(x2>=0 && "argument must be non-negative"); 152 | 153 | // FIXME check if bigger bounds are possible 154 | if(x2>=taylor_n_bound) { 155 | // slow fall-back solution 156 | scalar x = sqrt(x2); 157 | return std::make_pair(cos(x), sin(x)/x); // x is greater than 0. 158 | } 159 | 160 | // FIXME Replace by Horner-Scheme (4 instead of 5 FLOP/term, numerically more stable, theoretically cos and sinc can be calculated in parallel using SSE2 mulpd/addpd) 161 | // TODO Find optimal coefficients using Remez algorithm 162 | static scalar const inv[] = {1/3., 1/4., 1/5., 1/6., 1/7., 1/8., 1/9.}; 163 | scalar cosi = 1., sinc=1; 164 | scalar term = -1/2. * x2; 165 | for(int i=0; i<3; ++i) { 166 | cosi += term; 167 | term *= inv[2*i]; 168 | sinc += term; 169 | term *= -inv[2*i+1] * x2; 170 | } 171 | 172 | return std::make_pair(cosi, sinc); 173 | 174 | } 175 | 176 | template 177 | Eigen::Matrix hat(const Base& v) { 178 | Eigen::Matrix res; 179 | res << 0, -v[2], v[1], 180 | v[2], 0, -v[0], 181 | -v[1], v[0], 0; 182 | return res; 183 | } 184 | 185 | template 186 | Eigen::Matrix A_inv_trans(const Base& v){ 187 | Eigen::Matrix res; 188 | if(v.norm() > MTK::tolerance()) 189 | { 190 | res = Eigen::Matrix::Identity() + 0.5 * hat(v) + (1 - v.norm() * std::cos(v.norm() / 2) / 2 / std::sin(v.norm() / 2)) * hat(v) * hat(v) / v.squaredNorm(); 191 | 192 | } 193 | else 194 | { 195 | res = Eigen::Matrix::Identity(); 196 | } 197 | 198 | return res; 199 | } 200 | 201 | template 202 | Eigen::Matrix A_inv(const Base& v){ 203 | Eigen::Matrix res; 204 | if(v.norm() > MTK::tolerance()) 205 | { 206 | res = Eigen::Matrix::Identity() - 0.5 * hat(v) + (1 - v.norm() * std::cos(v.norm() / 2) / 2 / std::sin(v.norm() / 2)) * hat(v) * hat(v) / v.squaredNorm(); 207 | 208 | } 209 | else 210 | { 211 | res = Eigen::Matrix::Identity(); 212 | } 213 | 214 | return res; 215 | } 216 | 217 | template 218 | Eigen::Matrix S2_w_expw_( Eigen::Matrix v, scalar length) 219 | { 220 | Eigen::Matrix res; 221 | scalar norm = std::sqrt(v[0]*v[0] + v[1]*v[1]); 222 | if(norm < MTK::tolerance()){ 223 | res = Eigen::Matrix::Zero(); 224 | res(0, 1) = 1; 225 | res(1, 2) = 1; 226 | res /= length; 227 | } 228 | else{ 229 | res << -v[0]*(1/norm-1/std::tan(norm))/std::sin(norm), norm/std::sin(norm), 0, 230 | -v[1]*(1/norm-1/std::tan(norm))/std::sin(norm), 0, norm/std::sin(norm); 231 | res /= length; 232 | } 233 | } 234 | 235 | template 236 | Eigen::Matrix A_matrix(const Base & v){ 237 | Eigen::Matrix res; 238 | double squaredNorm = v[0] * v[0] + v[1] * v[1] + v[2] * v[2]; 239 | double norm = std::sqrt(squaredNorm); 240 | if(norm < MTK::tolerance()){ 241 | res = Eigen::Matrix::Identity(); 242 | } 243 | else{ 244 | res = Eigen::Matrix::Identity() + (1 - std::cos(norm)) / squaredNorm * hat(v) + (1 - std::sin(norm) / norm) / squaredNorm * hat(v) * hat(v); 245 | } 246 | return res; 247 | } 248 | 249 | template 250 | scalar exp(vectview result, vectview vec, const scalar& scale = 1) { 251 | scalar norm2 = vec.squaredNorm(); 252 | std::pair cos_sinc = cos_sinc_sqrt(scale*scale * norm2); 253 | scalar mult = cos_sinc.second * scale; 254 | result = mult * vec; 255 | return cos_sinc.first; 256 | } 257 | 258 | 259 | /** 260 | * Inverse function to @c exp. 261 | * 262 | * @param result @c vectview to the result 263 | * @param w scalar part of input 264 | * @param vec vector part of input 265 | * @param scale scale result by this value 266 | * @param plus_minus_periodicity if true values @f$[w, vec]@f$ and @f$[-w, -vec]@f$ give the same result 267 | */ 268 | template 269 | void log(vectview result, 270 | const scalar &w, const vectview vec, 271 | const scalar &scale, bool plus_minus_periodicity) 272 | { 273 | // FIXME implement optimized case for vec.squaredNorm() <= tolerance() * (w*w) via Rational Remez approximation ~> only one division 274 | scalar nv = vec.norm(); 275 | if(nv < tolerance()) { 276 | if(!plus_minus_periodicity && w < 0) { 277 | // find the maximal entry: 278 | int i; 279 | nv = vec.cwiseAbs().maxCoeff(&i); 280 | result = scale * std::atan2(nv, w) * vect::Unit(i); 281 | return; 282 | } 283 | nv = tolerance(); 284 | } 285 | scalar s = scale / nv * (plus_minus_periodicity ? std::atan(nv / w) : std::atan2(nv, w) ); 286 | 287 | result = s * vec; 288 | } 289 | 290 | 291 | } // namespace MTK 292 | 293 | 294 | #endif /* MTKMATH_H_ */ 295 | -------------------------------------------------------------------------------- /include/IKFoM_toolkit/mtk/src/vectview.hpp: -------------------------------------------------------------------------------- 1 | 2 | /* 3 | * Copyright (c) 2008--2011, Universitaet Bremen 4 | * All rights reserved. 5 | * 6 | * Author: Christoph Hertzberg 7 | * 8 | * Redistribution and use in source and binary forms, with or without 9 | * modification, are permitted provided that the following conditions 10 | * are met: 11 | * 12 | * * Redistributions of source code must retain the above copyright 13 | * notice, this list of conditions and the following disclaimer. 14 | * * Redistributions in binary form must reproduce the above 15 | * copyright notice, this list of conditions and the following 16 | * disclaimer in the documentation and/or other materials provided 17 | * with the distribution. 18 | * * Neither the name of the Universitaet Bremen nor the names of its 19 | * contributors may be used to endorse or promote products derived 20 | * from this software without specific prior written permission. 21 | * 22 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 23 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 24 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 25 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 26 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 27 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 28 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 29 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 30 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 31 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 32 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 33 | * POSSIBILITY OF SUCH DAMAGE. 34 | */ 35 | /** 36 | * @file mtk/src/vectview.hpp 37 | * @brief Wrapper class around a pointer used as interface for plain vectors. 38 | */ 39 | 40 | #ifndef VECTVIEW_HPP_ 41 | #define VECTVIEW_HPP_ 42 | 43 | #include 44 | 45 | namespace MTK { 46 | 47 | /** 48 | * A view to a vector. 49 | * Essentially, @c vectview is only a pointer to @c scalar but can be used directly in @c Eigen expressions. 50 | * The dimension of the vector is given as template parameter and type-checked when used in expressions. 51 | * Data has to be modifiable. 52 | * 53 | * @tparam scalar Scalar type of the vector. 54 | * @tparam dim Dimension of the vector. 55 | * 56 | * @todo @c vectview can be replaced by simple inheritance of @c Eigen::Map, as soon as they get const-correct 57 | */ 58 | namespace internal { 59 | template 60 | struct CovBlock { 61 | typedef typename Eigen::Block, T1::DOF, T2::DOF> Type; 62 | typedef typename Eigen::Block, T1::DOF, T2::DOF> ConstType; 63 | }; 64 | 65 | template 66 | struct CovBlock_ { 67 | typedef typename Eigen::Block, T1::DIM, T2::DIM> Type; 68 | typedef typename Eigen::Block, T1::DIM, T2::DIM> ConstType; 69 | }; 70 | 71 | template 72 | struct CrossCovBlock { 73 | typedef typename Eigen::Block, T1::DOF, T2::DOF> Type; 74 | typedef typename Eigen::Block, T1::DOF, T2::DOF> ConstType; 75 | }; 76 | 77 | template 78 | struct CrossCovBlock_ { 79 | typedef typename Eigen::Block, T1::DIM, T2::DIM> Type; 80 | typedef typename Eigen::Block, T1::DIM, T2::DIM> ConstType; 81 | }; 82 | 83 | template 84 | struct VectviewBase { 85 | typedef Eigen::Matrix matrix_type; 86 | typedef typename matrix_type::MapType Type; 87 | typedef typename matrix_type::ConstMapType ConstType; 88 | }; 89 | 90 | template 91 | struct UnalignedType { 92 | typedef T type; 93 | }; 94 | } 95 | 96 | template 97 | class vectview : public internal::VectviewBase::Type { 98 | typedef internal::VectviewBase VectviewBase; 99 | public: 100 | //! plain matrix type 101 | typedef typename VectviewBase::matrix_type matrix_type; 102 | //! base type 103 | typedef typename VectviewBase::Type base; 104 | //! construct from pointer 105 | explicit 106 | vectview(scalar* data, int dim_=dim) : base(data, dim_) {} 107 | //! construct from plain matrix 108 | vectview(matrix_type& m) : base(m.data(), m.size()) {} 109 | //! construct from another @c vectview 110 | vectview(const vectview &v) : base(v) {} 111 | //! construct from Eigen::Block: 112 | template 113 | vectview(Eigen::VectorBlock block) : base(&block.coeffRef(0), block.size()) {} 114 | template 115 | vectview(Eigen::Block block) : base(&block.coeffRef(0), block.size()) {} 116 | 117 | //! inherit assignment operator 118 | using base::operator=; 119 | //! data pointer 120 | scalar* data() {return const_cast(base::data());} 121 | }; 122 | 123 | /** 124 | * @c const version of @c vectview. 125 | * Compared to @c Eigen::Map this implementation is const correct, i.e., 126 | * data will not be modifiable using this view. 127 | * 128 | * @tparam scalar Scalar type of the vector. 129 | * @tparam dim Dimension of the vector. 130 | * 131 | * @sa vectview 132 | */ 133 | template 134 | class vectview : public internal::VectviewBase::ConstType { 135 | typedef internal::VectviewBase VectviewBase; 136 | public: 137 | //! plain matrix type 138 | typedef typename VectviewBase::matrix_type matrix_type; 139 | //! base type 140 | typedef typename VectviewBase::ConstType base; 141 | //! construct from const pointer 142 | explicit 143 | vectview(const scalar* data, int dim_ = dim) : base(data, dim_) {} 144 | //! construct from column vector 145 | template 146 | vectview(const Eigen::Matrix& m) : base(m.data()) {} 147 | //! construct from row vector 148 | template 149 | vectview(const Eigen::Matrix& m) : base(m.data()) {} 150 | //! construct from another @c vectview 151 | vectview(vectview x) : base(x.data()) {} 152 | //! construct from base 153 | vectview(const base &x) : base(x) {} 154 | /** 155 | * Construct from Block 156 | * @todo adapt this, when Block gets const-correct 157 | */ 158 | template 159 | vectview(Eigen::VectorBlock block) : base(&block.coeffRef(0)) {} 160 | template 161 | vectview(Eigen::Block block) : base(&block.coeffRef(0)) {} 162 | 163 | }; 164 | 165 | 166 | } // namespace MTK 167 | 168 | #endif /* VECTVIEW_HPP_ */ 169 | -------------------------------------------------------------------------------- /include/IKFoM_toolkit/mtk/startIdx.hpp: -------------------------------------------------------------------------------- 1 | // This is an advanced implementation of the algorithm described in the 2 | // following paper: 3 | // C. Hertzberg, R. Wagner, U. Frese, and L. Schroder. Integratinggeneric sensor fusion algorithms with sound state representationsthrough encapsulation of manifolds. 4 | // CoRR, vol. abs/1107.1119, 2011.[Online]. Available: http://arxiv.org/abs/1107.1119 5 | 6 | /* 7 | * Copyright (c) 2019--2023, The University of Hong Kong 8 | * All rights reserved. 9 | * 10 | * Modifier: Dongjiao HE 11 | * 12 | * Redistribution and use in source and binary forms, with or without 13 | * modification, are permitted provided that the following conditions 14 | * are met: 15 | * 16 | * * Redistributions of source code must retain the above copyright 17 | * notice, this list of conditions and the following disclaimer. 18 | * * Redistributions in binary form must reproduce the above 19 | * copyright notice, this list of conditions and the following 20 | * disclaimer in the documentation and/or other materials provided 21 | * with the distribution. 22 | * * Neither the name of the Universitaet Bremen nor the names of its 23 | * contributors may be used to endorse or promote products derived 24 | * from this software without specific prior written permission. 25 | * 26 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 27 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 28 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 29 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 30 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 31 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 32 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 33 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 34 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 35 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 36 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 37 | * POSSIBILITY OF SUCH DAMAGE. 38 | */ 39 | 40 | /* 41 | * Copyright (c) 2008--2011, Universitaet Bremen 42 | * All rights reserved. 43 | * 44 | * Author: Christoph Hertzberg 45 | * 46 | * Redistribution and use in source and binary forms, with or without 47 | * modification, are permitted provided that the following conditions 48 | * are met: 49 | * 50 | * * Redistributions of source code must retain the above copyright 51 | * notice, this list of conditions and the following disclaimer. 52 | * * Redistributions in binary form must reproduce the above 53 | * copyright notice, this list of conditions and the following 54 | * disclaimer in the documentation and/or other materials provided 55 | * with the distribution. 56 | * * Neither the name of the Universitaet Bremen nor the names of its 57 | * contributors may be used to endorse or promote products derived 58 | * from this software without specific prior written permission. 59 | * 60 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 61 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 62 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 63 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 64 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 65 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 66 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 67 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 68 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 69 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 70 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 71 | * POSSIBILITY OF SUCH DAMAGE. 72 | */ 73 | /** 74 | * @file mtk/startIdx.hpp 75 | * @brief Tools to access sub-elements of compound manifolds. 76 | */ 77 | #ifndef GET_START_INDEX_H_ 78 | #define GET_START_INDEX_H_ 79 | 80 | #include 81 | 82 | #include "src/SubManifold.hpp" 83 | #include "src/vectview.hpp" 84 | 85 | namespace MTK { 86 | 87 | 88 | /** 89 | * \defgroup SubManifolds Accessing Submanifolds 90 | * For compound manifolds constructed using MTK_BUILD_MANIFOLD, member pointers 91 | * can be used to get sub-vectors or matrix-blocks of a corresponding big matrix. 92 | * E.g. for a type @a pose consisting of @a orient and @a trans the member pointers 93 | * @c &pose::orient and @c &pose::trans give all required information and are still 94 | * valid if the base type gets extended or the actual types of @a orient and @a trans 95 | * change (e.g. from 2D to 3D). 96 | * 97 | * @todo Maybe require manifolds to typedef MatrixType and VectorType, etc. 98 | */ 99 | //@{ 100 | 101 | /** 102 | * Determine the index of a sub-variable within a compound variable. 103 | */ 104 | template 105 | int getStartIdx( MTK::SubManifold Base::*) 106 | { 107 | return idx; 108 | } 109 | 110 | template 111 | int getStartIdx_( MTK::SubManifold Base::*) 112 | { 113 | return dim; 114 | } 115 | 116 | /** 117 | * Determine the degrees of freedom of a sub-variable within a compound variable. 118 | */ 119 | template 120 | int getDof( MTK::SubManifold Base::*) 121 | { 122 | return T::DOF; 123 | } 124 | template 125 | int getDim( MTK::SubManifold Base::*) 126 | { 127 | return T::DIM; 128 | } 129 | 130 | /** 131 | * set the diagonal elements of a covariance matrix corresponding to a sub-variable 132 | */ 133 | template 134 | void setDiagonal(Eigen::Matrix &cov, 135 | MTK::SubManifold Base::*, const typename Base::scalar &val) 136 | { 137 | cov.diagonal().template segment(idx).setConstant(val); 138 | } 139 | 140 | template 141 | void setDiagonal_(Eigen::Matrix &cov, 142 | MTK::SubManifold Base::*, const typename Base::scalar &val) 143 | { 144 | cov.diagonal().template segment(dim).setConstant(val); 145 | } 146 | 147 | /** 148 | * Get the subblock of corresponding to two members, i.e. 149 | * \code 150 | * Eigen::Matrix m; 151 | * MTK::subblock(m, &Pose::orient, &Pose::trans) = some_expression; 152 | * MTK::subblock(m, &Pose::trans, &Pose::orient) = some_expression.trans(); 153 | * \endcode 154 | * lets you modify mixed covariance entries in a bigger covariance matrix. 155 | */ 156 | template 157 | typename MTK::internal::CovBlock::Type 158 | subblock(Eigen::Matrix &cov, 159 | MTK::SubManifold Base::*, MTK::SubManifold Base::*) 160 | { 161 | return cov.template block(idx1, idx2); 162 | } 163 | 164 | template 165 | typename MTK::internal::CovBlock_::Type 166 | subblock_(Eigen::Matrix &cov, 167 | MTK::SubManifold Base::*, MTK::SubManifold Base::*) 168 | { 169 | return cov.template block(dim1, dim2); 170 | } 171 | 172 | template 173 | typename MTK::internal::CrossCovBlock::Type 174 | subblock(Eigen::Matrix &cov, MTK::SubManifold Base1::*, MTK::SubManifold Base2::*) 175 | { 176 | return cov.template block(idx1, idx2); 177 | } 178 | 179 | template 180 | typename MTK::internal::CrossCovBlock_::Type 181 | subblock_(Eigen::Matrix &cov, MTK::SubManifold Base1::*, MTK::SubManifold Base2::*) 182 | { 183 | return cov.template block(dim1, dim2); 184 | } 185 | /** 186 | * Get the subblock of corresponding to a member, i.e. 187 | * \code 188 | * Eigen::Matrix m; 189 | * MTK::subblock(m, &Pose::orient) = some_expression; 190 | * \endcode 191 | * lets you modify covariance entries in a bigger covariance matrix. 192 | */ 193 | template 194 | typename MTK::internal::CovBlock_::Type 195 | subblock_(Eigen::Matrix &cov, 196 | MTK::SubManifold Base::*) 197 | { 198 | return cov.template block(dim, dim); 199 | } 200 | 201 | template 202 | typename MTK::internal::CovBlock::Type 203 | subblock(Eigen::Matrix &cov, 204 | MTK::SubManifold Base::*) 205 | { 206 | return cov.template block(idx, idx); 207 | } 208 | 209 | template 210 | class get_cov { 211 | public: 212 | typedef Eigen::Matrix type; 213 | typedef const Eigen::Matrix const_type; 214 | }; 215 | 216 | template 217 | class get_cov_ { 218 | public: 219 | typedef Eigen::Matrix type; 220 | typedef const Eigen::Matrix const_type; 221 | }; 222 | 223 | template 224 | class get_cross_cov { 225 | public: 226 | typedef Eigen::Matrix type; 227 | typedef const type const_type; 228 | }; 229 | 230 | template 231 | class get_cross_cov_ { 232 | public: 233 | typedef Eigen::Matrix type; 234 | typedef const type const_type; 235 | }; 236 | 237 | 238 | template 239 | vectview 240 | subvector_impl_(vectview vec, SubManifold Base::*) 241 | { 242 | return vec.template segment(dim); 243 | } 244 | 245 | template 246 | vectview 247 | subvector_impl(vectview vec, SubManifold Base::*) 248 | { 249 | return vec.template segment(idx); 250 | } 251 | 252 | /** 253 | * Get the subvector corresponding to a sub-manifold from a bigger vector. 254 | */ 255 | template 256 | vectview 257 | subvector_(vectview vec, SubManifold Base::* ptr) 258 | { 259 | return subvector_impl_(vec, ptr); 260 | } 261 | 262 | template 263 | vectview 264 | subvector(vectview vec, SubManifold Base::* ptr) 265 | { 266 | return subvector_impl(vec, ptr); 267 | } 268 | 269 | /** 270 | * @todo This should be covered already by subvector(vectview vec,SubManifold Base::*) 271 | */ 272 | template 273 | vectview 274 | subvector(Eigen::Matrix& vec, SubManifold Base::* ptr) 275 | { 276 | return subvector_impl(vectview(vec), ptr); 277 | } 278 | 279 | template 280 | vectview 281 | subvector_(Eigen::Matrix& vec, SubManifold Base::* ptr) 282 | { 283 | return subvector_impl_(vectview(vec), ptr); 284 | } 285 | 286 | template 287 | vectview 288 | subvector_(const Eigen::Matrix& vec, SubManifold Base::* ptr) 289 | { 290 | return subvector_impl_(vectview(vec), ptr); 291 | } 292 | 293 | template 294 | vectview 295 | subvector(const Eigen::Matrix& vec, SubManifold Base::* ptr) 296 | { 297 | return subvector_impl(vectview(vec), ptr); 298 | } 299 | 300 | 301 | /** 302 | * const version of subvector(vectview vec,SubManifold Base::*) 303 | */ 304 | template 305 | vectview 306 | subvector_impl(const vectview cvec, SubManifold Base::*) 307 | { 308 | return cvec.template segment(idx); 309 | } 310 | 311 | template 312 | vectview 313 | subvector_impl_(const vectview cvec, SubManifold Base::*) 314 | { 315 | return cvec.template segment(dim); 316 | } 317 | 318 | template 319 | vectview 320 | subvector(const vectview cvec, SubManifold Base::* ptr) 321 | { 322 | return subvector_impl(cvec, ptr); 323 | } 324 | 325 | 326 | } // namespace MTK 327 | 328 | #endif // GET_START_INDEX_H_ 329 | -------------------------------------------------------------------------------- /include/IKFoM_toolkit/mtk/types/S2.hpp: -------------------------------------------------------------------------------- 1 | // This is a NEW implementation of the algorithm described in the 2 | // following paper: 3 | // C. Hertzberg, R. Wagner, U. Frese, and L. Schroder. Integratinggeneric sensor fusion algorithms with sound state representationsthrough encapsulation of manifolds. 4 | // CoRR, vol. abs/1107.1119, 2011.[Online]. Available: http://arxiv.org/abs/1107.1119 5 | 6 | /* 7 | * Copyright (c) 2019--2023, The University of Hong Kong 8 | * All rights reserved. 9 | * 10 | * Modifier: Dongjiao HE 11 | * 12 | * Redistribution and use in source and binary forms, with or without 13 | * modification, are permitted provided that the following conditions 14 | * are met: 15 | * 16 | * * Redistributions of source code must retain the above copyright 17 | * notice, this list of conditions and the following disclaimer. 18 | * * Redistributions in binary form must reproduce the above 19 | * copyright notice, this list of conditions and the following 20 | * disclaimer in the documentation and/or other materials provided 21 | * with the distribution. 22 | * * Neither the name of the Universitaet Bremen nor the names of its 23 | * contributors may be used to endorse or promote products derived 24 | * from this software without specific prior written permission. 25 | * 26 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 27 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 28 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 29 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 30 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 31 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 32 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 33 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 34 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 35 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 36 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 37 | * POSSIBILITY OF SUCH DAMAGE. 38 | */ 39 | 40 | /* 41 | * Copyright (c) 2008--2011, Universitaet Bremen 42 | * All rights reserved. 43 | * 44 | * Author: Christoph Hertzberg 45 | * 46 | * Redistribution and use in source and binary forms, with or without 47 | * modification, are permitted provided that the following conditions 48 | * are met: 49 | * 50 | * * Redistributions of source code must retain the above copyright 51 | * notice, this list of conditions and the following disclaimer. 52 | * * Redistributions in binary form must reproduce the above 53 | * copyright notice, this list of conditions and the following 54 | * disclaimer in the documentation and/or other materials provided 55 | * with the distribution. 56 | * * Neither the name of the Universitaet Bremen nor the names of its 57 | * contributors may be used to endorse or promote products derived 58 | * from this software without specific prior written permission. 59 | * 60 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 61 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 62 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 63 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 64 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 65 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 66 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 67 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 68 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 69 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 70 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 71 | * POSSIBILITY OF SUCH DAMAGE. 72 | */ 73 | /** 74 | * @file mtk/types/S2.hpp 75 | * @brief Unit vectors on the sphere, or directions in 3D. 76 | */ 77 | #ifndef S2_H_ 78 | #define S2_H_ 79 | 80 | 81 | #include "vect.hpp" 82 | 83 | #include "SOn.hpp" 84 | #include "../src/mtkmath.hpp" 85 | 86 | 87 | 88 | 89 | namespace MTK { 90 | 91 | /** 92 | * Manifold representation of @f$ S^2 @f$. 93 | * Used for unit vectors on the sphere or directions in 3D. 94 | * 95 | * @todo add conversions from/to polar angles? 96 | */ 97 | template 98 | struct S2 { 99 | 100 | typedef _scalar scalar; 101 | typedef vect<3, scalar> vect_type; 102 | typedef SO3 SO3_type; 103 | typedef typename vect_type::base vec3; 104 | scalar length = scalar(den)/scalar(num); 105 | enum {DOF=2, TYP = 1, DIM = 3}; 106 | 107 | //private: 108 | /** 109 | * Unit vector on the sphere, or vector pointing in a direction 110 | */ 111 | vect_type vec; 112 | 113 | public: 114 | S2() { 115 | if(S2_typ == 3) vec=length * vec3(0, 0, std::sqrt(1)); 116 | if(S2_typ == 2) vec=length * vec3(0, std::sqrt(1), 0); 117 | if(S2_typ == 1) vec=length * vec3(std::sqrt(1), 0, 0); 118 | } 119 | S2(const scalar &x, const scalar &y, const scalar &z) : vec(vec3(x, y, z)) { 120 | vec.normalize(); 121 | vec = vec * length; 122 | } 123 | 124 | S2(const vect_type &_vec) : vec(_vec) { 125 | vec.normalize(); 126 | vec = vec * length; 127 | } 128 | 129 | void oplus(MTK::vectview delta, scalar scale = 1) 130 | { 131 | SO3_type res; 132 | res.w() = MTK::exp(res.vec(), delta, scalar(scale/2)); 133 | vec = res.toRotationMatrix() * vec; 134 | } 135 | 136 | void boxplus(MTK::vectview delta, scalar scale=1) { 137 | Eigen::Matrix Bx; 138 | S2_Bx(Bx); 139 | vect_type Bu = Bx*delta;SO3_type res; 140 | res.w() = MTK::exp(res.vec(), Bu, scalar(scale/2)); 141 | vec = res.toRotationMatrix() * vec; 142 | } 143 | 144 | void boxminus(MTK::vectview res, const S2& other) const { 145 | scalar v_sin = (MTK::hat(vec)*other.vec).norm(); 146 | scalar v_cos = vec.transpose() * other.vec; 147 | scalar theta = std::atan2(v_sin, v_cos); 148 | if(v_sin < MTK::tolerance()) 149 | { 150 | if(std::fabs(theta) > MTK::tolerance() ) 151 | { 152 | res[0] = 3.1415926; 153 | res[1] = 0; 154 | } 155 | else{ 156 | res[0] = 0; 157 | res[1] = 0; 158 | } 159 | } 160 | else 161 | { 162 | S2 other_copy = other; 163 | Eigen::MatrixBx; 164 | other_copy.S2_Bx(Bx); 165 | res = theta/v_sin * Bx.transpose() * MTK::hat(other.vec)*vec; 166 | } 167 | } 168 | 169 | void S2_hat(Eigen::Matrix &res) 170 | { 171 | Eigen::Matrix skew_vec; 172 | skew_vec << scalar(0), -vec[2], vec[1], 173 | vec[2], scalar(0), -vec[0], 174 | -vec[1], vec[0], scalar(0); 175 | res = skew_vec; 176 | } 177 | 178 | 179 | void S2_Bx(Eigen::Matrix &res) 180 | { 181 | if(S2_typ == 3) 182 | { 183 | if(vec[2] + length > tolerance()) 184 | { 185 | 186 | res << length - vec[0]*vec[0]/(length+vec[2]), -vec[0]*vec[1]/(length+vec[2]), 187 | -vec[0]*vec[1]/(length+vec[2]), length-vec[1]*vec[1]/(length+vec[2]), 188 | -vec[0], -vec[1]; 189 | res /= length; 190 | } 191 | else 192 | { 193 | res = Eigen::Matrix::Zero(); 194 | res(1, 1) = -1; 195 | res(2, 0) = 1; 196 | } 197 | } 198 | else if(S2_typ == 2) 199 | { 200 | if(vec[1] + length > tolerance()) 201 | { 202 | 203 | res << length - vec[0]*vec[0]/(length+vec[1]), -vec[0]*vec[2]/(length+vec[1]), 204 | -vec[0], -vec[2], 205 | -vec[0]*vec[2]/(length+vec[1]), length-vec[2]*vec[2]/(length+vec[1]); 206 | res /= length; 207 | } 208 | else 209 | { 210 | res = Eigen::Matrix::Zero(); 211 | res(1, 1) = -1; 212 | res(2, 0) = 1; 213 | } 214 | } 215 | else 216 | { 217 | if(vec[0] + length > tolerance()) 218 | { 219 | 220 | res << -vec[1], -vec[2], 221 | length - vec[1]*vec[1]/(length+vec[0]), -vec[2]*vec[1]/(length+vec[0]), 222 | -vec[2]*vec[1]/(length+vec[0]), length-vec[2]*vec[2]/(length+vec[0]); 223 | res /= length; 224 | } 225 | else 226 | { 227 | res = Eigen::Matrix::Zero(); 228 | res(1, 1) = -1; 229 | res(2, 0) = 1; 230 | } 231 | } 232 | } 233 | 234 | void S2_Nx(Eigen::Matrix &res, S2& subtrahend) 235 | { 236 | if((vec+subtrahend.vec).norm() > tolerance()) 237 | { 238 | Eigen::Matrix Bx; 239 | S2_Bx(Bx); 240 | if((vec-subtrahend.vec).norm() > tolerance()) 241 | { 242 | scalar v_sin = (MTK::hat(vec)*subtrahend.vec).norm(); 243 | scalar v_cos = vec.transpose() * subtrahend.vec; 244 | 245 | res = Bx.transpose() * (std::atan2(v_sin, v_cos)/v_sin*MTK::hat(vec)+MTK::hat(vec)*subtrahend.vec*((-v_cos/v_sin/v_sin/length/length/length/length+std::atan2(v_sin, v_cos)/v_sin/v_sin/v_sin)*subtrahend.vec.transpose()*MTK::hat(vec)*MTK::hat(vec)-vec.transpose()/length/length/length/length)); 246 | } 247 | else 248 | { 249 | res = 1/length/length*Bx.transpose()*MTK::hat(vec); 250 | } 251 | } 252 | else 253 | { 254 | std::cerr << "No N(x, y) for x=-y" << std::endl; 255 | std::exit(100); 256 | } 257 | } 258 | 259 | void S2_Nx_yy(Eigen::Matrix &res) 260 | { 261 | Eigen::Matrix Bx; 262 | S2_Bx(Bx); 263 | res = 1/length/length*Bx.transpose()*MTK::hat(vec); 264 | } 265 | 266 | void S2_Mx(Eigen::Matrix &res, MTK::vectview delta) 267 | { 268 | Eigen::Matrix Bx; 269 | S2_Bx(Bx); 270 | if(delta.norm() < tolerance()) 271 | { 272 | res = -MTK::hat(vec)*Bx; 273 | } 274 | else{ 275 | vect_type Bu = Bx*delta; 276 | SO3_type exp_delta; 277 | exp_delta.w() = MTK::exp(exp_delta.vec(), Bu, scalar(1/2)); 278 | res = -exp_delta.toRotationMatrix()*MTK::hat(vec)*MTK::A_matrix(Bu).transpose()*Bx; 279 | } 280 | } 281 | 282 | operator const vect_type&() const{ 283 | return vec; 284 | } 285 | 286 | const vect_type& get_vect() const { 287 | return vec; 288 | } 289 | 290 | friend S2 operator*(const SO3& rot, const S2& dir) 291 | { 292 | S2 ret; 293 | ret.vec = rot * dir.vec; 294 | return ret; 295 | } 296 | 297 | scalar operator[](int idx) const {return vec[idx]; } 298 | 299 | friend std::ostream& operator<<(std::ostream &os, const S2& vec){ 300 | return os << vec.vec.transpose() << " "; 301 | } 302 | friend std::istream& operator>>(std::istream &is, S2& vec){ 303 | for(int i=0; i<3; ++i) 304 | is >> vec.vec[i]; 305 | vec.vec.normalize(); 306 | vec.vec = vec.vec * vec.length; 307 | return is; 308 | 309 | } 310 | }; 311 | 312 | 313 | } // namespace MTK 314 | 315 | 316 | #endif /*S2_H_*/ 317 | -------------------------------------------------------------------------------- /include/IKFoM_toolkit/mtk/types/SOn.hpp: -------------------------------------------------------------------------------- 1 | // This is an advanced implementation of the algorithm described in the 2 | // following paper: 3 | // C. Hertzberg, R. Wagner, U. Frese, and L. Schroder. Integratinggeneric sensor fusion algorithms with sound state representationsthrough encapsulation of manifolds. 4 | // CoRR, vol. abs/1107.1119, 2011.[Online]. Available: http://arxiv.org/abs/1107.1119 5 | 6 | /* 7 | * Copyright (c) 2019--2023, The University of Hong Kong 8 | * All rights reserved. 9 | * 10 | * Modifier: Dongjiao HE 11 | * 12 | * Redistribution and use in source and binary forms, with or without 13 | * modification, are permitted provided that the following conditions 14 | * are met: 15 | * 16 | * * Redistributions of source code must retain the above copyright 17 | * notice, this list of conditions and the following disclaimer. 18 | * * Redistributions in binary form must reproduce the above 19 | * copyright notice, this list of conditions and the following 20 | * disclaimer in the documentation and/or other materials provided 21 | * with the distribution. 22 | * * Neither the name of the Universitaet Bremen nor the names of its 23 | * contributors may be used to endorse or promote products derived 24 | * from this software without specific prior written permission. 25 | * 26 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 27 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 28 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 29 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 30 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 31 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 32 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 33 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 34 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 35 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 36 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 37 | * POSSIBILITY OF SUCH DAMAGE. 38 | */ 39 | 40 | /* 41 | * Copyright (c) 2008--2011, Universitaet Bremen 42 | * All rights reserved. 43 | * 44 | * Author: Christoph Hertzberg 45 | * 46 | * Redistribution and use in source and binary forms, with or without 47 | * modification, are permitted provided that the following conditions 48 | * are met: 49 | * 50 | * * Redistributions of source code must retain the above copyright 51 | * notice, this list of conditions and the following disclaimer. 52 | * * Redistributions in binary form must reproduce the above 53 | * copyright notice, this list of conditions and the following 54 | * disclaimer in the documentation and/or other materials provided 55 | * with the distribution. 56 | * * Neither the name of the Universitaet Bremen nor the names of its 57 | * contributors may be used to endorse or promote products derived 58 | * from this software without specific prior written permission. 59 | * 60 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 61 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 62 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 63 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 64 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 65 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 66 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 67 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 68 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 69 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 70 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 71 | * POSSIBILITY OF SUCH DAMAGE. 72 | */ 73 | /** 74 | * @file mtk/types/SOn.hpp 75 | * @brief Standard Orthogonal Groups i.e.\ rotatation groups. 76 | */ 77 | #ifndef SON_H_ 78 | #define SON_H_ 79 | 80 | #include 81 | 82 | #include "vect.hpp" 83 | #include "../src/mtkmath.hpp" 84 | 85 | 86 | namespace MTK { 87 | 88 | 89 | /** 90 | * Two-dimensional orientations represented as scalar. 91 | * There is no guarantee that the representing scalar is within any interval, 92 | * but the result of boxminus will always have magnitude @f$\le\pi @f$. 93 | */ 94 | template 95 | struct SO2 : public Eigen::Rotation2D<_scalar> { 96 | enum {DOF = 1, DIM = 2, TYP = 3}; 97 | 98 | typedef _scalar scalar; 99 | typedef Eigen::Rotation2D base; 100 | typedef vect vect_type; 101 | 102 | //! Construct from angle 103 | SO2(const scalar& angle = 0) : base(angle) { } 104 | 105 | //! Construct from Eigen::Rotation2D 106 | SO2(const base& src) : base(src) {} 107 | 108 | /** 109 | * Construct from 2D vector. 110 | * Resulting orientation will rotate the first unit vector to point to vec. 111 | */ 112 | SO2(const vect_type &vec) : base(atan2(vec[1], vec[0])) {}; 113 | 114 | 115 | //! Calculate @c this->inverse() * @c r 116 | SO2 operator%(const base &r) const { 117 | return base::inverse() * r; 118 | } 119 | 120 | //! Calculate @c this->inverse() * @c r 121 | template 122 | vect_type operator%(const Eigen::MatrixBase &vec) const { 123 | return base::inverse() * vec; 124 | } 125 | 126 | //! Calculate @c *this * @c r.inverse() 127 | SO2 operator/(const SO2 &r) const { 128 | return *this * r.inverse(); 129 | } 130 | 131 | //! Gets the angle as scalar. 132 | operator scalar() const { 133 | return base::angle(); 134 | } 135 | void S2_hat(Eigen::Matrix &res) 136 | { 137 | res = Eigen::Matrix::Zero(); 138 | } 139 | //! @name Manifold requirements 140 | void S2_Nx_yy(Eigen::Matrix &res) 141 | { 142 | std::cerr << "wrong idx for S2" << std::endl; 143 | std::exit(100); 144 | res = Eigen::Matrix::Zero(); 145 | } 146 | 147 | void S2_Mx(Eigen::Matrix &res, MTK::vectview delta) 148 | { 149 | std::cerr << "wrong idx for S2" << std::endl; 150 | std::exit(100); 151 | res = Eigen::Matrix::Zero(); 152 | } 153 | 154 | void oplus(MTK::vectview vec, scalar scale = 1) { 155 | base::angle() += scale * vec[0]; 156 | } 157 | 158 | void boxplus(MTK::vectview vec, scalar scale = 1) { 159 | base::angle() += scale * vec[0]; 160 | } 161 | void boxminus(MTK::vectview res, const SO2& other) const { 162 | res[0] = MTK::normalize(base::angle() - other.angle(), scalar(MTK::pi)); 163 | } 164 | 165 | friend std::istream& operator>>(std::istream &is, SO2& ang){ 166 | return is >> ang.angle(); 167 | } 168 | 169 | }; 170 | 171 | 172 | /** 173 | * Three-dimensional orientations represented as Quaternion. 174 | * It is assumed that the internal Quaternion always stays normalized, 175 | * should this not be the case, call inherited member function @c normalize(). 176 | */ 177 | template 178 | struct SO3 : public Eigen::Quaternion<_scalar, Options> { 179 | enum {DOF = 3, DIM = 3, TYP = 2}; 180 | typedef _scalar scalar; 181 | typedef Eigen::Quaternion base; 182 | typedef Eigen::Quaternion Quaternion; 183 | typedef vect vect_type; 184 | 185 | //! Calculate @c this->inverse() * @c r 186 | template EIGEN_STRONG_INLINE 187 | Quaternion operator%(const Eigen::QuaternionBase &r) const { 188 | return base::conjugate() * r; 189 | } 190 | 191 | //! Calculate @c this->inverse() * @c r 192 | template 193 | vect_type operator%(const Eigen::MatrixBase &vec) const { 194 | return base::conjugate() * vec; 195 | } 196 | 197 | //! Calculate @c this * @c r.conjugate() 198 | template EIGEN_STRONG_INLINE 199 | Quaternion operator/(const Eigen::QuaternionBase &r) const { 200 | return *this * r.conjugate(); 201 | } 202 | 203 | /** 204 | * Construct from real part and three imaginary parts. 205 | * Quaternion is normalized after construction. 206 | */ 207 | SO3(const scalar& w, const scalar& x, const scalar& y, const scalar& z) : base(w, x, y, z) { 208 | base::normalize(); 209 | } 210 | 211 | /** 212 | * Construct from Eigen::Quaternion. 213 | * @note Non-normalized input may result result in spurious behavior. 214 | */ 215 | SO3(const base& src = base::Identity()) : base(src) {} 216 | 217 | /** 218 | * Construct from rotation matrix. 219 | * @note Invalid rotation matrices may lead to spurious behavior. 220 | */ 221 | template 222 | SO3(const Eigen::MatrixBase& matrix) : base(matrix) {} 223 | 224 | /** 225 | * Construct from arbitrary rotation type. 226 | * @note Invalid rotation matrices may lead to spurious behavior. 227 | */ 228 | template 229 | SO3(const Eigen::RotationBase& rotation) : base(rotation.derived()) {} 230 | 231 | //! @name Manifold requirements 232 | 233 | void boxplus(MTK::vectview vec, scalar scale=1) { 234 | SO3 delta = exp(vec, scale); 235 | *this = *this * delta; 236 | } 237 | void boxminus(MTK::vectview res, const SO3& other) const { 238 | res = SO3::log(other.conjugate() * *this); 239 | } 240 | //} 241 | 242 | void oplus(MTK::vectview vec, scalar scale=1) { 243 | SO3 delta = exp(vec, scale); 244 | *this = *this * delta; 245 | } 246 | 247 | void S2_hat(Eigen::Matrix &res) 248 | { 249 | res = Eigen::Matrix::Zero(); 250 | } 251 | void S2_Nx_yy(Eigen::Matrix &res) 252 | { 253 | std::cerr << "wrong idx for S2" << std::endl; 254 | std::exit(100); 255 | res = Eigen::Matrix::Zero(); 256 | } 257 | 258 | void S2_Mx(Eigen::Matrix &res, MTK::vectview delta) 259 | { 260 | std::cerr << "wrong idx for S2" << std::endl; 261 | std::exit(100); 262 | res = Eigen::Matrix::Zero(); 263 | } 264 | 265 | friend std::ostream& operator<<(std::ostream &os, const SO3& q){ 266 | return os << q.coeffs().transpose() << " "; 267 | } 268 | 269 | friend std::istream& operator>>(std::istream &is, SO3& q){ 270 | vect<4,scalar> coeffs; 271 | is >> coeffs; 272 | q.coeffs() = coeffs.normalized(); 273 | return is; 274 | } 275 | 276 | //! @name Helper functions 277 | //{ 278 | /** 279 | * Calculate the exponential map. In matrix terms this would correspond 280 | * to the Rodrigues formula. 281 | */ 282 | // FIXME vectview<> can't be constructed from every MatrixBase<>, use const Vector3x& as workaround 283 | // static SO3 exp(MTK::vectview dvec, scalar scale = 1){ 284 | static SO3 exp(const Eigen::Matrix& dvec, scalar scale = 1){ 285 | SO3 res; 286 | res.w() = MTK::exp(res.vec(), dvec, scalar(scale/2)); 287 | return res; 288 | } 289 | /** 290 | * Calculate the inverse of @c exp. 291 | * Only guarantees that exp(log(x)) == x 292 | */ 293 | static typename base::Vector3 log(const SO3 &orient){ 294 | typename base::Vector3 res; 295 | MTK::log(res, orient.w(), orient.vec(), scalar(2), true); 296 | return res; 297 | } 298 | }; 299 | 300 | namespace internal { 301 | template 302 | struct UnalignedType >{ 303 | typedef SO2 type; 304 | }; 305 | 306 | template 307 | struct UnalignedType >{ 308 | typedef SO3 type; 309 | }; 310 | 311 | } // namespace internal 312 | 313 | 314 | } // namespace MTK 315 | 316 | #endif /*SON_H_*/ 317 | 318 | -------------------------------------------------------------------------------- /include/IKFoM_toolkit/mtk/types/vect.hpp: -------------------------------------------------------------------------------- 1 | // This is an advanced implementation of the algorithm described in the 2 | // following paper: 3 | // C. Hertzberg, R. Wagner, U. Frese, and L. Schroder. Integratinggeneric sensor fusion algorithms with sound state representationsthrough encapsulation of manifolds. 4 | // CoRR, vol. abs/1107.1119, 2011.[Online]. Available: http://arxiv.org/abs/1107.1119 5 | 6 | /* 7 | * Copyright (c) 2019--2023, The University of Hong Kong 8 | * All rights reserved. 9 | * 10 | * Modifier: Dongjiao HE 11 | * 12 | * Redistribution and use in source and binary forms, with or without 13 | * modification, are permitted provided that the following conditions 14 | * are met: 15 | * 16 | * * Redistributions of source code must retain the above copyright 17 | * notice, this list of conditions and the following disclaimer. 18 | * * Redistributions in binary form must reproduce the above 19 | * copyright notice, this list of conditions and the following 20 | * disclaimer in the documentation and/or other materials provided 21 | * with the distribution. 22 | * * Neither the name of the Universitaet Bremen nor the names of its 23 | * contributors may be used to endorse or promote products derived 24 | * from this software without specific prior written permission. 25 | * 26 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 27 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 28 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 29 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 30 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 31 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 32 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 33 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 34 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 35 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 36 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 37 | * POSSIBILITY OF SUCH DAMAGE. 38 | */ 39 | 40 | /* 41 | * Copyright (c) 2008--2011, Universitaet Bremen 42 | * All rights reserved. 43 | * 44 | * Author: Christoph Hertzberg 45 | * 46 | * Redistribution and use in source and binary forms, with or without 47 | * modification, are permitted provided that the following conditions 48 | * are met: 49 | * 50 | * * Redistributions of source code must retain the above copyright 51 | * notice, this list of conditions and the following disclaimer. 52 | * * Redistributions in binary form must reproduce the above 53 | * copyright notice, this list of conditions and the following 54 | * disclaimer in the documentation and/or other materials provided 55 | * with the distribution. 56 | * * Neither the name of the Universitaet Bremen nor the names of its 57 | * contributors may be used to endorse or promote products derived 58 | * from this software without specific prior written permission. 59 | * 60 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 61 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 62 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 63 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 64 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 65 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 66 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 67 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 68 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 69 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 70 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 71 | * POSSIBILITY OF SUCH DAMAGE. 72 | */ 73 | /** 74 | * @file mtk/types/vect.hpp 75 | * @brief Basic vectors interpreted as manifolds. 76 | * 77 | * This file also implements a simple wrapper for matrices, for arbitrary scalars 78 | * and for positive scalars. 79 | */ 80 | #ifndef VECT_H_ 81 | #define VECT_H_ 82 | 83 | #include 84 | #include 85 | #include 86 | 87 | #include "../src/vectview.hpp" 88 | 89 | namespace MTK { 90 | 91 | static const Eigen::IOFormat IO_no_spaces(Eigen::StreamPrecision, Eigen::DontAlignCols, ",", ",", "", "", "[", "]"); 92 | 93 | 94 | /** 95 | * A simple vector class. 96 | * Implementation is basically a wrapper around Eigen::Matrix with manifold 97 | * requirements added. 98 | */ 99 | template 100 | struct vect : public Eigen::Matrix<_scalar, D, 1, _Options> { 101 | typedef Eigen::Matrix<_scalar, D, 1, _Options> base; 102 | enum {DOF = D, DIM = D, TYP = 0}; 103 | typedef _scalar scalar; 104 | 105 | //using base::operator=; 106 | 107 | /** Standard constructor. Sets all values to zero. */ 108 | vect(const base &src = base::Zero()) : base(src) {} 109 | 110 | /** Constructor copying the value of the expression \a other */ 111 | template 112 | EIGEN_STRONG_INLINE vect(const Eigen::DenseBase& other) : base(other) {} 113 | 114 | /** Construct from memory. */ 115 | vect(const scalar* src, int size = DOF) : base(base::Map(src, size)) { } 116 | 117 | void boxplus(MTK::vectview vec, scalar scale=1) { 118 | *this += scale * vec; 119 | } 120 | void boxminus(MTK::vectview res, const vect& other) const { 121 | res = *this - other; 122 | } 123 | 124 | void oplus(MTK::vectview vec, scalar scale=1) { 125 | *this += scale * vec; 126 | } 127 | 128 | void S2_hat(Eigen::Matrix &res) 129 | { 130 | res = Eigen::Matrix::Zero(); 131 | } 132 | 133 | void S2_Nx_yy(Eigen::Matrix &res) 134 | { 135 | std::cerr << "wrong idx for S2" << std::endl; 136 | std::exit(100); 137 | res = Eigen::Matrix::Zero(); 138 | } 139 | 140 | void S2_Mx(Eigen::Matrix &res, MTK::vectview delta) 141 | { 142 | std::cerr << "wrong idx for S2" << std::endl; 143 | std::exit(100); 144 | res = Eigen::Matrix::Zero(); 145 | } 146 | 147 | friend std::ostream& operator<<(std::ostream &os, const vect& v){ 148 | // Eigen sometimes messes with the streams flags, so output manually: 149 | for(int i=0; i>(std::istream &is, vect& v){ 154 | char term=0; 155 | is >> std::ws; // skip whitespace 156 | switch(is.peek()) { 157 | case '(': term=')'; is.ignore(1); break; 158 | case '[': term=']'; is.ignore(1); break; 159 | case '{': term='}'; is.ignore(1); break; 160 | default: break; 161 | } 162 | if(D==Eigen::Dynamic) { 163 | assert(term !=0 && "Dynamic vectors must be embraced"); 164 | std::vector temp; 165 | while(is.good() && is.peek() != term) { 166 | scalar x; 167 | is >> x; 168 | temp.push_back(x); 169 | if(is.peek()==',') is.ignore(1); 170 | } 171 | v = vect::Map(temp.data(), temp.size()); 172 | } else 173 | for(int i=0; i> v[i]; 175 | if(is.peek()==',') { // ignore commas between values 176 | is.ignore(1); 177 | } 178 | } 179 | if(term!=0) { 180 | char x; 181 | is >> x; 182 | if(x!=term) { 183 | is.setstate(is.badbit); 184 | // assert(x==term && "start and end bracket do not match!"); 185 | } 186 | } 187 | return is; 188 | } 189 | 190 | template 191 | vectview tail(){ 192 | BOOST_STATIC_ASSERT(0< dim && dim <= DOF); 193 | return base::template tail(); 194 | } 195 | template 196 | vectview tail() const{ 197 | BOOST_STATIC_ASSERT(0< dim && dim <= DOF); 198 | return base::template tail(); 199 | } 200 | template 201 | vectview head(){ 202 | BOOST_STATIC_ASSERT(0< dim && dim <= DOF); 203 | return base::template head(); 204 | } 205 | template 206 | vectview head() const{ 207 | BOOST_STATIC_ASSERT(0< dim && dim <= DOF); 208 | return base::template head(); 209 | } 210 | }; 211 | 212 | 213 | /** 214 | * A simple matrix class. 215 | * Implementation is basically a wrapper around Eigen::Matrix with manifold 216 | * requirements added, i.e., matrix is viewed as a plain vector for that. 217 | */ 218 | template::Options> 219 | struct matrix : public Eigen::Matrix<_scalar, M, N, _Options> { 220 | typedef Eigen::Matrix<_scalar, M, N, _Options> base; 221 | enum {DOF = M * N, TYP = 4, DIM=0}; 222 | typedef _scalar scalar; 223 | 224 | using base::operator=; 225 | 226 | /** Standard constructor. Sets all values to zero. */ 227 | matrix() { 228 | base::setZero(); 229 | } 230 | 231 | /** Constructor copying the value of the expression \a other */ 232 | template 233 | EIGEN_STRONG_INLINE matrix(const Eigen::MatrixBase& other) : base(other) {} 234 | 235 | /** Construct from memory. */ 236 | matrix(const scalar* src) : base(src) { } 237 | 238 | void boxplus(MTK::vectview vec, scalar scale = 1) { 239 | *this += scale * base::Map(vec.data()); 240 | } 241 | void boxminus(MTK::vectview res, const matrix& other) const { 242 | base::Map(res.data()) = *this - other; 243 | } 244 | 245 | void S2_hat(Eigen::Matrix &res) 246 | { 247 | res = Eigen::Matrix::Zero(); 248 | } 249 | 250 | void oplus(MTK::vectview vec, scalar scale = 1) { 251 | *this += scale * base::Map(vec.data()); 252 | } 253 | 254 | void S2_Nx_yy(Eigen::Matrix &res) 255 | { 256 | std::cerr << "wrong idx for S2" << std::endl; 257 | std::exit(100); 258 | res = Eigen::Matrix::Zero(); 259 | } 260 | 261 | void S2_Mx(Eigen::Matrix &res, MTK::vectview delta) 262 | { 263 | std::cerr << "wrong idx for S2" << std::endl; 264 | std::exit(100); 265 | res = Eigen::Matrix::Zero(); 266 | } 267 | 268 | friend std::ostream& operator<<(std::ostream &os, const matrix& mat){ 269 | for(int i=0; i>(std::istream &is, matrix& mat){ 275 | for(int i=0; i> mat.data()[i]; 277 | } 278 | return is; 279 | } 280 | };// @todo What if M / N = Eigen::Dynamic? 281 | 282 | 283 | 284 | /** 285 | * A simple scalar type. 286 | */ 287 | template 288 | struct Scalar { 289 | enum {DOF = 1, TYP = 5, DIM=0}; 290 | typedef _scalar scalar; 291 | 292 | scalar value; 293 | 294 | Scalar(const scalar& value = scalar(0)) : value(value) {} 295 | operator const scalar&() const { return value; } 296 | operator scalar&() { return value; } 297 | Scalar& operator=(const scalar& val) { value = val; return *this; } 298 | 299 | void S2_hat(Eigen::Matrix &res) 300 | { 301 | res = Eigen::Matrix::Zero(); 302 | } 303 | 304 | void S2_Nx_yy(Eigen::Matrix &res) 305 | { 306 | std::cerr << "wrong idx for S2" << std::endl; 307 | std::exit(100); 308 | res = Eigen::Matrix::Zero(); 309 | } 310 | 311 | void S2_Mx(Eigen::Matrix &res, MTK::vectview delta) 312 | { 313 | std::cerr << "wrong idx for S2" << std::endl; 314 | std::exit(100); 315 | res = Eigen::Matrix::Zero(); 316 | } 317 | 318 | void oplus(MTK::vectview vec, scalar scale=1) { 319 | value += scale * vec[0]; 320 | } 321 | 322 | void boxplus(MTK::vectview vec, scalar scale=1) { 323 | value += scale * vec[0]; 324 | } 325 | void boxminus(MTK::vectview res, const Scalar& other) const { 326 | res[0] = *this - other; 327 | } 328 | }; 329 | 330 | /** 331 | * Positive scalars. 332 | * Boxplus is implemented using multiplication by @f$x\boxplus\delta = x\cdot\exp(\delta) @f$. 333 | */ 334 | template 335 | struct PositiveScalar { 336 | enum {DOF = 1, TYP = 6, DIM=0}; 337 | typedef _scalar scalar; 338 | 339 | scalar value; 340 | 341 | PositiveScalar(const scalar& value = scalar(1)) : value(value) { 342 | assert(value > scalar(0)); 343 | } 344 | operator const scalar&() const { return value; } 345 | PositiveScalar& operator=(const scalar& val) { assert(val>0); value = val; return *this; } 346 | 347 | void boxplus(MTK::vectview vec, scalar scale = 1) { 348 | value *= std::exp(scale * vec[0]); 349 | } 350 | void boxminus(MTK::vectview res, const PositiveScalar& other) const { 351 | res[0] = std::log(*this / other); 352 | } 353 | 354 | void oplus(MTK::vectview vec, scalar scale = 1) { 355 | value *= std::exp(scale * vec[0]); 356 | } 357 | 358 | void S2_hat(Eigen::Matrix &res) 359 | { 360 | res = Eigen::Matrix::Zero(); 361 | } 362 | 363 | void S2_Nx_yy(Eigen::Matrix &res) 364 | { 365 | std::cerr << "wrong idx for S2" << std::endl; 366 | std::exit(100); 367 | res = Eigen::Matrix::Zero(); 368 | } 369 | 370 | void S2_Mx(Eigen::Matrix &res, MTK::vectview delta) 371 | { 372 | std::cerr << "wrong idx for S2" << std::endl; 373 | std::exit(100); 374 | res = Eigen::Matrix::Zero(); 375 | } 376 | 377 | 378 | friend std::istream& operator>>(std::istream &is, PositiveScalar& s){ 379 | is >> s.value; 380 | assert(s.value > 0); 381 | return is; 382 | } 383 | }; 384 | 385 | template 386 | struct Complex : public std::complex<_scalar>{ 387 | enum {DOF = 2, TYP = 7, DIM=0}; 388 | typedef _scalar scalar; 389 | 390 | typedef std::complex Base; 391 | 392 | Complex(const Base& value) : Base(value) {} 393 | Complex(const scalar& re = 0.0, const scalar& im = 0.0) : Base(re, im) {} 394 | Complex(const MTK::vectview &in) : Base(in[0], in[1]) {} 395 | template 396 | Complex(const Eigen::DenseBase &in) : Base(in[0], in[1]) {} 397 | 398 | void boxplus(MTK::vectview vec, scalar scale = 1) { 399 | Base::real() += scale * vec[0]; 400 | Base::imag() += scale * vec[1]; 401 | }; 402 | void boxminus(MTK::vectview res, const Complex& other) const { 403 | Complex diff = *this - other; 404 | res << diff.real(), diff.imag(); 405 | } 406 | 407 | void S2_hat(Eigen::Matrix &res) 408 | { 409 | res = Eigen::Matrix::Zero(); 410 | } 411 | 412 | void oplus(MTK::vectview vec, scalar scale = 1) { 413 | Base::real() += scale * vec[0]; 414 | Base::imag() += scale * vec[1]; 415 | }; 416 | 417 | void S2_Nx_yy(Eigen::Matrix &res) 418 | { 419 | std::cerr << "wrong idx for S2" << std::endl; 420 | std::exit(100); 421 | res = Eigen::Matrix::Zero(); 422 | } 423 | 424 | void S2_Mx(Eigen::Matrix &res, MTK::vectview delta) 425 | { 426 | std::cerr << "wrong idx for S2" << std::endl; 427 | std::exit(100); 428 | res = Eigen::Matrix::Zero(); 429 | } 430 | 431 | scalar squaredNorm() const { 432 | return std::pow(Base::real(),2) + std::pow(Base::imag(),2); 433 | } 434 | 435 | const scalar& operator()(int i) const { 436 | assert(0<=i && i<2 && "Index out of range"); 437 | return i==0 ? Base::real() : Base::imag(); 438 | } 439 | scalar& operator()(int i){ 440 | assert(0<=i && i<2 && "Index out of range"); 441 | return i==0 ? Base::real() : Base::imag(); 442 | } 443 | }; 444 | 445 | 446 | namespace internal { 447 | 448 | template 449 | struct UnalignedType >{ 450 | typedef vect type; 451 | }; 452 | 453 | } // namespace internal 454 | 455 | 456 | } // namespace MTK 457 | 458 | 459 | 460 | 461 | #endif /*VECT_H_*/ 462 | -------------------------------------------------------------------------------- /include/IKFoM_toolkit/mtk/types/wrapped_cv_mat.hpp: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (c) 2010--2011, Universitaet Bremen and DFKI GmbH 3 | * All rights reserved. 4 | * 5 | * Author: Rene Wagner 6 | * Christoph Hertzberg 7 | * 8 | * Redistribution and use in source and binary forms, with or without 9 | * modification, are permitted provided that the following conditions 10 | * are met: 11 | * 12 | * * Redistributions of source code must retain the above copyright 13 | * notice, this list of conditions and the following disclaimer. 14 | * * Redistributions in binary form must reproduce the above 15 | * copyright notice, this list of conditions and the following 16 | * disclaimer in the documentation and/or other materials provided 17 | * with the distribution. 18 | * * Neither the name of the Universitaet Bremen nor the DFKI GmbH 19 | * nor the names of its contributors may be used to endorse or 20 | * promote products derived from this software without specific 21 | * prior written permission. 22 | * 23 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 24 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 25 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 26 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 27 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 28 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 29 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 30 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 31 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 32 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 33 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 34 | * POSSIBILITY OF SUCH DAMAGE. 35 | */ 36 | 37 | #ifndef WRAPPED_CV_MAT_HPP_ 38 | #define WRAPPED_CV_MAT_HPP_ 39 | 40 | #include 41 | #include 42 | 43 | namespace MTK { 44 | 45 | template 46 | struct cv_f_type; 47 | 48 | template<> 49 | struct cv_f_type 50 | { 51 | enum {value = CV_64F}; 52 | }; 53 | 54 | template<> 55 | struct cv_f_type 56 | { 57 | enum {value = CV_32F}; 58 | }; 59 | 60 | /** 61 | * cv_mat wraps a CvMat around an Eigen Matrix 62 | */ 63 | template 64 | class cv_mat : public matrix 65 | { 66 | typedef matrix base_type; 67 | enum {type_ = cv_f_type::value}; 68 | CvMat cv_mat_; 69 | 70 | public: 71 | cv_mat() 72 | { 73 | cv_mat_ = cvMat(rows, cols, type_, base_type::data()); 74 | } 75 | 76 | cv_mat(const cv_mat& oth) : base_type(oth) 77 | { 78 | cv_mat_ = cvMat(rows, cols, type_, base_type::data()); 79 | } 80 | 81 | template 82 | cv_mat(const Eigen::MatrixBase &value) : base_type(value) 83 | { 84 | cv_mat_ = cvMat(rows, cols, type_, base_type::data()); 85 | } 86 | 87 | template 88 | cv_mat& operator=(const Eigen::MatrixBase &value) 89 | { 90 | base_type::operator=(value); 91 | return *this; 92 | } 93 | 94 | cv_mat& operator=(const cv_mat& value) 95 | { 96 | base_type::operator=(value); 97 | return *this; 98 | } 99 | 100 | // FIXME: Maybe overloading operator& is not a good idea ... 101 | CvMat* operator&() 102 | { 103 | return &cv_mat_; 104 | } 105 | const CvMat* operator&() const 106 | { 107 | return &cv_mat_; 108 | } 109 | }; 110 | 111 | } // namespace MTK 112 | 113 | #endif /* WRAPPED_CV_MAT_HPP_ */ 114 | -------------------------------------------------------------------------------- /include/common_lib.h: -------------------------------------------------------------------------------- 1 | #ifndef COMMON_LIB_H 2 | #define COMMON_LIB_H 3 | 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include 9 | #include 10 | #include 11 | #include 12 | #include 13 | 14 | using namespace std; 15 | using namespace Eigen; 16 | 17 | #define USE_IKFOM 18 | 19 | #define PI_M (3.14159265358) 20 | #define G_m_s2 (9.81) // Gravaty const in GuangDong/China 21 | #define DIM_STATE (18) // Dimension of states (Let Dim(SO(3)) = 3) 22 | #define DIM_PROC_N (12) // Dimension of process noise (Let Dim(SO(3)) = 3) 23 | #define CUBE_LEN (6.0) 24 | #define LIDAR_SP_LEN (2) 25 | #define INIT_COV (1) 26 | #define NUM_MATCH_POINTS (5) 27 | #define MAX_MEAS_DIM (10000) 28 | 29 | #define VEC_FROM_ARRAY(v) v[0],v[1],v[2] 30 | #define MAT_FROM_ARRAY(v) v[0],v[1],v[2],v[3],v[4],v[5],v[6],v[7],v[8] 31 | #define CONSTRAIN(v,min,max) ((v>min)?((v (mat.data(), mat.data() + mat.rows() * mat.cols()) 34 | #define DEBUG_FILE_DIR(name) (string(string(ROOT_DIR) + "Log/"+ name)) 35 | 36 | typedef fast_lio::Pose6D Pose6D; 37 | typedef pcl::PointXYZINormal PointType; 38 | typedef pcl::PointCloud PointCloudXYZI; 39 | typedef vector> PointVector; 40 | typedef Vector3d V3D; 41 | typedef Matrix3d M3D; 42 | typedef Vector3f V3F; 43 | typedef Matrix3f M3F; 44 | 45 | #define MD(a,b) Matrix 46 | #define VD(a) Matrix 47 | #define MF(a,b) Matrix 48 | #define VF(a) Matrix 49 | 50 | M3D Eye3d(M3D::Identity()); 51 | M3F Eye3f(M3F::Identity()); 52 | V3D Zero3d(0, 0, 0); 53 | V3F Zero3f(0, 0, 0); 54 | 55 | struct MeasureGroup // Lidar data and imu dates for the curent process 56 | { 57 | MeasureGroup() 58 | { 59 | lidar_beg_time = 0.0; 60 | this->lidar.reset(new PointCloudXYZI()); 61 | }; 62 | double lidar_beg_time; 63 | double lidar_end_time; 64 | PointCloudXYZI::Ptr lidar; 65 | deque imu; 66 | }; 67 | 68 | struct StatesGroup 69 | { 70 | StatesGroup() { 71 | this->rot_end = M3D::Identity(); 72 | this->pos_end = Zero3d; 73 | this->vel_end = Zero3d; 74 | this->bias_g = Zero3d; 75 | this->bias_a = Zero3d; 76 | this->gravity = Zero3d; 77 | this->cov = MD(DIM_STATE,DIM_STATE)::Identity() * INIT_COV; 78 | this->cov.block<9,9>(9,9) = MD(9,9)::Identity() * 0.00001; 79 | }; 80 | 81 | StatesGroup(const StatesGroup& b) { 82 | this->rot_end = b.rot_end; 83 | this->pos_end = b.pos_end; 84 | this->vel_end = b.vel_end; 85 | this->bias_g = b.bias_g; 86 | this->bias_a = b.bias_a; 87 | this->gravity = b.gravity; 88 | this->cov = b.cov; 89 | }; 90 | 91 | StatesGroup& operator=(const StatesGroup& b) 92 | { 93 | this->rot_end = b.rot_end; 94 | this->pos_end = b.pos_end; 95 | this->vel_end = b.vel_end; 96 | this->bias_g = b.bias_g; 97 | this->bias_a = b.bias_a; 98 | this->gravity = b.gravity; 99 | this->cov = b.cov; 100 | return *this; 101 | }; 102 | 103 | StatesGroup operator+(const Matrix &state_add) 104 | { 105 | StatesGroup a; 106 | a.rot_end = this->rot_end * Exp(state_add(0,0), state_add(1,0), state_add(2,0)); 107 | a.pos_end = this->pos_end + state_add.block<3,1>(3,0); 108 | a.vel_end = this->vel_end + state_add.block<3,1>(6,0); 109 | a.bias_g = this->bias_g + state_add.block<3,1>(9,0); 110 | a.bias_a = this->bias_a + state_add.block<3,1>(12,0); 111 | a.gravity = this->gravity + state_add.block<3,1>(15,0); 112 | a.cov = this->cov; 113 | return a; 114 | }; 115 | 116 | StatesGroup& operator+=(const Matrix &state_add) 117 | { 118 | this->rot_end = this->rot_end * Exp(state_add(0,0), state_add(1,0), state_add(2,0)); 119 | this->pos_end += state_add.block<3,1>(3,0); 120 | this->vel_end += state_add.block<3,1>(6,0); 121 | this->bias_g += state_add.block<3,1>(9,0); 122 | this->bias_a += state_add.block<3,1>(12,0); 123 | this->gravity += state_add.block<3,1>(15,0); 124 | return *this; 125 | }; 126 | 127 | Matrix operator-(const StatesGroup& b) 128 | { 129 | Matrix a; 130 | M3D rotd(b.rot_end.transpose() * this->rot_end); 131 | a.block<3,1>(0,0) = Log(rotd); 132 | a.block<3,1>(3,0) = this->pos_end - b.pos_end; 133 | a.block<3,1>(6,0) = this->vel_end - b.vel_end; 134 | a.block<3,1>(9,0) = this->bias_g - b.bias_g; 135 | a.block<3,1>(12,0) = this->bias_a - b.bias_a; 136 | a.block<3,1>(15,0) = this->gravity - b.gravity; 137 | return a; 138 | }; 139 | 140 | void resetpose() 141 | { 142 | this->rot_end = M3D::Identity(); 143 | this->pos_end = Zero3d; 144 | this->vel_end = Zero3d; 145 | } 146 | 147 | M3D rot_end; // the estimated attitude (rotation matrix) at the end lidar point 148 | V3D pos_end; // the estimated position at the end lidar point (world frame) 149 | V3D vel_end; // the estimated velocity at the end lidar point (world frame) 150 | V3D bias_g; // gyroscope bias 151 | V3D bias_a; // accelerator bias 152 | V3D gravity; // the estimated gravity acceleration 153 | Matrix cov; // states covariance 154 | }; 155 | 156 | template 157 | T rad2deg(T radians) 158 | { 159 | return radians * 180.0 / PI_M; 160 | } 161 | 162 | template 163 | T deg2rad(T degrees) 164 | { 165 | return degrees * PI_M / 180.0; 166 | } 167 | 168 | template 169 | auto set_pose6d(const double t, const Matrix &a, const Matrix &g, \ 170 | const Matrix &v, const Matrix &p, const Matrix &R) 171 | { 172 | Pose6D rot_kp; 173 | rot_kp.offset_time = t; 174 | for (int i = 0; i < 3; i++) 175 | { 176 | rot_kp.acc[i] = a(i); 177 | rot_kp.gyr[i] = g(i); 178 | rot_kp.vel[i] = v(i); 179 | rot_kp.pos[i] = p(i); 180 | for (int j = 0; j < 3; j++) rot_kp.rot[i*3+j] = R(i,j); 181 | } 182 | return move(rot_kp); 183 | } 184 | 185 | /* comment 186 | plane equation: Ax + By + Cz + D = 0 187 | convert to: A/D*x + B/D*y + C/D*z = -1 188 | solve: A0*x0 = b0 189 | where A0_i = [x_i, y_i, z_i], x0 = [A/D, B/D, C/D]^T, b0 = [-1, ..., -1]^T 190 | normvec: normalized x0 191 | */ 192 | template 193 | bool esti_normvector(Matrix &normvec, const PointVector &point, const T &threshold, const int &point_num) 194 | { 195 | MatrixXf A(point_num, 3); 196 | MatrixXf b(point_num, 1); 197 | b.setOnes(); 198 | b *= -1.0f; 199 | 200 | for (int j = 0; j < point_num; j++) 201 | { 202 | A(j,0) = point[j].x; 203 | A(j,1) = point[j].y; 204 | A(j,2) = point[j].z; 205 | } 206 | normvec = A.colPivHouseholderQr().solve(b); 207 | 208 | for (int j = 0; j < point_num; j++) 209 | { 210 | if (fabs(normvec(0) * point[j].x + normvec(1) * point[j].y + normvec(2) * point[j].z + 1.0f) > threshold) 211 | { 212 | return false; 213 | } 214 | } 215 | 216 | normvec.normalize(); 217 | return true; 218 | } 219 | 220 | float calc_dist(PointType p1, PointType p2){ 221 | float d = (p1.x - p2.x) * (p1.x - p2.x) + (p1.y - p2.y) * (p1.y - p2.y) + (p1.z - p2.z) * (p1.z - p2.z); 222 | return d; 223 | } 224 | 225 | template 226 | bool esti_plane(Matrix &pca_result, const PointVector &point, const T &threshold) 227 | { 228 | Matrix A; 229 | Matrix b; 230 | A.setZero(); 231 | b.setOnes(); 232 | b *= -1.0f; 233 | 234 | for (int j = 0; j < NUM_MATCH_POINTS; j++) 235 | { 236 | A(j,0) = point[j].x; 237 | A(j,1) = point[j].y; 238 | A(j,2) = point[j].z; 239 | } 240 | 241 | Matrix normvec = A.colPivHouseholderQr().solve(b); 242 | 243 | T n = normvec.norm(); 244 | pca_result(0) = normvec(0) / n; 245 | pca_result(1) = normvec(1) / n; 246 | pca_result(2) = normvec(2) / n; 247 | pca_result(3) = 1.0 / n; 248 | 249 | for (int j = 0; j < NUM_MATCH_POINTS; j++) 250 | { 251 | if (fabs(pca_result(0) * point[j].x + pca_result(1) * point[j].y + pca_result(2) * point[j].z + pca_result(3)) > threshold) 252 | { 253 | return false; 254 | } 255 | } 256 | return true; 257 | } 258 | 259 | #endif -------------------------------------------------------------------------------- /include/so3_math.h: -------------------------------------------------------------------------------- 1 | #ifndef SO3_MATH_H 2 | #define SO3_MATH_H 3 | 4 | #include 5 | #include 6 | 7 | #define SKEW_SYM_MATRX(v) 0.0,-v[2],v[1],v[2],0.0,-v[0],-v[1],v[0],0.0 8 | 9 | template 10 | Eigen::Matrix skew_sym_mat(const Eigen::Matrix &v) 11 | { 12 | Eigen::Matrix skew_sym_mat; 13 | skew_sym_mat<<0.0,-v[2],v[1],v[2],0.0,-v[0],-v[1],v[0],0.0; 14 | return skew_sym_mat; 15 | } 16 | 17 | template 18 | Eigen::Matrix Exp(const Eigen::Matrix &&ang) 19 | { 20 | T ang_norm = ang.norm(); 21 | Eigen::Matrix Eye3 = Eigen::Matrix::Identity(); 22 | if (ang_norm > 0.0000001) 23 | { 24 | Eigen::Matrix r_axis = ang / ang_norm; 25 | Eigen::Matrix K; 26 | K << SKEW_SYM_MATRX(r_axis); 27 | /// Roderigous Tranformation 28 | return Eye3 + std::sin(ang_norm) * K + (1.0 - std::cos(ang_norm)) * K * K; 29 | } 30 | else 31 | { 32 | return Eye3; 33 | } 34 | } 35 | 36 | template 37 | Eigen::Matrix Exp(const Eigen::Matrix &ang_vel, const Ts &dt) 38 | { 39 | T ang_vel_norm = ang_vel.norm(); 40 | Eigen::Matrix Eye3 = Eigen::Matrix::Identity(); 41 | 42 | if (ang_vel_norm > 0.0000001) 43 | { 44 | Eigen::Matrix r_axis = ang_vel / ang_vel_norm; 45 | Eigen::Matrix K; 46 | 47 | K << SKEW_SYM_MATRX(r_axis); 48 | 49 | T r_ang = ang_vel_norm * dt; 50 | 51 | /// Roderigous Tranformation 52 | return Eye3 + std::sin(r_ang) * K + (1.0 - std::cos(r_ang)) * K * K; 53 | } 54 | else 55 | { 56 | return Eye3; 57 | } 58 | } 59 | 60 | template 61 | Eigen::Matrix Exp(const T &v1, const T &v2, const T &v3) 62 | { 63 | T &&norm = sqrt(v1 * v1 + v2 * v2 + v3 * v3); 64 | Eigen::Matrix Eye3 = Eigen::Matrix::Identity(); 65 | if (norm > 0.00001) 66 | { 67 | T r_ang[3] = {v1 / norm, v2 / norm, v3 / norm}; 68 | Eigen::Matrix K; 69 | K << SKEW_SYM_MATRX(r_ang); 70 | 71 | /// Roderigous Tranformation 72 | return Eye3 + std::sin(norm) * K + (1.0 - std::cos(norm)) * K * K; 73 | } 74 | else 75 | { 76 | return Eye3; 77 | } 78 | } 79 | 80 | /* Logrithm of a Rotation Matrix */ 81 | template 82 | Eigen::Matrix Log(const Eigen::Matrix &R) 83 | { 84 | T theta = (R.trace() > 3.0 - 1e-6) ? 0.0 : std::acos(0.5 * (R.trace() - 1)); 85 | Eigen::Matrix K(R(2,1) - R(1,2), R(0,2) - R(2,0), R(1,0) - R(0,1)); 86 | return (std::abs(theta) < 0.001) ? (0.5 * K) : (0.5 * theta / std::sin(theta) * K); 87 | } 88 | 89 | template 90 | Eigen::Matrix RotMtoEuler(const Eigen::Matrix &rot) 91 | { 92 | T sy = sqrt(rot(0,0)*rot(0,0) + rot(1,0)*rot(1,0)); 93 | bool singular = sy < 1e-6; 94 | T x, y, z; 95 | if(!singular) 96 | { 97 | x = atan2(rot(2, 1), rot(2, 2)); 98 | y = atan2(-rot(2, 0), sy); 99 | z = atan2(rot(1, 0), rot(0, 0)); 100 | } 101 | else 102 | { 103 | x = atan2(-rot(1, 2), rot(1, 1)); 104 | y = atan2(-rot(2, 0), sy); 105 | z = 0; 106 | } 107 | Eigen::Matrix ang(x, y, z); 108 | return ang; 109 | } 110 | 111 | #endif 112 | -------------------------------------------------------------------------------- /include/use-ikfom.hpp: -------------------------------------------------------------------------------- 1 | #ifndef USE_IKFOM_H 2 | #define USE_IKFOM_H 3 | 4 | #include 5 | 6 | typedef MTK::vect<3, double> vect3; 7 | typedef MTK::SO3 SO3; 8 | typedef MTK::S2 S2; 9 | typedef MTK::vect<1, double> vect1; 10 | typedef MTK::vect<2, double> vect2; 11 | 12 | MTK_BUILD_MANIFOLD(state_ikfom, 13 | ((vect3, pos)) 14 | ((SO3, rot)) 15 | ((SO3, offset_R_L_I)) 16 | ((vect3, offset_T_L_I)) 17 | ((vect3, vel)) 18 | ((vect3, bg)) 19 | ((vect3, ba)) 20 | ((S2, grav)) 21 | ); 22 | 23 | MTK_BUILD_MANIFOLD(input_ikfom, 24 | ((vect3, acc)) 25 | ((vect3, gyro)) 26 | ); 27 | 28 | MTK_BUILD_MANIFOLD(process_noise_ikfom, 29 | ((vect3, ng)) 30 | ((vect3, na)) 31 | ((vect3, nbg)) 32 | ((vect3, nba)) 33 | ); 34 | 35 | MTK::get_cov::type process_noise_cov() 36 | { 37 | MTK::get_cov::type cov = MTK::get_cov::type::Zero(); 38 | MTK::setDiagonal(cov, &process_noise_ikfom::ng, 0.0001);// 0.03 39 | MTK::setDiagonal(cov, &process_noise_ikfom::na, 0.0001); // *dt 0.01 0.01 * dt * dt 0.05 40 | MTK::setDiagonal(cov, &process_noise_ikfom::nbg, 0.00001); // *dt 0.00001 0.00001 * dt *dt 0.3 //0.001 0.0001 0.01 41 | MTK::setDiagonal(cov, &process_noise_ikfom::nba, 0.00001); //0.001 0.05 0.0001/out 0.01 42 | return cov; 43 | } 44 | 45 | //double L_offset_to_I[3] = {0.04165, 0.02326, -0.0284}; // Avia 46 | //vect3 Lidar_offset_to_IMU(L_offset_to_I, 3); 47 | Eigen::Matrix get_f(state_ikfom &s, const input_ikfom &in) 48 | { 49 | Eigen::Matrix res = Eigen::Matrix::Zero(); 50 | vect3 omega; 51 | in.gyro.boxminus(omega, s.bg); 52 | vect3 a_inertial = s.rot * (in.acc-s.ba); 53 | for(int i = 0; i < 3; i++ ){ 54 | res(i) = s.vel[i]; 55 | res(i + 3) = omega[i]; 56 | res(i + 12) = a_inertial[i] + s.grav[i]; 57 | } 58 | return res; 59 | } 60 | 61 | Eigen::Matrix df_dx(state_ikfom &s, const input_ikfom &in) 62 | { 63 | Eigen::Matrix cov = Eigen::Matrix::Zero(); 64 | cov.template block<3, 3>(0, 12) = Eigen::Matrix3d::Identity(); 65 | vect3 acc_; 66 | in.acc.boxminus(acc_, s.ba); 67 | vect3 omega; 68 | in.gyro.boxminus(omega, s.bg); 69 | cov.template block<3, 3>(12, 3) = -s.rot.toRotationMatrix()*MTK::hat(acc_); 70 | cov.template block<3, 3>(12, 18) = -s.rot.toRotationMatrix(); 71 | Eigen::Matrix vec = Eigen::Matrix::Zero(); 72 | Eigen::Matrix grav_matrix; 73 | s.S2_Mx(grav_matrix, vec, 21); 74 | cov.template block<3, 2>(12, 21) = grav_matrix; 75 | cov.template block<3, 3>(3, 15) = -Eigen::Matrix3d::Identity(); 76 | return cov; 77 | } 78 | 79 | 80 | Eigen::Matrix df_dw(state_ikfom &s, const input_ikfom &in) 81 | { 82 | Eigen::Matrix cov = Eigen::Matrix::Zero(); 83 | cov.template block<3, 3>(12, 3) = -s.rot.toRotationMatrix(); 84 | cov.template block<3, 3>(3, 0) = -Eigen::Matrix3d::Identity(); 85 | cov.template block<3, 3>(15, 6) = Eigen::Matrix3d::Identity(); 86 | cov.template block<3, 3>(18, 9) = Eigen::Matrix3d::Identity(); 87 | return cov; 88 | } 89 | 90 | vect3 SO3ToEuler(const SO3 &orient) 91 | { 92 | Eigen::Matrix _ang; 93 | Eigen::Vector4d q_data = orient.coeffs().transpose(); 94 | //scalar w=orient.coeffs[3], x=orient.coeffs[0], y=orient.coeffs[1], z=orient.coeffs[2]; 95 | double sqw = q_data[3]*q_data[3]; 96 | double sqx = q_data[0]*q_data[0]; 97 | double sqy = q_data[1]*q_data[1]; 98 | double sqz = q_data[2]*q_data[2]; 99 | double unit = sqx + sqy + sqz + sqw; // if normalized is one, otherwise is correction factor 100 | double test = q_data[3]*q_data[1] - q_data[2]*q_data[0]; 101 | 102 | if (test > 0.49999*unit) { // singularity at north pole 103 | 104 | _ang << 2 * std::atan2(q_data[0], q_data[3]), M_PI/2, 0; 105 | double temp[3] = {_ang[0] * 57.3, _ang[1] * 57.3, _ang[2] * 57.3}; 106 | vect3 euler_ang(temp, 3); 107 | return euler_ang; 108 | } 109 | if (test < -0.49999*unit) { // singularity at south pole 110 | _ang << -2 * std::atan2(q_data[0], q_data[3]), -M_PI/2, 0; 111 | double temp[3] = {_ang[0] * 57.3, _ang[1] * 57.3, _ang[2] * 57.3}; 112 | vect3 euler_ang(temp, 3); 113 | return euler_ang; 114 | } 115 | 116 | _ang << 117 | std::atan2(2*q_data[0]*q_data[3]+2*q_data[1]*q_data[2] , -sqx - sqy + sqz + sqw), 118 | std::asin (2*test/unit), 119 | std::atan2(2*q_data[2]*q_data[3]+2*q_data[1]*q_data[0] , sqx - sqy - sqz + sqw); 120 | double temp[3] = {_ang[0] * 57.3, _ang[1] * 57.3, _ang[2] * 57.3}; 121 | vect3 euler_ang(temp, 3); 122 | // euler_ang[0] = roll, euler_ang[1] = pitch, euler_ang[2] = yaw 123 | return euler_ang; 124 | } 125 | 126 | #endif -------------------------------------------------------------------------------- /launch/gdb_debug_example.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 21 | 22 | 23 | -------------------------------------------------------------------------------- /launch/mapping_avia.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | -------------------------------------------------------------------------------- /launch/mapping_horizon.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | -------------------------------------------------------------------------------- /launch/mapping_marsim.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | -------------------------------------------------------------------------------- /launch/mapping_mid360.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | -------------------------------------------------------------------------------- /launch/mapping_ouster64.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | -------------------------------------------------------------------------------- /launch/mapping_velodyne.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | -------------------------------------------------------------------------------- /msg/Pose6D.msg: -------------------------------------------------------------------------------- 1 | # the preintegrated Lidar states at the time of IMU measurements in a frame 2 | float64 offset_time # the offset time of IMU measurement w.r.t the first lidar point 3 | float64[3] acc # the preintegrated total acceleration (global frame) at the Lidar origin 4 | float64[3] gyr # the unbiased angular velocity (body frame) at the Lidar origin 5 | float64[3] vel # the preintegrated velocity (global frame) at the Lidar origin 6 | float64[3] pos # the preintegrated position (global frame) at the Lidar origin 7 | float64[9] rot # the preintegrated rotation (global frame) at the Lidar origin -------------------------------------------------------------------------------- /package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | fast_lio 4 | 0.0.0 5 | 6 | 7 | This is a modified version of LOAM which is original algorithm 8 | is described in the following paper: 9 | J. Zhang and S. Singh. LOAM: Lidar Odometry and Mapping in Real-time. 10 | Robotics: Science and Systems Conference (RSS). Berkeley, CA, July 2014. 11 | 12 | 13 | claydergc 14 | 15 | BSD 16 | 17 | Ji Zhang 18 | 19 | catkin 20 | geometry_msgs 21 | nav_msgs 22 | roscpp 23 | rospy 24 | std_msgs 25 | sensor_msgs 26 | tf 27 | pcl_ros 28 | livox_ros_driver 29 | message_generation 30 | 31 | geometry_msgs 32 | nav_msgs 33 | sensor_msgs 34 | roscpp 35 | rospy 36 | std_msgs 37 | tf 38 | pcl_ros 39 | livox_ros_driver 40 | message_runtime 41 | 42 | rostest 43 | rosbag 44 | 45 | 46 | 47 | 48 | -------------------------------------------------------------------------------- /rviz_cfg/.gitignore: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/FAST_LIO/7cc4175de6f8ba2edf34bab02a42195b141027e9/rviz_cfg/.gitignore -------------------------------------------------------------------------------- /rviz_cfg/loam_livox.rviz: -------------------------------------------------------------------------------- 1 | Panels: 2 | - Class: rviz/Displays 3 | Help Height: 0 4 | Name: Displays 5 | Property Tree Widget: 6 | Expanded: 7 | - /Global Options1 8 | - /mapping1 9 | - /mapping1/surround1 10 | - /mapping1/currPoints1 11 | - /mapping1/currPoints1/Autocompute Value Bounds1 12 | - /Odometry1/Odometry1 13 | - /Odometry1/Odometry1/Shape1 14 | - /Odometry1/Odometry1/Covariance1 15 | - /Odometry1/Odometry1/Covariance1/Position1 16 | - /Odometry1/Odometry1/Covariance1/Orientation1 17 | - /MarkerArray1/Namespaces1 18 | Splitter Ratio: 0.6432291865348816 19 | Tree Height: 811 20 | - Class: rviz/Selection 21 | Name: Selection 22 | - Class: rviz/Tool Properties 23 | Expanded: 24 | - /2D Pose Estimate1 25 | - /2D Nav Goal1 26 | - /Publish Point1 27 | Name: Tool Properties 28 | Splitter Ratio: 0.5886790156364441 29 | - Class: rviz/Views 30 | Expanded: 31 | - /Current View1 32 | Name: Views 33 | Splitter Ratio: 0.5 34 | - Class: rviz/Time 35 | Experimental: false 36 | Name: Time 37 | SyncMode: 0 38 | SyncSource: surround 39 | Preferences: 40 | PromptSaveOnExit: true 41 | Toolbars: 42 | toolButtonStyle: 2 43 | Visualization Manager: 44 | Class: "" 45 | Displays: 46 | - Alpha: 1 47 | Cell Size: 1000 48 | Class: rviz/Grid 49 | Color: 160; 160; 164 50 | Enabled: false 51 | Line Style: 52 | Line Width: 0.029999999329447746 53 | Value: Lines 54 | Name: Grid 55 | Normal Cell Count: 0 56 | Offset: 57 | X: 0 58 | Y: 0 59 | Z: 0 60 | Plane: XY 61 | Plane Cell Count: 40 62 | Reference Frame: 63 | Value: false 64 | - Class: rviz/Axes 65 | Enabled: false 66 | Length: 0.699999988079071 67 | Name: Axes 68 | Radius: 0.05999999865889549 69 | Reference Frame: 70 | Value: false 71 | - Class: rviz/Group 72 | Displays: 73 | - Alpha: 1 74 | Autocompute Intensity Bounds: true 75 | Autocompute Value Bounds: 76 | Max Value: 10 77 | Min Value: -10 78 | Value: true 79 | Axis: Z 80 | Channel Name: intensity 81 | Class: rviz/PointCloud2 82 | Color: 238; 238; 236 83 | Color Transformer: Intensity 84 | Decay Time: 0 85 | Enabled: true 86 | Invert Rainbow: false 87 | Max Color: 255; 255; 255 88 | Min Color: 238; 238; 236 89 | Name: surround 90 | Position Transformer: XYZ 91 | Queue Size: 1 92 | Selectable: false 93 | Size (Pixels): 3 94 | Size (m): 0.05000000074505806 95 | Style: Points 96 | Topic: /cloud_registered 97 | Unreliable: false 98 | Use Fixed Frame: true 99 | Use rainbow: true 100 | Value: true 101 | - Alpha: 0.10000000149011612 102 | Autocompute Intensity Bounds: true 103 | Autocompute Value Bounds: 104 | Max Value: 15 105 | Min Value: -5 106 | Value: false 107 | Axis: Z 108 | Channel Name: intensity 109 | Class: rviz/PointCloud2 110 | Color: 255; 255; 255 111 | Color Transformer: Intensity 112 | Decay Time: 1000 113 | Enabled: true 114 | Invert Rainbow: true 115 | Max Color: 255; 255; 255 116 | Min Color: 0; 0; 0 117 | Name: currPoints 118 | Position Transformer: XYZ 119 | Queue Size: 100000 120 | Selectable: true 121 | Size (Pixels): 1 122 | Size (m): 0.009999999776482582 123 | Style: Points 124 | Topic: /cloud_registered 125 | Unreliable: false 126 | Use Fixed Frame: true 127 | Use rainbow: true 128 | Value: true 129 | - Alpha: 1 130 | Autocompute Intensity Bounds: true 131 | Autocompute Value Bounds: 132 | Max Value: 10 133 | Min Value: -10 134 | Value: true 135 | Axis: Z 136 | Channel Name: intensity 137 | Class: rviz/PointCloud2 138 | Color: 255; 0; 0 139 | Color Transformer: FlatColor 140 | Decay Time: 0 141 | Enabled: false 142 | Invert Rainbow: false 143 | Max Color: 255; 255; 255 144 | Min Color: 0; 0; 0 145 | Name: PointCloud2 146 | Position Transformer: XYZ 147 | Queue Size: 10 148 | Selectable: true 149 | Size (Pixels): 3 150 | Size (m): 0.10000000149011612 151 | Style: Flat Squares 152 | Topic: /Laser_map 153 | Unreliable: false 154 | Use Fixed Frame: true 155 | Use rainbow: true 156 | Value: false 157 | Enabled: true 158 | Name: mapping 159 | - Class: rviz/Group 160 | Displays: 161 | - Angle Tolerance: 0.009999999776482582 162 | Class: rviz/Odometry 163 | Covariance: 164 | Orientation: 165 | Alpha: 0.5 166 | Color: 255; 255; 127 167 | Color Style: Unique 168 | Frame: Local 169 | Offset: 1 170 | Scale: 1 171 | Value: true 172 | Position: 173 | Alpha: 0.30000001192092896 174 | Color: 204; 51; 204 175 | Scale: 1 176 | Value: true 177 | Value: true 178 | Enabled: true 179 | Keep: 1 180 | Name: Odometry 181 | Position Tolerance: 0.0010000000474974513 182 | Shape: 183 | Alpha: 1 184 | Axes Length: 1 185 | Axes Radius: 0.20000000298023224 186 | Color: 255; 85; 0 187 | Head Length: 0 188 | Head Radius: 0 189 | Shaft Length: 0.05000000074505806 190 | Shaft Radius: 0.05000000074505806 191 | Value: Axes 192 | Topic: /Odometry 193 | Unreliable: false 194 | Value: true 195 | Enabled: true 196 | Name: Odometry 197 | - Class: rviz/Axes 198 | Enabled: true 199 | Length: 0.699999988079071 200 | Name: Axes 201 | Radius: 0.10000000149011612 202 | Reference Frame: 203 | Value: true 204 | - Alpha: 0 205 | Buffer Length: 2 206 | Class: rviz/Path 207 | Color: 25; 255; 255 208 | Enabled: true 209 | Head Diameter: 0 210 | Head Length: 0 211 | Length: 0.30000001192092896 212 | Line Style: Billboards 213 | Line Width: 0.20000000298023224 214 | Name: Path 215 | Offset: 216 | X: 0 217 | Y: 0 218 | Z: 0 219 | Pose Color: 25; 255; 255 220 | Pose Style: None 221 | Radius: 0.029999999329447746 222 | Shaft Diameter: 0.4000000059604645 223 | Shaft Length: 0.4000000059604645 224 | Topic: /path 225 | Unreliable: false 226 | Value: true 227 | - Alpha: 1 228 | Autocompute Intensity Bounds: false 229 | Autocompute Value Bounds: 230 | Max Value: 10 231 | Min Value: -10 232 | Value: true 233 | Axis: Z 234 | Channel Name: intensity 235 | Class: rviz/PointCloud2 236 | Color: 255; 255; 255 237 | Color Transformer: Intensity 238 | Decay Time: 0 239 | Enabled: false 240 | Invert Rainbow: false 241 | Max Color: 239; 41; 41 242 | Max Intensity: 0 243 | Min Color: 239; 41; 41 244 | Min Intensity: 0 245 | Name: PointCloud2 246 | Position Transformer: XYZ 247 | Queue Size: 10 248 | Selectable: true 249 | Size (Pixels): 4 250 | Size (m): 0.30000001192092896 251 | Style: Spheres 252 | Topic: /cloud_effected 253 | Unreliable: false 254 | Use Fixed Frame: true 255 | Use rainbow: true 256 | Value: false 257 | - Alpha: 1 258 | Autocompute Intensity Bounds: true 259 | Autocompute Value Bounds: 260 | Max Value: 13.139549255371094 261 | Min Value: -32.08251953125 262 | Value: true 263 | Axis: Z 264 | Channel Name: intensity 265 | Class: rviz/PointCloud2 266 | Color: 138; 226; 52 267 | Color Transformer: FlatColor 268 | Decay Time: 0 269 | Enabled: false 270 | Invert Rainbow: false 271 | Max Color: 138; 226; 52 272 | Min Color: 138; 226; 52 273 | Name: PointCloud2 274 | Position Transformer: XYZ 275 | Queue Size: 10 276 | Selectable: true 277 | Size (Pixels): 3 278 | Size (m): 0.10000000149011612 279 | Style: Flat Squares 280 | Topic: /Laser_map 281 | Unreliable: false 282 | Use Fixed Frame: true 283 | Use rainbow: true 284 | Value: false 285 | - Class: rviz/MarkerArray 286 | Enabled: false 287 | Marker Topic: /MarkerArray 288 | Name: MarkerArray 289 | Namespaces: 290 | {} 291 | Queue Size: 100 292 | Value: false 293 | Enabled: true 294 | Global Options: 295 | Background Color: 0; 0; 0 296 | Default Light: true 297 | Fixed Frame: camera_init 298 | Frame Rate: 10 299 | Name: root 300 | Tools: 301 | - Class: rviz/Interact 302 | Hide Inactive Objects: true 303 | - Class: rviz/MoveCamera 304 | - Class: rviz/Select 305 | - Class: rviz/FocusCamera 306 | - Class: rviz/Measure 307 | - Class: rviz/SetInitialPose 308 | Theta std deviation: 0.2617993950843811 309 | Topic: /initialpose 310 | X std deviation: 0.5 311 | Y std deviation: 0.5 312 | - Class: rviz/SetGoal 313 | Topic: /move_base_simple/goal 314 | - Class: rviz/PublishPoint 315 | Single click: true 316 | Topic: /clicked_point 317 | Value: true 318 | Views: 319 | Current: 320 | Class: rviz/Orbit 321 | Distance: 46.0853271484375 322 | Enable Stereo Rendering: 323 | Stereo Eye Separation: 0.05999999865889549 324 | Stereo Focal Distance: 1 325 | Swap Stereo Eyes: false 326 | Value: false 327 | Focal Point: 328 | X: -4.982542037963867 329 | Y: -15.83572006225586 330 | Z: -3.063523054122925 331 | Focal Shape Fixed Size: true 332 | Focal Shape Size: 0.05000000074505806 333 | Invert Z Axis: false 334 | Name: Current View 335 | Near Clip Distance: 0.009999999776482582 336 | Pitch: 0.399796724319458 337 | Target Frame: global 338 | Value: Orbit (rviz) 339 | Yaw: 1.277182698249817 340 | Saved: ~ 341 | Window Geometry: 342 | Displays: 343 | collapsed: false 344 | Height: 1028 345 | Hide Left Dock: false 346 | Hide Right Dock: true 347 | QMainWindow State: 000000ff00000000fd0000000400000000000001c800000368fc020000000dfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000002700000368000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d0061006700650000000297000001dc0000000000000000fb0000000a0049006d0061006700650000000394000001600000000000000000fb0000000a0049006d00610067006501000002c5000000c70000000000000000fb0000000a0049006d00610067006501000002c5000000c70000000000000000fb0000000a0049006d00610067006501000002c5000000c700000000000000000000000100000152000004b7fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d000004b7000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000061f00000052fc0100000002fb0000000800540069006d006501000000000000061f000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000004510000036800000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 348 | Selection: 349 | collapsed: false 350 | Time: 351 | collapsed: false 352 | Tool Properties: 353 | collapsed: false 354 | Views: 355 | collapsed: true 356 | Width: 1567 357 | X: 67 358 | Y: 24 359 | -------------------------------------------------------------------------------- /src/IMU_Processing.hpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include 9 | #include 10 | #include 11 | #include 12 | #include 13 | #include 14 | #include 15 | #include 16 | #include 17 | #include 18 | #include 19 | #include 20 | #include 21 | #include 22 | #include 23 | #include 24 | #include 25 | #include "use-ikfom.hpp" 26 | #include "preprocess.h" 27 | 28 | /// *************Preconfiguration 29 | 30 | #define MAX_INI_COUNT (10) 31 | 32 | const bool time_list(PointType &x, PointType &y) {return (x.curvature < y.curvature);}; 33 | 34 | /// *************IMU Process and undistortion 35 | class ImuProcess 36 | { 37 | public: 38 | EIGEN_MAKE_ALIGNED_OPERATOR_NEW 39 | 40 | ImuProcess(); 41 | ~ImuProcess(); 42 | 43 | void Reset(); 44 | void Reset(double start_timestamp, const sensor_msgs::ImuConstPtr &lastimu); 45 | void set_extrinsic(const V3D &transl, const M3D &rot); 46 | void set_extrinsic(const V3D &transl); 47 | void set_extrinsic(const MD(4,4) &T); 48 | void set_gyr_cov(const V3D &scaler); 49 | void set_acc_cov(const V3D &scaler); 50 | void set_gyr_bias_cov(const V3D &b_g); 51 | void set_acc_bias_cov(const V3D &b_a); 52 | Eigen::Matrix Q; 53 | void Process(const MeasureGroup &meas, esekfom::esekf &kf_state, PointCloudXYZI::Ptr pcl_un_); 54 | 55 | ofstream fout_imu; 56 | V3D cov_acc; 57 | V3D cov_gyr; 58 | V3D cov_acc_scale; 59 | V3D cov_gyr_scale; 60 | V3D cov_bias_gyr; 61 | V3D cov_bias_acc; 62 | double first_lidar_time; 63 | int lidar_type; 64 | 65 | private: 66 | void IMU_init(const MeasureGroup &meas, esekfom::esekf &kf_state, int &N); 67 | void UndistortPcl(const MeasureGroup &meas, esekfom::esekf &kf_state, PointCloudXYZI &pcl_in_out); 68 | 69 | PointCloudXYZI::Ptr cur_pcl_un_; 70 | sensor_msgs::ImuConstPtr last_imu_; 71 | deque v_imu_; 72 | vector IMUpose; 73 | vector v_rot_pcl_; 74 | M3D Lidar_R_wrt_IMU; 75 | V3D Lidar_T_wrt_IMU; 76 | V3D mean_acc; 77 | V3D mean_gyr; 78 | V3D angvel_last; 79 | V3D acc_s_last; 80 | double start_timestamp_; 81 | double last_lidar_end_time_; 82 | int init_iter_num = 1; 83 | bool b_first_frame_ = true; 84 | bool imu_need_init_ = true; 85 | }; 86 | 87 | ImuProcess::ImuProcess() 88 | : b_first_frame_(true), imu_need_init_(true), start_timestamp_(-1) 89 | { 90 | init_iter_num = 1; 91 | Q = process_noise_cov(); 92 | cov_acc = V3D(0.1, 0.1, 0.1); 93 | cov_gyr = V3D(0.1, 0.1, 0.1); 94 | cov_bias_gyr = V3D(0.0001, 0.0001, 0.0001); 95 | cov_bias_acc = V3D(0.0001, 0.0001, 0.0001); 96 | mean_acc = V3D(0, 0, -1.0); 97 | mean_gyr = V3D(0, 0, 0); 98 | angvel_last = Zero3d; 99 | Lidar_T_wrt_IMU = Zero3d; 100 | Lidar_R_wrt_IMU = Eye3d; 101 | last_imu_.reset(new sensor_msgs::Imu()); 102 | } 103 | 104 | ImuProcess::~ImuProcess() {} 105 | 106 | void ImuProcess::Reset() 107 | { 108 | // ROS_WARN("Reset ImuProcess"); 109 | mean_acc = V3D(0, 0, -1.0); 110 | mean_gyr = V3D(0, 0, 0); 111 | angvel_last = Zero3d; 112 | imu_need_init_ = true; 113 | start_timestamp_ = -1; 114 | init_iter_num = 1; 115 | v_imu_.clear(); 116 | IMUpose.clear(); 117 | last_imu_.reset(new sensor_msgs::Imu()); 118 | cur_pcl_un_.reset(new PointCloudXYZI()); 119 | } 120 | 121 | void ImuProcess::set_extrinsic(const MD(4,4) &T) 122 | { 123 | Lidar_T_wrt_IMU = T.block<3,1>(0,3); 124 | Lidar_R_wrt_IMU = T.block<3,3>(0,0); 125 | } 126 | 127 | void ImuProcess::set_extrinsic(const V3D &transl) 128 | { 129 | Lidar_T_wrt_IMU = transl; 130 | Lidar_R_wrt_IMU.setIdentity(); 131 | } 132 | 133 | void ImuProcess::set_extrinsic(const V3D &transl, const M3D &rot) 134 | { 135 | Lidar_T_wrt_IMU = transl; 136 | Lidar_R_wrt_IMU = rot; 137 | } 138 | 139 | void ImuProcess::set_gyr_cov(const V3D &scaler) 140 | { 141 | cov_gyr_scale = scaler; 142 | } 143 | 144 | void ImuProcess::set_acc_cov(const V3D &scaler) 145 | { 146 | cov_acc_scale = scaler; 147 | } 148 | 149 | void ImuProcess::set_gyr_bias_cov(const V3D &b_g) 150 | { 151 | cov_bias_gyr = b_g; 152 | } 153 | 154 | void ImuProcess::set_acc_bias_cov(const V3D &b_a) 155 | { 156 | cov_bias_acc = b_a; 157 | } 158 | 159 | void ImuProcess::IMU_init(const MeasureGroup &meas, esekfom::esekf &kf_state, int &N) 160 | { 161 | /** 1. initializing the gravity, gyro bias, acc and gyro covariance 162 | ** 2. normalize the acceleration measurenments to unit gravity **/ 163 | 164 | V3D cur_acc, cur_gyr; 165 | 166 | if (b_first_frame_) 167 | { 168 | Reset(); 169 | N = 1; 170 | b_first_frame_ = false; 171 | const auto &imu_acc = meas.imu.front()->linear_acceleration; 172 | const auto &gyr_acc = meas.imu.front()->angular_velocity; 173 | mean_acc << imu_acc.x, imu_acc.y, imu_acc.z; 174 | mean_gyr << gyr_acc.x, gyr_acc.y, gyr_acc.z; 175 | first_lidar_time = meas.lidar_beg_time; 176 | } 177 | 178 | for (const auto &imu : meas.imu) 179 | { 180 | const auto &imu_acc = imu->linear_acceleration; 181 | const auto &gyr_acc = imu->angular_velocity; 182 | cur_acc << imu_acc.x, imu_acc.y, imu_acc.z; 183 | cur_gyr << gyr_acc.x, gyr_acc.y, gyr_acc.z; 184 | 185 | mean_acc += (cur_acc - mean_acc) / N; 186 | mean_gyr += (cur_gyr - mean_gyr) / N; 187 | 188 | cov_acc = cov_acc * (N - 1.0) / N + (cur_acc - mean_acc).cwiseProduct(cur_acc - mean_acc) * (N - 1.0) / (N * N); 189 | cov_gyr = cov_gyr * (N - 1.0) / N + (cur_gyr - mean_gyr).cwiseProduct(cur_gyr - mean_gyr) * (N - 1.0) / (N * N); 190 | 191 | // cout<<"acc norm: "<::cov init_P = kf_state.get_P(); 205 | init_P.setIdentity(); 206 | init_P(6,6) = init_P(7,7) = init_P(8,8) = 0.00001; 207 | init_P(9,9) = init_P(10,10) = init_P(11,11) = 0.00001; 208 | init_P(15,15) = init_P(16,16) = init_P(17,17) = 0.0001; 209 | init_P(18,18) = init_P(19,19) = init_P(20,20) = 0.001; 210 | init_P(21,21) = init_P(22,22) = 0.00001; 211 | kf_state.change_P(init_P); 212 | last_imu_ = meas.imu.back(); 213 | 214 | } 215 | 216 | void ImuProcess::UndistortPcl(const MeasureGroup &meas, esekfom::esekf &kf_state, PointCloudXYZI &pcl_out) 217 | { 218 | /*** add the imu of the last frame-tail to the of current frame-head ***/ 219 | auto v_imu = meas.imu; 220 | v_imu.push_front(last_imu_); 221 | const double &imu_beg_time = v_imu.front()->header.stamp.toSec(); 222 | const double &imu_end_time = v_imu.back()->header.stamp.toSec(); 223 | 224 | double pcl_beg_time = meas.lidar_beg_time; 225 | double pcl_end_time = meas.lidar_end_time; 226 | 227 | if (lidar_type == MARSIM) { 228 | pcl_beg_time = last_lidar_end_time_; 229 | pcl_end_time = meas.lidar_beg_time; 230 | } 231 | 232 | /*** sort point clouds by offset time ***/ 233 | pcl_out = *(meas.lidar); 234 | sort(pcl_out.points.begin(), pcl_out.points.end(), time_list); 235 | // cout<<"[ IMU Process ]: Process lidar from "<header.stamp.toSec() < last_lidar_end_time_) continue; 256 | 257 | angvel_avr<<0.5 * (head->angular_velocity.x + tail->angular_velocity.x), 258 | 0.5 * (head->angular_velocity.y + tail->angular_velocity.y), 259 | 0.5 * (head->angular_velocity.z + tail->angular_velocity.z); 260 | acc_avr <<0.5 * (head->linear_acceleration.x + tail->linear_acceleration.x), 261 | 0.5 * (head->linear_acceleration.y + tail->linear_acceleration.y), 262 | 0.5 * (head->linear_acceleration.z + tail->linear_acceleration.z); 263 | 264 | // fout_imu << setw(10) << head->header.stamp.toSec() - first_lidar_time << " " << angvel_avr.transpose() << " " << acc_avr.transpose() << endl; 265 | 266 | acc_avr = acc_avr * G_m_s2 / mean_acc.norm(); // - state_inout.ba; 267 | 268 | if(head->header.stamp.toSec() < last_lidar_end_time_) 269 | { 270 | dt = tail->header.stamp.toSec() - last_lidar_end_time_; 271 | // dt = tail->header.stamp.toSec() - pcl_beg_time; 272 | } 273 | else 274 | { 275 | dt = tail->header.stamp.toSec() - head->header.stamp.toSec(); 276 | } 277 | 278 | in.acc = acc_avr; 279 | in.gyro = angvel_avr; 280 | Q.block<3, 3>(0, 0).diagonal() = cov_gyr; 281 | Q.block<3, 3>(3, 3).diagonal() = cov_acc; 282 | Q.block<3, 3>(6, 6).diagonal() = cov_bias_gyr; 283 | Q.block<3, 3>(9, 9).diagonal() = cov_bias_acc; 284 | kf_state.predict(dt, Q, in); 285 | 286 | /* save the poses at each IMU measurements */ 287 | imu_state = kf_state.get_x(); 288 | angvel_last = angvel_avr - imu_state.bg; 289 | acc_s_last = imu_state.rot * (acc_avr - imu_state.ba); 290 | for(int i=0; i<3; i++) 291 | { 292 | acc_s_last[i] += imu_state.grav[i]; 293 | } 294 | double &&offs_t = tail->header.stamp.toSec() - pcl_beg_time; 295 | IMUpose.push_back(set_pose6d(offs_t, acc_s_last, angvel_last, imu_state.vel, imu_state.pos, imu_state.rot.toRotationMatrix())); 296 | } 297 | 298 | /*** calculated the pos and attitude prediction at the frame-end ***/ 299 | double note = pcl_end_time > imu_end_time ? 1.0 : -1.0; 300 | dt = note * (pcl_end_time - imu_end_time); 301 | kf_state.predict(dt, Q, in); 302 | 303 | imu_state = kf_state.get_x(); 304 | last_imu_ = meas.imu.back(); 305 | last_lidar_end_time_ = pcl_end_time; 306 | 307 | /*** undistort each lidar point (backward propagation) ***/ 308 | if (pcl_out.points.begin() == pcl_out.points.end()) return; 309 | 310 | if(lidar_type != MARSIM){ 311 | auto it_pcl = pcl_out.points.end() - 1; 312 | for (auto it_kp = IMUpose.end() - 1; it_kp != IMUpose.begin(); it_kp--) 313 | { 314 | auto head = it_kp - 1; 315 | auto tail = it_kp; 316 | R_imu<rot); 317 | // cout<<"head imu acc: "<vel); 319 | pos_imu<pos); 320 | acc_imu<acc); 321 | angvel_avr<gyr); 322 | 323 | for(; it_pcl->curvature / double(1000) > head->offset_time; it_pcl --) 324 | { 325 | dt = it_pcl->curvature / double(1000) - head->offset_time; 326 | 327 | /* Transform to the 'end' frame, using only the rotation 328 | * Note: Compensation direction is INVERSE of Frame's moving direction 329 | * So if we want to compensate a point at timestamp-i to the frame-e 330 | * P_compensate = R_imu_e ^ T * (R_i * P_i + T_ei) where T_ei is represented in global frame */ 331 | M3D R_i(R_imu * Exp(angvel_avr, dt)); 332 | 333 | V3D P_i(it_pcl->x, it_pcl->y, it_pcl->z); 334 | V3D T_ei(pos_imu + vel_imu * dt + 0.5 * acc_imu * dt * dt - imu_state.pos); 335 | V3D P_compensate = imu_state.offset_R_L_I.conjugate() * (imu_state.rot.conjugate() * (R_i * (imu_state.offset_R_L_I * P_i + imu_state.offset_T_L_I) + T_ei) - imu_state.offset_T_L_I);// not accurate! 336 | 337 | // save Undistorted points and their rotation 338 | it_pcl->x = P_compensate(0); 339 | it_pcl->y = P_compensate(1); 340 | it_pcl->z = P_compensate(2); 341 | 342 | if (it_pcl == pcl_out.points.begin()) break; 343 | } 344 | } 345 | } 346 | } 347 | 348 | void ImuProcess::Process(const MeasureGroup &meas, esekfom::esekf &kf_state, PointCloudXYZI::Ptr cur_pcl_un_) 349 | { 350 | double t1,t2,t3; 351 | t1 = omp_get_wtime(); 352 | 353 | if(meas.imu.empty()) {return;}; 354 | ROS_ASSERT(meas.lidar != nullptr); 355 | 356 | if (imu_need_init_) 357 | { 358 | /// The very first lidar frame 359 | IMU_init(meas, kf_state, init_iter_num); 360 | 361 | imu_need_init_ = true; 362 | 363 | last_imu_ = meas.imu.back(); 364 | 365 | state_ikfom imu_state = kf_state.get_x(); 366 | if (init_iter_num > MAX_INI_COUNT) 367 | { 368 | cov_acc *= pow(G_m_s2 / mean_acc.norm(), 2); 369 | imu_need_init_ = false; 370 | 371 | cov_acc = cov_acc_scale; 372 | cov_gyr = cov_gyr_scale; 373 | ROS_INFO("IMU Initial Done"); 374 | // ROS_INFO("IMU Initial Done: Gravity: %.4f %.4f %.4f %.4f; state.bias_g: %.4f %.4f %.4f; acc covarience: %.8f %.8f %.8f; gry covarience: %.8f %.8f %.8f",\ 375 | // imu_state.grav[0], imu_state.grav[1], imu_state.grav[2], mean_acc.norm(), cov_bias_gyr[0], cov_bias_gyr[1], cov_bias_gyr[2], cov_acc[0], cov_acc[1], cov_acc[2], cov_gyr[0], cov_gyr[1], cov_gyr[2]); 376 | fout_imu.open(DEBUG_FILE_DIR("imu.txt"),ios::out); 377 | } 378 | 379 | return; 380 | } 381 | 382 | UndistortPcl(meas, kf_state, *cur_pcl_un_); 383 | 384 | t2 = omp_get_wtime(); 385 | t3 = omp_get_wtime(); 386 | 387 | // cout<<"[ IMU Process ]: Time: "< 6 | #include 7 | #include 8 | #include 9 | 10 | using namespace std; 11 | 12 | #define IS_VALID(a) ((abs(a)>1e8) ? true : false) 13 | 14 | typedef pcl::PointXYZINormal PointType; 15 | typedef pcl::PointCloud PointCloudXYZI; 16 | 17 | enum LID_TYPE{AVIA = 1, VELO16, OUST64, MARSIM}; //{1, 2, 3} 18 | enum TIME_UNIT{SEC = 0, MS = 1, US = 2, NS = 3}; 19 | enum Feature{Nor, Poss_Plane, Real_Plane, Edge_Jump, Edge_Plane, Wire, ZeroPoint}; 20 | enum Surround{Prev, Next}; 21 | enum E_jump{Nr_nor, Nr_zero, Nr_180, Nr_inf, Nr_blind}; 22 | 23 | struct orgtype 24 | { 25 | double range; 26 | double dista; 27 | double angle[2]; 28 | double intersect; 29 | E_jump edj[2]; 30 | Feature ftype; 31 | orgtype() 32 | { 33 | range = 0; 34 | edj[Prev] = Nr_nor; 35 | edj[Next] = Nr_nor; 36 | ftype = Nor; 37 | intersect = 2; 38 | } 39 | }; 40 | 41 | namespace velodyne_ros { 42 | struct EIGEN_ALIGN16 Point { 43 | PCL_ADD_POINT4D; 44 | float intensity; 45 | float time; 46 | uint16_t ring; 47 | EIGEN_MAKE_ALIGNED_OPERATOR_NEW 48 | }; 49 | } // namespace velodyne_ros 50 | POINT_CLOUD_REGISTER_POINT_STRUCT(velodyne_ros::Point, 51 | (float, x, x) 52 | (float, y, y) 53 | (float, z, z) 54 | (float, intensity, intensity) 55 | (float, time, time) 56 | (uint16_t, ring, ring) 57 | ) 58 | 59 | namespace ouster_ros { 60 | struct EIGEN_ALIGN16 Point { 61 | PCL_ADD_POINT4D; 62 | float intensity; 63 | uint32_t t; 64 | uint16_t reflectivity; 65 | uint8_t ring; 66 | uint16_t ambient; 67 | uint32_t range; 68 | EIGEN_MAKE_ALIGNED_OPERATOR_NEW 69 | }; 70 | } // namespace ouster_ros 71 | 72 | // clang-format off 73 | POINT_CLOUD_REGISTER_POINT_STRUCT(ouster_ros::Point, 74 | (float, x, x) 75 | (float, y, y) 76 | (float, z, z) 77 | (float, intensity, intensity) 78 | // use std::uint32_t to avoid conflicting with pcl::uint32_t 79 | (std::uint32_t, t, t) 80 | (std::uint16_t, reflectivity, reflectivity) 81 | (std::uint8_t, ring, ring) 82 | (std::uint16_t, ambient, ambient) 83 | (std::uint32_t, range, range) 84 | ) 85 | 86 | class Preprocess 87 | { 88 | public: 89 | // EIGEN_MAKE_ALIGNED_OPERATOR_NEW 90 | 91 | Preprocess(); 92 | ~Preprocess(); 93 | 94 | void process(const livox_ros_driver::CustomMsg::ConstPtr &msg, PointCloudXYZI::Ptr &pcl_out); 95 | void process(const sensor_msgs::PointCloud2::ConstPtr &msg, PointCloudXYZI::Ptr &pcl_out); 96 | void set(bool feat_en, int lid_type, double bld, int pfilt_num); 97 | 98 | // sensor_msgs::PointCloud2::ConstPtr pointcloud; 99 | PointCloudXYZI pl_full, pl_corn, pl_surf; 100 | PointCloudXYZI pl_buff[128]; //maximum 128 line lidar 101 | vector typess[128]; //maximum 128 line lidar 102 | float time_unit_scale; 103 | int lidar_type, point_filter_num, N_SCANS, SCAN_RATE, time_unit; 104 | double blind; 105 | bool feature_enabled, given_offset_time; 106 | ros::Publisher pub_full, pub_surf, pub_corn; 107 | 108 | 109 | private: 110 | void avia_handler(const livox_ros_driver::CustomMsg::ConstPtr &msg); 111 | void oust64_handler(const sensor_msgs::PointCloud2::ConstPtr &msg); 112 | void velodyne_handler(const sensor_msgs::PointCloud2::ConstPtr &msg); 113 | void sim_handler(const sensor_msgs::PointCloud2::ConstPtr &msg); 114 | void give_feature(PointCloudXYZI &pl, vector &types); 115 | void pub_func(PointCloudXYZI &pl, const ros::Time &ct); 116 | int plane_judge(const PointCloudXYZI &pl, vector &types, uint i, uint &i_nex, Eigen::Vector3d &curr_direct); 117 | bool small_plane(const PointCloudXYZI &pl, vector &types, uint i_cur, uint &i_nex, Eigen::Vector3d &curr_direct); 118 | bool edge_jump_judge(const PointCloudXYZI &pl, vector &types, uint i, Surround nor_dir); 119 | 120 | int group_size; 121 | double disA, disB, inf_bound; 122 | double limit_maxmid, limit_midmin, limit_maxmin; 123 | double p2l_ratio; 124 | double jump_up_limit, jump_down_limit; 125 | double cos160; 126 | double edgea, edgeb; 127 | double smallp_intersect, smallp_ratio; 128 | double vx, vy, vz; 129 | }; 130 | #endif --------------------------------------------------------------------------------