Full Code of zhuge2333/4DRadarSLAM for AI

main dd2ee8c23786 cached
79 files
508.8 KB
143.8k tokens
453 symbols
1 requests
Download .txt
Showing preview only (536K chars total). Download the full file or copy to clipboard to get everything.
Repository: zhuge2333/4DRadarSLAM
Branch: main
Commit: dd2ee8c23786
Files: 79
Total size: 508.8 KB

Directory structure:
gitextract_sqtxga8a/

├── CMakeLists.txt
├── LICENSE
├── README.md
├── apps/
│   ├── preprocessing_nodelet.cpp
│   ├── radar_graph_slam_nodelet.cpp
│   └── scan_matching_odometry_nodelet.cpp
├── cmake/
│   └── FindG2O.cmake
├── config/
│   └── params.yaml
├── include/
│   ├── dbscan/
│   │   ├── DBSCAN_kdtree.h
│   │   ├── DBSCAN_precomp.h
│   │   └── DBSCAN_simple.h
│   ├── g2o/
│   │   ├── edge_plane_identity.hpp
│   │   ├── edge_plane_parallel.hpp
│   │   ├── edge_plane_prior.hpp
│   │   ├── edge_se3_gt_utm.hpp
│   │   ├── edge_se3_plane.hpp
│   │   ├── edge_se3_priorquat.hpp
│   │   ├── edge_se3_priorvec.hpp
│   │   ├── edge_se3_priorxy.hpp
│   │   ├── edge_se3_priorxyz.hpp
│   │   ├── edge_se3_priorz.hpp
│   │   ├── edge_se3_se3.hpp
│   │   ├── edge_se3_z.hpp
│   │   └── robust_kernel_io.hpp
│   ├── radar_ego_velocity_estimator.h
│   ├── radar_graph_slam/
│   │   ├── graph_slam.hpp
│   │   ├── information_matrix_calculator.hpp
│   │   ├── keyframe.hpp
│   │   ├── keyframe_updater.hpp
│   │   ├── loop_detector.hpp
│   │   ├── map_cloud_generator.hpp
│   │   ├── nmea_sentence_parser.hpp
│   │   ├── polynomial_interpolation.hpp
│   │   ├── registrations.hpp
│   │   ├── ros_time_hash.hpp
│   │   └── ros_utils.hpp
│   ├── rio_utils/
│   │   ├── data_types.h
│   │   ├── math_helper.h
│   │   ├── radar_point_cloud.h
│   │   ├── ros_helper.h
│   │   ├── simple_profiler.h
│   │   └── strapdown.h
│   ├── scan_context/
│   │   ├── KDTreeVectorOfVectorsAdaptor.h
│   │   ├── Scancontext.h
│   │   ├── nanoflann.hpp
│   │   └── tictoc.h
│   └── utility_radar.h
├── launch/
│   ├── radar_graph_slam.launch
│   ├── rosbag_play_radar_carpark1.launch
│   ├── rosbag_play_radar_carpark3.launch
│   ├── rosbag_play_radar_garden.launch
│   ├── rosbag_play_radar_nanyanglink.launch
│   ├── rosbag_play_radar_ntuloop1.launch
│   ├── rosbag_play_radar_ntuloop2.launch
│   ├── rosbag_play_radar_ntuloop3.launch
│   └── rosbag_play_radar_smoke.launch
├── msg/
│   ├── FloorCoeffs.msg
│   └── ScanMatchingStatus.msg
├── nodelet_plugins.xml
├── package.xml
├── rviz/
│   └── radar_graph_slam.rviz
├── setup.py
├── src/
│   ├── g2o/
│   │   └── robust_kernel_io.cpp
│   ├── gps_traj_align.cpp
│   ├── gt_adjust.cpp
│   ├── radar_ego_velocity_estimator.cpp
│   └── radar_graph_slam/
│       ├── Scancontext.cpp
│       ├── __init__.py
│       ├── bag_player.py
│       ├── ford2bag.py
│       ├── graph_slam.cpp
│       ├── information_matrix_calculator.cpp
│       ├── keyframe.cpp
│       ├── loop_detector.cpp
│       ├── map2odom_publisher.py
│       ├── map_cloud_generator.cpp
│       └── registrations.cpp
└── srv/
    ├── DumpGraph.srv
    └── SaveMap.srv

================================================
FILE CONTENTS
================================================

================================================
FILE: CMakeLists.txt
================================================
# SPDX-License-Identifier: BSD-2-Clause
cmake_minimum_required(VERSION 2.8.3)
project(radar_graph_slam)

# Can we use C++17 in indigo?
add_definitions(-msse -msse2 -msse3 -msse4 -msse4.1 -msse4.2)
# add_definitions("-Wall -g")
set(CMAKE_CXX_FLAGS "-msse -msse2 -msse3 -msse4 -msse4.1 -msse4.2")
set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} "${CMAKE_CURRENT_LIST_DIR}/cmake")

# pcl 1.7 causes a segfault when it is built with debug mode
set(CMAKE_BUILD_TYPE "RELEASE")

find_package(catkin REQUIRED COMPONENTS
  roscpp
  rospy
  pcl_ros
  geodesy
  nmea_msgs
  sensor_msgs
  geometry_msgs
  message_generation
  interactive_markers
  ndt_omp
  fast_gicp
  image_transport
  cv_bridge
  # rosopencv
)
catkin_python_setup()

find_package(OpenCV REQUIRED)
include_directories(${OpenCV_INCLUDE_DIRS})
message(STATUS "version: ${OpenCV_VERSION}")

find_package(PCL REQUIRED)
include_directories(${PCL_INCLUDE_DIRS})
link_directories(${PCL_LIBRARY_DIRS})
add_definitions(${PCL_DEFINITIONS})

message(STATUS "PCL_INCLUDE_DIRS:" ${PCL_INCLUDE_DIRS})
message(STATUS "PCL_LIBRARY_DIRS:" ${PCL_LIBRARY_DIRS})
message(STATUS "PCL_DEFINITIONS:" ${PCL_DEFINITIONS})

find_package(G2O REQUIRED)
include_directories(SYSTEM ${G2O_INCLUDE_DIR} ${G2O_INCLUDE_DIRS})
link_directories(${G2O_LIBRARY_DIRS})
# link_libraries(${G2O_LIBRARIES})

find_package(OpenMP)
if (OPENMP_FOUND)
    set (CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${OpenMP_C_FLAGS}")
    set (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${OpenMP_CXX_FLAGS}")
endif()

find_package(GTSAM REQUIRED QUIET)
link_directories(${GTSAM_LIBRARY_DIRS})

find_library(VGICP_CUDA_FOUND NAMES fast_vgicp_cuda)
message(STATUS "VGICP_CUDA_FOUND:" ${VGICP_CUDA_FOUND})
if(VGICP_CUDA_FOUND)
  add_definitions(-DUSE_VGICP_CUDA)
endif()

########################
## message generation ##
########################
add_message_files(FILES
  FloorCoeffs.msg
  ScanMatchingStatus.msg
)

add_service_files(FILES
  SaveMap.srv
  DumpGraph.srv
)

generate_messages(DEPENDENCIES std_msgs geometry_msgs)

###################################
## catkin specific configuration ##
###################################
catkin_package(
  INCLUDE_DIRS include
  LIBRARIES radar_graph_slam_nodelet
#  CATKIN_DEPENDS pcl_ros roscpp sensor_msgs
  DEPENDS system_lib GTSAM OpenCV
)

###########
## Build ##
###########
include_directories(include)
include_directories(
  ${PCL_INCLUDE_DIRS}
  ${catkin_INCLUDE_DIRS}
  ${GTSAM_INCLUDE_DIR}
  "~/sensor_ws/devel/include"
)

# nodelets
add_library(preprocessing_nodelet
  apps/preprocessing_nodelet.cpp
  src/radar_ego_velocity_estimator.cpp
  #src/lib/radar_body_velocity_estimator.cpp
  #src/lib/radar_body_velocity_estimator_ros.cpp
)
target_link_libraries(preprocessing_nodelet
  ${catkin_LIBRARIES}
  ${PCL_LIBRARIES}
  ${OpenCV_LIBRARIES}
  ${Boost_LIBRARIES}
)
add_dependencies(preprocessing_nodelet ${PROJECT_NAME}_gencpp)


add_library(scan_matching_odometry_nodelet
  apps/scan_matching_odometry_nodelet.cpp
  src/radar_graph_slam/registrations.cpp
)
target_link_libraries(scan_matching_odometry_nodelet
  ${catkin_LIBRARIES}
  ${PCL_LIBRARIES}
)
add_dependencies(scan_matching_odometry_nodelet ${PROJECT_NAME}_gencpp)


add_library(radar_graph_slam_nodelet
  apps/radar_graph_slam_nodelet.cpp
  src/radar_graph_slam/graph_slam.cpp
  src/radar_graph_slam/loop_detector.cpp
  src/radar_graph_slam/Scancontext.cpp
  src/radar_graph_slam/keyframe.cpp
  src/radar_graph_slam/map_cloud_generator.cpp
  src/radar_graph_slam/registrations.cpp
  src/radar_graph_slam/information_matrix_calculator.cpp
  src/g2o/robust_kernel_io.cpp
)
target_link_libraries(radar_graph_slam_nodelet
  ${catkin_LIBRARIES}
  ${OpenCV_LIBS}
  ${PCL_LIBRARIES}
  ${G2O_TYPES_DATA}
  ${G2O_CORE_LIBRARY}
  ${G2O_STUFF_LIBRARY}
  ${G2O_SOLVER_PCG}
  ${G2O_SOLVER_CSPARSE}   # be aware of that CSPARSE is released under LGPL
  ${G2O_SOLVER_CHOLMOD}   # be aware of that cholmod is released under GPL
  ${G2O_TYPES_SLAM3D}
  ${G2O_TYPES_SLAM3D_ADDONS}
)
add_dependencies(radar_graph_slam_nodelet ${PROJECT_NAME}_gencpp)



# Adjust Groundtruth
add_executable(gt_adjust src/gt_adjust.cpp )
target_link_libraries(gt_adjust
  radar_graph_slam_nodelet
  ${catkin_LIBRARIES}
  ${Boost_LIBRARIES}
  ${G2O_TYPES_DATA}
  ${G2O_CORE_LIBRARY}
  ${G2O_STUFF_LIBRARY}
  ${G2O_SOLVER_PCG}
  ${G2O_SOLVER_CSPARSE}   # be aware of that CSPARSE is released under LGPL
  ${G2O_SOLVER_CHOLMOD}   # be aware of that cholmod is released under GPL
  ${G2O_TYPES_SLAM3D}
  ${G2O_TYPES_SLAM3D_ADDONS}
)
# Calculate UTM->world Transform
add_executable(gps_traj_align src/gps_traj_align.cpp )
target_link_libraries(gps_traj_align
  radar_graph_slam_nodelet
  ${catkin_LIBRARIES}
  ${Boost_LIBRARIES}
  ${G2O_TYPES_DATA}
  ${G2O_CORE_LIBRARY}
  ${G2O_STUFF_LIBRARY}
  ${G2O_SOLVER_PCG}
  ${G2O_SOLVER_CSPARSE}   # be aware of that CSPARSE is released under LGPL
  ${G2O_SOLVER_CHOLMOD}   # be aware of that cholmod is released under GPL
  ${G2O_TYPES_SLAM3D}
  ${G2O_TYPES_SLAM3D_ADDONS}
)

catkin_install_python(
  PROGRAMS
    src/${PROJECT_NAME}/bag_player.py
    src/${PROJECT_NAME}/ford2bag.py
    src/${PROJECT_NAME}/map2odom_publisher.py
  DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

install(FILES nodelet_plugins.xml
  DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
)

install(TARGETS
  preprocessing_nodelet
  scan_matching_odometry_nodelet 
  radar_graph_slam_nodelet
  LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION})


================================================
FILE: LICENSE
================================================
                    GNU GENERAL PUBLIC LICENSE
                       Version 3, 29 June 2007

 Copyright (C) 2007 Free Software Foundation, Inc. <https://fsf.org/>
 Everyone is permitted to copy and distribute verbatim copies
 of this license document, but changing it is not allowed.

                            Preamble

  The GNU General Public License is a free, copyleft license for
software and other kinds of works.

  The licenses for most software and other practical works are designed
to take away your freedom to share and change the works.  By contrast,
the GNU General Public License is intended to guarantee your freedom to
share and change all versions of a program--to make sure it remains free
software for all its users.  We, the Free Software Foundation, use the
GNU General Public License for most of our software; it applies also to
any other work released this way by its authors.  You can apply it to
your programs, too.

  When we speak of free software, we are referring to freedom, not
price.  Our General Public Licenses are designed to make sure that you
have the freedom to distribute copies of free software (and charge for
them if you wish), that you receive source code or can get it if you
want it, that you can change the software or use pieces of it in new
free programs, and that you know you can do these things.

  To protect your rights, we need to prevent others from denying you
these rights or asking you to surrender the rights.  Therefore, you have
certain responsibilities if you distribute copies of the software, or if
you modify it: responsibilities to respect the freedom of others.

  For example, if you distribute copies of such a program, whether
gratis or for a fee, you must pass on to the recipients the same
freedoms that you received.  You must make sure that they, too, receive
or can get the source code.  And you must show them these terms so they
know their rights.

  Developers that use the GNU GPL protect your rights with two steps:
(1) assert copyright on the software, and (2) offer you this License
giving you legal permission to copy, distribute and/or modify it.

  For the developers' and authors' protection, the GPL clearly explains
that there is no warranty for this free software.  For both users' and
authors' sake, the GPL requires that modified versions be marked as
changed, so that their problems will not be attributed erroneously to
authors of previous versions.

  Some devices are designed to deny users access to install or run
modified versions of the software inside them, although the manufacturer
can do so.  This is fundamentally incompatible with the aim of
protecting users' freedom to change the software.  The systematic
pattern of such abuse occurs in the area of products for individuals to
use, which is precisely where it is most unacceptable.  Therefore, we
have designed this version of the GPL to prohibit the practice for those
products.  If such problems arise substantially in other domains, we
stand ready to extend this provision to those domains in future versions
of the GPL, as needed to protect the freedom of users.

  Finally, every program is threatened constantly by software patents.
States should not allow patents to restrict development and use of
software on general-purpose computers, but in those that do, we wish to
avoid the special danger that patents applied to a free program could
make it effectively proprietary.  To prevent this, the GPL assures that
patents cannot be used to render the program non-free.

  The precise terms and conditions for copying, distribution and
modification follow.

                       TERMS AND CONDITIONS

  0. Definitions.

  "This License" refers to version 3 of the GNU General Public License.

  "Copyright" also means copyright-like laws that apply to other kinds of
works, such as semiconductor masks.

  "The Program" refers to any copyrightable work licensed under this
License.  Each licensee is addressed as "you".  "Licensees" and
"recipients" may be individuals or organizations.

  To "modify" a work means to copy from or adapt all or part of the work
in a fashion requiring copyright permission, other than the making of an
exact copy.  The resulting work is called a "modified version" of the
earlier work or a work "based on" the earlier work.

  A "covered work" means either the unmodified Program or a work based
on the Program.

  To "propagate" a work means to do anything with it that, without
permission, would make you directly or secondarily liable for
infringement under applicable copyright law, except executing it on a
computer or modifying a private copy.  Propagation includes copying,
distribution (with or without modification), making available to the
public, and in some countries other activities as well.

  To "convey" a work means any kind of propagation that enables other
parties to make or receive copies.  Mere interaction with a user through
a computer network, with no transfer of a copy, is not conveying.

  An interactive user interface displays "Appropriate Legal Notices"
to the extent that it includes a convenient and prominently visible
feature that (1) displays an appropriate copyright notice, and (2)
tells the user that there is no warranty for the work (except to the
extent that warranties are provided), that licensees may convey the
work under this License, and how to view a copy of this License.  If
the interface presents a list of user commands or options, such as a
menu, a prominent item in the list meets this criterion.

  1. Source Code.

  The "source code" for a work means the preferred form of the work
for making modifications to it.  "Object code" means any non-source
form of a work.

  A "Standard Interface" means an interface that either is an official
standard defined by a recognized standards body, or, in the case of
interfaces specified for a particular programming language, one that
is widely used among developers working in that language.

  The "System Libraries" of an executable work include anything, other
than the work as a whole, that (a) is included in the normal form of
packaging a Major Component, but which is not part of that Major
Component, and (b) serves only to enable use of the work with that
Major Component, or to implement a Standard Interface for which an
implementation is available to the public in source code form.  A
"Major Component", in this context, means a major essential component
(kernel, window system, and so on) of the specific operating system
(if any) on which the executable work runs, or a compiler used to
produce the work, or an object code interpreter used to run it.

  The "Corresponding Source" for a work in object code form means all
the source code needed to generate, install, and (for an executable
work) run the object code and to modify the work, including scripts to
control those activities.  However, it does not include the work's
System Libraries, or general-purpose tools or generally available free
programs which are used unmodified in performing those activities but
which are not part of the work.  For example, Corresponding Source
includes interface definition files associated with source files for
the work, and the source code for shared libraries and dynamically
linked subprograms that the work is specifically designed to require,
such as by intimate data communication or control flow between those
subprograms and other parts of the work.

  The Corresponding Source need not include anything that users
can regenerate automatically from other parts of the Corresponding
Source.

  The Corresponding Source for a work in source code form is that
same work.

  2. Basic Permissions.

  All rights granted under this License are granted for the term of
copyright on the Program, and are irrevocable provided the stated
conditions are met.  This License explicitly affirms your unlimited
permission to run the unmodified Program.  The output from running a
covered work is covered by this License only if the output, given its
content, constitutes a covered work.  This License acknowledges your
rights of fair use or other equivalent, as provided by copyright law.

  You may make, run and propagate covered works that you do not
convey, without conditions so long as your license otherwise remains
in force.  You may convey covered works to others for the sole purpose
of having them make modifications exclusively for you, or provide you
with facilities for running those works, provided that you comply with
the terms of this License in conveying all material for which you do
not control copyright.  Those thus making or running the covered works
for you must do so exclusively on your behalf, under your direction
and control, on terms that prohibit them from making any copies of
your copyrighted material outside their relationship with you.

  Conveying under any other circumstances is permitted solely under
the conditions stated below.  Sublicensing is not allowed; section 10
makes it unnecessary.

  3. Protecting Users' Legal Rights From Anti-Circumvention Law.

  No covered work shall be deemed part of an effective technological
measure under any applicable law fulfilling obligations under article
11 of the WIPO copyright treaty adopted on 20 December 1996, or
similar laws prohibiting or restricting circumvention of such
measures.

  When you convey a covered work, you waive any legal power to forbid
circumvention of technological measures to the extent such circumvention
is effected by exercising rights under this License with respect to
the covered work, and you disclaim any intention to limit operation or
modification of the work as a means of enforcing, against the work's
users, your or third parties' legal rights to forbid circumvention of
technological measures.

  4. Conveying Verbatim Copies.

  You may convey verbatim copies of the Program's source code as you
receive it, in any medium, provided that you conspicuously and
appropriately publish on each copy an appropriate copyright notice;
keep intact all notices stating that this License and any
non-permissive terms added in accord with section 7 apply to the code;
keep intact all notices of the absence of any warranty; and give all
recipients a copy of this License along with the Program.

  You may charge any price or no price for each copy that you convey,
and you may offer support or warranty protection for a fee.

  5. Conveying Modified Source Versions.

  You may convey a work based on the Program, or the modifications to
produce it from the Program, in the form of source code under the
terms of section 4, provided that you also meet all of these conditions:

    a) The work must carry prominent notices stating that you modified
    it, and giving a relevant date.

    b) The work must carry prominent notices stating that it is
    released under this License and any conditions added under section
    7.  This requirement modifies the requirement in section 4 to
    "keep intact all notices".

    c) You must license the entire work, as a whole, under this
    License to anyone who comes into possession of a copy.  This
    License will therefore apply, along with any applicable section 7
    additional terms, to the whole of the work, and all its parts,
    regardless of how they are packaged.  This License gives no
    permission to license the work in any other way, but it does not
    invalidate such permission if you have separately received it.

    d) If the work has interactive user interfaces, each must display
    Appropriate Legal Notices; however, if the Program has interactive
    interfaces that do not display Appropriate Legal Notices, your
    work need not make them do so.

  A compilation of a covered work with other separate and independent
works, which are not by their nature extensions of the covered work,
and which are not combined with it such as to form a larger program,
in or on a volume of a storage or distribution medium, is called an
"aggregate" if the compilation and its resulting copyright are not
used to limit the access or legal rights of the compilation's users
beyond what the individual works permit.  Inclusion of a covered work
in an aggregate does not cause this License to apply to the other
parts of the aggregate.

  6. Conveying Non-Source Forms.

  You may convey a covered work in object code form under the terms
of sections 4 and 5, provided that you also convey the
machine-readable Corresponding Source under the terms of this License,
in one of these ways:

    a) Convey the object code in, or embodied in, a physical product
    (including a physical distribution medium), accompanied by the
    Corresponding Source fixed on a durable physical medium
    customarily used for software interchange.

    b) Convey the object code in, or embodied in, a physical product
    (including a physical distribution medium), accompanied by a
    written offer, valid for at least three years and valid for as
    long as you offer spare parts or customer support for that product
    model, to give anyone who possesses the object code either (1) a
    copy of the Corresponding Source for all the software in the
    product that is covered by this License, on a durable physical
    medium customarily used for software interchange, for a price no
    more than your reasonable cost of physically performing this
    conveying of source, or (2) access to copy the
    Corresponding Source from a network server at no charge.

    c) Convey individual copies of the object code with a copy of the
    written offer to provide the Corresponding Source.  This
    alternative is allowed only occasionally and noncommercially, and
    only if you received the object code with such an offer, in accord
    with subsection 6b.

    d) Convey the object code by offering access from a designated
    place (gratis or for a charge), and offer equivalent access to the
    Corresponding Source in the same way through the same place at no
    further charge.  You need not require recipients to copy the
    Corresponding Source along with the object code.  If the place to
    copy the object code is a network server, the Corresponding Source
    may be on a different server (operated by you or a third party)
    that supports equivalent copying facilities, provided you maintain
    clear directions next to the object code saying where to find the
    Corresponding Source.  Regardless of what server hosts the
    Corresponding Source, you remain obligated to ensure that it is
    available for as long as needed to satisfy these requirements.

    e) Convey the object code using peer-to-peer transmission, provided
    you inform other peers where the object code and Corresponding
    Source of the work are being offered to the general public at no
    charge under subsection 6d.

  A separable portion of the object code, whose source code is excluded
from the Corresponding Source as a System Library, need not be
included in conveying the object code work.

  A "User Product" is either (1) a "consumer product", which means any
tangible personal property which is normally used for personal, family,
or household purposes, or (2) anything designed or sold for incorporation
into a dwelling.  In determining whether a product is a consumer product,
doubtful cases shall be resolved in favor of coverage.  For a particular
product received by a particular user, "normally used" refers to a
typical or common use of that class of product, regardless of the status
of the particular user or of the way in which the particular user
actually uses, or expects or is expected to use, the product.  A product
is a consumer product regardless of whether the product has substantial
commercial, industrial or non-consumer uses, unless such uses represent
the only significant mode of use of the product.

  "Installation Information" for a User Product means any methods,
procedures, authorization keys, or other information required to install
and execute modified versions of a covered work in that User Product from
a modified version of its Corresponding Source.  The information must
suffice to ensure that the continued functioning of the modified object
code is in no case prevented or interfered with solely because
modification has been made.

  If you convey an object code work under this section in, or with, or
specifically for use in, a User Product, and the conveying occurs as
part of a transaction in which the right of possession and use of the
User Product is transferred to the recipient in perpetuity or for a
fixed term (regardless of how the transaction is characterized), the
Corresponding Source conveyed under this section must be accompanied
by the Installation Information.  But this requirement does not apply
if neither you nor any third party retains the ability to install
modified object code on the User Product (for example, the work has
been installed in ROM).

  The requirement to provide Installation Information does not include a
requirement to continue to provide support service, warranty, or updates
for a work that has been modified or installed by the recipient, or for
the User Product in which it has been modified or installed.  Access to a
network may be denied when the modification itself materially and
adversely affects the operation of the network or violates the rules and
protocols for communication across the network.

  Corresponding Source conveyed, and Installation Information provided,
in accord with this section must be in a format that is publicly
documented (and with an implementation available to the public in
source code form), and must require no special password or key for
unpacking, reading or copying.

  7. Additional Terms.

  "Additional permissions" are terms that supplement the terms of this
License by making exceptions from one or more of its conditions.
Additional permissions that are applicable to the entire Program shall
be treated as though they were included in this License, to the extent
that they are valid under applicable law.  If additional permissions
apply only to part of the Program, that part may be used separately
under those permissions, but the entire Program remains governed by
this License without regard to the additional permissions.

  When you convey a copy of a covered work, you may at your option
remove any additional permissions from that copy, or from any part of
it.  (Additional permissions may be written to require their own
removal in certain cases when you modify the work.)  You may place
additional permissions on material, added by you to a covered work,
for which you have or can give appropriate copyright permission.

  Notwithstanding any other provision of this License, for material you
add to a covered work, you may (if authorized by the copyright holders of
that material) supplement the terms of this License with terms:

    a) Disclaiming warranty or limiting liability differently from the
    terms of sections 15 and 16 of this License; or

    b) Requiring preservation of specified reasonable legal notices or
    author attributions in that material or in the Appropriate Legal
    Notices displayed by works containing it; or

    c) Prohibiting misrepresentation of the origin of that material, or
    requiring that modified versions of such material be marked in
    reasonable ways as different from the original version; or

    d) Limiting the use for publicity purposes of names of licensors or
    authors of the material; or

    e) Declining to grant rights under trademark law for use of some
    trade names, trademarks, or service marks; or

    f) Requiring indemnification of licensors and authors of that
    material by anyone who conveys the material (or modified versions of
    it) with contractual assumptions of liability to the recipient, for
    any liability that these contractual assumptions directly impose on
    those licensors and authors.

  All other non-permissive additional terms are considered "further
restrictions" within the meaning of section 10.  If the Program as you
received it, or any part of it, contains a notice stating that it is
governed by this License along with a term that is a further
restriction, you may remove that term.  If a license document contains
a further restriction but permits relicensing or conveying under this
License, you may add to a covered work material governed by the terms
of that license document, provided that the further restriction does
not survive such relicensing or conveying.

  If you add terms to a covered work in accord with this section, you
must place, in the relevant source files, a statement of the
additional terms that apply to those files, or a notice indicating
where to find the applicable terms.

  Additional terms, permissive or non-permissive, may be stated in the
form of a separately written license, or stated as exceptions;
the above requirements apply either way.

  8. Termination.

  You may not propagate or modify a covered work except as expressly
provided under this License.  Any attempt otherwise to propagate or
modify it is void, and will automatically terminate your rights under
this License (including any patent licenses granted under the third
paragraph of section 11).

  However, if you cease all violation of this License, then your
license from a particular copyright holder is reinstated (a)
provisionally, unless and until the copyright holder explicitly and
finally terminates your license, and (b) permanently, if the copyright
holder fails to notify you of the violation by some reasonable means
prior to 60 days after the cessation.

  Moreover, your license from a particular copyright holder is
reinstated permanently if the copyright holder notifies you of the
violation by some reasonable means, this is the first time you have
received notice of violation of this License (for any work) from that
copyright holder, and you cure the violation prior to 30 days after
your receipt of the notice.

  Termination of your rights under this section does not terminate the
licenses of parties who have received copies or rights from you under
this License.  If your rights have been terminated and not permanently
reinstated, you do not qualify to receive new licenses for the same
material under section 10.

  9. Acceptance Not Required for Having Copies.

  You are not required to accept this License in order to receive or
run a copy of the Program.  Ancillary propagation of a covered work
occurring solely as a consequence of using peer-to-peer transmission
to receive a copy likewise does not require acceptance.  However,
nothing other than this License grants you permission to propagate or
modify any covered work.  These actions infringe copyright if you do
not accept this License.  Therefore, by modifying or propagating a
covered work, you indicate your acceptance of this License to do so.

  10. Automatic Licensing of Downstream Recipients.

  Each time you convey a covered work, the recipient automatically
receives a license from the original licensors, to run, modify and
propagate that work, subject to this License.  You are not responsible
for enforcing compliance by third parties with this License.

  An "entity transaction" is a transaction transferring control of an
organization, or substantially all assets of one, or subdividing an
organization, or merging organizations.  If propagation of a covered
work results from an entity transaction, each party to that
transaction who receives a copy of the work also receives whatever
licenses to the work the party's predecessor in interest had or could
give under the previous paragraph, plus a right to possession of the
Corresponding Source of the work from the predecessor in interest, if
the predecessor has it or can get it with reasonable efforts.

  You may not impose any further restrictions on the exercise of the
rights granted or affirmed under this License.  For example, you may
not impose a license fee, royalty, or other charge for exercise of
rights granted under this License, and you may not initiate litigation
(including a cross-claim or counterclaim in a lawsuit) alleging that
any patent claim is infringed by making, using, selling, offering for
sale, or importing the Program or any portion of it.

  11. Patents.

  A "contributor" is a copyright holder who authorizes use under this
License of the Program or a work on which the Program is based.  The
work thus licensed is called the contributor's "contributor version".

  A contributor's "essential patent claims" are all patent claims
owned or controlled by the contributor, whether already acquired or
hereafter acquired, that would be infringed by some manner, permitted
by this License, of making, using, or selling its contributor version,
but do not include claims that would be infringed only as a
consequence of further modification of the contributor version.  For
purposes of this definition, "control" includes the right to grant
patent sublicenses in a manner consistent with the requirements of
this License.

  Each contributor grants you a non-exclusive, worldwide, royalty-free
patent license under the contributor's essential patent claims, to
make, use, sell, offer for sale, import and otherwise run, modify and
propagate the contents of its contributor version.

  In the following three paragraphs, a "patent license" is any express
agreement or commitment, however denominated, not to enforce a patent
(such as an express permission to practice a patent or covenant not to
sue for patent infringement).  To "grant" such a patent license to a
party means to make such an agreement or commitment not to enforce a
patent against the party.

  If you convey a covered work, knowingly relying on a patent license,
and the Corresponding Source of the work is not available for anyone
to copy, free of charge and under the terms of this License, through a
publicly available network server or other readily accessible means,
then you must either (1) cause the Corresponding Source to be so
available, or (2) arrange to deprive yourself of the benefit of the
patent license for this particular work, or (3) arrange, in a manner
consistent with the requirements of this License, to extend the patent
license to downstream recipients.  "Knowingly relying" means you have
actual knowledge that, but for the patent license, your conveying the
covered work in a country, or your recipient's use of the covered work
in a country, would infringe one or more identifiable patents in that
country that you have reason to believe are valid.

  If, pursuant to or in connection with a single transaction or
arrangement, you convey, or propagate by procuring conveyance of, a
covered work, and grant a patent license to some of the parties
receiving the covered work authorizing them to use, propagate, modify
or convey a specific copy of the covered work, then the patent license
you grant is automatically extended to all recipients of the covered
work and works based on it.

  A patent license is "discriminatory" if it does not include within
the scope of its coverage, prohibits the exercise of, or is
conditioned on the non-exercise of one or more of the rights that are
specifically granted under this License.  You may not convey a covered
work if you are a party to an arrangement with a third party that is
in the business of distributing software, under which you make payment
to the third party based on the extent of your activity of conveying
the work, and under which the third party grants, to any of the
parties who would receive the covered work from you, a discriminatory
patent license (a) in connection with copies of the covered work
conveyed by you (or copies made from those copies), or (b) primarily
for and in connection with specific products or compilations that
contain the covered work, unless you entered into that arrangement,
or that patent license was granted, prior to 28 March 2007.

  Nothing in this License shall be construed as excluding or limiting
any implied license or other defenses to infringement that may
otherwise be available to you under applicable patent law.

  12. No Surrender of Others' Freedom.

  If conditions are imposed on you (whether by court order, agreement or
otherwise) that contradict the conditions of this License, they do not
excuse you from the conditions of this License.  If you cannot convey a
covered work so as to satisfy simultaneously your obligations under this
License and any other pertinent obligations, then as a consequence you may
not convey it at all.  For example, if you agree to terms that obligate you
to collect a royalty for further conveying from those to whom you convey
the Program, the only way you could satisfy both those terms and this
License would be to refrain entirely from conveying the Program.

  13. Use with the GNU Affero General Public License.

  Notwithstanding any other provision of this License, you have
permission to link or combine any covered work with a work licensed
under version 3 of the GNU Affero General Public License into a single
combined work, and to convey the resulting work.  The terms of this
License will continue to apply to the part which is the covered work,
but the special requirements of the GNU Affero General Public License,
section 13, concerning interaction through a network will apply to the
combination as such.

  14. Revised Versions of this License.

  The Free Software Foundation may publish revised and/or new versions of
the GNU General Public License from time to time.  Such new versions will
be similar in spirit to the present version, but may differ in detail to
address new problems or concerns.

  Each version is given a distinguishing version number.  If the
Program specifies that a certain numbered version of the GNU General
Public License "or any later version" applies to it, you have the
option of following the terms and conditions either of that numbered
version or of any later version published by the Free Software
Foundation.  If the Program does not specify a version number of the
GNU General Public License, you may choose any version ever published
by the Free Software Foundation.

  If the Program specifies that a proxy can decide which future
versions of the GNU General Public License can be used, that proxy's
public statement of acceptance of a version permanently authorizes you
to choose that version for the Program.

  Later license versions may give you additional or different
permissions.  However, no additional obligations are imposed on any
author or copyright holder as a result of your choosing to follow a
later version.

  15. Disclaimer of Warranty.

  THERE IS NO WARRANTY FOR THE PROGRAM, TO THE EXTENT PERMITTED BY
APPLICABLE LAW.  EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT
HOLDERS AND/OR OTHER PARTIES PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY
OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO,
THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
PURPOSE.  THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE PROGRAM
IS WITH YOU.  SHOULD THE PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF
ALL NECESSARY SERVICING, REPAIR OR CORRECTION.

  16. Limitation of Liability.

  IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING
WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MODIFIES AND/OR CONVEYS
THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY
GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING OUT OF THE
USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED TO LOSS OF
DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD
PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER PROGRAMS),
EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF
SUCH DAMAGES.

  17. Interpretation of Sections 15 and 16.

  If the disclaimer of warranty and limitation of liability provided
above cannot be given local legal effect according to their terms,
reviewing courts shall apply local law that most closely approximates
an absolute waiver of all civil liability in connection with the
Program, unless a warranty or assumption of liability accompanies a
copy of the Program in return for a fee.

                     END OF TERMS AND CONDITIONS

            How to Apply These Terms to Your New Programs

  If you develop a new program, and you want it to be of the greatest
possible use to the public, the best way to achieve this is to make it
free software which everyone can redistribute and change under these terms.

  To do so, attach the following notices to the program.  It is safest
to attach them to the start of each source file to most effectively
state the exclusion of warranty; and each file should have at least
the "copyright" line and a pointer to where the full notice is found.

    <one line to give the program's name and a brief idea of what it does.>
    Copyright (C) <year>  <name of author>

    This program is free software: you can redistribute it and/or modify
    it under the terms of the GNU General Public License as published by
    the Free Software Foundation, either version 3 of the License, or
    (at your option) any later version.

    This program is distributed in the hope that it will be useful,
    but WITHOUT ANY WARRANTY; without even the implied warranty of
    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
    GNU General Public License for more details.

    You should have received a copy of the GNU General Public License
    along with this program.  If not, see <https://www.gnu.org/licenses/>.

Also add information on how to contact you by electronic and paper mail.

  If the program does terminal interaction, make it output a short
notice like this when it starts in an interactive mode:

    <program>  Copyright (C) <year>  <name of author>
    This program comes with ABSOLUTELY NO WARRANTY; for details type `show w'.
    This is free software, and you are welcome to redistribute it
    under certain conditions; type `show c' for details.

The hypothetical commands `show w' and `show c' should show the appropriate
parts of the General Public License.  Of course, your program's commands
might be different; for a GUI interface, you would use an "about box".

  You should also get your employer (if you work as a programmer) or school,
if any, to sign a "copyright disclaimer" for the program, if necessary.
For more information on this, and how to apply and follow the GNU GPL, see
<https://www.gnu.org/licenses/>.

  The GNU General Public License does not permit incorporating your program
into proprietary programs.  If your program is a subroutine library, you
may consider it more useful to permit linking proprietary applications with
the library.  If this is what you want to do, use the GNU Lesser General
Public License instead of this License.  But first, please read
<https://www.gnu.org/licenses/why-not-lgpl.html>.


================================================
FILE: README.md
================================================
# 4DRadarSLAM
## A 4D Imaging Radar SLAM System for Large-scale Environments based on Pose Graph Optimization

[Paper (ResearchGate)](https://www.researchgate.net/publication/371309896_4DRadarSLAM_A_4D_Imaging_Radar_SLAM_System_for_Large-scale_Environments_based_on_Pose_Graph_Optimization), [IEEEXplore](https://ieeexplore.ieee.org/document/10160670), [Video](https://www.youtube.com/watch?v=Qlvs7ywA5TI), [Dataset (NTU4DRadLM)](https://github.com/junzhang2016/NTU4DRadLM)

***4DRadarSLAM*** is an open source ROS package for real-time 6DOF SLAM using a 4D Radar. It is based on 3D Graph SLAM with Adaptive Probability Distribution GICP scan matching-based odometry estimation and Intensity Scan Context loop detection. It also supports several graph constraints, such as GPS. We have tested this package with ***Oculli Eagle*** in outdoor structured (buildings), unstructured (trees and grasses) and semi-structured environments.

4DRadarSLAM can operate in adverse wheather. We did a experiment in which sensors are covered by dense ***Smoke***. The Lidar SLAM (R2LIVE) failed, but our 4DRadarSLAM is not affected by it, thanks to the penetration of millimeter waves to small objects such as smoke and rain.

<p align='center'>
    <img src="./doc/mapping_smoke.gif" alt="drawing" width="800"/>
</p>


## 1. Dependency
### 1.1 **Ubuntu** and **ROS**
Ubuntu 64-bit 18.04 or 20.04.
ROS Melodic or Noetic. [ROS Installation](http://wiki.ros.org/ROS/Installation):

### 1.2 ***4DRadarSLAM*** requires the following libraries:
- Eigen3
- OpenMP
- PCL
- g2o
### 1.3 The following ROS packages are required:
- geodesy
- nmea_msgs
- pcl_ros
- Our modified [fast_apdgicp](https://github.com/zhuge2333/fast_apdgicp), in which Adaptive Probability Distribution GICP algorithum module is added. The original is [fast_gicp](https://github.com/SMRT-AIST/fast_gicp)
- [barometer_bmp388](https://github.com/zhuge2333/barometer_bmp388.git)
```
    sudo apt-get install ros-XXX-geodesy ros-XXX-pcl-ros ros-XXX-nmea-msgs ros-XXX-libg2o
```
**NOTICE:** remember to replace "XXX" on above command as your ROS distributions, for example, if your use ROS-noetic, the command should be:
```
    sudo apt-get install ros-noetic-geodesy ros-noetic-pcl-ros ros-noetic-nmea-msgs ros-noetic-libg2o
```

## 2. System architecture
***4DRadarSLAM*** consists of three nodelets.

- *preprocessing_nodelet*
- *scan_matching_odometry_nodelet*
- *radar_graph_slam_nodelet*

The input point cloud is first downsampled by ***preprocessing_nodelet***; the radar pointcloud is transformed to Livox LiDAR frame; estimate its ego velocity and remove dynamic objects, and then passed to the next nodelets. While scan_matching_odometry_nodelet estimates the sensor pose by iteratively applying a scan matching between consecutive frames (i.e., odometry estimation). The estimated odometry are sent to ***radar_graph_slam***. To compensate the accumulated error of the scan matching, it performs loop detection and optimizes a pose graph which takes various constraints into account.

<div align="center">
    <img src="doc/fig_flowchart_system.png" width = 100% >
</div>

## 3. Parameter tuning guide
The mapping quality largely depends on the parameter setting. In particular, scan matching parameters have a big impact on the result. Tune the parameters accoding to the following instructions:

### 3.1 Point cloud registration
- ***registration_method***

This parameter allows to change the registration method to be used for odometry estimation and loop detection. Our code gives five options: ICP, NDT_OMP, FAST_GICP, FAST_APDGICP, FAST_VGICP. 

FAST_APDGICP is the implementation of our proposed Adaptive Probability Distribution GICP, it utilizes OpenMP for acceleration. Note that FAST_APDGICP requires extra parameters.
Point uncertainty parameters:
- ***dist_var***
- ***azimuth_var***
- ***elevation_var***

*dist_var* means the uncertainty of a point’s range measurement at 100m range, *azimuth_var* and *elevation_var* denote the azimuth and elevation angle accuracy (degree)

### 3.2 Loop detection 
- ***accum_distance_thresh***: Minimum distance beteen two edges of the loop
- ***min_loop_interval_dist***: Minimum distance between a new loop edge and the last one
- ***max_baro_difference***: Maximum altitude difference beteen two edges' odometry
- ***max_yaw_difference***: Maximum yaw difference beteen two edges' odometry
- ***odom_check_trans_thresh***: Translation threshold of Odometry Check
- ***odom_check_rot_thresh***: Rotation threshold of Odometry Check
- ***sc_dist_thresh***: Matching score threshold of Scan Context

### 3.3 Other parameters
  All the configurable parameters are available in the launch file. Many are similar to the project ***hdl_graph_slam***.

## 4. Run the package
Download [our recorded rosbag](https://drive.google.com/drive/folders/14jVa_dzmckVMDdfELmY32fJlKrZG1Afv?usp=sharing)  (**More datasets**: [NTU4DRadLM](https://github.com/junzhang2016/NTU4DRadLM)) and, then
```
roslaunch radar_graph_slam radar_graph_slam.launch
```
You'll see a point cloud like:
<div align="center">
    <img src="doc/fig_carpark_map.png" width = 80% >
</div>
You can choose the dataset to play at end of the launch file.
In our paper, we did evaluation on five datasets, mapping results are presented below:
<div align="center">
    <img src="doc/fig_map_compare.png" width = 100% >
</div>



## 5. Evaluate the results
In our paper, we use [rpg_trajectory_evaluation](https://github.com/uzh-rpg/rpg_trajectory_evaluation.git), the performance indices used are RE (relative error) and ATE (absolute trajectory error).

## 6. Collect your own datasets
You need a 4D Imaging radar (we use Oculii's Eagle). Also, a barometer (we use BMP388) and GPS/RTK-GPS (we use ZED-F9P) are optional. If you need to compare Lidar SLAM between the algorithum, or use its trajectory as ground truth, calibrating the transform between Radar and Lidar is a precondition.

## 7. Acknowlegement
1. 4DRadarSLAM is based on [koide3/hdl_graph_slam](https://github.com/koide3/hdl_graph_slam) 
2. [irapkaist/scancontext](https://github.com/irapkaist/scancontext) scan context
3. [wh200720041/iscloam](https://github.com/wh200720041/iscloam) intensity scan context
4. [christopherdoer/reve](https://github.com/christopherdoer/reve) radar ego-velocity estimator
5. [NeBula-Autonomy/LAMP](https://github.com/NeBula-Autonomy/LAMP) odometry check for loop closure validation
6. [slambook-en](https://github.com/gaoxiang12/slambook-en) and [Dr. Gao Xiang (高翔)](https://github.com/gaoxiang12). His SLAM tutorial and blogs are the starting point of our SLAM journey.
7. [lvt2calib](https://github.com/Clothooo/lvt2calib) by LIUY Clothooo for sensor calibration.
## 8. Citation
If you find this work is useful for your research, please consider citing:
```
@INPROCEEDINGS{ZhangZhuge2023ICRA,
  author={Zhang, Jun and Zhuge, Huayang and Wu, Zhenyu and Peng, Guohao and Wen, Mingxing and Liu, Yiyao and Wang, Danwei},
  booktitle={2023 IEEE International Conference on Robotics and Automation (ICRA)}, 
  title={4DRadarSLAM: A 4D Imaging Radar SLAM System for Large-scale Environments based on Pose Graph Optimization}, 
  year={2023},
  volume={},
  number={},
  pages={8333-8340},
  doi={10.1109/ICRA48891.2023.10160670}}
```


```
@INPROCEEDINGS{ZhangZhugeLiu2023ITSC,  
author={Jun Zhang∗, Huayang Zhuge∗, Yiyao Liu∗, Guohao Peng, Zhenyu Wu, Haoyuan Zhang, Qiyang Lyu, Heshan Li, Chunyang Zhao, Dogan Kircali, Sanat Mharolkar, Xun Yang, Su Yi, Yuanzhe Wang+ and Danwei Wang},  
booktitle={2023 IEEE 26th International Conference on Intelligent Transportation Systems (ITSC)},   
title={NTU4DRadLM: 4D Radar-centric Multi-Modal Dataset for Localization and Mapping},  
year={2023},  
volume={},  
number={},  
pages={},  
doi={}}
```


================================================
FILE: apps/preprocessing_nodelet.cpp
================================================
// SPDX-License-Identifier: BSD-2-Clause

#include <string>
#include <fstream>
#include <functional>

#include <ros/ros.h>
#include <ros/time.h>
#include <pcl_ros/transforms.h>
#include <pcl_ros/point_cloud.h>
#include <tf/transform_listener.h>
#include <tf/transform_broadcaster.h>

#include <std_msgs/String.h>
#include <sensor_msgs/Imu.h>
#include <sensor_msgs/PointCloud2.h>
#include <sensor_msgs/PointCloud.h>
#include <geometry_msgs/TwistWithCovarianceStamped.h>
#include <nav_msgs/Odometry.h>

#include <nodelet/nodelet.h>
#include <pluginlib/class_list_macros.h>

#include <pcl/point_types.h>
#include <pcl/point_cloud.h>
#include <pcl/filters/passthrough.h>
#include <pcl/filters/voxel_grid.h>
#include <pcl/filters/approximate_voxel_grid.h>
#include <pcl/filters/radius_outlier_removal.h>
#include <pcl/filters/statistical_outlier_removal.h>
#include <pcl/filters/fast_bilateral.h>
#include <pcl/filters/filter.h>

#include <opencv2/imgproc/imgproc.hpp>

#include <Eigen/Dense>

#include "radar_ego_velocity_estimator.h"
#include "rio_utils/radar_point_cloud.h"
#include "utility_radar.h"

using namespace std;

namespace radar_graph_slam {

class PreprocessingNodelet : public nodelet::Nodelet, public ParamServer {
public: 
  // typedef pcl::PointXYZI PointT;
  typedef pcl::PointXYZI PointT;

  PreprocessingNodelet() {}
  virtual ~PreprocessingNodelet() {}

  virtual void onInit() {
    nh = getNodeHandle();
    private_nh = getPrivateNodeHandle();

    initializeTransformation();
    initializeParams();

    points_sub = nh.subscribe(pointCloudTopic, 64, &PreprocessingNodelet::cloud_callback, this);
    imu_sub = nh.subscribe(imuTopic, 1, &PreprocessingNodelet::imu_callback, this);
    command_sub = nh.subscribe("/command", 10, &PreprocessingNodelet::command_callback, this);

    points_pub = nh.advertise<sensor_msgs::PointCloud2>("/filtered_points", 32);
    colored_pub = nh.advertise<sensor_msgs::PointCloud2>("/colored_points", 32);
    imu_pub = nh.advertise<sensor_msgs::Imu>("/imu", 32);
    gt_pub = nh.advertise<nav_msgs::Odometry>("/aftmapped_to_init", 16);
  
    std::string topic_twist = private_nh.param<std::string>("topic_twist", "/eagle_data/twist");
    std::string topic_inlier_pc2 = private_nh.param<std::string>("topic_inlier_pc2", "/eagle_data/inlier_pc2");
    std::string topic_outlier_pc2 = private_nh.param<std::string>("topic_outlier_pc2", "/eagle_data/outlier_pc2");
    pub_twist = nh.advertise<geometry_msgs::TwistWithCovarianceStamped>(topic_twist, 5);
    pub_inlier_pc2 = nh.advertise<sensor_msgs::PointCloud2>(topic_inlier_pc2, 5);
    pub_outlier_pc2 = nh.advertise<sensor_msgs::PointCloud2>(topic_outlier_pc2, 5);
    pc2_raw_pub = nh.advertise<sensor_msgs::PointCloud2>("/eagle_data/pc2_raw",1);
    enable_dynamic_object_removal = private_nh.param<bool>("enable_dynamic_object_removal", false);
    power_threshold = private_nh.param<float>("power_threshold", 0);
  }

private:
  void initializeTransformation(){
    livox_to_RGB = (cv::Mat_<double>(4,4) << 
    -0.006878330000, -0.999969000000, 0.003857230000, 0.029164500000,  
    -7.737180000000E-05, -0.003856790000, -0.999993000000, 0.045695200000,
     0.999976000000, -0.006878580000, -5.084110000000E-05, -0.19018000000,
    0,  0,  0,  1);
    RGB_to_livox =livox_to_RGB.inv();
    Thermal_to_RGB = (cv::Mat_<double>(4,4) <<
    0.9999526089706319, 0.008963747151337641, -0.003798822163962599, 0.18106962419014,  
    -0.008945181135788245, 0.9999481006917174, 0.004876439015823288, -0.04546324090016857,
    0.00384233617405678, -0.004842226763999368, 0.999980894463835, 0.08046453079998771,
    0,0,0,1);
    Radar_to_Thermal = (cv::Mat_<double>(4,4) <<
    0.999665,    0.00925436,  -0.0241851,  -0.0248342,
    -0.00826999, 0.999146,    0.0404891,   0.0958317,
    0.0245392,   -0.0402755,  0.998887,    0.0268037,
    0,  0,  0,  1);
    Change_Radarframe=(cv::Mat_<double>(4,4) <<
    0,-1,0,0,
    0,0,-1,0,
    1,0,0,0,
    0,0,0,1);
    Radar_to_livox=RGB_to_livox*Thermal_to_RGB*Radar_to_Thermal*Change_Radarframe;
    std::cout << "Radar_to_livox = "<< std::endl << " "  << Radar_to_livox << std::endl << std::endl;
  }
  void initializeParams() {
    std::string downsample_method = private_nh.param<std::string>("downsample_method", "VOXELGRID");
    double downsample_resolution = private_nh.param<double>("downsample_resolution", 0.1);

    if(downsample_method == "VOXELGRID") {
      std::cout << "downsample: VOXELGRID " << downsample_resolution << std::endl;
      auto voxelgrid = new pcl::VoxelGrid<PointT>();
      voxelgrid->setLeafSize(downsample_resolution, downsample_resolution, downsample_resolution);
      downsample_filter.reset(voxelgrid);
    } else if(downsample_method == "APPROX_VOXELGRID") {
      std::cout << "downsample: APPROX_VOXELGRID " << downsample_resolution << std::endl;
      pcl::ApproximateVoxelGrid<PointT>::Ptr approx_voxelgrid(new pcl::ApproximateVoxelGrid<PointT>());
      approx_voxelgrid->setLeafSize(downsample_resolution, downsample_resolution, downsample_resolution);
      downsample_filter = approx_voxelgrid;
    } else {
      if(downsample_method != "NONE") {
        std::cerr << "warning: unknown downsampling type (" << downsample_method << ")" << std::endl;
        std::cerr << "       : use passthrough filter" << std::endl;
      }
      std::cout << "downsample: NONE" << std::endl;
    }

    std::string outlier_removal_method = private_nh.param<std::string>("outlier_removal_method", "STATISTICAL");
    if(outlier_removal_method == "STATISTICAL") {
      int mean_k = private_nh.param<int>("statistical_mean_k", 20);
      double stddev_mul_thresh = private_nh.param<double>("statistical_stddev", 1.0);
      std::cout << "outlier_removal: STATISTICAL " << mean_k << " - " << stddev_mul_thresh << std::endl;

      pcl::StatisticalOutlierRemoval<PointT>::Ptr sor(new pcl::StatisticalOutlierRemoval<PointT>());
      sor->setMeanK(mean_k);
      sor->setStddevMulThresh(stddev_mul_thresh);
      outlier_removal_filter = sor;
    } else if(outlier_removal_method == "RADIUS") {
      double radius = private_nh.param<double>("radius_radius", 0.8);
      int min_neighbors = private_nh.param<int>("radius_min_neighbors", 2);
      std::cout << "outlier_removal: RADIUS " << radius << " - " << min_neighbors << std::endl;

      pcl::RadiusOutlierRemoval<PointT>::Ptr rad(new pcl::RadiusOutlierRemoval<PointT>());
      rad->setRadiusSearch(radius);
      rad->setMinNeighborsInRadius(min_neighbors);
      outlier_removal_filter = rad;
    } 
    // else if (outlier_removal_method == "BILATERAL")
    // {
    //   double sigma_s = private_nh.param<double>("bilateral_sigma_s", 5.0);
    //   double sigma_r = private_nh.param<double>("bilateral_sigma_r", 0.03);
    //   std::cout << "outlier_removal: BILATERAL " << sigma_s << " - " << sigma_r << std::endl;

    //   pcl::FastBilateralFilter<PointT>::Ptr fbf(new pcl::FastBilateralFilter<PointT>());
    //   fbf->setSigmaS (sigma_s);
    //   fbf->setSigmaR (sigma_r);
    //   outlier_removal_filter = fbf;
    // }
     else {
      std::cout << "outlier_removal: NONE" << std::endl;
    }

    use_distance_filter = private_nh.param<bool>("use_distance_filter", true);
    distance_near_thresh = private_nh.param<double>("distance_near_thresh", 1.0);
    distance_far_thresh = private_nh.param<double>("distance_far_thresh", 100.0);
    z_low_thresh = private_nh.param<double>("z_low_thresh", -5.0);
    z_high_thresh = private_nh.param<double>("z_high_thresh", 20.0);


    std::string file_name = private_nh.param<std::string>("gt_file_location", "");
    publish_tf = private_nh.param<bool>("publish_tf", false);

    ifstream file_in(file_name);
    if (!file_in.is_open()) {
        cout << "Can not open this gt file" << endl;
    }
    else{
      std::vector<std::string> vectorLines;
      std::string line;
      while (getline(file_in, line)) {
          vectorLines.push_back(line);
      }
      
      for (size_t i = 1; i < vectorLines.size(); i++) {
          std::string line_ = vectorLines.at(i);
          double stamp,tx,ty,tz,qx,qy,qz,qw;
          stringstream data(line_);
          data >> stamp >> tx >> ty >> tz >> qx >> qy >> qz >> qw;
          nav_msgs::Odometry odom_msg;
          odom_msg.header.frame_id = mapFrame;
          odom_msg.child_frame_id = baselinkFrame;
          odom_msg.header.stamp = ros::Time().fromSec(stamp);
          odom_msg.pose.pose.orientation.w = qw;
          odom_msg.pose.pose.orientation.x = qx;
          odom_msg.pose.pose.orientation.y = qy;
          odom_msg.pose.pose.orientation.z = qz;
          odom_msg.pose.pose.position.x = tx;
          odom_msg.pose.pose.position.y = ty;
          odom_msg.pose.pose.position.z = tz;
          std::lock_guard<std::mutex> lock(odom_queue_mutex);
          odom_msgs.push_back(odom_msg);
      }
    }
    file_in.close();
  }

  void imu_callback(const sensor_msgs::ImuConstPtr& imu_msg) {
    sensor_msgs::Imu imu_data;
    imu_data.header.stamp = imu_msg->header.stamp;
    imu_data.header.seq = imu_msg->header.seq;
    imu_data.header.frame_id = "imu_frame";
    Eigen::Quaterniond q_ahrs(imu_msg->orientation.w,
                              imu_msg->orientation.x,
                              imu_msg->orientation.y,
                              imu_msg->orientation.z);
    Eigen::Quaterniond q_r = 
        Eigen::AngleAxisd( M_PI, Eigen::Vector3d::UnitZ()) * 
        Eigen::AngleAxisd( M_PI, Eigen::Vector3d::UnitY()) * 
        Eigen::AngleAxisd( 0.00000, Eigen::Vector3d::UnitX());
    Eigen::Quaterniond q_rr = 
        Eigen::AngleAxisd( 0.00000, Eigen::Vector3d::UnitZ()) * 
        Eigen::AngleAxisd( 0.00000, Eigen::Vector3d::UnitY()) * 
        Eigen::AngleAxisd( M_PI, Eigen::Vector3d::UnitX());
    Eigen::Quaterniond q_out =  q_r * q_ahrs * q_rr;
    imu_data.orientation.w = q_out.w();
    imu_data.orientation.x = q_out.x();
    imu_data.orientation.y = q_out.y();
    imu_data.orientation.z = q_out.z();
    imu_data.angular_velocity.x = imu_msg->angular_velocity.x;
    imu_data.angular_velocity.y = -imu_msg->angular_velocity.y;
    imu_data.angular_velocity.z = -imu_msg->angular_velocity.z;
    imu_data.linear_acceleration.x = imu_msg->linear_acceleration.x;
    imu_data.linear_acceleration.y = -imu_msg->linear_acceleration.y;
    imu_data.linear_acceleration.z = -imu_msg->linear_acceleration.z;
    imu_pub.publish(imu_data);
    // imu_queue.push_back(imu_msg);
    double time_now = imu_msg->header.stamp.toSec();
    bool updated = false;
    if (odom_msgs.size() != 0) {
      while (odom_msgs.front().header.stamp.toSec() + 0.001 < time_now) {
        std::lock_guard<std::mutex> lock(odom_queue_mutex);
        odom_msgs.pop_front();
        updated = true;
        if (odom_msgs.size() == 0)
          break;
      }
    }
    if (updated == true && odom_msgs.size() > 0){
      if (publish_tf) {
        geometry_msgs::TransformStamped tf_msg;
        tf_msg.child_frame_id = baselinkFrame;
        tf_msg.header.frame_id = mapFrame;
        tf_msg.header.stamp = odom_msgs.front().header.stamp;
        // tf_msg.header.stamp = ros::Time().now();
        tf_msg.transform.rotation = odom_msgs.front().pose.pose.orientation;
        tf_msg.transform.translation.x = odom_msgs.front().pose.pose.position.x;
        tf_msg.transform.translation.y = odom_msgs.front().pose.pose.position.y;
        tf_msg.transform.translation.z = odom_msgs.front().pose.pose.position.z;
        tf_broadcaster.sendTransform(tf_msg);
      }
      
      gt_pub.publish(odom_msgs.front());
    }
  }

  void cloud_callback(const sensor_msgs::PointCloud::ConstPtr&  eagle_msg) { // const pcl::PointCloud<PointT>& src_cloud_r
    
    RadarPointCloudType radarpoint_raw;
    PointT radarpoint_xyzi;
    pcl::PointCloud<RadarPointCloudType>::Ptr radarcloud_raw( new pcl::PointCloud<RadarPointCloudType> );
    pcl::PointCloud<PointT>::Ptr radarcloud_xyzi( new pcl::PointCloud<PointT> );

    radarcloud_xyzi->header.frame_id = baselinkFrame;
    radarcloud_xyzi->header.seq = eagle_msg->header.seq;
    radarcloud_xyzi->header.stamp = eagle_msg->header.stamp.toSec() * 1e6;
    for(int i = 0; i < eagle_msg->points.size(); i++)
    {
        // cout << i << ":    " <<eagle_msg->points[i].x<<endl;
        if(eagle_msg->channels[2].values[i] > power_threshold) //"Power"
        {
            if (eagle_msg->points[i].x == NAN || eagle_msg->points[i].y == NAN || eagle_msg->points[i].z == NAN) continue;
            if (eagle_msg->points[i].x == INFINITY || eagle_msg->points[i].y == INFINITY || eagle_msg->points[i].z == INFINITY) continue;
            cv::Mat ptMat, dstMat;
            ptMat = (cv::Mat_<double>(4, 1) << eagle_msg->points[i].x, eagle_msg->points[i].y, eagle_msg->points[i].z, 1);    
            // Perform matrix multiplication and save as Mat_ for easy element access
            dstMat= Radar_to_livox * ptMat;
            radarpoint_raw.x = dstMat.at<double>(0,0);
            radarpoint_raw.y = dstMat.at<double>(1,0);
            radarpoint_raw.z = dstMat.at<double>(2,0);
            radarpoint_raw.intensity = eagle_msg->channels[2].values[i];
            radarpoint_raw.doppler = eagle_msg->channels[0].values[i];
            radarpoint_xyzi.x = dstMat.at<double>(0,0);
            radarpoint_xyzi.y = dstMat.at<double>(1,0);
            radarpoint_xyzi.z = dstMat.at<double>(2,0);
            radarpoint_xyzi.intensity = eagle_msg->channels[2].values[i];

            radarcloud_raw->points.push_back(radarpoint_raw);
            radarcloud_xyzi->points.push_back(radarpoint_xyzi);
        }
    }

    //********** Publish PointCloud2 Format Raw Cloud **********
    sensor_msgs::PointCloud2 pc2_raw_msg;
    pcl::toROSMsg(*radarcloud_raw, pc2_raw_msg);
    pc2_raw_msg.header.stamp = eagle_msg->header.stamp;
    pc2_raw_msg.header.frame_id = baselinkFrame;
    pc2_raw_pub.publish(pc2_raw_msg);

    //********** Ego Velocity Estimation **********
    Eigen::Vector3d v_r, sigma_v_r;
    sensor_msgs::PointCloud2 inlier_radar_msg, outlier_radar_msg;
    clock_t start_ms = clock();
    if (estimator.estimate(pc2_raw_msg, v_r, sigma_v_r, inlier_radar_msg, outlier_radar_msg))
    {
        clock_t end_ms = clock();
        double time_used = double(end_ms - start_ms) / CLOCKS_PER_SEC;
        egovel_time.push_back(time_used);
        
        geometry_msgs::TwistWithCovarianceStamped twist;
        twist.header.stamp         = pc2_raw_msg.header.stamp;
        twist.twist.twist.linear.x = v_r.x();
        twist.twist.twist.linear.y = v_r.y();
        twist.twist.twist.linear.z = v_r.z();

        twist.twist.covariance.at(0)  = std::pow(sigma_v_r.x(), 2);
        twist.twist.covariance.at(7)  = std::pow(sigma_v_r.y(), 2);
        twist.twist.covariance.at(14) = std::pow(sigma_v_r.z(), 2);

        pub_twist.publish(twist);
        pub_inlier_pc2.publish(inlier_radar_msg);
        pub_outlier_pc2.publish(outlier_radar_msg);

    }
    else{;}

    pcl::PointCloud<PointT>::Ptr radarcloud_inlier( new pcl::PointCloud<PointT> );
    pcl::fromROSMsg (inlier_radar_msg, *radarcloud_inlier);

    pcl::PointCloud<PointT>::ConstPtr src_cloud;
    if (enable_dynamic_object_removal)
      src_cloud = radarcloud_inlier;
    else
      src_cloud = radarcloud_xyzi;

    
    if(src_cloud->empty()) {
      return;
    }

    src_cloud = deskewing(src_cloud);

    // if baselinkFrame is defined, transform the input cloud to the frame
    if(!baselinkFrame.empty()) {
      if(!tf_listener.canTransform(baselinkFrame, src_cloud->header.frame_id, ros::Time(0))) {
        std::cerr << "failed to find transform between " << baselinkFrame << " and " << src_cloud->header.frame_id << std::endl;
      }

      tf::StampedTransform transform;
      tf_listener.waitForTransform(baselinkFrame, src_cloud->header.frame_id, ros::Time(0), ros::Duration(2.0));
      tf_listener.lookupTransform(baselinkFrame, src_cloud->header.frame_id, ros::Time(0), transform);

      pcl::PointCloud<PointT>::Ptr transformed(new pcl::PointCloud<PointT>());
      pcl_ros::transformPointCloud(*src_cloud, *transformed, transform);
      transformed->header.frame_id = baselinkFrame;
      transformed->header.stamp = src_cloud->header.stamp;
      src_cloud = transformed;
    }

    pcl::PointCloud<PointT>::ConstPtr filtered = distance_filter(src_cloud);
    // filtered = passthrough(filtered);
    filtered = downsample(filtered);
    filtered = outlier_removal(filtered);

    // Distance Histogram
    static size_t num_frame = 0;
    if (num_frame % 10 == 0) {
      Eigen::VectorXi num_at_dist = Eigen::VectorXi::Zero(100);
      for (int i = 0; i < filtered->size(); i++){
        int dist = floor(filtered->at(i).getVector3fMap().norm());
        if (dist < 100)
          num_at_dist(dist) += 1;
      }
      num_at_dist_vec.push_back(num_at_dist);
    }

    points_pub.publish(*filtered);
    
  }


  pcl::PointCloud<PointT>::ConstPtr passthrough(const pcl::PointCloud<PointT>::ConstPtr& cloud) const {
    pcl::PointCloud<PointT>::Ptr filtered(new pcl::PointCloud<PointT>());
    PointT pt;
    for(int i = 0; i < cloud->size(); i++){
      if (cloud->at(i).z < 10 && cloud->at(i).z > -2){
        pt.x = (*cloud)[i].x;
        pt.y = (*cloud)[i].y;
        pt.z = (*cloud)[i].z;
        pt.intensity = (*cloud)[i].intensity;
        filtered->points.push_back(pt);
      }
    }
    filtered->header = cloud->header;
    return filtered;
  }

  pcl::PointCloud<PointT>::ConstPtr downsample(const pcl::PointCloud<PointT>::ConstPtr& cloud) const {
    if(!downsample_filter) {
      // Remove NaN/Inf points
      pcl::PointCloud<PointT>::Ptr cloudout(new pcl::PointCloud<PointT>());
      std::vector<int> indices;
      pcl::removeNaNFromPointCloud(*cloud, *cloudout, indices);
      
      return cloudout;
    }

    pcl::PointCloud<PointT>::Ptr filtered(new pcl::PointCloud<PointT>());
    downsample_filter->setInputCloud(cloud);
    downsample_filter->filter(*filtered);
    filtered->header = cloud->header;

    return filtered;
  }

  pcl::PointCloud<PointT>::ConstPtr outlier_removal(const pcl::PointCloud<PointT>::ConstPtr& cloud) const {
    if(!outlier_removal_filter) {
      return cloud;
    }

    pcl::PointCloud<PointT>::Ptr filtered(new pcl::PointCloud<PointT>());
    outlier_removal_filter->setInputCloud(cloud);
    outlier_removal_filter->filter(*filtered);
    filtered->header = cloud->header;

    return filtered;
  }

  pcl::PointCloud<PointT>::ConstPtr distance_filter(const pcl::PointCloud<PointT>::ConstPtr& cloud) const {
    pcl::PointCloud<PointT>::Ptr filtered(new pcl::PointCloud<PointT>());

    filtered->reserve(cloud->size());
    std::copy_if(cloud->begin(), cloud->end(), std::back_inserter(filtered->points), [&](const PointT& p) {
      double d = p.getVector3fMap().norm();
      double z = p.z;
      return d > distance_near_thresh && d < distance_far_thresh && z < z_high_thresh && z > z_low_thresh;
    });
    // for (size_t i=0; i<cloud->size(); i++){
    //   const PointT p = cloud->points.at(i);
    //   double d = p.getVector3fMap().norm();
    //   double z = p.z;
    //   if (d > distance_near_thresh && d < distance_far_thresh && z < z_high_thresh && z > z_low_thresh)
    //     filtered->points.push_back(p);
    // }

    filtered->width = filtered->size();
    filtered->height = 1;
    filtered->is_dense = false;

    filtered->header = cloud->header;

    return filtered;
  }

  pcl::PointCloud<PointT>::ConstPtr deskewing(const pcl::PointCloud<PointT>::ConstPtr& cloud) {
    ros::Time stamp = pcl_conversions::fromPCL(cloud->header.stamp);
    if(imu_queue.empty()) {
      return cloud;
    }

    // the color encodes the point number in the point sequence
    if(colored_pub.getNumSubscribers()) {
      pcl::PointCloud<pcl::PointXYZRGB>::Ptr colored(new pcl::PointCloud<pcl::PointXYZRGB>());
      colored->header = cloud->header;
      colored->is_dense = cloud->is_dense;
      colored->width = cloud->width;
      colored->height = cloud->height;
      colored->resize(cloud->size());

      for(int i = 0; i < cloud->size(); i++) {
        double t = static_cast<double>(i) / cloud->size();
        colored->at(i).getVector4fMap() = cloud->at(i).getVector4fMap();
        colored->at(i).r = 255 * t;
        colored->at(i).g = 128;
        colored->at(i).b = 255 * (1 - t);
      }
      colored_pub.publish(*colored);
    }

    sensor_msgs::ImuConstPtr imu_msg = imu_queue.front();

    auto loc = imu_queue.begin();
    for(; loc != imu_queue.end(); loc++) {
      imu_msg = (*loc);
      if((*loc)->header.stamp > stamp) {
        break;
      }
    }

    imu_queue.erase(imu_queue.begin(), loc);

    Eigen::Vector3f ang_v(imu_msg->angular_velocity.x, imu_msg->angular_velocity.y, imu_msg->angular_velocity.z);
    ang_v *= -1;

    pcl::PointCloud<PointT>::Ptr deskewed(new pcl::PointCloud<PointT>());
    deskewed->header = cloud->header;
    deskewed->is_dense = cloud->is_dense;
    deskewed->width = cloud->width;
    deskewed->height = cloud->height;
    deskewed->resize(cloud->size());

    double scan_period = private_nh.param<double>("scan_period", 0.1);
    for(int i = 0; i < cloud->size(); i++) {
      const auto& pt = cloud->at(i);

      // TODO: transform IMU data into the LIDAR frame
      double delta_t = scan_period * static_cast<double>(i) / cloud->size();
      Eigen::Quaternionf delta_q(1, delta_t / 2.0 * ang_v[0], delta_t / 2.0 * ang_v[1], delta_t / 2.0 * ang_v[2]);
      Eigen::Vector3f pt_ = delta_q.inverse() * pt.getVector3fMap();

      deskewed->at(i) = cloud->at(i);
      deskewed->at(i).getVector3fMap() = pt_;
    }

    return deskewed;
  }

  bool RadarRaw2PointCloudXYZ(const pcl::PointCloud<RadarPointCloudType>::ConstPtr &raw, pcl::PointCloud<pcl::PointXYZ>::Ptr &cloudxyz)
  {
      pcl::PointXYZ point_xyz;
      for(int i = 0; i < raw->size(); i++)
      {
          point_xyz.x = (*raw)[i].x;
          point_xyz.y = (*raw)[i].y;
          point_xyz.z = (*raw)[i].z;
          cloudxyz->points.push_back(point_xyz);
      }
      return true;
  }
  bool RadarRaw2PointCloudXYZI(const pcl::PointCloud<RadarPointCloudType>::ConstPtr &raw, pcl::PointCloud<pcl::PointXYZI>::Ptr &cloudxyzi)
  {
      pcl::PointXYZI radarpoint_xyzi;
      for(int i = 0; i < raw->size(); i++)
      {
          radarpoint_xyzi.x = (*raw)[i].x;
          radarpoint_xyzi.y = (*raw)[i].y;
          radarpoint_xyzi.z = (*raw)[i].z;
          radarpoint_xyzi.intensity = (*raw)[i].intensity;
          cloudxyzi->points.push_back(radarpoint_xyzi);
      }
      return true;
  }

  void command_callback(const std_msgs::String& str_msg) {
    if (str_msg.data == "time") {
      std::sort(egovel_time.begin(), egovel_time.end());
      double median = egovel_time.at(size_t(egovel_time.size() / 2));
      cout << "Ego velocity time cost (median): " << median << endl;
    }
    else if (str_msg.data == "point_distribution") {
      Eigen::VectorXi data(100);
      for (size_t i = 0; i < num_at_dist_vec.size(); i++){ // N
        Eigen::VectorXi& nad = num_at_dist_vec.at(i);
        for (int j = 0; j< 100; j++){
          data(j) += nad(j);
        }
      }
      data /= num_at_dist_vec.size();
      for (int i=0; i<data.size(); i++){
        cout << data(i) << ", ";
      }
      cout << endl;
    }
  }

private:
  ros::NodeHandle nh;
  ros::NodeHandle private_nh;

  ros::Subscriber imu_sub;
  std::vector<sensor_msgs::ImuConstPtr> imu_queue;
  ros::Subscriber points_sub;
  
  ros::Publisher points_pub;
  ros::Publisher colored_pub;
  ros::Publisher imu_pub;
  ros::Publisher gt_pub;

  tf::TransformListener tf_listener;
  tf::TransformBroadcaster tf_broadcaster;


  bool use_distance_filter;
  double distance_near_thresh;
  double distance_far_thresh;
  double z_low_thresh;
  double z_high_thresh;

  pcl::Filter<PointT>::Ptr downsample_filter;
  pcl::Filter<PointT>::Ptr outlier_removal_filter;

  cv::Mat Radar_to_livox; // Transform Radar point cloud to LiDAR Frame
  cv::Mat Thermal_to_RGB,Radar_to_Thermal,RGB_to_livox,livox_to_RGB,Change_Radarframe;
  rio::RadarEgoVelocityEstimator estimator;
  ros::Publisher pub_twist, pub_inlier_pc2, pub_outlier_pc2, pc2_raw_pub;

  float power_threshold;
  bool enable_dynamic_object_removal = false;

  std::mutex odom_queue_mutex;
  std::deque<nav_msgs::Odometry> odom_msgs;
  bool publish_tf;

  ros::Subscriber command_sub;
  std::vector<double> egovel_time;

  std::vector<Eigen::VectorXi> num_at_dist_vec;
};

}  // namespace radar_graph_slam

PLUGINLIB_EXPORT_CLASS(radar_graph_slam::PreprocessingNodelet, nodelet::Nodelet)


================================================
FILE: apps/radar_graph_slam_nodelet.cpp
================================================
// SPDX-License-Identifier: BSD-2-Clause

#include <ctime>
#include <mutex>
#include <atomic>
#include <memory>
#include <iomanip>
#include <iostream>
#include <fstream>
#include <string>
#include <unordered_map>
#include <boost/format.hpp>
#include <boost/thread.hpp>
#include <boost/filesystem.hpp>
#include <boost/algorithm/string.hpp>
#include <Eigen/Dense>
#include <pcl/io/pcd_io.h>
#include <pcl_ros/point_cloud.h>
#include <pcl/registration/icp.h>
#include <pcl/octree/octree_search.h>

#include <ros/ros.h>
#include <geodesy/utm.h>
#include <geodesy/wgs84.h>
#include <message_filters/subscriber.h>
#include <message_filters/time_synchronizer.h>
#include <message_filters/sync_policies/approximate_time.h>
#include <tf_conversions/tf_eigen.h>
#include <tf/transform_listener.h>
#include <tf/transform_broadcaster.h>

#include <std_msgs/Time.h>
#include <std_msgs/String.h>
#include <nav_msgs/Odometry.h>
#include <nmea_msgs/Sentence.h>
#include <sensor_msgs/Imu.h>
#include <sensor_msgs/NavSatFix.h>
#include <sensor_msgs/PointCloud2.h>
#include <geographic_msgs/GeoPointStamped.h>
#include <visualization_msgs/MarkerArray.h>

#include <nodelet/nodelet.h>
#include <pluginlib/class_list_macros.h>

#include <radar_graph_slam/SaveMap.h>
#include <radar_graph_slam/DumpGraph.h>
#include <radar_graph_slam/ros_utils.hpp>
#include <radar_graph_slam/ros_time_hash.hpp>
#include <radar_graph_slam/FloorCoeffs.h>
#include <radar_graph_slam/graph_slam.hpp>
#include <radar_graph_slam/keyframe.hpp>
#include <radar_graph_slam/keyframe_updater.hpp>
#include <radar_graph_slam/loop_detector.hpp>
#include <radar_graph_slam/information_matrix_calculator.hpp>
#include <radar_graph_slam/map_cloud_generator.hpp>
#include <radar_graph_slam/nmea_sentence_parser.hpp>
#include "radar_graph_slam/polynomial_interpolation.hpp"
#include <radar_graph_slam/registrations.hpp>

#include "scan_context/Scancontext.h"

#include <g2o/types/slam3d/edge_se3.h>
#include <g2o/types/slam3d/vertex_se3.h>
#include <g2o/edge_se3_plane.hpp>
#include <g2o/edge_se3_priorxy.hpp>
#include <g2o/edge_se3_priorxyz.hpp>
#include <g2o/edge_se3_priorz.hpp>
#include <g2o/edge_se3_priorvec.hpp>
#include <g2o/edge_se3_priorquat.hpp>

#include <barometer_bmp388/Barometer.h>

#include "utility_radar.h"

using namespace std;

namespace radar_graph_slam {

class RadarGraphSlamNodelet : public nodelet::Nodelet, public ParamServer {
public:
  typedef pcl::PointXYZI PointT;
  typedef PointXYZIRPYT  PointTypePose;
  typedef message_filters::sync_policies::ApproximateTime<nav_msgs::Odometry, sensor_msgs::PointCloud2> ApproxSyncPolicy;

  RadarGraphSlamNodelet() {}
  virtual ~RadarGraphSlamNodelet() {}

  virtual void onInit() {
    nh = getNodeHandle();
    mt_nh = getMTNodeHandle();
    private_nh = getPrivateNodeHandle();

    // init parameters
    map_cloud_resolution = private_nh.param<double>("map_cloud_resolution", 0.05);
    trans_odom2map.setIdentity();
    trans_aftmapped.setIdentity();
    trans_aftmapped_incremental.setIdentity();
    initial_pose.setIdentity();

    max_keyframes_per_update = private_nh.param<int>("max_keyframes_per_update", 10);

    anchor_node = nullptr;
    anchor_edge = nullptr;
    floor_plane_node = nullptr;
    graph_slam.reset(new GraphSLAM(private_nh.param<std::string>("g2o_solver_type", "lm_var")));
    keyframe_updater.reset(new KeyframeUpdater(private_nh));
    loop_detector.reset(new LoopDetector(private_nh));
    map_cloud_generator.reset(new MapCloudGenerator());
    inf_calclator.reset(new InformationMatrixCalculator(private_nh));
    nmea_parser.reset(new NmeaSentenceParser());

    gps_edge_intervals = private_nh.param<int>("gps_edge_intervals", 10);
    gps_time_offset = private_nh.param<double>("gps_time_offset", 0.0);
    gps_edge_stddev_xy = private_nh.param<double>("gps_edge_stddev_xy", 10000.0);
    gps_edge_stddev_z = private_nh.param<double>("gps_edge_stddev_z", 10.0);
    max_gps_edge_stddev_xy = private_nh.param<double>("max_gps_edge_stddev_xy", 1.0);
    max_gps_edge_stddev_z = private_nh.param<double>("max_gps_edge_stddev_z", 2.0);

    // Preintegration Parameters
    enable_preintegration = private_nh.param<bool>("enable_preintegration", false);
    use_egovel_preinteg_trans = private_nh.param<bool>("use_egovel_preinteg_trans", false);
    preinteg_trans_stddev = private_nh.param<double>("preinteg_trans_stddev", 1.0);
    preinteg_orient_stddev = private_nh.param<double>("preinteg_orient_stddev", 2.0);

    enable_barometer = private_nh.param<bool>("enable_barometer", false);
    barometer_edge_type = private_nh.param<int>("barometer_edge_type", 2);
    barometer_edge_stddev = private_nh.param<double>("barometer_edge_stddev", 0.5);

    points_topic = private_nh.param<std::string>("points_topic", "/radar_enhanced_pcl");

    show_sphere = private_nh.param<bool>("show_sphere", false);

    dataset_name = private_nh.param<std::string>("dataset_name", "");

    registration = select_registration_method(private_nh);

    // subscribers
    odom_sub.reset(new message_filters::Subscriber<nav_msgs::Odometry>(mt_nh, odomTopic, 256));
    cloud_sub.reset(new message_filters::Subscriber<sensor_msgs::PointCloud2>(mt_nh, "/filtered_points", 32));
    sync.reset(new message_filters::Synchronizer<ApproxSyncPolicy>(ApproxSyncPolicy(32), *odom_sub, *cloud_sub));
    sync->registerCallback(boost::bind(&RadarGraphSlamNodelet::cloud_callback, this, _1, _2));
    
    if(private_nh.param<bool>("enable_gps", true)) {
      gps_sub = mt_nh.subscribe("/gps/geopoint", 1024, &RadarGraphSlamNodelet::gps_callback, this);
      nmea_sub = mt_nh.subscribe("/gpsimu_driver/nmea_sentence", 1024, &RadarGraphSlamNodelet::nmea_callback, this);
      navsat_sub = mt_nh.subscribe(gpsTopic, 1024, &RadarGraphSlamNodelet::navsat_callback, this);
    }
    if(private_nh.param<bool>("enable_barometer", false)) {
      barometer_sub = mt_nh.subscribe("/barometer/filtered", 16, &RadarGraphSlamNodelet::barometer_callback, this);
    }
    if (enable_preintegration)
      imu_odom_sub = nh.subscribe("/imu_pre_integ/imu_odom_incre", 1024, &RadarGraphSlamNodelet::imu_odom_callback, this);
    imu_sub = nh.subscribe("/imu", 1024, &RadarGraphSlamNodelet::imu_callback, this);
    command_sub = nh.subscribe("/command", 10, &RadarGraphSlamNodelet::command_callback, this);

    //***** publishers ******
    markers_pub = mt_nh.advertise<visualization_msgs::MarkerArray>("/radar_graph_slam/markers", 16);
    // Transform RadarOdom_to_base
    odom2base_pub = mt_nh.advertise<geometry_msgs::TransformStamped>("/radar_graph_slam/odom2base", 16);
    aftmapped_odom_pub = mt_nh.advertise<nav_msgs::Odometry>("/radar_graph_slam/aftmapped_odom", 16);
    aftmapped_odom_incremenral_pub = mt_nh.advertise<nav_msgs::Odometry>("/radar_graph_slam/aftmapped_odom_incremental", 16);
    map_points_pub = mt_nh.advertise<sensor_msgs::PointCloud2>("/radar_graph_slam/map_points", 1, true);
    read_until_pub = mt_nh.advertise<std_msgs::Header>("/radar_graph_slam/read_until", 32);
    odom_frame2frame_pub = mt_nh.advertise<nav_msgs::Odometry>("/radar_graph_slam/odom_frame2frame", 16);

    dump_service_server = mt_nh.advertiseService("/radar_graph_slam/dump", &RadarGraphSlamNodelet::dump_service, this);
    save_map_service_server = mt_nh.advertiseService("/radar_graph_slam/save_map", &RadarGraphSlamNodelet::save_map_service, this);

    graph_updated = false;
    double graph_update_interval = private_nh.param<double>("graph_update_interval", 3.0);
    double map_cloud_update_interval = private_nh.param<double>("map_cloud_update_interval", 10.0);
    optimization_timer = mt_nh.createWallTimer(ros::WallDuration(graph_update_interval), &RadarGraphSlamNodelet::optimization_timer_callback, this);
    map_publish_timer = mt_nh.createWallTimer(ros::WallDuration(map_cloud_update_interval), &RadarGraphSlamNodelet::map_points_publish_timer_callback, this);
  
    if (dataset_name == "loop3")
    utm_to_world << 
     -0.057621,       0.996222,      -0.064972, -128453.624105,
     -0.998281,      -0.058194,      -0.006954,  361869.958099,
     -0.010708,       0.064459,       0.997863,   -5882.237973,
      0.000000,       0.000000,       0.000000,       1.000000;
    else if (dataset_name == "loop2")
    utm_to_world <<
     -0.085585,       0.995774,      -0.033303, -117561.214476,
     -0.996323,      -0.085401,       0.006904,  364927.287181,
      0.004031,       0.033772,       0.999421,   -6478.377842,
      0.000000,       0.000000,       0.000000,       1.000000;
  }


private:
  /**
   * @brief received point clouds are pushed to #keyframe_queue
   * @param odom_msg
   * @param cloud_msg
   */
  void cloud_callback(const nav_msgs::OdometryConstPtr& odom_msg, const sensor_msgs::PointCloud2::ConstPtr& cloud_msg) {
    const ros::Time& stamp = cloud_msg->header.stamp;
    Eigen::Isometry3d odom_now = odom2isometry(odom_msg);
    Eigen::Matrix4d matrix_map2base;
    // Publish TF between /map and /base_link
    if(keyframes.size() > 0)
    {
      const KeyFrame::Ptr& keyframe_last = keyframes.back();
      Eigen::Isometry3d lastkeyframe_odom_incre =  keyframe_last->odom_scan2scan.inverse() * odom_now;
      Eigen::Isometry3d keyframe_map2base_matrix = keyframe_last->node->estimate();
      // map2base = odom^(-1) * base
      matrix_map2base = (keyframe_map2base_matrix * lastkeyframe_odom_incre).matrix();
    }
    geometry_msgs::TransformStamped map2base_trans = matrix2transform(cloud_msg->header.stamp, matrix_map2base, mapFrame, baselinkFrame);
    if (pow(map2base_trans.transform.rotation.w,2)+pow(map2base_trans.transform.rotation.x,2)+
      pow(map2base_trans.transform.rotation.y,2)+pow(map2base_trans.transform.rotation.z,2) < pow(0.9,2)) 
      {map2base_trans.transform.rotation.w=1; map2base_trans.transform.rotation.x=0; map2base_trans.transform.rotation.y=0; map2base_trans.transform.rotation.z=0;}
    map2base_broadcaster.sendTransform(map2base_trans);
   
    pcl::PointCloud<PointT>::Ptr cloud(new pcl::PointCloud<PointT>());
    pcl::fromROSMsg(*cloud_msg, *cloud);
    if(baselinkFrame.empty()) {
      baselinkFrame = cloud_msg->header.frame_id;
    }
    
    // Push ego velocity to queue
    geometry_msgs::TwistStamped::Ptr twist_(new geometry_msgs::TwistStamped);
    twist_->header.stamp = cloud_msg->header.stamp;
    twist_->twist.linear = odom_msg->twist.twist.linear;
    {
      std::lock_guard<std::mutex> lock(keyframe_queue_mutex);
      twist_queue.push_back(twist_);
    }

    //********** Decided whether to accept the frame as a key frame or not **********
    if(!keyframe_updater->decide(odom_now, stamp)) {
      std::lock_guard<std::mutex> lock(keyframe_queue_mutex);
      if(keyframe_queue.empty()) {
        std_msgs::Header read_until;
        read_until.stamp = stamp + ros::Duration(10, 0);
        read_until.frame_id = points_topic;
        read_until_pub.publish(read_until);
        read_until.frame_id = "/filtered_points";
        read_until_pub.publish(read_until);
      }
      return;
    }
    // Get time of this key frame for Intergeration, to integerate between two key frames
    thisKeyframeTime = cloud_msg->header.stamp.toSec();
    
    double accum_d = keyframe_updater->get_accum_distance();
    // Construct keyframe
    KeyFrame::Ptr keyframe(new KeyFrame(keyframe_index, stamp, odom_now, accum_d, cloud));
    keyframe_index ++;

    if (enable_preintegration){
      // Intergerate translation of ego velocity, add rotation
      geometry_msgs::Transform transf_integ = preIntegrationTransform();
      static uint32_t sequ = 0;
      nav_msgs::Odometry odom_frame2frame;
      odom_frame2frame.pose.pose.orientation = transf_integ.rotation;
      odom_frame2frame.pose.pose.position.x = transf_integ.translation.x;
      odom_frame2frame.pose.pose.position.y = transf_integ.translation.y;
      odom_frame2frame.pose.pose.position.z = transf_integ.translation.z;
      odom_frame2frame.header.frame_id = "map";
      odom_frame2frame.header.stamp = cloud_msg->header.stamp;
      odom_frame2frame.header.seq = sequ; sequ ++;
      odom_frame2frame_pub.publish(odom_frame2frame);
      keyframe->trans_integrated = transf_integ;
    }

    std::lock_guard<std::mutex> lock(keyframe_queue_mutex);
    keyframe_queue.push_back(keyframe);

    // Scan Context loop detector - giseop
    // - SINGLE_SCAN_FULL: using downsampled original point cloud (/full_cloud_projected + downsampling)
    // - SINGLE_SCAN_FEAT: using surface feature as an input point cloud for scan context (2020.04.01: checked it works.)
    // - MULTI_SCAN_FEAT: using NearKeyframes (because a MulRan scan does not have beyond region, so to solve this issue ... )
    const SCInputType sc_input_type = SCInputType::SINGLE_SCAN_FULL; // change this 

    if( sc_input_type == SCInputType::SINGLE_SCAN_FULL ) {
        loop_detector->scManager->makeAndSaveScancontextAndKeys(*cloud);
    }
    // else if (sc_input_type == SCInputType::SINGLE_SCAN_FEAT) { 
    //     scManager.makeAndSaveScancontextAndKeys(*thisSurfKeyFrame); 
    // }
    // else if (sc_input_type == SCInputType::MULTI_SCAN_FEAT) { 
    //     pcl::PointCloud<PointT>::Ptr multiKeyFrameFeatureCloud(new pcl::PointCloud<PointT>());
    //     loopFindNearKeyframes(multiKeyFrameFeatureCloud, cloudKeyPoses6D->size() - 1, historyKeyframeSearchNum);
    //     scManager.makeAndSaveScancontextAndKeys(*multiKeyFrameFeatureCloud); 
    // }
    

    lastKeyframeTime = thisKeyframeTime;
  }


  void imu_callback(const sensor_msgs::ImuConstPtr& imu_odom_msg) {
    // Transform to Radar's Frame
    geometry_msgs::QuaternionStamped::Ptr imu_quat(new geometry_msgs::QuaternionStamped);
    imu_quat->quaternion = imu_odom_msg->orientation;
    Eigen::Quaterniond imu_quat_from(imu_quat->quaternion.w, imu_quat->quaternion.x, imu_quat->quaternion.y, imu_quat->quaternion.z);
    Eigen::Quaterniond imu_quat_deskew = imu_quat_from * extQRPY;
    imu_quat_deskew.normalize();

    static int cnt = 0;
    if(cnt == 0) {
      double roll, pitch, yaw;
      tf::Quaternion orientation = tf::Quaternion(imu_quat_deskew.x(),imu_quat_deskew.y(),imu_quat_deskew.z(),imu_quat_deskew.w());
      tf::quaternionMsgToTF(imu_odom_msg->orientation, orientation);
      tf::Matrix3x3(orientation).getRPY(roll, pitch, yaw);
      // Eigen::Matrix3d imu_mat_deskew = imu_quat_deskew.toRotationMatrix();
      // Eigen::Vector3d eulerAngle = imu_mat_deskew.eulerAngles(0,1,2); // roll pitch yaw
      Eigen::AngleAxisd rollAngle(AngleAxisd(roll,Vector3d::UnitX()));
      Eigen::AngleAxisd pitchAngle(AngleAxisd(pitch,Vector3d::UnitY()));
      Eigen::AngleAxisd yawAngle(AngleAxisd(0.0,Vector3d::UnitZ()));
      Eigen::Matrix3d imu_mat_final; imu_mat_final = yawAngle * pitchAngle * rollAngle;

      Eigen::Isometry3d isom_initial_pose;
      isom_initial_pose.setIdentity();
      isom_initial_pose.rotate(imu_mat_final); // Set rotation
      initial_pose = isom_initial_pose.matrix();
      ROS_INFO("Initial Position Matrix = ");
      std::cout << 
        initial_pose(0,0) << ", " << initial_pose(0,1) << ", " << initial_pose(0,2) << ", " << initial_pose(0,3) << ", " << std::endl <<
        initial_pose(1,0) << ", " << initial_pose(1,1) << ", " << initial_pose(1,2) << ", " << initial_pose(1,3) << ", " << std::endl <<
        initial_pose(2,0) << ", " << initial_pose(2,1) << ", " << initial_pose(2,2) << ", " << initial_pose(2,3) << ", " << std::endl <<
        initial_pose(3,0) << ", " << initial_pose(3,1) << ", " << initial_pose(3,2) << ", " << initial_pose(3,3) << ", " << std::endl << std::endl;
      cnt = 1;
    }
  }

  void imu_odom_callback(const nav_msgs::OdometryConstPtr& imu_odom_msg) {
    {
    std::lock_guard<std::mutex> lock(keyframe_queue_mutex);
    imu_odom_queue.push_back(imu_odom_msg);
    }
  }

  geometry_msgs::Transform preIntegrationTransform(){
    double lastImuOdomQT = -1;
    // double lastTwistQT = -1;
    double delta_t = 0;
    size_t imu_odom_end_index = 0; // The index of the last used IMU odom
    geometry_msgs::Transform trans_; // Transform to return
    // pop old IMU orientation message
    while (!imu_odom_queue.empty() && imu_odom_queue.front()->header.stamp.toSec() < lastKeyframeTime - delta_t){
        lastImuOdomQT = imu_odom_queue.front()->header.stamp.toSec();
        imu_odom_queue.pop_front();
    }
    // pop old Twist message
    while (!twist_queue.empty() && twist_queue.front()->header.stamp.toSec() < lastKeyframeTime - delta_t){
        // lastTwistQT = twist_queue.front()->header.stamp.toSec();
        twist_queue.pop_front();
    }
    // repropogate
    Eigen::Isometry3d isom_frame2frame;  // Translation increment between last key frame and this IMU msg
    Eigen::Isometry3d isometry_rotation; // Rotation of IMU odom
    Eigen::Isometry3d isometry_translation;  // Translation of IMU odom
    isom_frame2frame.setIdentity();
    isometry_rotation.setIdentity();
    geometry_msgs::Vector3 translation_frame2frame; // Translation between two key frames
    if (!imu_odom_queue.empty())
    {
      // (Doing this because some imu_odom later than thisKeyframeTime will be recieved)
      for (size_t i = 0; i < imu_odom_queue.size(); ++i){
        if (imu_odom_queue.at(i)->header.stamp.toSec() < thisKeyframeTime)
          imu_odom_end_index = i;
      }
      std::unique_ptr<CubicInterpolation> egovelIntegratorX;
      std::unique_ptr<CubicInterpolation> egovelIntegratorY;
      std::unique_ptr<CubicInterpolation> egovelIntegratorZ;
      if (use_egovel_preinteg_trans) {
        // integrate imu message from the beginning of this optimization
        size_t twist_length = twist_queue.size();
        Eigen::MatrixXd q_via_x(twist_length,3),q_via_y(twist_length,3),q_via_z(twist_length,3);
        Eigen::VectorXd t_via_x(twist_length),t_via_y(twist_length),t_via_z(twist_length);
        // double dt = 1.0/12;
        for (size_t i=0; i < twist_length; i++){
          q_via_x(i, 0) = twist_queue.at(i)->twist.linear.x;  q_via_x(i, 1) = 0;  q_via_x(i, 2) = 0;
          // acc: q(i,1)=(twist_queue.at(i+1).twist.linear.x - twist_queue.at(i).twist.linear.x) / dt;
          t_via_x(i) = twist_queue.at(i)->header.stamp.toSec();
          q_via_y(i, 0) = twist_queue.at(i)->twist.linear.y;  q_via_y(i, 1) = 0;  q_via_y(i, 2) = 0;
          t_via_y(i) = t_via_x(i);
          q_via_z(i, 0) = twist_queue.at(i)->twist.linear.z;  q_via_z(i, 1) = 0;  q_via_z(i, 2) = 0;
          t_via_z(i) = t_via_x(i);
        }
        egovelIntegratorX.reset(new CubicInterpolation(q_via_x, t_via_x)); // Integrator of ego velocity at X axis
        egovelIntegratorY.reset(new CubicInterpolation(q_via_y, t_via_y)); // Integrator of ego velocity at Y axis
        egovelIntegratorZ.reset(new CubicInterpolation(q_via_z, t_via_z)); // Integrator of ego velocity at Z axis
        // ROS_INFO("Twist queue - Start time: %f Stop time: %f", t_via_x(0), t_via_x(t_via_x.size()-1));
      }
      Eigen::Isometry3d isom_imu_odom_last(Eigen::Isometry3d::Identity());
      Eigen::Quaterniond q_imu_odom(imu_odom_queue.front()->pose.pose.orientation.w,
                                imu_odom_queue.front()->pose.pose.orientation.x,
                                imu_odom_queue.front()->pose.pose.orientation.y,
                                imu_odom_queue.front()->pose.pose.orientation.z);
      isom_imu_odom_last.rotate(q_imu_odom);
      isom_imu_odom_last.pretranslate(Eigen::Vector3d(imu_odom_queue.front()->pose.pose.position.x,
                                                  imu_odom_queue.front()->pose.pose.position.y,
                                                  imu_odom_queue.front()->pose.pose.position.z));
      Eigen::Isometry3d isom_imu_odom_this(Eigen::Isometry3d::Identity());
      q_imu_odom = Eigen::Quaterniond(imu_odom_queue.at(imu_odom_end_index)->pose.pose.orientation.w,
                                imu_odom_queue.at(imu_odom_end_index)->pose.pose.orientation.x,
                                imu_odom_queue.at(imu_odom_end_index)->pose.pose.orientation.y,
                                imu_odom_queue.at(imu_odom_end_index)->pose.pose.orientation.z);
      isom_imu_odom_this.rotate(q_imu_odom);
      isom_imu_odom_this.pretranslate(Eigen::Vector3d(imu_odom_queue.at(imu_odom_end_index)->pose.pose.position.x,
                                                  imu_odom_queue.at(imu_odom_end_index)->pose.pose.position.y,
                                                  imu_odom_queue.at(imu_odom_end_index)->pose.pose.position.z));
      Eigen::Isometry3d isom_imu_odom_btn = isom_imu_odom_last.inverse() * isom_imu_odom_this;
      // cout << isom_imu_odom_btn.matrix() << endl;
      // ROS_INFO("IMU Odom queue - Start time: %f Stop time: %f", imu_odom_queue.at(0)->header.stamp.toSec(), imu_odom_queue.at(imu_odom_end_index)->header.stamp.toSec());
      if (use_egovel_preinteg_trans){ // Use Ego vel as translation integration
        for (size_t i = 0; i < imu_odom_end_index + 1; i++)
        {
            nav_msgs::Odometry::ConstPtr thisImu = imu_odom_queue.at(i);
            double imuOdomTime = thisImu->header.stamp.toSec();
            isometry_translation.setIdentity();
            isometry_rotation.setIdentity();
            
            double dt = (lastImuOdomQT < 0) ? (1.0 / 200.0) :(imuOdomTime - lastImuOdomQT);
            Eigen::Vector3d translation_ = Eigen::Vector3d( egovelIntegratorX->getPosition(imuOdomTime),
                                                            egovelIntegratorY->getPosition(imuOdomTime),
                                                            egovelIntegratorZ->getPosition(imuOdomTime))* dt;
            isometry_translation.pretranslate(translation_); // Set translation
            isom_frame2frame = isom_frame2frame.pretranslate(isometry_translation.translation());

            lastImuOdomQT = imuOdomTime;
        }
      }
      else {  // Use IMU as translation integration
        isom_frame2frame = isom_imu_odom_btn;
      }
      translation_frame2frame.x = isom_frame2frame.translation().x();
      translation_frame2frame.y = isom_frame2frame.translation().y();
      translation_frame2frame.z = isom_frame2frame.translation().z();
      const auto& last_imu_orien = imu_odom_queue.at(imu_odom_end_index);
      trans_.rotation = last_imu_orien->pose.pose.orientation;
      trans_.translation = translation_frame2frame;
    }
    return trans_;
  }


  void barometer_callback(const barometer_bmp388::BarometerPtr& baro_msg) {
    if(!enable_barometer) {
      return;
    }
    std::lock_guard<std::mutex> lock(barometer_queue_mutex);
    barometer_queue.push_back(baro_msg);
  }

  bool flush_barometer_queue() {
    std::lock_guard<std::mutex> lock(barometer_queue_mutex);
    if(keyframes.empty() || barometer_queue.empty()) {
      return false;
    }
    bool updated = false;
    auto barometer_cursor = barometer_queue.begin();

    for(size_t i=0; i < keyframes.size(); i++) {
      auto keyframe = keyframes.at(i);
      if(keyframe->stamp > barometer_queue.back()->header.stamp) {
        break;
      }
      if(keyframe->stamp < (*barometer_cursor)->header.stamp || keyframe->altitude) {
        continue;
      }
      // find the barometer data which is closest to the keyframe_
      auto closest_barometer = barometer_cursor;
      for(auto baro = barometer_cursor; baro != barometer_queue.end(); baro++) {
        auto dt = ((*closest_barometer)->header.stamp - keyframe->stamp).toSec();
        auto dt2 = ((*baro)->header.stamp - keyframe->stamp).toSec();
        if(std::abs(dt) < std::abs(dt2)) {
          break;
        }
        closest_barometer = baro;
      }
      // if the time residual between the barometer and keyframe_ is too large, skip it
      barometer_cursor = closest_barometer;
      if(0.2 < std::abs(((*closest_barometer)->header.stamp - keyframe->stamp).toSec())) {
        continue;
      }

      Eigen::Vector4d aftmapped_pos(keyframe->odom_scan2scan.translation().x(), keyframe->odom_scan2scan.translation().y(), (*closest_barometer)->altitude, 1.0);
      aftmapped_pos = initial_pose * aftmapped_pos;
      // std::cout << "baro position: " << aftmapped_pos(0) << ", " << aftmapped_pos(1) << ", " << aftmapped_pos(2) << std::endl;
      
      nav_msgs::Odometry initial_odom; // Initial posture
      initial_odom = matrix2odom(keyframe->stamp, initial_pose, mapFrame, baselinkFrame);

      Eigen::Vector1d z(aftmapped_pos(2));
      // the first barometer data position will be the origin of the map
      if(!zero_alt) {
        zero_alt = z;
      }
      z -= (*zero_alt);
      keyframe->altitude = z;

      if (enable_barometer){ 
        //********** G2O Edge *********** 
        if (barometer_edge_type == 1){
          g2o::OptimizableGraph::Edge* edge;
          Eigen::Vector1d information_matrix = Eigen::Vector1d::Identity() / barometer_edge_stddev;
          edge = graph_slam->add_se3_prior_z_edge(keyframe->node, z, information_matrix);
          graph_slam->add_robust_kernel(edge, private_nh.param<std::string>("barometer_edge_robust_kernel", "NONE"), private_nh.param<double>("barometer_edge_robust_kernel_size", 1.0));
        }
        else if (barometer_edge_type == 2 && i != 0 && keyframes.at(i-1)->altitude.is_initialized()){
          g2o::OptimizableGraph::Edge* edge;
          Eigen::Vector1d information_matrix = Eigen::Vector1d::Identity() / barometer_edge_stddev;
          Eigen::Vector1d relative_z(keyframe->altitude.value() - keyframes.at(i-1)->altitude.value());
          edge = graph_slam->add_se3_z_edge(keyframe->node, keyframes.at(i-1)->node, relative_z, information_matrix);
          graph_slam->add_robust_kernel(edge, private_nh.param<std::string>("barometer_edge_robust_kernel", "NONE"), private_nh.param<double>("barometer_edge_robust_kernel_size", 1.0));
        }
      }
      updated = true;
    }
    auto remove_loc = std::upper_bound(barometer_queue.begin(), barometer_queue.end(), keyframes.back()->stamp, [=](const ros::Time& stamp, const barometer_bmp388::BarometerConstPtr& baropoint) { return stamp < baropoint->header.stamp; });
    barometer_queue.erase(barometer_queue.begin(), remove_loc);
    return updated;
  }

  /**
   * @brief this method adds all the keyframes_ in #keyframe_queue to the pose graph (odometry edges)
   * @return if true, at least one keyframe_ was added to the pose graph
   */
  bool flush_keyframe_queue() {
    std::lock_guard<std::mutex> lock(keyframe_queue_mutex);

    if(keyframe_queue.empty()) {
      return false;
    }

    trans_odom2map_mutex.lock();
    Eigen::Isometry3d odom2map(trans_odom2map.cast<double>());
    trans_odom2map_mutex.unlock();

    int num_processed = 0;
    // ********** Select number of keyframess to be optimized **********
    for(int i = 0; i < std::min<int>(keyframe_queue.size(), max_keyframes_per_update); i++) {
      num_processed = i;

      const auto& keyframe = keyframe_queue[i];
      // new_keyframess will be tested later for loop closure
      new_keyframes.push_back(keyframe);

      // add pose node
      Eigen::Isometry3d odom = odom2map * keyframe->odom_scan2scan;
      // ********** Vertex of keyframess is contructed here ***********
      keyframe->node = graph_slam->add_se3_node(odom);
      keyframe_hash[keyframe->stamp] = keyframe;

      // fix the first node
      if(keyframes.empty() && new_keyframes.size() == 1) {
        if(private_nh.param<bool>("fix_first_node", false)) {
          Eigen::MatrixXd inf = Eigen::MatrixXd::Identity(6, 6);
          std::stringstream sst(private_nh.param<std::string>("fix_first_node_stddev", "1 1 1 1 1 1"));
          for(int i = 0; i < 6; i++) {
            double stddev = 1.0;
            sst >> stddev;
            inf(i, i) = 1.0 / stddev;
          }
          anchor_node = graph_slam->add_se3_node(Eigen::Isometry3d::Identity());
          anchor_node->setFixed(true);
          anchor_edge = graph_slam->add_se3_edge(anchor_node, keyframe->node, Eigen::Isometry3d::Identity(), inf);
        }
      }
      
      if(i == 0 && keyframes.empty()) {
        continue;
      }

      /***** Scan-to-Scan Add edge to between consecutive keyframes *****/
      const auto& prev_keyframe = i == 0 ? keyframes.back() : keyframe_queue[i - 1];
      // relative pose between odom of previous frame and this frame R2=R12*R1 => R12 = inv(R2) * R1
      Eigen::Isometry3d relative_pose = keyframe->odom_scan2scan.inverse() * prev_keyframe->odom_scan2scan;
      // calculate fitness score as information 
      Eigen::MatrixXd information = inf_calclator->calc_information_matrix(keyframe->cloud, prev_keyframe->cloud, relative_pose);
      auto edge = graph_slam->add_se3_edge(keyframe->node, prev_keyframe->node, relative_pose, information);
      // cout << information << endl;
      graph_slam->add_robust_kernel(edge, private_nh.param<std::string>("odometry_edge_robust_kernel", "NONE"), private_nh.param<double>("odometry_edge_robust_kernel_size", 1.0));
      

      if (enable_preintegration){
        // Add Preintegration edge
        geometry_msgs::Transform relative_trans = keyframe->trans_integrated;
        g2o::SE3Quat relative_se3quat ( Eigen::Quaterniond(relative_trans.rotation.w, relative_trans.rotation.x, relative_trans.rotation.y, relative_trans.rotation.z), 
                                        Eigen::Vector3d(relative_trans.translation.x, relative_trans.translation.y, relative_trans.translation.z));
        Eigen::Isometry3d relative_isometry = transform2isometry(relative_trans);
        Eigen::MatrixXd information_integ = Eigen::MatrixXd::Identity(6, 6);
        information_integ <<  1.0 / preinteg_trans_stddev, 0, 0, 0, 0, 0,
                              0, 1.0 / preinteg_trans_stddev, 0, 0, 0, 0,
                              0, 0, 1.0 / preinteg_trans_stddev, 0, 0, 0,
                              0, 0, 0, 1.0 / preinteg_orient_stddev, 0, 0,
                              0, 0, 0, 0, 1.0 / preinteg_orient_stddev, 0,
                              0, 0, 0, 0, 0, 1.0 / preinteg_orient_stddev; 
        auto edge_integ = graph_slam->add_se3_edge(prev_keyframe->node, keyframe->node, relative_isometry, information_integ);
        graph_slam->add_robust_kernel(edge_integ, private_nh.param<std::string>("integ_edge_robust_kernel", "NONE"), private_nh.param<double>("integ_edge_robust_kernel_size", 1.0));
      }
    }

    std_msgs::Header read_until;
    read_until.stamp = keyframe_queue[num_processed]->stamp + ros::Duration(10, 0);
    read_until.frame_id = points_topic;
    read_until_pub.publish(read_until);
    read_until.frame_id = "/filtered_points";
    read_until_pub.publish(read_until);

    keyframe_queue.erase(keyframe_queue.begin(), keyframe_queue.begin() + num_processed + 1);
    return true;
  }


  /**
   * @brief Back-end Optimization. This methods adds all the data in the queues to the pose graph, and then optimizes the pose graph
   * @param event
   */
  void optimization_timer_callback(const ros::WallTimerEvent& event) {
    std::lock_guard<std::mutex> lock(main_thread_mutex);

    // add keyframes_ and floor coeffs in the queues to the pose graph
    bool keyframe_updated = flush_keyframe_queue();

    if(!keyframe_updated) {
      std_msgs::Header read_until;
      read_until.stamp = ros::Time::now() + ros::Duration(30, 0);
      read_until.frame_id = points_topic;
      read_until_pub.publish(read_until);
      read_until.frame_id = "/filtered_points";
      read_until_pub.publish(read_until);
    }

    if(!keyframe_updated & !flush_gps_queue() & !flush_barometer_queue()) {
      return;
    }
    
    // loop detection
    if(private_nh.param<bool>("enable_loop_closure", false)){
      std::vector<Loop::Ptr> loops = loop_detector->detect(keyframes, new_keyframes, *graph_slam);
    }

    // Copy "new_keyframes_" to vector  "keyframes_", "new_keyframes_" was used for loop detaction 
    std::copy(new_keyframes.begin(), new_keyframes.end(), std::back_inserter(keyframes));
    new_keyframes.clear();

    if(private_nh.param<bool>("enable_loop_closure", false))
      addLoopFactor();

    // move the first node / position to the current estimate of the first node pose
    // so the first node moves freely while trying to stay around the origin
    if(anchor_node && private_nh.param<bool>("fix_first_node_adaptive", true)) {
      Eigen::Isometry3d anchor_target = static_cast<g2o::VertexSE3*>(anchor_edge->vertices()[1])->estimate();
      anchor_node->setEstimate(anchor_target);
    }

    // optimize the pose graph
    int num_iterations = private_nh.param<int>("g2o_solver_num_iterations", 1024);
    clock_t start_ms = clock();
    graph_slam->optimize(num_iterations);
    clock_t end_ms = clock();
    double time_used = double(end_ms - start_ms) / CLOCKS_PER_SEC;
    opt_time.push_back(time_used);

    //********** publish tf **********
    const auto& keyframe = keyframes.back();
    // RadarOdom_to_base = map_to_base * map_to_RadarOdom^(-1)
    Eigen::Isometry3d trans = keyframe->node->estimate() * keyframe->odom_scan2scan.inverse();
    Eigen::Isometry3d map2base_trans = keyframe->node->estimate();
    trans_odom2map_mutex.lock();
    trans_odom2map = trans.matrix();
    // map2base_incremental = map2base_last^(-1) * map2base_this 
    trans_aftmapped_incremental = trans_aftmapped.inverse() * map2base_trans;
    trans_aftmapped = map2base_trans;
    trans_odom2map_mutex.unlock();

    std::vector<KeyFrameSnapshot::Ptr> snapshot(keyframes.size());
    std::transform(keyframes.begin(), keyframes.end(), snapshot.begin(), [=](const KeyFrame::Ptr& k) { return std::make_shared<KeyFrameSnapshot>(k); });

    keyframes_snapshot_mutex.lock();
    keyframes_snapshot.swap(snapshot);
    keyframes_snapshot_mutex.unlock();
    graph_updated = true;

    // Publish After-Mapped Odometry
    nav_msgs::Odometry aft = isometry2odom(keyframe->stamp, trans_aftmapped, mapFrame, odometryFrame);
    aftmapped_odom_pub.publish(aft);

    // Publish After-Mapped Odometry Incrementation
    nav_msgs::Odometry aft_incre = isometry2odom(keyframe->stamp, trans_aftmapped_incremental, mapFrame, odometryFrame);
    aftmapped_odom_incremenral_pub.publish(aft_incre);

    // Publish /odom to /base_link
    if(odom2base_pub.getNumSubscribers()) {  // Returns the number of subscribers that are currently connected to this Publisher
      geometry_msgs::TransformStamped ts = matrix2transform(keyframe->stamp, trans.matrix(), mapFrame, odometryFrame);
      odom2base_pub.publish(ts);
    }

    if(markers_pub.getNumSubscribers()) {
      auto markers = create_marker_array(ros::Time::now());
      markers_pub.publish(markers);
    }
  }

  void addLoopFactor()
  {
    if (loop_detector->loopIndexQueue.empty())
      return;
    for (int i = 0; i < (int)loop_detector->loopIndexQueue.size(); ++i){
      int indexFrom = loop_detector->loopIndexQueue[i].first;
      int indexTo = loop_detector->loopIndexQueue[i].second;
      Eigen::Isometry3d poseBetween = loop_detector->loopPoseQueue[i];
      Eigen::MatrixXd information_matrix = loop_detector->loopInfoQueue[i];
      auto edge = graph_slam->add_se3_edge(keyframes[indexFrom]->node, keyframes[indexTo]->node, poseBetween, information_matrix);
      graph_slam->add_robust_kernel(edge, private_nh.param<std::string>("loop_closure_edge_robust_kernel", "NONE"), private_nh.param<double>("loop_closure_edge_robust_kernel_size", 1.0));
    }
    // loopIndexQueue.clear();
    // loopPoseQueue.clear();
    // loopInfoQueue.clear();
    // aLoopIsClosed = true;
  }

  /**
   * @brief generate map point cloud and publish it
   * @param event
   */
  void map_points_publish_timer_callback(const ros::WallTimerEvent& event) {
    if(!map_points_pub.getNumSubscribers() || !graph_updated) {
      return;
    }
    std::vector<KeyFrameSnapshot::Ptr> snapshot;
    keyframes_snapshot_mutex.lock();
    snapshot = keyframes_snapshot;
    keyframes_snapshot_mutex.unlock();

    auto cloud = map_cloud_generator->generate(snapshot, map_cloud_resolution);
    if(!cloud) {
      return;
    }
    cloud->header.frame_id = mapFrame;
    cloud->header.stamp = snapshot.back()->cloud->header.stamp;

    sensor_msgs::PointCloud2Ptr cloud_msg(new sensor_msgs::PointCloud2());
    pcl::toROSMsg(*cloud, *cloud_msg);

    map_points_pub.publish(cloud_msg);
  }

  /**
   * @brief create visualization marker
   * @param stamp
   * @return
   */
  visualization_msgs::MarkerArray create_marker_array(const ros::Time& stamp) const {
    visualization_msgs::MarkerArray markers;
    if (show_sphere)
      markers.markers.resize(5);
    else
      markers.markers.resize(4);

    // loop edges
    visualization_msgs::Marker& loop_marker = markers.markers[0];
    loop_marker.header.frame_id = "map";
    loop_marker.header.stamp = stamp;
    loop_marker.action = visualization_msgs::Marker::ADD;
    loop_marker.type = visualization_msgs::Marker::LINE_LIST;
    loop_marker.ns = "loop_edges";
    loop_marker.id = 1;
    loop_marker.pose.orientation.w = 1;
    loop_marker.scale.x = 0.1; loop_marker.scale.y = 0.1; loop_marker.scale.z = 0.1;
    loop_marker.color.r = 0.9; loop_marker.color.g = 0.9; loop_marker.color.b = 0;
    loop_marker.color.a = 1;
    for (auto it = loop_detector->loopIndexContainer.begin(); it != loop_detector->loopIndexContainer.end(); ++it)
    {
      int key_cur = it->first;
      int key_pre = it->second;
      geometry_msgs::Point p;
      Eigen::Vector3d pos = keyframes[key_cur]->node->estimate().translation();
      p.x = pos.x();
      p.y = pos.y();
      p.z = pos.z();
      loop_marker.points.push_back(p);
      pos = keyframes[key_pre]->node->estimate().translation();
      p.x = pos.x();
      p.y = pos.y();
      p.z = pos.z();
      loop_marker.points.push_back(p);
    }

    // node markers
    visualization_msgs::Marker& traj_marker = markers.markers[1];
    traj_marker.header.frame_id = "map";
    traj_marker.header.stamp = stamp;
    traj_marker.ns = "nodes";
    traj_marker.id = 0;
    traj_marker.type = visualization_msgs::Marker::SPHERE_LIST;

    traj_marker.pose.orientation.w = 1.0;
    traj_marker.scale.x = traj_marker.scale.y = traj_marker.scale.z = 0.3;

    visualization_msgs::Marker& imu_marker = markers.markers[2];
    imu_marker.header = traj_marker.header;
    imu_marker.ns = "imu";
    imu_marker.id = 1;
    imu_marker.type = visualization_msgs::Marker::SPHERE_LIST;

    imu_marker.pose.orientation.w = 1.0;
    imu_marker.scale.x = imu_marker.scale.y = imu_marker.scale.z = 0.75;

    traj_marker.points.resize(keyframes.size());
    traj_marker.colors.resize(keyframes.size());
    for(size_t i = 0; i < keyframes.size(); i++) {
      Eigen::Vector3d pos = keyframes[i]->node->estimate().translation();
      traj_marker.points[i].x = pos.x();
      traj_marker.points[i].y = pos.y();
      traj_marker.points[i].z = pos.z();

      double p = static_cast<double>(i) / keyframes.size();
      traj_marker.colors[i].r = 0.0;//1.0 - p;
      traj_marker.colors[i].g = 1.0;//p;
      traj_marker.colors[i].b = 0.0;
      traj_marker.colors[i].a = 1.0;

      if(keyframes[i]->acceleration) {
        Eigen::Vector3d pos = keyframes[i]->node->estimate().translation();
        geometry_msgs::Point point;
        point.x = pos.x();
        point.y = pos.y();
        point.z = pos.z();

        std_msgs::ColorRGBA color;
        color.r = 0.0;
        color.g = 0.0;
        color.b = 1.0;
        color.a = 0.1;

        imu_marker.points.push_back(point);
        imu_marker.colors.push_back(color);
      }
    }

    // edge markers
    visualization_msgs::Marker& edge_marker = markers.markers[3];
    edge_marker.header.frame_id = "map";
    edge_marker.header.stamp = stamp;
    edge_marker.ns = "edges";
    edge_marker.id = 2;
    edge_marker.type = visualization_msgs::Marker::LINE_LIST;

    edge_marker.pose.orientation.w = 1.0;
    edge_marker.scale.x = 0.05;

    edge_marker.points.resize(graph_slam->graph->edges().size() * 2);
    edge_marker.colors.resize(graph_slam->graph->edges().size() * 2);

    auto edge_itr = graph_slam->graph->edges().begin();
    for(int i = 0; edge_itr != graph_slam->graph->edges().end(); edge_itr++, i++) {
      g2o::HyperGraph::Edge* edge = *edge_itr;
      g2o::EdgeSE3* edge_se3 = dynamic_cast<g2o::EdgeSE3*>(edge);
      if(edge_se3) {
        g2o::VertexSE3* v1 = dynamic_cast<g2o::VertexSE3*>(edge_se3->vertices()[0]);
        g2o::VertexSE3* v2 = dynamic_cast<g2o::VertexSE3*>(edge_se3->vertices()[1]);
        
        Eigen::Vector3d pt1 = v1->estimate().translation();
        Eigen::Vector3d pt2 = v2->estimate().translation();

        edge_marker.points[i * 2].x = pt1.x();
        edge_marker.points[i * 2].y = pt1.y();
        edge_marker.points[i * 2].z = pt1.z();
        edge_marker.points[i * 2 + 1].x = pt2.x();
        edge_marker.points[i * 2 + 1].y = pt2.y();
        edge_marker.points[i * 2 + 1].z = pt2.z();

        double p1 = static_cast<double>(v1->id()) / graph_slam->graph->vertices().size();
        double p2 = static_cast<double>(v2->id()) / graph_slam->graph->vertices().size();
        edge_marker.colors[i * 2].r = 0.0;//1.0 - p1;
        edge_marker.colors[i * 2].g = 1.0;//p1;
        edge_marker.colors[i * 2].a = 1.0;
        edge_marker.colors[i * 2 + 1].r = 0.0;//1.0 - p2;
        edge_marker.colors[i * 2 + 1].g = 1.0;//p2;
        edge_marker.colors[i * 2 + 1].a = 1.0;

        if(std::abs(v1->id() - v2->id()) > 2) {
          // edge_marker.points[i * 2].z += 0.5;
          // edge_marker.points[i * 2 + 1].z += 0.5;
          edge_marker.colors[i * 2].r = 0.9;
          edge_marker.colors[i * 2].g = 0.9;
          edge_marker.colors[i * 2].b = 0.0;
          edge_marker.colors[i * 2 + 1].r = 0.9;
          edge_marker.colors[i * 2 + 1].g = 0.9;
          edge_marker.colors[i * 2 + 1].b = 0.0;
          edge_marker.colors[i * 2].a = 0.0;
          edge_marker.colors[i * 2 + 1].a += 0.0;
        }
        continue;
      }

      g2o::EdgeSE3Plane* edge_plane = dynamic_cast<g2o::EdgeSE3Plane*>(edge);
      if(edge_plane) {
        g2o::VertexSE3* v1 = dynamic_cast<g2o::VertexSE3*>(edge_plane->vertices()[0]);
        Eigen::Vector3d pt1 = v1->estimate().translation();
        Eigen::Vector3d pt2(pt1.x(), pt1.y(), 0.0);

        edge_marker.points[i * 2].x = pt1.x();
        edge_marker.points[i * 2].y = pt1.y();
        edge_marker.points[i * 2].z = pt1.z();
        edge_marker.points[i * 2 + 1].x = pt2.x();
        edge_marker.points[i * 2 + 1].y = pt2.y();
        edge_marker.points[i * 2 + 1].z = pt2.z();

        edge_marker.colors[i * 2].b = 1.0;
        edge_marker.colors[i * 2].a = 1.0;
        edge_marker.colors[i * 2 + 1].b = 1.0;
        edge_marker.colors[i * 2 + 1].a = 1.0;

        continue;
      }

      g2o::EdgeSE3PriorXY* edge_priori_xy = dynamic_cast<g2o::EdgeSE3PriorXY*>(edge);
      if(edge_priori_xy) {
        g2o::VertexSE3* v1 = dynamic_cast<g2o::VertexSE3*>(edge_priori_xy->vertices()[0]);
        Eigen::Vector3d pt1 = v1->estimate().translation();
        Eigen::Vector3d pt2 = Eigen::Vector3d::Zero();
        pt2.head<2>() = edge_priori_xy->measurement();

        edge_marker.points[i * 2].x = pt1.x();
        edge_marker.points[i * 2].y = pt1.y();
        edge_marker.points[i * 2].z = pt1.z() + 0.5;
        edge_marker.points[i * 2 + 1].x = pt2.x();
        edge_marker.points[i * 2 + 1].y = pt2.y();
        edge_marker.points[i * 2 + 1].z = pt2.z() + 0.5;

        edge_marker.colors[i * 2].r = 1.0;
        edge_marker.colors[i * 2].a = 1.0;
        edge_marker.colors[i * 2 + 1].r = 1.0;
        edge_marker.colors[i * 2 + 1].a = 1.0;

        continue;
      }

      g2o::EdgeSE3PriorXYZ* edge_priori_xyz = dynamic_cast<g2o::EdgeSE3PriorXYZ*>(edge);
      if(edge_priori_xyz) {
        g2o::VertexSE3* v1 = dynamic_cast<g2o::VertexSE3*>(edge_priori_xyz->vertices()[0]);
        Eigen::Vector3d pt1 = v1->estimate().translation();
        Eigen::Vector3d pt2 = edge_priori_xyz->measurement();

        edge_marker.points[i * 2].x = pt1.x();
        edge_marker.points[i * 2].y = pt1.y();
        edge_marker.points[i * 2].z = pt1.z() + 0.5;
        edge_marker.points[i * 2 + 1].x = pt2.x();
        edge_marker.points[i * 2 + 1].y = pt2.y();
        edge_marker.points[i * 2 + 1].z = pt2.z();

        edge_marker.colors[i * 2].r = 1.0;
        edge_marker.colors[i * 2].a = 1.0;
        edge_marker.colors[i * 2 + 1].r = 1.0;
        edge_marker.colors[i * 2 + 1].a = 1.0;

        continue;
      }
    }

    if (show_sphere)
    {
      // sphere
      visualization_msgs::Marker& sphere_marker = markers.markers[4];
      sphere_marker.header.frame_id = "map";
      sphere_marker.header.stamp = stamp;
      sphere_marker.ns = "loop_close_radius";
      sphere_marker.id = 3;
      sphere_marker.type = visualization_msgs::Marker::SPHERE;

      if(!keyframes.empty()) {
        Eigen::Vector3d pos = keyframes.back()->node->estimate().translation();
        sphere_marker.pose.position.x = pos.x();
        sphere_marker.pose.position.y = pos.y();
        sphere_marker.pose.position.z = pos.z();
      }
      sphere_marker.pose.orientation.w = 1.0;
      sphere_marker.scale.x = sphere_marker.scale.y = sphere_marker.scale.z = loop_detector->get_distance_thresh() * 2.0;

      sphere_marker.color.r = 1.0;
      sphere_marker.color.a = 0.3;
    }

    return markers;
  }

  /**
   * @brief dump all data to the current directory
   * @param req
   * @param res
   * @return
   */
  bool dump_service(radar_graph_slam::DumpGraphRequest& req, radar_graph_slam::DumpGraphResponse& res) {
    std::lock_guard<std::mutex> lock(main_thread_mutex);

    std::string directory = req.destination;

    if(directory.empty()) {
      std::array<char, 64> buffer;
      buffer.fill(0);
      time_t rawtime;
      time(&rawtime);
      const auto timeinfo = localtime(&rawtime);
      strftime(buffer.data(), sizeof(buffer), "%d-%m-%Y %H:%M:%S", timeinfo);
    }

    if(!boost::filesystem::is_directory(directory)) {
      boost::filesystem::create_directory(directory);
    }

    std::cout << "all data dumped to:" << directory << std::endl;

    graph_slam->save(directory + "/graph.g2o");
    for(size_t i = 0; i < keyframes.size(); i++) {
      std::stringstream sst;
      sst << boost::format("%s/%06d") % directory % i;

      keyframes[i]->save(sst.str());
    }

    if(zero_utm) {
      std::ofstream zero_utm_ofs(directory + "/zero_utm");
      zero_utm_ofs << boost::format("%.6f %.6f %.6f") % zero_utm->x() % zero_utm->y() % zero_utm->z() << std::endl;
    }

    std::ofstream ofs(directory + "/special_nodes.csv");
    ofs << "anchor_node " << (anchor_node == nullptr ? -1 : anchor_node->id()) << std::endl;
    ofs << "anchor_edge " << (anchor_edge == nullptr ? -1 : anchor_edge->id()) << std::endl;
    ofs << "floor_node " << (floor_plane_node == nullptr ? -1 : floor_plane_node->id()) << std::endl;

    res.success = true;
    return true;
  }

  /**
   * @brief save map data as pcd
   * @param req
   * @param res
   * @return
   */
  bool save_map_service(radar_graph_slam::SaveMapRequest& req, radar_graph_slam::SaveMapResponse& res) {
    std::vector<KeyFrameSnapshot::Ptr> snapshot;

    keyframes_snapshot_mutex.lock();
    snapshot = keyframes_snapshot;
    keyframes_snapshot_mutex.unlock();

    auto cloud = map_cloud_generator->generate(snapshot, req.resolution);
    if(!cloud) {
      res.success = false;
      return true;
    }

    if(zero_utm && req.utm) {
      for(auto& pt : cloud->points) {
        pt.getVector3fMap() += (*zero_utm).cast<float>();
      }
    }

    cloud->header.frame_id = mapFrame;
    cloud->header.stamp = snapshot.back()->cloud->header.stamp;

    if(zero_utm) {
      std::ofstream ofs(req.destination + ".utm");
      ofs << boost::format("%.6f %.6f %.6f") % zero_utm->x() % zero_utm->y() % zero_utm->z() << std::endl;
    }

    int ret = pcl::io::savePCDFileBinary(req.destination, *cloud);
    res.success = ret == 0;

    return true;
  }

  void nmea_callback(const nmea_msgs::SentenceConstPtr& nmea_msg) {
    GPRMC grmc = nmea_parser->parse(nmea_msg->sentence);
    if(grmc.status != 'A')
      return;
    geographic_msgs::GeoPointStampedPtr gps_msg(new geographic_msgs::GeoPointStamped());
    gps_msg->header = nmea_msg->header;
    gps_msg->position.latitude = grmc.latitude;
    gps_msg->position.longitude = grmc.longitude;
    gps_msg->position.altitude = NAN;
    gps_callback(gps_msg);
  }

  void navsat_callback(const sensor_msgs::NavSatFixConstPtr& navsat_msg) {
    sensor_msgs::NavSatFix gps_msg;
    gps_msg.header = navsat_msg->header;
    gps_msg.latitude = navsat_msg->latitude;
    gps_msg.longitude = navsat_msg->longitude;
    gps_msg.altitude = navsat_msg->altitude;
    gps_msg.position_covariance = navsat_msg->position_covariance;
    gps_msg.position_covariance_type = navsat_msg->position_covariance_type;
    gps_msg.status = navsat_msg->status;
    gps_navsat_queue.push_back(gps_msg);
  }

  /**
   * @brief received gps data is added to #gps_queue_
   * @param gps_msg
   */
  void gps_callback(const geographic_msgs::GeoPointStampedPtr& gps_msg) {
    std::lock_guard<std::mutex> lock(gps_queue_mutex);
    gps_msg->header.stamp += ros::Duration(gps_time_offset);
    gps_geopoint_queue.push_back(gps_msg);
  }

  /**
   * @brief
   * @return
   */
  bool flush_gps_queue() {
    std::lock_guard<std::mutex> lock(gps_queue_mutex);

    if(keyframes.empty() || gps_navsat_queue.empty()) {
      return false;
    }
    
    bool updated = false;
    auto gps_cursor = gps_navsat_queue.begin();

    for(auto& keyframe : keyframes) {
      if (keyframe->index - last_gps_edge_index < gps_edge_intervals) continue;
      if (keyframe->stamp > gps_navsat_queue.back().header.stamp) {
        break;
      }
      if (keyframe->stamp < (*gps_cursor).header.stamp || keyframe->utm_coord) {
        continue;
      }
      // find the gps data which is closest to the keyframe_
      auto closest_gps = gps_cursor;
      for(auto gps = gps_cursor; gps != gps_navsat_queue.end(); gps++) {
        auto dt = ((*closest_gps).header.stamp - keyframe->stamp).toSec();
        auto dt2 = ((*gps).header.stamp - keyframe->stamp).toSec();
        if(std::abs(dt) < std::abs(dt2)) {
          break;
        }
        closest_gps = gps;
      }
      // if the time residual between the gps and keyframe_ is too large, skip it
      gps_cursor = closest_gps;
      if(0.2 < std::abs(((*closest_gps).header.stamp - keyframe->stamp).toSec())) {
        continue;
      }

      // convert (latitude, longitude, altitude) -> (easting, northing, altitude) in UTM coordinate
      geographic_msgs::GeoPoint gps_geopoint;
      gps_geopoint.altitude = (*closest_gps).altitude;
      gps_geopoint.latitude = (*closest_gps).latitude;
      gps_geopoint.longitude = (*closest_gps).longitude;
      geodesy::UTMPoint utm;
      geodesy::fromMsg(gps_geopoint, utm); 
      Eigen::Vector3d xyz(utm.easting, utm.northing, utm.altitude);
      double cov_x = (*closest_gps).position_covariance.at(0);
      double cov_y = (*closest_gps).position_covariance.at(4);
      double cov_z = (*closest_gps).position_covariance.at(8);
      if (cov_x > max_gps_edge_stddev_xy || cov_y > max_gps_edge_stddev_xy || cov_z > max_gps_edge_stddev_z)
        continue;

      // the first gps data position will be the origin of the map
      // if(!zero_utm) {
      //   zero_utm = xyz;
      // }
      // xyz -= (*zero_utm);
      keyframe->utm_coord = xyz;
      Eigen::Vector3d world_coordinate = (utm_to_world * Eigen::Vector4d(utm.easting, utm.northing, utm.altitude, 1)).head(3);
      Eigen::Vector3d trans_err = keyframe->node->estimate().translation() - world_coordinate;
      if (trans_err.norm() < 5.0) continue;
      //********** G2O Edge ***********
      g2o::OptimizableGraph::Edge* edge;
      if(std::isnan(world_coordinate.z())) {
        Eigen::Matrix2d information_matrix = Eigen::Matrix2d::Identity() / cov_x;
        edge = graph_slam->add_se3_prior_xy_edge(keyframe->node, world_coordinate.head<2>(), information_matrix);
      } else {
        Eigen::Matrix3d information_matrix = Eigen::Matrix3d::Identity();
        information_matrix(0, 0) /= cov_x;
        information_matrix(1, 1) /= cov_y;
        information_matrix(2, 2) /= cov_z;
        edge = graph_slam->add_se3_prior_xyz_edge(keyframe->node, world_coordinate, information_matrix);
      }
      graph_slam->add_robust_kernel(edge, private_nh.param<std::string>("gps_edge_robust_kernel", "NONE"), private_nh.param<double>("gps_edge_robust_kernel_size", 1.0));

      last_gps_edge_index = keyframe->index;
      updated = true;
    }
    
    auto remove_loc = std::upper_bound(gps_navsat_queue.begin(), gps_navsat_queue.end(), keyframes.back()->stamp, [=](const ros::Time& stamp, const sensor_msgs::NavSatFix& geopoint) { return stamp < geopoint.header.stamp; });
    gps_navsat_queue.erase(gps_navsat_queue.begin(), remove_loc);
    
    return updated;
  }
  
  void command_callback(const std_msgs::String& str_msg) {
    if (str_msg.data == "output_aftmapped") {
      ofstream fout;
      fout.open("/home/zhuge/stamped_pose_graph_estimate.txt", ios::out);
      fout << "# timestamp tx ty tz qx qy qz qw" << endl;
      fout.setf(ios::fixed, ios::floatfield);  // fixed mode,float
      fout.precision(8);  // Set precision 8
      for(size_t i = 0; i < keyframes.size(); i++) {
        Eigen::Vector3d pos_ = keyframes[i]->node->estimate().translation();
        Eigen::Matrix3d rot_ = keyframes[i]->node->estimate().rotation();
        Eigen::Quaterniond quat_(rot_);
        double timestamp = keyframes[i]->stamp.toSec();
        double tx = pos_(0), ty = pos_(1), tz = pos_(2);
        double qx = quat_.x(), qy = quat_.y(), qz = quat_.z(), qw = quat_.w();

        fout << timestamp << " "
          << tx << " " << ty << " " << tz << " "
          << qx << " " << qy << " " << qz << " " << qw << endl;
      }
      fout.close();
      ROS_INFO("Optimized edges have been output!");
    }
    else if (str_msg.data == "time") {
      if (loop_detector->pf_time.size() > 0) {
        std::sort(loop_detector->pf_time.begin(), loop_detector->pf_time.end());
        double median = loop_detector->pf_time.at(floor((double)loop_detector->pf_time.size() / 2));
        cout << "Pre-filtering Matching time cost (median): " << median << endl;
      }
      if (loop_detector->sc_time.size() > 0) {
        std::sort(loop_detector->sc_time.begin(), loop_detector->sc_time.end());
        double median = loop_detector->sc_time.at(floor((double)loop_detector->sc_time.size() / 2));
        cout << "Scan Context time cost (median): " << median << endl;
      }
      if (loop_detector->oc_time.size() > 0) {
        std::sort(loop_detector->oc_time.begin(), loop_detector->oc_time.end());
        double median = loop_detector->oc_time.at(floor((double)loop_detector->oc_time.size() / 2));
        cout << "Odometry Check time cost (median): " << median << endl;
      }
      if (opt_time.size() > 0) {
        std::sort(opt_time.begin(), opt_time.end());
        double median = opt_time.at(floor((double)opt_time.size() / 2));
        cout << "Optimization time cost (median): " << median << endl;
      }
    }
  }


private:
  // ROS
  ros::NodeHandle nh;
  ros::NodeHandle mt_nh;
  ros::NodeHandle private_nh;
  ros::WallTimer optimization_timer;
  ros::WallTimer map_publish_timer;

  std::unique_ptr<message_filters::Subscriber<nav_msgs::Odometry>> odom_sub;
  std::unique_ptr<message_filters::Subscriber<sensor_msgs::PointCloud2>> cloud_sub;
  std::unique_ptr<message_filters::Synchronizer<ApproxSyncPolicy>> sync;

  ros::Subscriber barometer_sub;
  ros::Subscriber gps_sub;
  ros::Subscriber nmea_sub;
  ros::Subscriber navsat_sub;

  ros::Subscriber imu_odom_sub;
  ros::Subscriber imu_sub;
  ros::Subscriber command_sub;

  ros::Publisher imu_odom_pub;
  ros::Publisher markers_pub;

  std::mutex trans_odom2map_mutex;
  Eigen::Matrix4d trans_odom2map; // keyframe->node->estimate() * keyframe->odom.inverse();
  Eigen::Isometry3d trans_aftmapped;  // Odometry from /map to /base_link
  Eigen::Isometry3d trans_aftmapped_incremental;
  ros::Publisher odom2base_pub;
  ros::Publisher aftmapped_odom_pub;
  ros::Publisher aftmapped_odom_incremenral_pub;
  ros::Publisher odom_frame2frame_pub;

  std::string points_topic;
  ros::Publisher read_until_pub;
  ros::Publisher map_points_pub;

  tf::TransformListener tf_listener;
  tf::TransformBroadcaster map2base_broadcaster; // odom_frame => base_frame

  ros::ServiceServer dump_service_server;
  ros::ServiceServer save_map_service_server; 

  // keyframe queue
  std::mutex keyframe_queue_mutex;
  std::deque<KeyFrame::Ptr> keyframe_queue;
  std::deque<geometry_msgs::TwistStampedConstPtr> twist_queue;
  std::deque<nav_msgs::OdometryConstPtr> imu_odom_queue;
  double thisKeyframeTime;
  double lastKeyframeTime;
  size_t keyframe_index = 0;

  // IMU / Ego Velocity Integration
  bool enable_preintegration;
  double preinteg_orient_stddev;
  double preinteg_trans_stddev;
  bool enable_imu_orientation;
  bool use_egovel_preinteg_trans;
  Eigen::Matrix4d initial_pose;

  // barometer queue
  bool enable_barometer;
  int barometer_edge_type;
  double barometer_edge_stddev;
  boost::optional<Eigen::Vector1d> zero_alt;
  std::mutex barometer_queue_mutex;
  std::deque<barometer_bmp388::BarometerConstPtr> barometer_queue;

  // gps queue
  int gps_edge_intervals;
  int last_gps_edge_index;
  double gps_time_offset;
  double gps_edge_stddev_xy;
  double gps_edge_stddev_z;
  double max_gps_edge_stddev_xy;
  double max_gps_edge_stddev_z;
  boost::optional<Eigen::Vector3d> zero_utm;
  std::mutex gps_queue_mutex;
  std::deque<geographic_msgs::GeoPointStampedConstPtr> gps_geopoint_queue;
  std::deque<sensor_msgs::NavSatFix>           gps_navsat_queue;
  Eigen::Matrix4d utm_to_world;
  std::string dataset_name;

  // Marker coefficients
  bool show_sphere;

  // for map cloud generation
  std::atomic_bool graph_updated;
  double map_cloud_resolution;
  std::mutex keyframes_snapshot_mutex;
  std::vector<KeyFrameSnapshot::Ptr> keyframes_snapshot;
  std::unique_ptr<MapCloudGenerator> map_cloud_generator;

  // graph slam
  // all the below members must be accessed after locking main_thread_mutex
  std::mutex main_thread_mutex;

  int max_keyframes_per_update;
  //  Used for Loop Closure detection source, 
  //  pushed form keyframe_queue at "flush_keyframe_queue()", 
  //  inserted to "keyframes_" before optimization
  std::deque<KeyFrame::Ptr> new_keyframes;
  //  Previous keyframes_
  std::vector<KeyFrame::Ptr> keyframes;
  std::unordered_map<ros::Time, KeyFrame::Ptr, RosTimeHash> keyframe_hash;
  g2o::VertexSE3* anchor_node;
  g2o::EdgeSE3* anchor_edge;
  g2o::VertexPlane* floor_plane_node;

  std::unique_ptr<GraphSLAM> graph_slam;
  std::unique_ptr<LoopDetector> loop_detector;
  std::unique_ptr<KeyframeUpdater> keyframe_updater;
  std::unique_ptr<NmeaSentenceParser> nmea_parser;
  std::unique_ptr<InformationMatrixCalculator> inf_calclator;

  // Registration Method
  pcl::Registration<PointT, PointT>::Ptr registration;
  pcl::KdTreeFLANN<PointT>::Ptr kdtreeHistoryKeyPoses;

  std::vector<double> opt_time;
};

}  // namespace radar_graph_slam

PLUGINLIB_EXPORT_CLASS(radar_graph_slam::RadarGraphSlamNodelet, nodelet::Nodelet)


================================================
FILE: apps/scan_matching_odometry_nodelet.cpp
================================================
// SPDX-License-Identifier: BSD-2-Clause

#include <ctime>
#include <chrono>
#include <mutex>
#include <atomic>
#include <memory>
#include <iomanip>
#include <iostream>
#include <cmath>
#include <unordered_map>
#include <boost/format.hpp>
#include <boost/thread.hpp>
#include <boost/filesystem.hpp>
#include <boost/algorithm/string.hpp>

#include <ros/ros.h>
#include <ros/time.h>
#include <ros/duration.h>

#include <tf_conversions/tf_eigen.h>
#include <tf/transform_listener.h>
#include <tf/transform_broadcaster.h>
#include <message_filters/subscriber.h>
#include <message_filters/time_synchronizer.h>
#include <message_filters/synchronizer.h>
#include <message_filters/sync_policies/approximate_time.h>

#include <std_msgs/String.h>
#include <std_msgs/Time.h>
#include <nav_msgs/Odometry.h>
#include <sensor_msgs/PointCloud2.h>
#include <sensor_msgs/Imu.h>
#include <geometry_msgs/TransformStamped.h>
#include <geometry_msgs/PoseWithCovarianceStamped.h>
#include <geometry_msgs/TwistWithCovarianceStamped.h>

#include <nodelet/nodelet.h>
#include <pluginlib/class_list_macros.h>

#include <pcl_ros/point_cloud.h>
#include <pcl/filters/voxel_grid.h>
#include <pcl/filters/passthrough.h>
#include <pcl/filters/approximate_voxel_grid.h>
#include <pcl/octree/octree_search.h>

#include <Eigen/Dense>

#include <radar_graph_slam/ros_utils.hpp>
#include <radar_graph_slam/registrations.hpp>
#include <radar_graph_slam/ScanMatchingStatus.h>
#include <radar_graph_slam/keyframe.hpp>
#include <radar_graph_slam/keyframe_updater.hpp>
#include <radar_graph_slam/graph_slam.hpp>
#include <radar_graph_slam/information_matrix_calculator.hpp>

#include "utility_radar.h"

using namespace std;

namespace radar_graph_slam {

class ScanMatchingOdometryNodelet : public nodelet::Nodelet, public ParamServer {
public:
  typedef pcl::PointXYZI PointT;
  typedef message_filters::sync_policies::ApproximateTime<geometry_msgs::TwistWithCovarianceStamped, sensor_msgs::PointCloud2> ApproxSyncPolicy;
  // typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::PointCloud2, geometry_msgs::TransformStamped> ApproxSyncPolicy2;
  EIGEN_MAKE_ALIGNED_OPERATOR_NEW

  ScanMatchingOdometryNodelet() {}
  virtual ~ScanMatchingOdometryNodelet() {}

  virtual void onInit() {
    NODELET_DEBUG("initializing scan_matching_odometry_nodelet...");
    nh = getNodeHandle();
    mt_nh = getMTNodeHandle();
    private_nh = getPrivateNodeHandle();

    initialize_params(); // this

    if(private_nh.param<bool>("enable_imu_frontend", false)) {
      msf_pose_sub = nh.subscribe<geometry_msgs::PoseWithCovarianceStamped>("/msf_core/pose", 1, boost::bind(&ScanMatchingOdometryNodelet::msf_pose_callback, this, _1, false));
      msf_pose_after_update_sub = nh.subscribe<geometry_msgs::PoseWithCovarianceStamped>("/msf_core/pose_after_update", 1, boost::bind(&ScanMatchingOdometryNodelet::msf_pose_callback, this, _1, true));
    }
    //******** Subscribers **********
    ego_vel_sub.reset(new message_filters::Subscriber<geometry_msgs::TwistWithCovarianceStamped>(mt_nh, "/eagle_data/twist", 256));
    points_sub.reset(new message_filters::Subscriber<sensor_msgs::PointCloud2>(mt_nh, "/filtered_points", 32));
    sync.reset(new message_filters::Synchronizer<ApproxSyncPolicy>(ApproxSyncPolicy(32), *ego_vel_sub, *points_sub));
    sync->registerCallback(boost::bind(&ScanMatchingOdometryNodelet::pointcloud_callback, this, _1, _2));
    imu_sub = nh.subscribe("/imu", 1024, &ScanMatchingOdometryNodelet::imu_callback, this);
    command_sub = nh.subscribe("/command", 10, &ScanMatchingOdometryNodelet::command_callback, this);

    //******** Publishers **********
    read_until_pub = nh.advertise<std_msgs::Header>("/scan_matching_odometry/read_until", 32);
    // Odometry of Radar scan-matching_
    odom_pub = nh.advertise<nav_msgs::Odometry>(odomTopic, 32);
    // Transformation of Radar scan-matching_
    trans_pub = nh.advertise<geometry_msgs::TransformStamped>("/scan_matching_odometry/transform", 32);
    status_pub = private_nh.advertise<ScanMatchingStatus>("/scan_matching_odometry/status", 8);
    aligned_points_pub = nh.advertise<sensor_msgs::PointCloud2>("/aligned_points", 32);
    submap_pub = nh.advertise<sensor_msgs::PointCloud2>("/radar_graph_slam/submap", 2);
  }

private:
  /**
   * @brief initialize parameters
   */
  void initialize_params() {
    auto& pnh = private_nh;
    points_topic = pnh.param<std::string>("points_topic", "/radar_enhanced_pcl");
    use_ego_vel = pnh.param<bool>("use_ego_vel", false);

    // The minimum tranlational distance and rotation angle between keyframes_.
    // If this value is zero, frames are always compared with the previous frame
    keyframe_delta_trans = pnh.param<double>("keyframe_delta_trans", 0.25);
    keyframe_delta_angle = pnh.param<double>("keyframe_delta_angle", 0.15);
    keyframe_delta_time = pnh.param<double>("keyframe_delta_time", 1.0);

    // Registration validation by thresholding
    enable_transform_thresholding = pnh.param<bool>("enable_transform_thresholding", false);
    enable_imu_thresholding = pnh.param<bool>("enable_imu_thresholding", false);
    max_acceptable_trans = pnh.param<double>("max_acceptable_trans", 1.0);
    max_acceptable_angle = pnh.param<double>("max_acceptable_angle", 1.0);
    max_diff_trans = pnh.param<double>("max_diff_trans", 1.0);
    max_diff_angle = pnh.param<double>("max_diff_angle", 1.0);
    max_egovel_cum = pnh.param<double>("max_egovel_cum", 1.0);

    map_cloud_resolution = pnh.param<double>("map_cloud_resolution", 0.05);
    keyframe_updater.reset(new KeyframeUpdater(pnh));

    enable_scan_to_map = pnh.param<bool>("enable_scan_to_map", false);
    max_submap_frames = pnh.param<int>("max_submap_frames", 5);

    enable_imu_fusion = private_nh.param<bool>("enable_imu_fusion", false);
    imu_debug_out = private_nh.param<bool>("imu_debug_out", false);
    cout << "enable_imu_fusion = " << enable_imu_fusion << endl;
    imu_fusion_ratio = private_nh.param<double>("imu_fusion_ratio", 0.1);

    // graph_slam.reset(new GraphSLAM(pnh.param<std::string>("g2o_solver_type", "lm_var")));

    // select a downsample method (VOXELGRID, APPROX_VOXELGRID, NONE)
    std::string downsample_method = pnh.param<std::string>("downsample_method", "VOXELGRID");
    double downsample_resolution = pnh.param<double>("downsample_resolution", 0.1);
    if(downsample_method == "VOXELGRID") {
      std::cout << "downsample: VOXELGRID " << downsample_resolution << std::endl;
      auto voxelgrid = new pcl::VoxelGrid<PointT>();
      voxelgrid->setLeafSize(downsample_resolution, downsample_resolution, downsample_resolution);
      downsample_filter.reset(voxelgrid);
    } else if(downsample_method == "APPROX_VOXELGRID") {
      std::cout << "downsample: APPROX_VOXELGRID " << downsample_resolution << std::endl;
      pcl::ApproximateVoxelGrid<PointT>::Ptr approx_voxelgrid(new pcl::ApproximateVoxelGrid<PointT>());
      approx_voxelgrid->setLeafSize(downsample_resolution, downsample_resolution, downsample_resolution);
      downsample_filter = approx_voxelgrid;
    } else {
      if(downsample_method != "NONE") {
        std::cerr << "warning: unknown downsampling type (" << downsample_method << ")" << std::endl;
        std::cerr << "       : use passthrough filter" << std::endl;
      }
      std::cout << "downsample: NONE" << std::endl;
      pcl::PassThrough<PointT>::Ptr passthrough(new pcl::PassThrough<PointT>());
      downsample_filter = passthrough;
    }
    registration_s2s = select_registration_method(pnh);
    registration_s2m = select_registration_method(pnh);
  }

  void imu_callback(const sensor_msgs::ImuConstPtr& imu_msg) {
    
    Eigen::Quaterniond imu_quat_from(imu_msg->orientation.w, imu_msg->orientation.x, imu_msg->orientation.y, imu_msg->orientation.z);
    Eigen::Quaterniond imu_quat_deskew = imu_quat_from * extQRPY;
    imu_quat_deskew.normalize();

    double roll, pitch, yaw;
    // tf::quaternionMsgToTF(imu_odom_msg->orientation, orientation);
    tf::Quaternion orientation = tf::Quaternion(imu_quat_deskew.x(),imu_quat_deskew.y(),imu_quat_deskew.z(),imu_quat_deskew.w());
    tf::Matrix3x3(orientation).getRPY(roll, pitch, yaw);
    imuPointerLast = (imuPointerLast + 1) % imuQueLength;
    imuTime[imuPointerLast] = imu_msg->header.stamp.toSec();
    imuRoll[imuPointerLast] = roll;
    imuPitch[imuPointerLast] = pitch;
    // cout << "get imu rp: " << roll << " " << pitch << endl;

    sensor_msgs::ImuPtr imu(new sensor_msgs::Imu);
    imu->header = imu_msg->header;
    imu->angular_velocity = imu_msg->angular_velocity; imu->linear_acceleration = imu_msg->linear_acceleration;
    imu->angular_velocity_covariance = imu_msg->angular_velocity_covariance;
    imu->linear_acceleration_covariance, imu_msg->linear_acceleration_covariance;
    imu->orientation_covariance = imu_msg->orientation_covariance;
    imu->orientation.w=imu_quat_deskew.w(); imu->orientation.x = imu_quat_deskew.x(); imu->orientation.y = imu_quat_deskew.y(); imu->orientation.z = imu_quat_deskew.z();
    {
      std::lock_guard<std::mutex> lock(imu_queue_mutex);
      imu_queue.push_back(imu);
    }

    static int cnt = 0;
    if(cnt == 0) {
      geometry_msgs::Quaternion imuQuat = tf::createQuaternionMsgFromRollPitchYaw(roll, pitch, 0);
      global_orient_matrix = Eigen::Quaterniond(imuQuat.w, imuQuat.x, imuQuat.y, imuQuat.z).toRotationMatrix();
      ROS_INFO_STREAM("Initial IMU euler angles (RPY): "
            << RAD2DEG(roll) << ", " << RAD2DEG(pitch) << ", " << RAD2DEG(yaw));
      cnt = 1;
    }
    
  }

  bool flush_imu_queue() {
    std::lock_guard<std::mutex> lock(imu_queue_mutex);
    if(keyframes.empty() || imu_queue.empty()) {
      return false;
    }
    bool updated = false;
    auto imu_cursor = imu_queue.begin();

    for(size_t i=0; i < keyframes.size(); i++) {
      auto keyframe = keyframes.at(i);
      if(keyframe->stamp < (*imu_cursor)->header.stamp) {
        continue;
      }
      if(keyframe->stamp > imu_queue.back()->header.stamp) {
        break;
      }
      // find the imu data which is closest to the keyframe_
      auto closest_imu = imu_cursor;
      for(auto imu = imu_cursor; imu != imu_queue.end(); imu++) {
        auto dt = ((*closest_imu)->header.stamp - keyframe->stamp).toSec();
        auto dt2 = ((*imu)->header.stamp - keyframe->stamp).toSec();
        if(std::abs(dt) < std::abs(dt2)) {
          break;
        }
        closest_imu = imu;
      }
      // if the time residual between the imu and keyframe_ is too large, skip it
      imu_cursor = closest_imu;
      if(0.2 < std::abs(((*closest_imu)->header.stamp - keyframe->stamp).toSec())) {
        continue;
      }
      sensor_msgs::Imu imu_;
      imu_.header = (*closest_imu)->header; imu_.orientation = (*closest_imu)->orientation;
      imu_.angular_velocity = (*closest_imu)->angular_velocity; imu_.linear_acceleration = (*closest_imu)->linear_acceleration;
      imu_.angular_velocity_covariance = (*closest_imu)->angular_velocity_covariance;
      imu_.linear_acceleration_covariance = (*closest_imu)->linear_acceleration_covariance;
      imu_.orientation_covariance = (*closest_imu)->orientation_covariance;
      keyframe->imu = imu_;
      updated = true;
    }
    auto remove_loc = std::upper_bound(imu_queue.begin(), imu_queue.end(), keyframes.back()->stamp, [=](const ros::Time& stamp, const sensor_msgs::ImuConstPtr& imupoint) { return stamp < imupoint->header.stamp; });
    imu_queue.erase(imu_queue.begin(), remove_loc);
    return updated;
  }

  std::pair<bool, sensor_msgs::Imu> get_closest_imu(ros::Time frame_stamp) {
    sensor_msgs::Imu imu_;
    std::pair<bool, sensor_msgs::Imu> false_result {false, imu_};
    if(keyframes.empty() || imu_queue.empty())
      return false_result;
    bool updated = false;
    auto imu_cursor = imu_queue.begin();
    
    // find the imu data which is closest to the keyframe_
    auto closest_imu = imu_cursor;
    for(auto imu = imu_cursor; imu != imu_queue.end(); imu++) {
      auto dt = ((*closest_imu)->header.stamp - frame_stamp).toSec();
      auto dt2 = ((*imu)->header.stamp - frame_stamp).toSec();
      if(std::abs(dt) < std::abs(dt2)) {
        break;
      }
      closest_imu = imu;
    }
    // if the time residual between the imu and keyframe_ is too large, skip it
    imu_cursor = closest_imu;
    if(0.2 < std::abs(((*closest_imu)->header.stamp - frame_stamp).toSec()))
      return false_result;

    imu_.header = (*closest_imu)->header; imu_.orientation = (*closest_imu)->orientation;
    imu_.angular_velocity = (*closest_imu)->angular_velocity; imu_.linear_acceleration = (*closest_imu)->linear_acceleration;
    imu_.angular_velocity_covariance = (*closest_imu)->angular_velocity_covariance; 
    imu_.linear_acceleration_covariance = (*closest_imu)->linear_acceleration_covariance;
    imu_.orientation_covariance = (*closest_imu)->orientation_covariance;

    updated = true;
    // cout << (*closest_imu)->orientation <<endl;
    std::pair<bool, sensor_msgs::Imu> result {updated, imu_};
    return result;
  }


  void transformUpdate(Eigen::Matrix4d& odom_to_update) // IMU
  {
		if (imuPointerLast >= 0) 
    {
      // cout << "    ";
      float imuRollLast = 0, imuPitchLast = 0;
      while (imuPointerFront != imuPointerLast) {
        if (timeLaserOdometry + scanPeriod < imuTime[imuPointerFront]) {
          break;
        }
        imuPointerFront = (imuPointerFront + 1) % imuQueLength;
      }
      cout << "    ";
      if (timeLaserOdometry + scanPeriod > imuTime[imuPointerFront]) {
        imuRollLast = imuRoll[imuPointerFront];
        imuPitchLast = imuPitch[imuPointerFront];
        cout << "    ";
      }
      else {
        cout << "    ";
        int imuPointerBack = (imuPointerFront + imuQueLength - 1) % imuQueLength;
        float ratioFront = (timeLaserOdometry + scanPeriod - imuTime[imuPointerBack])
                          / (imuTime[imuPointerFront] - imuTime[imuPointerBack]);
        float ratioBack = (imuTime[imuPointerFront] - timeLaserOdometry - scanPeriod) 
                        / (imuTime[imuPointerFront] - imuTime[imuPointerBack]);

        imuRollLast = imuRoll[imuPointerFront] * ratioFront + imuRoll[imuPointerBack] * ratioBack;
        imuPitchLast = imuPitch[imuPointerFront] * ratioFront + imuPitch[imuPointerBack] * ratioBack;
      }
      
      Eigen::Matrix3d matr = odom_to_update.block<3, 3>(0, 0);
      // Eigen::Vector3d xyz = odom_to_update.block<3, 1>(0, 3);
      Eigen::Vector3d ypr_odom = R2ypr(matr.block<3,3>(0,0));
      geometry_msgs::Quaternion imuQuat = tf::createQuaternionMsgFromRollPitchYaw(imuRollLast, imuPitchLast, ypr_odom(0));
      Eigen::Matrix3d imu_rot = Eigen::Matrix3d(Eigen::Quaterniond(imuQuat.w, imuQuat.x, imuQuat.y, imuQuat.z));
      Eigen::Vector3d ypr_imu = R2ypr(imu_rot);
      // IMU orientation transformed from world coordinate to map coordinate
      Eigen::Matrix3d imu_rot_transed = global_orient_matrix.inverse() * imu_rot;
      Eigen::Vector3d ypr_imu_trans = R2ypr(imu_rot_transed);
      double& yaw_ = ypr_odom(0);
      double pitch_fused = (1 - imu_fusion_ratio) * ypr_odom(1) + imu_fusion_ratio * ypr_imu_trans(1);
      double roll_fused = (1 - imu_fusion_ratio) * ypr_odom(2) + imu_fusion_ratio * ypr_imu_trans(2);
      geometry_msgs::Quaternion rosQuat = tf::createQuaternionMsgFromRollPitchYaw(roll_fused, pitch_fused, yaw_);
      Eigen::Quaterniond quat_updated = Eigen::Quaterniond(rosQuat.w, rosQuat.x, rosQuat.y, rosQuat.z);
      odom_to_update.block<3, 3>(0, 0) = quat_updated.toRotationMatrix();

      if (imu_debug_out)
        cout << "IMU rp: " << RAD2DEG(ypr_imu(2)) << " " << RAD2DEG(ypr_imu(1))
            << ". IMU transed rp: " << RAD2DEG(ypr_imu_trans(2)) << " " << RAD2DEG(ypr_imu_trans(1))
            // << ". Odom rp: " << RAD2DEG(ypr_odom(2)) << " " << RAD2DEG(ypr_odom(1))
            // << ". Updated rp: " << RAD2DEG(roll_fused) << " " << RAD2DEG(pitch_fused)
            // << ". Roll Pitch increment: " << RAD2DEG(roll_fused - ypr_odom(2)) << " " << RAD2DEG(pitch_fused - ypr_odom(1)) 
            << endl;
		}
  }

  /**
   * @brief callback for point clouds
   * @param cloud_msg  point cloud msg
   */
  void pointcloud_callback(const geometry_msgs::TwistWithCovarianceStampedConstPtr& twistMsg, const sensor_msgs::PointCloud2ConstPtr& cloud_msg) {
    if(!ros::ok()) {
      return;
    }
    timeLaserOdometry = cloud_msg->header.stamp.toSec();
    double this_cloud_time = cloud_msg->header.stamp.toSec();
    static double last_cloud_time = this_cloud_time;

    double dt = this_cloud_time - last_cloud_time;
    double egovel_cum_x = twistMsg->twist.twist.linear.x * dt;
    double egovel_cum_y = twistMsg->twist.twist.linear.y * dt;
    double egovel_cum_z = twistMsg->twist.twist.linear.z * dt;
    // If too large, set 0
    if (pow(egovel_cum_x,2)+pow(egovel_cum_y,2)+pow(egovel_cum_z,2) > pow(max_egovel_cum, 2));
    else egovel_cum.block<3, 1>(0, 3) = Eigen::Vector3d(egovel_cum_x, egovel_cum_y, egovel_cum_z);
    
    last_cloud_time = this_cloud_time;

    pcl::PointCloud<PointT>::Ptr cloud(new pcl::PointCloud<PointT>());
    pcl::fromROSMsg(*cloud_msg, *cloud);

    // Matching
    Eigen::Matrix4d pose = matching(cloud_msg->header.stamp, cloud);
    geometry_msgs::TwistWithCovariance twist = twistMsg->twist;
    // publish map to odom frame
    publish_odometry(cloud_msg->header.stamp, mapFrame, odometryFrame, pose, twist);

    // In offline estimation, point clouds will be supplied until the published time
    std_msgs::HeaderPtr read_until(new std_msgs::Header());
    read_until->frame_id = points_topic;
    read_until->stamp = cloud_msg->header.stamp + ros::Duration(1, 0);
    read_until_pub.publish(read_until);

    read_until->frame_id = "/filtered_points";
    read_until_pub.publish(read_until);
  }


  void msf_pose_callback(const geometry_msgs::PoseWithCovarianceStampedConstPtr& pose_msg, bool after_update) {
    if(after_update) {
      msf_pose_after_update = pose_msg;
    } else {
      msf_pose = pose_msg;
    }
  }

  /**
   * @brief downsample a point cloud
   * @param cloud  input cloud
   * @return downsampled point cloud
   */
  pcl::PointCloud<PointT>::ConstPtr downsample(const pcl::PointCloud<PointT>::ConstPtr& cloud) const {
    if(!downsample_filter) {
      return cloud;
    }

    pcl::PointCloud<PointT>::Ptr filtered(new pcl::PointCloud<PointT>());
    downsample_filter->setInputCloud(cloud);
    downsample_filter->filter(*filtered);

    return filtered;
  }

  /**
   * @brief estimate the relative pose between an input cloud and a keyframe_ cloud
   * @param stamp  the timestamp of the input cloud
   * @param cloud  the input cloud
   * @return the relative pose between the input cloud and the keyframe_ cloud
   */
  Eigen::Matrix4d matching(const ros::Time& stamp, const pcl::PointCloud<PointT>::ConstPtr& cloud) {
    if(!keyframe_cloud_s2s) {
      prev_time = ros::Time();
      prev_trans_s2s.setIdentity();
      keyframe_pose_s2s.setIdentity();
      keyframe_stamp = stamp;
      keyframe_cloud_s2s = cloud;//downsample(cloud);
      registration_s2s->setInputTarget(keyframe_cloud_s2s); // Scan-to-scan
      if (enable_scan_to_map){
        prev_trans_s2m.setIdentity();
        keyframe_pose_s2m.setIdentity();
        keyframe_cloud_s2m = cloud;
        registration_s2m->setInputTarget(keyframe_cloud_s2m);
      }
      return Eigen::Matrix4d::Identity();
    }
    // auto filtered = downsample(cloud);
    auto filtered = cloud;
    // Set Source Cloud
    registration_s2s->setInputSource(filtered);
    if (enable_scan_to_map)
      registration_s2m->setInputSource(filtered);

    std::string msf_source;
    Eigen::Isometry3d msf_delta = Eigen::Isometry3d::Identity();
    
    pcl::PointCloud<PointT>::Ptr aligned(new pcl::PointCloud<PointT>());
    Eigen::Matrix4d odom_s2s_now;
    Eigen::Matrix4d odom_s2m_now;

    // **********  Matching  **********
    Eigen::Matrix4d guess;
    if (use_ego_vel)
      guess = prev_trans_s2s * egovel_cum * msf_delta.matrix();
    else
      guess = prev_trans_s2s * msf_delta.matrix();

    chrono::steady_clock::time_point t1 = chrono::steady_clock::now();
    registration_s2s->align(*aligned, guess.cast<float>());
    chrono::steady_clock::time_point t2 = chrono::steady_clock::now();
    double time_used = chrono::duration_cast<chrono::duration<double>>(t2 - t1).count();
    s2s_matching_time.push_back(time_used);

    publish_scan_matching_status(stamp, cloud->header.frame_id, aligned, msf_source, msf_delta);

    // If not converged, use last transformation
    if(!registration_s2s->hasConverged()) {
      NODELET_INFO_STREAM("scan matching_ has not converged!!");
      NODELET_INFO_STREAM("ignore this frame(" << stamp << ")");
      if (enable_scan_to_map) return keyframe_pose_s2m * prev_trans_s2m;
      else return keyframe_pose_s2s * prev_trans_s2s;
    }
    Eigen::Matrix4d trans_s2s = registration_s2s->getFinalTransformation().cast<double>();
    odom_s2s_now = keyframe_pose_s2s * trans_s2s;

    Eigen::Matrix4d trans_s2m;
    if (enable_scan_to_map){
      registration_s2m->align(*aligned, guess.cast<float>());
      if(!registration_s2m->hasConverged()) {
        NODELET_INFO_STREAM("scan matching_ has not converged!!");
        NODELET_INFO_STREAM("ignore this frame(" << stamp << ")");
        return keyframe_pose_s2m * prev_trans_s2m;
      }
      trans_s2m = registration_s2m->getFinalTransformation().cast<double>();
      odom_s2m_now = keyframe_pose_s2m * trans_s2m;
    }

    // Add abnormal judgment, that is, if the difference between the two frames matching point cloud 
    // transition matrix is too large, it will be discarded
    bool thresholded = false;
    if(enable_transform_thresholding) {
      Eigen::Matrix4d radar_delta;
      if(enable_scan_to_map) radar_delta = prev_trans_s2m.inverse() * trans_s2m;
      else radar_delta = prev_trans_s2s.inverse() * trans_s2s;
      double dx_rd = radar_delta.block<3, 1>(0, 3).norm();
      // double da_rd = std::acos(Eigen::Quaterniond(radar_delta.block<3, 3>(0, 0)).w())*180/M_PI;
      Eigen::AngleAxisd rotation_vector;
      rotation_vector.fromRotationMatrix(radar_delta.block<3, 3>(0, 0));
      double da_rd = rotation_vector.angle();
      Eigen::Matrix3d rot_rd = radar_delta.block<3, 3>(0, 0).cast<double>();
      bool too_large_trans = dx_rd > max_acceptable_trans || da_rd > max_acceptable_angle;
      double da, dx, delta_rot_imu = 0;
      Eigen::Matrix3d matrix_rot; Eigen::Vector3d delta_trans_egovel;

      if (enable_imu_thresholding) {
        // Use IMU orientation to determine whether the matching result is good or not
        sensor_msgs::Imu frame_imu;
        Eigen::Matrix3d rot_imu = Eigen::Matrix3d::Identity();
        auto result = get_closest_imu(stamp);
        if (result.first) {
          frame_imu = result.second;
          Eigen::Quaterniond imu_quat(frame_imu.orientation.w, frame_imu.orientation.x, frame_imu.orientation.y, frame_imu.orientation.z);
          Eigen::Quaterniond prev_imu_quat(last_frame_imu.orientation.w, last_frame_imu.orientation.x, last_frame_imu.orientation.y, last_frame_imu.orientation.z);
          rot_imu = (prev_imu_quat.inverse() * imu_quat).toRotationMatrix();
          Eigen::Vector3d eulerAngle_imu = rot_imu.eulerAngles(0,1,2); // roll pitch yaw
          Eigen::Vector3d eulerAngle_rd = last_radar_delta.block<3,3>(0,0).eulerAngles(0,1,2);
          Eigen::AngleAxisd rollAngle(Eigen::AngleAxisd(restrict_rad(eulerAngle_imu(0)),Eigen::Vector3d::UnitX()));
          Eigen::AngleAxisd pitchAngle(Eigen::AngleAxisd(restrict_rad(eulerAngle_imu(1)),Eigen::Vector3d::UnitY()));
          Eigen::AngleAxisd yawAngle(Eigen::AngleAxisd(restrict_rad(eulerAngle_rd(2)),Eigen::Vector3d::UnitZ()));
          matrix_rot = yawAngle * pitchAngle * rollAngle;
          da = fabs(std::acos(Eigen::Quaterniond(rot_rd.inverse() * rot_imu).w()))*180/M_PI;
          delta_rot_imu = fabs(std::acos(Eigen::Quaterniond(rot_imu).w()))*180/M_PI;
          last_frame_imu = frame_imu;
        }
        delta_trans_egovel = egovel_cum.block<3,1>(0,3).cast<double>();
        Eigen::Vector3d delta_trans_radar = radar_delta.block<3,1>(0,3).cast<double>();
        dx = (delta_trans_egovel - delta_trans_radar).norm();

        if (dx > max_diff_trans || da > max_diff_angle || too_large_trans) {
          Eigen::Matrix4d mat_est(Eigen::Matrix4d::Identity());
          mat_est.block<3, 3>(0, 0) = matrix_rot;
          mat_est.block<3, 1>(0, 3) = delta_trans_egovel;
          if (too_large_trans) cout << "Too large transform! " << dx_rd << "[m] " << da_rd << "[deg] ";
          cout << "Difference of Odom and IMU/EgoVel too large " << dx << "[m] " << da << "[deg] (" << stamp << ")" << endl;
          prev_trans_s2s = prev_trans_s2s * mat_est;
          thresholded = true;
          if (enable_scan_to_map){
            prev_trans_s2m = prev_trans_s2m * mat_est;
            odom_s2m_now = keyframe_pose_s2m * prev_trans_s2m;
          }
          else odom_s2s_now = keyframe_pose_s2s * prev_trans_s2s;
        }
      }
      else {
        if (too_large_trans) {
          cout << "Too large transform!!  " << dx_rd << "[m] " << da_rd << "[degree]"<<
            " Ignore this frame (" << stamp << ")" << endl;
          prev_trans_s2s = trans_s2s;
          thresholded = true;
          if (enable_scan_to_map){
            prev_trans_s2m = trans_s2m;
            odom_s2m_now = keyframe_pose_s2m * prev_trans_s2m * radar_delta;
          }
          else odom_s2s_now = keyframe_pose_s2s * prev_trans_s2s * radar_delta;
        }
      }
      last_radar_delta = radar_delta;
      
      if(0){
        cout << "radar trans:" << dx_rd << " m rot:" << da_rd << " degree. EgoVel " << delta_trans_egovel.norm() << " m. "
        << "IMU rot " << delta_rot_imu << " degree." << endl;
        cout << "dx " << dx << " m. da " << da << " degree." << endl;
      }
    }
    prev_time = stamp;
    if (!thresholded) {
      prev_trans_s2s = trans_s2s;
      prev_trans_s2m = trans_s2m;
    }
    
    //********** Decided whether to accept the frame as a key frame or not **********
    if(keyframe_updater->decide(Eigen::Isometry3d(odom_s2s_now), stamp)) {
      // Loose Coupling the IMU roll & pitch
      if (enable_imu_fusion){
        if(enable_scan_to_map) transformUpdate(odom_s2m_now);
        else transformUpdate(odom_s2s_now);
      }

      keyframe_cloud_s2s = filtered;
      registration_s2s->setInputTarget(keyframe_cloud_s2s);
      keyframe_pose_s2s = odom_s2s_now;
      keyframe_stamp = stamp;
      prev_time = stamp;
      prev_trans_s2s.setIdentity();

      double accum_d = keyframe_updater->get_accum_distance();
      KeyFrame::Ptr keyframe(new KeyFrame(keyframe_index, stamp, Eigen::Isometry3d(odom_s2s_now.cast<double>()), accum_d, cloud));
      keyframe_index ++;
      keyframes.push_back(keyframe);

      // record keyframe's imu
      flush_imu_queue();

      if (enable_scan_to_map){
        pcl::PointCloud<PointT>::Ptr submap_cloud(new pcl::PointCloud<PointT>());
        pcl::PointCloud<PointT>::ConstPtr submap_cloud_downsampled;
        for(size_t i=std::max(0, (int)keyframes.size()-max_submap_frames); i < keyframes.size()-1; i++){
          Eigen::Matrix4d rel_pose = keyframes.at(i)->odom_scan2scan.matrix().inverse() * keyframes.back()->odom_scan2scan.matrix();
          pcl::PointCloud<PointT>::Ptr cloud_transformed(new pcl::PointCloud<PointT>());
          pcl::transformPointCloud(*keyframes.at(i)->cloud, *cloud_transformed, rel_pose);
          *submap_cloud += *cloud_transformed;
        }
        submap_cloud_downsampled = downsample(submap_cloud);
        keyframe_cloud_s2m = submap_cloud_downsampled;
        registration_s2m->setInputTarget(keyframe_cloud_s2m);
        
        keyframes.back()->odom_scan2map = Eigen::Isometry3d(odom_s2m_now);
        keyframe_pose_s2m = odom_s2m_now;
        prev_trans_s2m.setIdentity();
      }
    }
    
    if (aligned_points_pub.getNumSubscribers() > 0)
    {
      pcl::transformPointCloud (*cloud, *aligned, odom_s2s_now);
      aligned->header.frame_id = odometryFrame;
      aligned_points_pub.publish(*aligned);
    }

    if (enable_scan_to_map)
      return odom_s2m_now;
    else
      return odom_s2s_now;
  }


  /**
   * @brief publish odometry
   * @param stamp  timestamp
   * @param pose   odometry pose to be published
   */
  void publish_odometry(const ros::Time& stamp, const std::string& father_frame_id, const std::string& child_frame_id, const Eigen::Matrix4d& pose_in, const geometry_msgs::TwistWithCovariance twist_in) {
    // publish transform stamped for IMU integration
    geometry_msgs::TransformStamped odom_trans = matrix2transform(stamp, pose_in, father_frame_id, child_frame_id); //"map" 
    trans_pub.publish(odom_trans);

    // broadcast the transform over TF
    map2odom_broadcaster.sendTransform(odom_trans);

    // publish the transform
    nav_msgs::Odometry odom;
    odom.header.stamp = stamp;
    odom.header.frame_id = father_frame_id;   // frame: /odom
    odom.child_frame_id = child_frame_id;

    odom.pose.pose.position.x = pose_in(0, 3);
    odom.pose.pose.position.y = pose_in(1, 3);
    odom.pose.pose.position.z = pose_in(2, 3);
    odom.pose.pose.orientation = odom_trans.transform.rotation;
    odom.twist = twist_in;

    odom_pub.publish(odom);
  }

  /**
   * @brief publish scan matching_ status
   */
  void publish_scan_matching_status(const ros::Time& stamp, const std::string& frame_id, pcl::PointCloud<pcl::PointXYZI>::ConstPtr aligned, const std::string& msf_source, const Eigen::Isometry3d& msf_delta) {
    if(!status_pub.getNumSubscribers()) {
      return;
    }

    ScanMatchingStatus status;
    status.header.frame_id = frame_id;
    status.header.stamp = stamp;
    status.has_converged = registration_s2s->hasConverged();
    status.matching_error = registration_s2s->getFitnessScore();

    const double max_correspondence_dist = 0.5;

    int num_inliers = 0;
    std::vector<int> k_indices;
    std::vector<float> k_sq_dists;
    for(int i=0; i<aligned->size(); i++) {
      const auto& pt = aligned->at(i);
      registration_s2s->getSearchMethodTarget()->nearestKSearch(pt, 1, k_indices, k_sq_dists);
      if(k_sq_dists[0] < max_correspondence_dist * max_correspondence_dist) {
        num_inliers++;
      }
    }
    status.inlier_fraction = static_cast<float>(num_inliers) / aligned->size();

    status.relative_pose = isometry2pose(Eigen::Isometry3d(registration_s2s->getFinalTransformation().cast<double>()));

    if(!msf_source.empty()) {
      status.prediction_labels.resize(1);
      status.prediction_labels[0].data = msf_source;

      status.prediction_errors.resize(1);
      Eigen::Isometry3d error = Eigen::Isometry3d(registration_s2s->getFinalTransformation().cast<double>()).inverse() * msf_delta;
      status.prediction_errors[0] = isometry2pose(error.cast<double>());
    }

    status_pub.publish(status);
  }

  void command_callback(const std_msgs::String& str_msg) {
    if (str_msg.data == "time") {
      std::sort(s2s_matching_time.begin(), s2s_matching_time.end());
      double median = s2s_matching_time.at(size_t(s2s_matching_time.size() / 2));
      cout << "Scan Matching time cost (median): " << median << endl;
    }
  }

private:
  // ROS topics
  ros::NodeHandle nh;
  ros::NodeHandle mt_nh;
  ros::NodeHandle private_nh;

  // ros::Subscriber points_sub;
  ros::Subscriber msf_pose_sub;
  ros::Subscriber msf_pose_after_update_sub;
  ros::Subscriber imu_sub;

  std::mutex imu_queue_mutex;
  std::deque<sensor_msgs::ImuConstPtr> imu_queue;
  sensor_msgs::Imu last_frame_imu;

  bool enable_imu_fusion;
  bool imu_debug_out;
  Eigen::Matrix3d global_orient_matrix;  // The rotation matrix with initial IMU roll & pitch measurement (yaw = 0)
    double timeLaserOdometry = 0;
    int imuPointerFront;
    int imuPointerLast;
    double imuTime[imuQueLength];
    float imuRoll[imuQueLength];
    float imuPitch[imuQueLength];
    double imu_fusion_ratio;

  std::unique_ptr<message_filters::Subscriber<geometry_msgs::TwistWithCovarianceStamped>> ego_vel_sub;
  std::unique_ptr<message_filters::Subscriber<sensor_msgs::PointCloud2>> points_sub;
  std::unique_ptr<message_filters::Synchronizer<ApproxSyncPolicy>> sync;

  // Submap
  ros::Publisher submap_pub;
  std::unique_ptr<KeyframeUpdater> keyframe_updater;
  std::vector<KeyFrame::Ptr> keyframes;
  size_t keyframe_index = 0;
  double map_cloud_resolution;
  int  max_submap_frames;
  bool enable_scan_to_map;

  // std::unique_ptr<GraphSLAM> graph_slam;
  // std::unique_ptr<InformationMatrixCalculator> inf_calclator;
  
  ros::Publisher odom_pub;
  ros::Publisher trans_pub;
  // ros::Publisher keyframe_trans_pub;
  ros::Publisher aligned_points_pub;
  ros::Publisher status_pub;
  ros::Publisher read_until_pub;
  tf::TransformListener tf_listener;
  tf::TransformBroadcaster map2odom_broadcaster; // map => odom_frame

  std::string points_topic;


  // keyframe_ parameters
  double keyframe_delta_trans;  // minimum distance between keyframes_
  double keyframe_delta_angle;  //
  double keyframe_delta_time;   //

  // registration validation by thresholding
  bool enable_transform_thresholding;  //
  bool enable_imu_thresholding;
  double max_acceptable_trans;  //
  double max_acceptable_angle;
  double max_diff_trans;
  double max_diff_angle;
  double max_egovel_cum;
  Eigen::Matrix4d last_radar_delta = Eigen::Matrix4d::Identity();

  // odometry calculation
  geometry_msgs::PoseWithCovarianceStampedConstPtr msf_pose;
  geometry_msgs::PoseWithCovarianceStampedConstPtr msf_pose_after_update;

  Eigen::Matrix4d egovel_cum = Eigen::Matrix4d::Identity();
  bool use_ego_vel;

  ros::Time prev_time;
  Eigen::Matrix4d prev_trans_s2s;                  // previous relative transform from keyframe_
  Eigen::Matrix4d keyframe_pose_s2s;               // keyframe_ pose
  Eigen::Matrix4d prev_trans_s2m;
  Eigen::Matrix4d keyframe_pose_s2m;               // keyframe_ pose
  ros::Time keyframe_stamp;                    // keyframe_ time
  pcl::PointCloud<PointT>::ConstPtr keyframe_cloud_s2s;  // keyframe_ point cloud
  pcl::PointCloud<PointT>::ConstPtr keyframe_cloud_s2m;  // keyframe_ point cloud

  // Registration
  pcl::Filter<PointT>::Ptr downsample_filter;
  pcl::Registration<PointT, PointT>::Ptr registration_s2s;    // Scan-to-Scan Registration
  pcl::Registration<PointT, PointT>::Ptr registration_s2m;    // Scan-to-Submap Registration

  // Time evaluation
  std::vector<double> s2s_matching_time;
  ros::Subscriber command_sub;
};

}  // namespace radar_graph_slam

PLUGINLIB_EXPORT_CLASS(radar_graph_slam::ScanMatchingOdometryNodelet, nodelet::Nodelet)


================================================
FILE: cmake/FindG2O.cmake
================================================
# Find the header files

FIND_PATH(G2O_INCLUDE_DIR g2o/core/base_vertex.h
  ${G2O_ROOT}/include
  $ENV{G2O_ROOT}/include
  $ENV{G2O_ROOT}
  /usr/local/include
  /usr/include
  /opt/local/include
  /sw/local/include
  /sw/include
  /opt/ros/$ENV{ROS_DISTRO}/include
  NO_DEFAULT_PATH
  )

# Macro to unify finding both the debug and release versions of the
# libraries; this is adapted from the OpenSceneGraph FIND_LIBRARY
# macro.

MACRO(FIND_G2O_LIBRARY MYLIBRARY MYLIBRARYNAME)

  FIND_LIBRARY("${MYLIBRARY}_DEBUG"
    NAMES "g2o_${MYLIBRARYNAME}_d"
    PATHS
    ${G2O_ROOT}/lib/Debug
    ${G2O_ROOT}/lib
    $ENV{G2O_ROOT}/lib/Debug
    $ENV{G2O_ROOT}/lib
    /opt/ros/$ENV{ROS_DISTRO}/lib
    NO_DEFAULT_PATH
    )

  FIND_LIBRARY("${MYLIBRARY}_DEBUG"
    NAMES "g2o_${MYLIBRARYNAME}_d"
    PATHS
    ~/Library/Frameworks
    /Library/Frameworks
    /usr/local/lib
    /usr/local/lib64
    /usr/lib
    /usr/lib64
    /opt/local/lib
    /sw/local/lib
    /sw/lib
    )
  
  FIND_LIBRARY(${MYLIBRARY}
    NAMES "g2o_${MYLIBRARYNAME}"
    PATHS
    ${G2O_ROOT}/lib/Release
    ${G2O_ROOT}/lib
    $ENV{G2O_ROOT}/lib/Release
    $ENV{G2O_ROOT}/lib
    /opt/ros/$ENV{ROS_DISTRO}/lib
    NO_DEFAULT_PATH
    )

  FIND_LIBRARY(${MYLIBRARY}
    NAMES "g2o_${MYLIBRARYNAME}"
    PATHS
    ~/Library/Frameworks
    /Library/Frameworks
    /usr/local/lib
    /usr/local/lib64
    /usr/lib
    /usr/lib64
    /opt/local/lib
    /sw/local/lib
    /sw/lib
    )
  
  IF(NOT ${MYLIBRARY}_DEBUG)
    IF(MYLIBRARY)
      SET(${MYLIBRARY}_DEBUG ${MYLIBRARY})
    ENDIF(MYLIBRARY)
  ENDIF( NOT ${MYLIBRARY}_DEBUG)
  
ENDMACRO(FIND_G2O_LIBRARY LIBRARY LIBRARYNAME)

# Find the core elements
FIND_G2O_LIBRARY(G2O_STUFF_LIBRARY stuff)
FIND_G2O_LIBRARY(G2O_CORE_LIBRARY core)

# Find the CLI library
FIND_G2O_LIBRARY(G2O_CLI_LIBRARY cli)

# Find the pluggable solvers
FIND_G2O_LIBRARY(G2O_SOLVER_CHOLMOD solver_cholmod)
FIND_G2O_LIBRARY(G2O_SOLVER_CSPARSE solver_csparse)
FIND_G2O_LIBRARY(G2O_SOLVER_CSPARSE_EXTENSION csparse_extension)
FIND_G2O_LIBRARY(G2O_SOLVER_DENSE solver_dense)
FIND_G2O_LIBRARY(G2O_SOLVER_PCG solver_pcg)
FIND_G2O_LIBRARY(G2O_SOLVER_SLAM2D_LINEAR solver_slam2d_linear)
FIND_G2O_LIBRARY(G2O_SOLVER_STRUCTURE_ONLY solver_structure_only)
FIND_G2O_LIBRARY(G2O_SOLVER_EIGEN solver_eigen)

# Find the predefined types
FIND_G2O_LIBRARY(G2O_TYPES_DATA types_data)
FIND_G2O_LIBRARY(G2O_TYPES_ICP types_icp)
FIND_G2O_LIBRARY(G2O_TYPES_SBA types_sba)
FIND_G2O_LIBRARY(G2O_TYPES_SCLAM2D types_sclam2d)
FIND_G2O_LIBRARY(G2O_TYPES_SIM3 types_sim3)
FIND_G2O_LIBRARY(G2O_TYPES_SLAM2D types_slam2d)
FIND_G2O_LIBRARY(G2O_TYPES_SLAM3D types_slam3d)
FIND_G2O_LIBRARY(G2O_TYPES_SLAM3D_ADDONS types_slam3d_addons)

# G2O solvers declared found if we found at least one solver
SET(G2O_SOLVERS_FOUND "NO")
IF(G2O_SOLVER_CHOLMOD OR G2O_SOLVER_CSPARSE OR G2O_SOLVER_DENSE OR G2O_SOLVER_PCG OR G2O_SOLVER_SLAM2D_LINEAR OR G2O_SOLVER_STRUCTURE_ONLY OR G2O_SOLVER_EIGEN)
  SET(G2O_SOLVERS_FOUND "YES")
ENDIF(G2O_SOLVER_CHOLMOD OR G2O_SOLVER_CSPARSE OR G2O_SOLVER_DENSE OR G2O_SOLVER_PCG OR G2O_SOLVER_SLAM2D_LINEAR OR G2O_SOLVER_STRUCTURE_ONLY OR G2O_SOLVER_EIGEN)

# G2O itself declared found if we found the core libraries and at least one solver
SET(G2O_FOUND "NO")
IF(G2O_STUFF_LIBRARY AND G2O_CORE_LIBRARY AND G2O_INCLUDE_DIR AND G2O_SOLVERS_FOUND)
  SET(G2O_FOUND "YES")
ENDIF(G2O_STUFF_LIBRARY AND G2O_CORE_LIBRARY AND G2O_INCLUDE_DIR AND G2O_SOLVERS_FOUND)


================================================
FILE: config/params.yaml
================================================
radar_slam:

  # Topics
  pointCloudTopic: "/radar_enhanced_pcl"               # Point cloud data <!-- pc2_raw inlier_pc2 segmented -->
  imuTopic: "/vectornav/imu"                         # IMU data
  odomTopic: "/odom"                   # IMU pre-preintegration odometry, same frequency as IMU
  gpsTopic: "/ublox/fix"                   # GPS odometry topic from navsat, see module_navsat.launch file

  # Frames
  lidarFrame: ""
  baselinkFrame: "base_link"
  odometryFrame: "odom"
  mapFrame: "map"

  # GPS Settings
  # useGpsElevation: false                      # if GPS elevation is bad, set to "false"
  # gpsCovThreshold: 2.0                        # m^2, threshold for using GPS data
  # poseCovThreshold: 25.0                      # m^2, threshold for using GPS data
  
  # Export settings
  # savePCD: false                              # 
  # savePCDDirectory: "/Downloads/4DRadarSLAM/"        #

  # Sensor Settings
  # downsampleRate: 1                           # default: 1. Downsample your data if too many points. i.e., 16 = 64 / 4, 16 = 16 / 1 
  # lidarMinRange: 1.0                          # default: 1.0, minimum lidar range to be used
  # lidarMaxRange: 1000.0                       # default: 1000.0, maximum lidar range to be used

  # IMU Settings
  imuAccNoise: 0.0022281160035059417 # 3.9939570888238808e-03
  imuGyrNoise: 0.00011667951042710442 # 1.5636343949698187e-03
  imuAccBiasN: 0.00011782392708033614 # 6.4356659353532566e-05
  imuGyrBiasN: 2.616129872371749e-06 # 3.5640318696367613e-05
  imuGravity: 9.80511
  imuRPYWeight: 0.01

  # Extrinsics (Lidar -> IMU)
  # extrinsicTrans: [0, 0, 0]
  extrinsicTrans: [-0.3176955976234, -0.13761019052125, 0.05898352725152]
  # extrinsicRot: [1, 0, 0,
  #                 0, -1, 0,
  #                 0, 0, -1]
  # extrinsicRPY: [1, 0, 0,
  #                 0, -1, 0,
  #                 0, 0, -1]
  extrinsicRot: [0.999735807578, -0.0215215701795, -0.0081643477385,
                 -0.02148120581797, -0.9997581134183, 0.00502853428037,
                 -0.00826995351904, -0.0048509797951, -0.99995400578406]
  extrinsicRPY: [0.999735807578, -0.0215215701795, -0.0081643477385,
                 -0.02148120581797, -0.9997581134183, 0.00502853428037,
                 -0.00826995351904, -0.0048509797951, -0.99995400578406]
  # extrinsicRot: [1, 0, 0,
  #                 0, 1, 0,
  #                 0, 0, 1]
  # extrinsicRPY: [1, 0, 0,
  #                 0, 1, 0,
  #                 0, 0, 1]




================================================
FILE: include/dbscan/DBSCAN_kdtree.h
================================================
#ifndef DBSCAN_KDTREE_H
#define DBSCAN_KDTREE_H

#include <pcl/point_types.h>
#include "DBSCAN_simple.h"

template <typename PointT>
class DBSCANKdtreeCluster: public DBSCANSimpleCluster<PointT> {
protected:
    virtual int radiusSearch (
        int index, double radius, std::vector<int> &k_indices,
        std::vector<float> &k_sqr_distances) const
    {
        return this->search_method_->radiusSearch(index, radius, k_indices, k_sqr_distances);
    }

}; // class DBSCANCluster

#endif // DBSCAN_KDTREE_H

================================================
FILE: include/dbscan/DBSCAN_precomp.h
================================================
#ifndef DBSCAN_PRECOMP_H
#define DBSCAN_PRECOMP_H

#include <pcl/point_types.h>
#include "DBSCAN_simple.h"

template <typename PointT>
class DBSCANPrecompCluster : public DBSCANSimpleCluster<PointT>  {
public:
    virtual void setInputCloud(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud) {
        this->input_cloud_ = cloud;
        int size = this->input_cloud_->points.size();
        adjoint_indexes_ = std::vector<std::vector<int>>(size, std::vector<int>());
        distances_ = std::vector<std::vector<float>>(size, std::vector<float>());
        precomp();
    }

protected:
    std::vector<std::vector<float>> distances_;
    std::vector<std::vector<int>> adjoint_indexes_;

    void precomp() {
        int size = this->input_cloud_->points.size();
        for (int i = 0; i < size; i++) {
            adjoint_indexes_[i].push_back(i);
            distances_[i].push_back(0.0);
        }
        double radius_square = this->eps_ * this->eps_;
        for (int i = 0; i < size; i++) {
            for (int j = i+1; j < size; j++) {
                double distance_x = this->input_cloud_->points[i].x - this->input_cloud_->points[j].x;
                double distance_y = this->input_cloud_->points[i].y - this->input_cloud_->points[j].y;
                double distance_z = this->input_cloud_->points[i].z - this->input_cloud_->points[j].z;
                double distance_square = distance_x * distance_x + distance_y * distance_y + distance_z * distance_z;
                if (distance_square <= radius_square) {
                    adjoint_indexes_[i].push_back(j);
                    adjoint_indexes_[j].push_back(i);
                    double distance = std::sqrt(distance_square);
                    distances_[i].push_back(distance);
                    distances_[j].push_back(distance);
                }
            }
        }
    }

    virtual int radiusSearch(
        int index, double radius, std::vector<int> &k_indices,
        std::vector<float> &k_sqr_distances) const
    {
        // radius = eps_
        k_indices = adjoint_indexes_[index];
        k_sqr_distances = distances_[index];
        return k_indices.size();
    }
}; // class DBSCANCluster

#endif // DBSCAN_PRECOMP_H

================================================
FILE: include/dbscan/DBSCAN_simple.h
================================================
#ifndef DBSCAN_H
#define DBSCAN_H

#include <pcl/point_types.h>

#define UN_PROCESSED 0
#define PROCESSING 1
#define PROCESSED 2

inline bool comparePointClusters (const pcl::PointIndices &a, const pcl::PointIndices &b) {
    return (a.indices.size () < b.indices.size ());
}

template <typename PointT>
class DBSCANSimpleCluster {
public:
    typedef typename pcl::PointCloud<PointT>::Ptr PointCloudPtr;
    typedef typename pcl::search::KdTree<PointT>::Ptr KdTreePtr;
    virtual void setInputCloud(PointCloudPtr cloud) {
        input_cloud_ = cloud;
    }

    void setSearchMethod(KdTreePtr tree) {
        search_method_ = tree;
    }

    void extract(std::vector<pcl::PointIndices>& cluster_indices) {
        std::vector<int> nn_indices;
        std::vector<float> nn_distances;
        std::vector<bool> is_noise(input_cloud_->points.size(), false);
        std::vector<int> types(input_cloud_->points.size(), UN_PROCESSED);
        for (int i = 0; i < input_cloud_->points.size(); i++) {
            if (types[i] == PROCESSED) {
                continue;
            }
            int nn_size = radiusSearch(i, eps_, nn_indices, nn_distances);
            if (nn_size < minPts_) {
                is_noise[i] = true;
                continue;
            }
            
            std::vector<int> seed_queue;
            seed_queue.push_back(i);
            types[i] = PROCESSED;
            
            for (int j = 0; j < nn_size; j++) {
                if (nn_indices[j] != i) {
                    seed_queue.push_back(nn_indices[j]);
                    types[nn_indices[j]] = PROCESSING;
                }
            } // for every point near the chosen core point.
            int sq_idx = 1;
            while (sq_idx < seed_queue.size()) {
                int cloud_index = seed_queue[sq_idx];
                if (is_noise[cloud_index] || types[cloud_index] == PROCESSED) {
                    // seed_queue.push_back(cloud_index);
                    types[cloud_index] = PROCESSED;
                    sq_idx++;
                    continue; // no need to check neighbors.
                }
                nn_size = radiusSearch(cloud_index, eps_, nn_indices, nn_distances);
                if (nn_size >= minPts_) {
                    for (int j = 0; j < nn_size; j++) {
                        if (types[nn_indices[j]] == UN_PROCESSED) {
                            
                            seed_queue.push_back(nn_indices[j]);
                            types[nn_indices[j]] = PROCESSING;
                        }
                    }
                }
                
                types[cloud_index] = PROCESSED;
                sq_idx++;
            }
            if (seed_queue.size() >= min_pts_per_cluster_ && seed_queue.size () <= max_pts_per_cluster_) {
                pcl::PointIndices r;
                r.indices.resize(seed_queue.size());
                for (int j = 0; j < seed_queue.size(); ++j) {
                    r.indices[j] = seed_queue[j];
                }
                // These two lines should not be needed: (can anyone confirm?) -FF
                std::sort (r.indices.begin (), r.indices.end ());
                r.indices.erase (std::unique (r.indices.begin (), r.indices.end ()), r.indices.end ());

                r.header = input_cloud_->header;
                cluster_indices.push_back (r);   // We could avoid a copy by working directly in the vector
            }
        } // for every point in input cloud
        std::sort (cluster_indices.rbegin (), cluster_indices.rend (), comparePointClusters);
    }

    void setClusterTolerance(double tolerance) {
        eps_ = tolerance; 
    }

    void setMinClusterSize (int min_cluster_size) { 
        min_pts_per_cluster_ = min_cluster_size; 
    }

    void setMaxClusterSize (int max_cluster_size) { 
        max_pts_per_cluster_ = max_cluster_size; 
    }
    
    void setCorePointMinPts(int core_point_min_pts) {
        minPts_ = core_point_min_pts;
    }

protected:
    PointCloudPtr input_cloud_;
    
    double eps_ {0.0};
    int minPts_ {1}; // not including the point itself.
    int min_pts_per_cluster_ {1};
    int max_pts_per_cluster_ {std::numeric_limits<int>::max()};

    KdTreePtr search_method_;

    virtual int radiusSearch(
        int index, double radius, std::vector<int> &k_indices,
        std::vector<float> &k_sqr_distances) const
    {
        k_indices.clear();
        k_sqr_distances.clear();
        k_indices.push_back(index);
        k_sqr_distances.push_back(0);
        int size = input_cloud_->points.size();
        double radius_square = radius * radius;
        for (int i = 0; i < size; i++) {
            if (i == index) {
                continue;
            }
            double distance_x = input_cloud_->points[i].x - input_cloud_->points[index].x;
            double distance_y = input_cloud_->points[i].y - input_cloud_->points[index].y;
            double distance_z = input_cloud_->points[i].z - input_cloud_->points[index].z;
            double distance_square = distance_x * distance_x + distance_y * distance_y + distance_z * distance_z;
            if (distance_square <= radius_square) {
                k_indices.push_back(i);
                k_sqr_distances.push_back(std::sqrt(distance_square));
            }
        }
        return k_indices.size();
    }
}; // class DBSCANCluster

#endif // DBSCAN_H

================================================
FILE: include/g2o/edge_plane_identity.hpp
================================================
// g2o - General Graph Optimization
// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard
// All rights reserved.
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are
// met:
//
// * Redistributions of source code must retain the above copyright notice,
//   this list of conditions and the following disclaimer.
// * Redistributions in binary form must reproduce the above copyright
//   notice, this list of conditions and the following disclaimer in the
//   documentation and/or other materials provided with the distribution.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS
// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A
// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED
// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

#ifndef EDGE_PLANE_IDENTITY_HPP
#define EDGE_PLANE_IDENTITY_HPP

#include <Eigen/Dense>
#include <g2o/core/base_binary_edge.h>
#include <g2o/types/slam3d_addons/vertex_plane.h>

namespace g2o {

/**
 * @brief A modified version of g2o::EdgePlane. This class takes care of flipped plane normals.
 *
 */
class EdgePlaneIdentity : public BaseBinaryEdge<4, Eigen::Vector4d, VertexPlane, VertexPlane> {
public:
  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  EdgePlaneIdentity() : BaseBinaryEdge<4, Eigen::Vector4d, VertexPlane, VertexPlane>() {
    _information.setIdentity();
    _error.setZero();
  }
  void computeError() {
    const VertexPlane* v1 = static_cast<const VertexPlane*>(_vertices[0]);
    const VertexPlane* v2 = static_cast<const VertexPlane*>(_vertices[1]);

    Eigen::Vector4d p1 = v1->estimate().toVector();
    Eigen::Vector4d p2 = v2->estimate().toVector();

    if(p1.dot(p2) < 0.0) {
      p2 = -p2;
    }

    _error = (p2 - p1) - _measurement;
  }
  virtual bool read(std::istream& is) override {
    Eigen::Vector4d v;
    for(int i = 0; i < 4; ++i) {
      is >> v[i];
    }

    setMeasurement(v);
    for(int i = 0; i < information().rows(); ++i) {
      for(int j = i; j < information().cols(); ++j) {
        is >> information()(i, j);
        if(i != j) {
          information()(j, i) = information()(i, j);
        }
      }
    }

    return true;
  }

  virtual bool write(std::ostream& os) const override {
    for(int i = 0; i < 4; ++i) {
      os << _measurement[i] << " ";
    }

    for(int i = 0; i < information().rows(); ++i) {
      for(int j = i; j < information().cols(); ++j) {
        os << " " << information()(i, j);
      };
    }
    return os.good();
  }

  virtual void setMeasurement(const Eigen::Vector4d& m) override {
    _measurement = m;
  }

  virtual int measurementDimension() const override {
    return 4;
  }
};

}  // namespace g2o

#endif  // EDGE_PLANE_PARALLEL_HPP


================================================
FILE: include/g2o/edge_plane_parallel.hpp
================================================
// g2o - General Graph Optimization
// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard
// All rights reserved.
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are
// met:
//
// * Redistributions of source code must retain the above copyright notice,
//   this list of conditions and the following disclaimer.
// * Redistributions in binary form must reproduce the above copyright
//   notice, this list of conditions and the following disclaimer in the
//   documentation and/or other materials provided with the distribution.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS
// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A
// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED
// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

#ifndef EDGE_PLANE_PARALLEL_HPP
#define EDGE_PLANE_PARALLEL_HPP

#include <Eigen/Dense>
#include <g2o/core/base_binary_edge.h>
#include <g2o/types/slam3d_addons/vertex_plane.h>

namespace g2o {

class EdgePlaneParallel : public BaseBinaryEdge<3, Eigen::Vector3d, VertexPlane, VertexPlane> {
public:
  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  EdgePlaneParallel() : BaseBinaryEdge<3, Eigen::Vector3d, VertexPlane, VertexPlane>() {
    _information.setIdentity();
    _error.setZero();
  }

  void computeError() override {
    const VertexPlane* v1 = static_cast<const VertexPlane*>(_vertices[0]);
    const VertexPlane* v2 = static_cast<const VertexPlane*>(_vertices[1]);

    Eigen::Vector3d normal1 = v1->estimate().normal();
    Eigen::Vector3d normal2 = v2->estimate().normal();

    if(normal1.dot(normal2) < 0.0) {
      normal2 = -normal2;
    }

    _error = (normal2 - normal1) - _measurement;
  }
  virtual bool read(std::istream& is) override {
    Eigen::Vector3d v;
    for(int i = 0; i < 3; ++i) {
      is >> v[i];
    }

    setMeasurement(v);
    for(int i = 0; i < information().rows(); ++i) {
      for(int j = i; j < information().cols(); ++j) {
        is >> information()(i, j);
        if(i != j) {
          information()(j, i) = information()(i, j);
        }
      }
    }

    return true;
  }

  virtual bool write(std::ostream& os) const override {
    for(int i = 0; i < 3; ++i) {
      os << _measurement[i] << " ";
    }

    for(int i = 0; i < information().rows(); ++i) {
      for(int j = i; j < information().cols(); ++j) {
        os << " " << information()(i, j);
      };
    }
    return os.good();
  }

  virtual void setMeasurement(const Eigen::Vector3d& m) override {
    _measurement = m;
  }

  virtual int measurementDimension() const override {
    return 3;
  }
};

class EdgePlanePerpendicular : public BaseBinaryEdge<1, Eigen::Vector3d, VertexPlane, VertexPlane> {
public:
  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  EdgePlanePerpendicular() : BaseBinaryEdge<1, Eigen::Vector3d, VertexPlane, VertexPlane>() {
    _information.setIdentity();
    _error.setZero();
  }

  void computeError() override {
    const VertexPlane* v1 = static_cast<const VertexPlane*>(_vertices[0]);
    const VertexPlane* v2 = static_cast<const VertexPlane*>(_vertices[1]);

    Eigen::Vector3d normal1 = v1->estimate().normal().normalized();
    Eigen::Vector3d normal2 = v2->estimate().normal().normalized();

    _error[0] = normal1.dot(normal2);
  }

  virtual bool read(std::istream& is) override {
    Eigen::Vector3d v;
    for(int i = 0; i < 3; ++i) {
      is >> v[i];
    }

    setMeasurement(v);
    for(int i = 0; i < information().rows(); ++i) {
      for(int j = i; j < information().cols(); ++j) {
        is >> information()(i, j);
        if(i != j) {
          information()(j, i) = information()(i, j);
        }
      }
    }

    return true;
  }

  virtual bool write(std::ostream& os) const override {
    for(int i = 0; i < 3; ++i) {
      os << _measurement[i] << " ";
    }

    for(int i = 0; i < information().rows(); ++i) {
      for(int j = i; j < information().cols(); ++j) {
        os << " " << information()(i, j);
      };
    }
    return os.good();
  }

  virtual void setMeasurement(const Eigen::Vector3d& m) override {
    _measurement = m;
  }

  virtual int measurementDimension() const override {
    return 3;
  }
};

}  // namespace g2o

#endif  // EDGE_PLANE_PARALLEL_HPP


================================================
FILE: include/g2o/edge_plane_prior.hpp
================================================
// g2o - General Graph Optimization
// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard
// All rights reserved.
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are
// met:
//
// * Redistributions of source code must retain the above copyright notice,
//   this list of conditions and the following disclaimer.
// * Redistributions in binary form must reproduce the above copyright
//   notice, this list of conditions and the following disclaimer in the
//   documentation and/or other materials provided with the distribution.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS
// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A
// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED
// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

#ifndef EDGE_PLANE_PRIOR_HPP
#define EDGE_PLANE_PRIOR_HPP

#include <Eigen/Dense>
#include <g2o/core/base_unary_edge.h>
#include <g2o/types/slam3d_addons/vertex_plane.h>

namespace g2o {
class EdgePlanePriorNormal : public g2o::BaseUnaryEdge<3, Eigen::Vector3d, g2o::VertexPlane> {
public:
  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  EdgePlanePriorNormal() : g2o::BaseUnaryEdge<3, Eigen::Vector3d, g2o::VertexPlane>() {}

  void computeError() override {
    const g2o::VertexPlane* v1 = static_cast<const g2o::VertexPlane*>(_vertices[0]);
    Eigen::Vector3d normal = v1->estimate().normal();

    if(normal.dot(_measurement) < 0.0) {
      normal = -normal;
    }

    _error = normal - _measurement;
  }

  void setMeasurement(const Eigen::Vector3d& m) override {
    _measurement = m;
  }

  virtual bool read(std::istream& is) override {
    Eigen::Vector3d v;
    is >> v(0) >> v(1) >> v(2);
    setMeasurement(v);
    for(int i = 0; i < information().rows(); ++i)
      for(int j = i; j < information().cols(); ++j) {
        is >> information()(i, j);
        if(i != j) information()(j, i) = information()(i, j);
      }
    return true;
  }
  virtual bool write(std::ostream& os) const override {
    Eigen::Vector3d v = _measurement;
    os << v(0) << " " << v(1) << " " << v(2) << " ";
    for(int i = 0; i < information().rows(); ++i)
      for(int j = i; j < information().cols(); ++j) os << " " << information()(i, j);
    return os.good();
  }
};

class EdgePlanePriorDistance : public g2o::BaseUnaryEdge<1, double, g2o::VertexPlane> {
public:
  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  EdgePlanePriorDistance() : g2o::BaseUnaryEdge<1, double, g2o::VertexPlane>() {}

  void computeError() override {
    const g2o::VertexPlane* v1 = static_cast<const g2o::VertexPlane*>(_vertices[0]);
    _error[0] = _measurement - v1->estimate().distance();
  }

  void setMeasurement(const double& m) override {
    _measurement = m;
  }

  virtual bool read(std::istream& is) override {
    is >> _measurement;
    for(int i = 0; i < information().rows(); ++i)
      for(int j = i; j < information().cols(); ++j) {
        is >> information()(i, j);
        if(i != j) information()(j, i) = information()(i, j);
      }
    return true;
  }
  virtual bool write(std::ostream& os) const override {
    os << _measurement;
    for(int i = 0; i < information().rows(); ++i)
      for(int j = i; j < information().cols(); ++j) os << " " << information()(i, j);
    return os.good();
  }
};
}  // namespace g2o

#endif  // EDGE_SE3_PRIORXY_HPP


================================================
FILE: include/g2o/edge_se3_gt_utm.hpp
================================================
// g2o - General Graph Optimization
// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard
// All rights reserved.
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are
// met:
//
// * Redistributions of source code must retain the above copyright notice,
//   this list of conditions and the following disclaimer.
// * Redistributions in binary form must reproduce the above copyright
//   notice, this list of conditions and the following disclaimer in the
//   documentation and/or other materials provided with the distribution.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS
// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A
// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED
// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

#ifndef KKL_G2O_EDGE_SE3_GTUTM_HPP
#define KKL_G2O_EDGE_SE3_GTUTM_HPP

#include <g2o/types/slam3d/types_slam3d.h>
#include <g2o/types/slam3d_addons/types_slam3d_addons.h>

namespace g2o {
class EdgeSE3GtUTM : public g2o::BaseUnaryEdge<3, Eigen::Vector3d, g2o::VertexSE3> {
public:
  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  EdgeSE3GtUTM() : g2o::BaseUnaryEdge<3, Eigen::Vector3d, g2o::VertexSE3>() {}

  void computeError() override {
    const g2o::VertexSE3* v1 = static_cast<const g2o::VertexSE3*>(_vertices[0]);

    Eigen::Vector4d utm_homogeneous = Eigen::Vector4d(_measurement_utm(0), _measurement_utm(1), _measurement_utm(2), 1);
    Eigen::Vector3d estimate = (v1->estimate() * utm_homogeneous).head(3);
    _error = estimate - _measurement;
  }

  void setMeasurement(const Eigen::Vector3d& m) override {
    _measurement = m;
  }

  void setMeasurement_utm(const Eigen::Vector3d& m){
    _measurement_utm = m;
  }

  virtual bool read(std::istream& is) override {
    Eigen::Vector3d v;
    is >> v(0) >> v(1) >> v(2);
    setMeasurement(v);
    for(int i = 0; i < information().rows(); ++i)
      for(int j = i; j < information().cols(); ++j) {
        is >> information()(i, j);
        if(i != j) information()(j, i) = information()(i, j);
      }
    return true;
  }
  virtual bool write(std::ostream& os) const override {
    Eigen::Vector3d v = _measurement;
    os << v(0) << " " << v(1) << " " << v(2) << " ";
    for(int i = 0; i < information().rows(); ++i)
      for(int j = i; j < information().cols(); ++j) os << " " << information()(i, j);
    return os.good();
  }
  private:
  Eigen::Vector3d _measurement_utm;
};
}  // namespace g2o

#endif


================================================
FILE: include/g2o/edge_se3_plane.hpp
================================================
// g2o - General Graph Optimization
// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard
// All rights reserved.
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are
// met:
//
// * Redistributions of source code must retain the above copyright notice,
//   this list of conditions and the following disclaimer.
// * Redistributions in binary form must reproduce the above copyright
//   notice, this list of conditions and the following disclaimer in the
//   documentation and/or other materials provided with the distribution.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS
// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A
// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED
// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF 
Download .txt
gitextract_sqtxga8a/

├── CMakeLists.txt
├── LICENSE
├── README.md
├── apps/
│   ├── preprocessing_nodelet.cpp
│   ├── radar_graph_slam_nodelet.cpp
│   └── scan_matching_odometry_nodelet.cpp
├── cmake/
│   └── FindG2O.cmake
├── config/
│   └── params.yaml
├── include/
│   ├── dbscan/
│   │   ├── DBSCAN_kdtree.h
│   │   ├── DBSCAN_precomp.h
│   │   └── DBSCAN_simple.h
│   ├── g2o/
│   │   ├── edge_plane_identity.hpp
│   │   ├── edge_plane_parallel.hpp
│   │   ├── edge_plane_prior.hpp
│   │   ├── edge_se3_gt_utm.hpp
│   │   ├── edge_se3_plane.hpp
│   │   ├── edge_se3_priorquat.hpp
│   │   ├── edge_se3_priorvec.hpp
│   │   ├── edge_se3_priorxy.hpp
│   │   ├── edge_se3_priorxyz.hpp
│   │   ├── edge_se3_priorz.hpp
│   │   ├── edge_se3_se3.hpp
│   │   ├── edge_se3_z.hpp
│   │   └── robust_kernel_io.hpp
│   ├── radar_ego_velocity_estimator.h
│   ├── radar_graph_slam/
│   │   ├── graph_slam.hpp
│   │   ├── information_matrix_calculator.hpp
│   │   ├── keyframe.hpp
│   │   ├── keyframe_updater.hpp
│   │   ├── loop_detector.hpp
│   │   ├── map_cloud_generator.hpp
│   │   ├── nmea_sentence_parser.hpp
│   │   ├── polynomial_interpolation.hpp
│   │   ├── registrations.hpp
│   │   ├── ros_time_hash.hpp
│   │   └── ros_utils.hpp
│   ├── rio_utils/
│   │   ├── data_types.h
│   │   ├── math_helper.h
│   │   ├── radar_point_cloud.h
│   │   ├── ros_helper.h
│   │   ├── simple_profiler.h
│   │   └── strapdown.h
│   ├── scan_context/
│   │   ├── KDTreeVectorOfVectorsAdaptor.h
│   │   ├── Scancontext.h
│   │   ├── nanoflann.hpp
│   │   └── tictoc.h
│   └── utility_radar.h
├── launch/
│   ├── radar_graph_slam.launch
│   ├── rosbag_play_radar_carpark1.launch
│   ├── rosbag_play_radar_carpark3.launch
│   ├── rosbag_play_radar_garden.launch
│   ├── rosbag_play_radar_nanyanglink.launch
│   ├── rosbag_play_radar_ntuloop1.launch
│   ├── rosbag_play_radar_ntuloop2.launch
│   ├── rosbag_play_radar_ntuloop3.launch
│   └── rosbag_play_radar_smoke.launch
├── msg/
│   ├── FloorCoeffs.msg
│   └── ScanMatchingStatus.msg
├── nodelet_plugins.xml
├── package.xml
├── rviz/
│   └── radar_graph_slam.rviz
├── setup.py
├── src/
│   ├── g2o/
│   │   └── robust_kernel_io.cpp
│   ├── gps_traj_align.cpp
│   ├── gt_adjust.cpp
│   ├── radar_ego_velocity_estimator.cpp
│   └── radar_graph_slam/
│       ├── Scancontext.cpp
│       ├── __init__.py
│       ├── bag_player.py
│       ├── ford2bag.py
│       ├── graph_slam.cpp
│       ├── information_matrix_calculator.cpp
│       ├── keyframe.cpp
│       ├── loop_detector.cpp
│       ├── map2odom_publisher.py
│       ├── map_cloud_generator.cpp
│       └── registrations.cpp
└── srv/
    ├── DumpGraph.srv
    └── SaveMap.srv
Download .txt
SYMBOL INDEX (453 symbols across 55 files)

FILE: apps/preprocessing_nodelet.cpp
  type radar_graph_slam (line 44) | namespace radar_graph_slam {
    class PreprocessingNodelet (line 46) | class PreprocessingNodelet : public nodelet::Nodelet, public ParamServ...
      method PreprocessingNodelet (line 51) | PreprocessingNodelet() {}
      method onInit (line 54) | virtual void onInit() {
      method initializeTransformation (line 82) | void initializeTransformation(){
      method initializeParams (line 107) | void initializeParams() {
      method imu_callback (line 208) | void imu_callback(const sensor_msgs::ImuConstPtr& imu_msg) {
      method cloud_callback (line 267) | void cloud_callback(const sensor_msgs::PointCloud::ConstPtr&  eagle_...
      method passthrough (line 392) | pcl::PointCloud<PointT>::ConstPtr passthrough(const pcl::PointCloud<...
      method downsample (line 408) | pcl::PointCloud<PointT>::ConstPtr downsample(const pcl::PointCloud<P...
      method outlier_removal (line 426) | pcl::PointCloud<PointT>::ConstPtr outlier_removal(const pcl::PointCl...
      method distance_filter (line 439) | pcl::PointCloud<PointT>::ConstPtr distance_filter(const pcl::PointCl...
      method deskewing (line 465) | pcl::PointCloud<PointT>::ConstPtr deskewing(const pcl::PointCloud<Po...
      method RadarRaw2PointCloudXYZ (line 528) | bool RadarRaw2PointCloudXYZ(const pcl::PointCloud<RadarPointCloudTyp...
      method RadarRaw2PointCloudXYZI (line 540) | bool RadarRaw2PointCloudXYZI(const pcl::PointCloud<RadarPointCloudTy...
      method command_callback (line 554) | void command_callback(const std_msgs::String& str_msg) {

FILE: apps/radar_graph_slam_nodelet.cpp
  type radar_graph_slam (line 77) | namespace radar_graph_slam {
    class RadarGraphSlamNodelet (line 79) | class RadarGraphSlamNodelet : public nodelet::Nodelet, public ParamSer...
      method RadarGraphSlamNodelet (line 85) | RadarGraphSlamNodelet() {}
      method onInit (line 88) | virtual void onInit() {
      method cloud_callback (line 196) | void cloud_callback(const nav_msgs::OdometryConstPtr& odom_msg, cons...
      method imu_callback (line 293) | void imu_callback(const sensor_msgs::ImuConstPtr& imu_odom_msg) {
      method imu_odom_callback (line 328) | void imu_odom_callback(const nav_msgs::OdometryConstPtr& imu_odom_ms...
      method preIntegrationTransform (line 335) | geometry_msgs::Transform preIntegrationTransform(){
      method barometer_callback (line 441) | void barometer_callback(const barometer_bmp388::BarometerPtr& baro_m...
      method flush_barometer_queue (line 449) | bool flush_barometer_queue() {
      method flush_keyframe_queue (line 523) | bool flush_keyframe_queue() {
      method optimization_timer_callback (line 614) | void optimization_timer_callback(const ros::WallTimerEvent& event) {
      method addLoopFactor (line 700) | void addLoopFactor()
      method map_points_publish_timer_callback (line 722) | void map_points_publish_timer_callback(const ros::WallTimerEvent& ev...
      method create_marker_array (line 749) | visualization_msgs::MarkerArray create_marker_array(const ros::Time&...
      method dump_service (line 990) | bool dump_service(radar_graph_slam::DumpGraphRequest& req, radar_gra...
      method save_map_service (line 1038) | bool save_map_service(radar_graph_slam::SaveMapRequest& req, radar_g...
      method nmea_callback (line 1071) | void nmea_callback(const nmea_msgs::SentenceConstPtr& nmea_msg) {
      method navsat_callback (line 1083) | void navsat_callback(const sensor_msgs::NavSatFixConstPtr& navsat_ms...
      method gps_callback (line 1099) | void gps_callback(const geographic_msgs::GeoPointStampedPtr& gps_msg) {
      method flush_gps_queue (line 1109) | bool flush_gps_queue() {
      method command_callback (line 1190) | void command_callback(const std_msgs::String& str_msg) {

FILE: apps/scan_matching_odometry_nodelet.cpp
  type radar_graph_slam (line 61) | namespace radar_graph_slam {
    class ScanMatchingOdometryNodelet (line 63) | class ScanMatchingOdometryNodelet : public nodelet::Nodelet, public Pa...
      method EIGEN_MAKE_ALIGNED_OPERATOR_NEW (line 68) | EIGEN_MAKE_ALIGNED_OPERATOR_NEW
      method onInit (line 73) | virtual void onInit() {
      method initialize_params (line 108) | void initialize_params() {
      method imu_callback (line 167) | void imu_callback(const sensor_msgs::ImuConstPtr& imu_msg) {
      method flush_imu_queue (line 206) | bool flush_imu_queue() {
      method get_closest_imu (line 251) | std::pair<bool, sensor_msgs::Imu> get_closest_imu(ros::Time frame_st...
      method transformUpdate (line 287) | void transformUpdate(Eigen::Matrix4d& odom_to_update) // IMU
      method pointcloud_callback (line 347) | void pointcloud_callback(const geometry_msgs::TwistWithCovarianceSta...
      method msf_pose_callback (line 385) | void msf_pose_callback(const geometry_msgs::PoseWithCovarianceStampe...
      method downsample (line 398) | pcl::PointCloud<PointT>::ConstPtr downsample(const pcl::PointCloud<P...
      method matching (line 416) | Eigen::Matrix4d matching(const ros::Time& stamp, const pcl::PointClo...
      method publish_odometry (line 627) | void publish_odometry(const ros::Time& stamp, const std::string& fat...
      method publish_scan_matching_status (line 653) | void publish_scan_matching_status(const ros::Time& stamp, const std:...
      method command_callback (line 692) | void command_callback(const std_msgs::String& str_msg) {

FILE: include/dbscan/DBSCAN_precomp.h
  function precomp (line 22) | void precomp() {
  function virtual (line 46) | virtual int radiusSearch(

FILE: include/dbscan/DBSCAN_simple.h
  function comparePointClusters (line 10) | inline bool comparePointClusters (const pcl::PointIndices &a, const pcl:...
  type typename (line 18) | typedef typename pcl::search::KdTree<PointT>::Ptr KdTreePtr;
  function virtual (line 19) | virtual void setInputCloud(PointCloudPtr cloud) {
  function setSearchMethod (line 23) | void setSearchMethod(KdTreePtr tree) {
  function extract (line 27) | void extract(std::vector<pcl::PointIndices>& cluster_indices) {
  function setClusterTolerance (line 92) | void setClusterTolerance(double tolerance) {
  function setMinClusterSize (line 96) | void setMinClusterSize (int min_cluster_size) {
  function setMaxClusterSize (line 100) | void setMaxClusterSize (int max_cluster_size) {
  function setCorePointMinPts (line 104) | void setCorePointMinPts(int core_point_min_pts) {
  function minPts_ (line 112) | int minPts_ {1}
  function min_pts_per_cluster_ (line 113) | int min_pts_per_cluster_ {1}
  function max_pts_per_cluster_ (line 114) | int max_pts_per_cluster_ {std::numeric_limits<int>::max()};

FILE: include/g2o/edge_plane_identity.hpp
  type g2o (line 34) | namespace g2o {
    class EdgePlaneIdentity (line 40) | class EdgePlaneIdentity : public BaseBinaryEdge<4, Eigen::Vector4d, Ve...
      method EIGEN_MAKE_ALIGNED_OPERATOR_NEW (line 42) | EIGEN_MAKE_ALIGNED_OPERATOR_NEW
      method computeError (line 47) | void computeError() {
      method read (line 60) | virtual bool read(std::istream& is) override {
      method write (line 79) | virtual bool write(std::ostream& os) const override {
      method setMeasurement (line 92) | virtual void setMeasurement(const Eigen::Vector4d& m) override {
      method measurementDimension (line 96) | virtual int measurementDimension() const override {

FILE: include/g2o/edge_plane_parallel.hpp
  type g2o (line 34) | namespace g2o {
    class EdgePlaneParallel (line 36) | class EdgePlaneParallel : public BaseBinaryEdge<3, Eigen::Vector3d, Ve...
      method EIGEN_MAKE_ALIGNED_OPERATOR_NEW (line 38) | EIGEN_MAKE_ALIGNED_OPERATOR_NEW
      method computeError (line 44) | void computeError() override {
      method read (line 57) | virtual bool read(std::istream& is) override {
      method write (line 76) | virtual bool write(std::ostream& os) const override {
      method setMeasurement (line 89) | virtual void setMeasurement(const Eigen::Vector3d& m) override {
      method measurementDimension (line 93) | virtual int measurementDimension() const override {
    class EdgePlanePerpendicular (line 98) | class EdgePlanePerpendicular : public BaseBinaryEdge<1, Eigen::Vector3...
      method EIGEN_MAKE_ALIGNED_OPERATOR_NEW (line 100) | EIGEN_MAKE_ALIGNED_OPERATOR_NEW
      method computeError (line 106) | void computeError() override {
      method read (line 116) | virtual bool read(std::istream& is) override {
      method write (line 135) | virtual bool write(std::ostream& os) const override {
      method setMeasurement (line 148) | virtual void setMeasurement(const Eigen::Vector3d& m) override {
      method measurementDimension (line 152) | virtual int measurementDimension() const override {

FILE: include/g2o/edge_plane_prior.hpp
  type g2o (line 34) | namespace g2o {
    class EdgePlanePriorNormal (line 35) | class EdgePlanePriorNormal : public g2o::BaseUnaryEdge<3, Eigen::Vecto...
      method EIGEN_MAKE_ALIGNED_OPERATOR_NEW (line 37) | EIGEN_MAKE_ALIGNED_OPERATOR_NEW
      method computeError (line 40) | void computeError() override {
      method setMeasurement (line 51) | void setMeasurement(const Eigen::Vector3d& m) override {
      method read (line 55) | virtual bool read(std::istream& is) override {
      method write (line 66) | virtual bool write(std::ostream& os) const override {
    class EdgePlanePriorDistance (line 75) | class EdgePlanePriorDistance : public g2o::BaseUnaryEdge<1, double, g2...
      method EIGEN_MAKE_ALIGNED_OPERATOR_NEW (line 77) | EIGEN_MAKE_ALIGNED_OPERATOR_NEW
      method computeError (line 80) | void computeError() override {
      method setMeasurement (line 85) | void setMeasurement(const double& m) override {
      method read (line 89) | virtual bool read(std::istream& is) override {
      method write (line 98) | virtual bool write(std::ostream& os) const override {

FILE: include/g2o/edge_se3_gt_utm.hpp
  type g2o (line 33) | namespace g2o {
    class EdgeSE3GtUTM (line 34) | class EdgeSE3GtUTM : public g2o::BaseUnaryEdge<3, Eigen::Vector3d, g2o...
      method EIGEN_MAKE_ALIGNED_OPERATOR_NEW (line 36) | EIGEN_MAKE_ALIGNED_OPERATOR_NEW
      method computeError (line 39) | void computeError() override {
      method setMeasurement (line 47) | void setMeasurement(const Eigen::Vector3d& m) override {
      method setMeasurement_utm (line 51) | void setMeasurement_utm(const Eigen::Vector3d& m){
      method read (line 55) | virtual bool read(std::istream& is) override {
      method write (line 66) | virtual bool write(std::ostream& os) const override {

FILE: include/g2o/edge_se3_plane.hpp
  type g2o (line 34) | namespace g2o {
    class EdgeSE3Plane (line 35) | class EdgeSE3Plane : public g2o::BaseBinaryEdge<3, g2o::Plane3D, g2o::...
      method EIGEN_MAKE_ALIGNED_OPERATOR_NEW (line 37) | EIGEN_MAKE_ALIGNED_OPERATOR_NEW
      method computeError (line 40) | void computeError() override {
      method setMeasurement (line 49) | void setMeasurement(const g2o::Plane3D& m) override {
      method read (line 53) | virtual bool read(std::istream& is) override {
      method write (line 64) | virtual bool write(std::ostream& os) const override {

FILE: include/g2o/edge_se3_priorquat.hpp
  type g2o (line 33) | namespace g2o {
    class EdgeSE3PriorQuat (line 34) | class EdgeSE3PriorQuat : public g2o::BaseUnaryEdge<3, Eigen::Quaternio...
      method EIGEN_MAKE_ALIGNED_OPERATOR_NEW (line 36) | EIGEN_MAKE_ALIGNED_OPERATOR_NEW
      method computeError (line 39) | void computeError() override {
      method setMeasurement (line 50) | void setMeasurement(const Eigen::Quaterniond& m) override {
      method read (line 57) | virtual bool read(std::istream& is) override {
      method write (line 68) | virtual bool write(std::ostream& os) const override {

FILE: include/g2o/edge_se3_priorvec.hpp
  type g2o (line 33) | namespace g2o {
    class EdgeSE3PriorVec (line 34) | class EdgeSE3PriorVec : public g2o::BaseUnaryEdge<3, Eigen::Matrix<dou...
      method EIGEN_MAKE_ALIGNED_OPERATOR_NEW (line 36) | EIGEN_MAKE_ALIGNED_OPERATOR_NEW
      method computeError (line 39) | void computeError() override {
      method setMeasurement (line 50) | void setMeasurement(const Eigen::Matrix<double, 6, 1>& m) override {
      method read (line 55) | virtual bool read(std::istream& is) override {
      method write (line 66) | virtual bool write(std::ostream& os) const override {

FILE: include/g2o/edge_se3_priorxy.hpp
  type g2o (line 33) | namespace g2o {
    class EdgeSE3PriorXY (line 34) | class EdgeSE3PriorXY : public g2o::BaseUnaryEdge<2, Eigen::Vector2d, g...
      method EIGEN_MAKE_ALIGNED_OPERATOR_NEW (line 36) | EIGEN_MAKE_ALIGNED_OPERATOR_NEW
      method computeError (line 39) | void computeError() override {
      method setMeasurement (line 46) | void setMeasurement(const Eigen::Vector2d& m) override {
      method read (line 50) | virtual bool read(std::istream& is) override {
      method write (line 61) | virtual bool write(std::ostream& os) const override {

FILE: include/g2o/edge_se3_priorxyz.hpp
  type g2o (line 33) | namespace g2o {
    class EdgeSE3PriorXYZ (line 34) | class EdgeSE3PriorXYZ : public g2o::BaseUnaryEdge<3, Eigen::Vector3d, ...
      method EIGEN_MAKE_ALIGNED_OPERATOR_NEW (line 36) | EIGEN_MAKE_ALIGNED_OPERATOR_NEW
      method computeError (line 39) | void computeError() override {
      method setMeasurement (line 46) | void setMeasurement(const Eigen::Vector3d& m) override {
      method read (line 50) | virtual bool read(std::istream& is) override {
      method write (line 61) | virtual bool write(std::ostream& os) const override {

FILE: include/g2o/edge_se3_priorz.hpp
  type Eigen (line 33) | namespace Eigen {
  type g2o (line 37) | namespace g2o {
    class EdgeSE3PriorZ (line 38) | class EdgeSE3PriorZ : public g2o::BaseUnaryEdge<1, Eigen::Vector1d, g2...
      method EIGEN_MAKE_ALIGNED_OPERATOR_NEW (line 41) | EIGEN_MAKE_ALIGNED_OPERATOR_NEW
      method computeError (line 44) | void computeError() override {
      method setMeasurement (line 51) | void setMeasurement(const Eigen::Vector1d& m) override {
      method read (line 55) | virtual bool read(std::istream& is) override {
      method write (line 66) | virtual bool write(std::ostream& os) const override {

FILE: include/g2o/edge_se3_se3.hpp
  type g2o (line 38) | namespace g2o {
    class EdgeSE3SE3 (line 39) | class EdgeSE3SE3 : public g2o::BaseBinaryEdge<6, g2o::SE3Quat, g2o::Ve...
      method EIGEN_MAKE_ALIGNED_OPERATOR_NEW (line 41) | EIGEN_MAKE_ALIGNED_OPERATOR_NEW
      method computeError (line 44) | void computeError() override {
      method setMeasurement (line 87) | void setMeasurement(const g2o::SE3Quat& m) override {
      method read (line 91) | virtual bool read(std::istream& is) override {
      method write (line 104) | virtual bool write(std::ostream& os) const override {

FILE: include/g2o/edge_se3_z.hpp
  type Eigen (line 33) | namespace Eigen {
  type g2o (line 37) | namespace g2o {
    class EdgeSE3Z (line 38) | class EdgeSE3Z : public g2o::BaseBinaryEdge<1, Eigen::Vector1d, g2o::V...
      method EIGEN_MAKE_ALIGNED_OPERATOR_NEW (line 41) | EIGEN_MAKE_ALIGNED_OPERATOR_NEW
      method computeError (line 44) | void computeError() override {
      method setMeasurement (line 52) | void setMeasurement(const Eigen::Vector1d& m) override {
      method read (line 56) | virtual bool read(std::istream& is) override {
      method write (line 67) | virtual bool write(std::ostream& os) const override {

FILE: include/g2o/robust_kernel_io.hpp
  type g2o (line 9) | namespace g2o {

FILE: include/radar_ego_velocity_estimator.h
  function namespace (line 27) | namespace rio

FILE: include/radar_graph_slam/graph_slam.hpp
  type g2o (line 16) | namespace g2o {
    class VertexSE3 (line 17) | class VertexSE3
    class VertexPlane (line 18) | class VertexPlane
    class VertexPointXYZ (line 19) | class VertexPointXYZ
    class EdgeSE3 (line 20) | class EdgeSE3
    class EdgeSE3Plane (line 21) | class EdgeSE3Plane
    class EdgeSE3PointXYZ (line 22) | class EdgeSE3PointXYZ
    class EdgeSE3PriorXY (line 23) | class EdgeSE3PriorXY
    class EdgeSE3PriorXYZ (line 24) | class EdgeSE3PriorXYZ
    class EdgeSE3PriorVec (line 25) | class EdgeSE3PriorVec
    class EdgeSE3PriorQuat (line 26) | class EdgeSE3PriorQuat
    class EdgePlane (line 27) | class EdgePlane
    class EdgePlaneIdentity (line 28) | class EdgePlaneIdentity
    class EdgePlaneParallel (line 29) | class EdgePlaneParallel
    class EdgePlanePerpendicular (line 30) | class EdgePlanePerpendicular
    class EdgePlanePriorNormal (line 31) | class EdgePlanePriorNormal
    class EdgePlanePriorDistance (line 32) | class EdgePlanePriorDistance
    class RobustKernelFactory (line 33) | class RobustKernelFactory
  type radar_graph_slam (line 36) | namespace radar_graph_slam {
    class GraphSLAM (line 38) | class GraphSLAM {

FILE: include/radar_graph_slam/information_matrix_calculator.hpp
  type radar_graph_slam (line 10) | namespace radar_graph_slam {
    class InformationMatrixCalculator (line 12) | class InformationMatrixCalculator {
      method InformationMatrixCalculator (line 16) | InformationMatrixCalculator() {}
      method load (line 21) | void load(ParamServer& params) {
      method weight (line 39) | double weight(double a, double max_x, double min_y, double max_y, do...

FILE: include/radar_graph_slam/keyframe.hpp
  type g2o (line 16) | namespace g2o {
    class VertexSE3 (line 17) | class VertexSE3
    class HyperGraph (line 18) | class HyperGraph
    class SparseOptimizer (line 19) | class SparseOptimizer
  type radar_graph_slam (line 22) | namespace radar_graph_slam {
    type KeyFrame (line 27) | struct KeyFrame {
    type KeyFrameSnapshot (line 67) | struct KeyFrameSnapshot {

FILE: include/radar_graph_slam/keyframe_updater.hpp
  type radar_graph_slam (line 11) | namespace radar_graph_slam {
    function decide (line 16) | class KeyframeUpdater {
    function get_accum_distance (line 69) | double get_accum_distance() const {

FILE: include/radar_graph_slam/loop_detector.hpp
  type radar_graph_slam (line 24) | namespace radar_graph_slam {
    type Loop (line 26) | struct Loop {
      method Loop (line 31) | Loop(const KeyFrame::Ptr& key1, const KeyFrame::Ptr& key2, const Eig...
    class LoopDetector (line 42) | class LoopDetector {
      method LoopDetector (line 50) | LoopDetector() {}

FILE: include/radar_graph_slam/map_cloud_generator.hpp
  type radar_graph_slam (line 11) | namespace radar_graph_slam {
    class MapCloudGenerator (line 16) | class MapCloudGenerator {

FILE: include/radar_graph_slam/nmea_sentence_parser.hpp
  type radar_graph_slam (line 12) | namespace radar_graph_slam {
    type GPRMC (line 14) | struct GPRMC {
      method GPRMC (line 16) | GPRMC() {
      method GPRMC (line 20) | GPRMC(const std::vector<std::string>& tokens) {
      method degmin2deg (line 51) | double degmin2deg(double degmin) {
    class NmeaSentenceParser (line 77) | class NmeaSentenceParser {
      method NmeaSentenceParser (line 79) | NmeaSentenceParser() {}
      method GPRMC (line 82) | GPRMC parse(const std::string& sentence) const {

FILE: include/radar_graph_slam/polynomial_interpolation.hpp
  class CubicInterpolation (line 6) | class CubicInterpolation {
    method CubicInterpolation (line 10) | CubicInterpolation(Eigen::MatrixXd q_via_, Eigen::VectorXd t_via_){
    method cubic (line 31) | Eigen::Vector4d cubic(double q0, double q1, double v0, double v1, doub...
    method getPosition (line 59) | double getPosition(double t){

FILE: include/radar_graph_slam/registrations.hpp
  type radar_graph_slam (line 10) | namespace radar_graph_slam {

FILE: include/radar_graph_slam/ros_time_hash.hpp
  class RosTimeHash (line 14) | class RosTimeHash {

FILE: include/radar_graph_slam/ros_utils.hpp
  type radar_graph_slam (line 14) | namespace radar_graph_slam {
    function restrict_rad (line 19) | double restrict_rad(double rad){
    function R2ypr (line 29) | Eigen::Vector3d R2ypr(const Eigen::Matrix3d& R) {
    function matrix2transform (line 54) | static geometry_msgs::TransformStamped matrix2transform(const ros::Tim...
    function matrix2odom (line 76) | static nav_msgs::Odometry matrix2odom(const ros::Time& stamp, const Ei...
    function pose2isometry (line 98) | static Eigen::Isometry3d pose2isometry(const geometry_msgs::Pose& pose) {
    function transform2isometry (line 105) | static Eigen::Isometry3d transform2isometry(const geometry_msgs::Trans...
    function tf2isometry (line 112) | static Eigen::Isometry3d tf2isometry(const tf::StampedTransform& trans) {
    function quaternion2isometry (line 119) | static Eigen::Isometry3d quaternion2isometry(const Eigen::Quaterniond&...
    function isometry2pose (line 125) | static geometry_msgs::Pose isometry2pose(const Eigen::Isometry3d& mat) {
    function isometry2odom (line 141) | static nav_msgs::Odometry isometry2odom(const ros::Time& stamp, const ...
    function odom2isometry (line 159) | static Eigen::Isometry3d odom2isometry(const nav_msgs::OdometryConstPt...

FILE: include/rio_utils/data_types.h
  function namespace (line 28) | namespace rio
  function Real (line 68) | Real pitch() const { return Vector3::y(); }
  function Real (line 71) | Real yaw() const { return Vector3::z(); }
  function v_n_b (line 83) | NavigationSolution(const Vector3& p_n_b, const Quaternion& q_n_b, const ...
  function setPosition_n_b (line 91) | void setPosition_n_b(const Vector3& p_n_b) { pose_n_b.translation() = p_...
  function setQuaternion (line 95) | void setQuaternion(const Quaternion& q_n_b) { pose_n_b.linear() = q_n_b....
  function EulerAngles (line 97) | EulerAngles getEuler_n_b() const
  type ImuData (line 132) | struct ImuData
  type ImuDataStamped (line 144) | struct ImuDataStamped

FILE: include/rio_utils/math_helper.h
  function namespace (line 22) | namespace rio
  function cartesianToSpherical (line 76) | static void cartesianToSpherical(const Vector3& v, Real& r, Real& azi, R...
  function ConvolveType (line 86) | enum class ConvolveType

FILE: include/rio_utils/radar_point_cloud.h
  function namespace (line 30) | namespace rio
  type RadarPointCloudType (line 37) | struct RadarPointCloudType
  type EaglePointXYZIVRAB (line 61) | struct EaglePointXYZIVRAB

FILE: include/rio_utils/ros_helper.h
  function namespace (line 21) | namespace rio

FILE: include/rio_utils/simple_profiler.h
  function namespace (line 29) | namespace rio

FILE: include/rio_utils/strapdown.h
  function namespace (line 22) | namespace rio

FILE: include/scan_context/KDTreeVectorOfVectorsAdaptor.h
  type typename (line 53) | typedef typename Distance::template traits<num_t,self_t>::distance_t met...
  type nanoflann (line 54) | typedef nanoflann::KDTreeSingleIndexAdaptor< metric_t,self_t,DIM,IndexTy...
  function m_data (line 59) | KDTreeVectorOfVectorsAdaptor(const size_t /* dimensionality */, const Ve...
  function num_t (line 103) | inline num_t kdtree_get_pt(const size_t idx, const size_t dim) const {

FILE: include/scan_context/Scancontext.h
  type PointXYZIRPYT (line 47) | struct PointXYZIRPYT
  function SCInputType (line 65) | enum class SCInputType {

FILE: include/scan_context/nanoflann.hpp
  function T (line 79) | T pi_const() {
  type has_resize (line 87) | struct has_resize : std::false_type {}
  type has_resize<T, decltype((void)std::declval<T>().resize(1), 0)> (line 90) | struct has_resize<T, decltype((void)std::declval<T>().resize(1), 0)>
  type has_assign (line 93) | struct has_assign : std::false_type {}
  type has_assign<T, decltype((void)std::declval<T>().assign(1, 0), 0)> (line 96) | struct has_assign<T, decltype((void)std::declval<T>().assign(1, 0), 0)>
  function resize (line 103) | inline typename std::enable_if<has_resize<Container>::value, void>::type
  function resize (line 113) | inline typename std::enable_if<!has_resize<Container>::value, void>::type
  function assign (line 123) | inline typename std::enable_if<has_assign<Container>::value, void>::type
  function assign (line 132) | inline typename std::enable_if<!has_assign<Container>::value, void>::type
  class KNNResultSet (line 142) | class KNNResultSet {
    method KNNResultSet (line 155) | inline KNNResultSet(CountType capacity_)
    method init (line 158) | inline void init(IndexType *indices_, DistanceType *dists_) {
    method CountType (line 166) | inline CountType size() const { return count; }
    method full (line 168) | inline bool full() const { return count == capacity; }
    method addPoint (line 175) | inline bool addPoint(DistanceType dist, IndexType index) {
    type IndexDist_Sorter (line 208) | struct IndexDist_Sorter {
    class RadiusResultSet (line 220) | class RadiusResultSet {
      method RadiusResultSet (line 230) | inline RadiusResultSet(
      method init (line 237) | inline void init() { clear(); }
      method clear (line 238) | inline void clear() { m_indices_dists.clear(); }
      method size (line 240) | inline size_t size() const { return m_indices_dists.size(); }
      method full (line 242) | inline bool full() const { return true; }
      method addPoint (line 249) | inline bool addPoint(DistanceType dist, IndexType index) {
      method DistanceType (line 255) | inline DistanceType worstDist() const { return radius; }
      method worst_item (line 261) | std::pair<IndexType, DistanceType> worst_item() const {
    method save_value (line 279) | void save_value(FILE *stream, const T &value, size_t count = 1) {
    method save_value (line 284) | void save_value(FILE *stream, const std::vector<T> &value) {
    method load_value (line 291) | void load_value(FILE *stream, T &value, size_t count = 1) {
    method load_value (line 298) | void load_value(FILE *stream, std::vector<T> &value) {
    type Metric (line 315) | struct Metric {}
    type L1_Adaptor (line 324) | struct L1_Adaptor {
      method L1_Adaptor (line 330) | L1_Adaptor(const DataSource &_data_source) : data_source(_data_sourc...
      method DistanceType (line 332) | inline DistanceType evalMetric(const T *a, const size_t b_idx, size_...
      method DistanceType (line 363) | inline DistanceType accum_dist(const U a, const V b, const size_t) c...
    type L2_Adaptor (line 375) | struct L2_Adaptor {
      method L2_Adaptor (line 381) | L2_Adaptor(const DataSource &_data_source) : data_source(_data_sourc...
      method DistanceType (line 383) | inline DistanceType evalMetric(const T *a, const size_t b_idx, size_...
      method DistanceType (line 411) | inline DistanceType accum_dist(const U a, const V b, const size_t) c...
    type L2_Simple_Adaptor (line 423) | struct L2_Simple_Adaptor {
      method L2_Simple_Adaptor (line 429) | L2_Simple_Adaptor(const DataSource &_data_source)
      method DistanceType (line 432) | inline DistanceType evalMetric(const T *a, const size_t b_idx,
      method DistanceType (line 443) | inline DistanceType accum_dist(const U a, const V b, const size_t) c...
    type SO2_Adaptor (line 455) | struct SO2_Adaptor {
      method SO2_Adaptor (line 461) | SO2_Adaptor(const DataSource &_data_source) : data_source(_data_sour...
      method DistanceType (line 463) | inline DistanceType evalMetric(const T *a, const size_t b_idx,
      method DistanceType (line 471) | inline DistanceType accum_dist(const U a, const V b, const size_t) c...
    type SO3_Adaptor (line 490) | struct SO3_Adaptor {
      method SO3_Adaptor (line 496) | SO3_Adaptor(const DataSource &_data_source)
      method DistanceType (line 499) | inline DistanceType evalMetric(const T *a, const size_t b_idx,
      method DistanceType (line 505) | inline DistanceType accum_dist(const U a, const V b, const size_t id...
    type metric_L1 (line 511) | struct metric_L1 : public Metric {
      type traits (line 512) | struct traits {
    type metric_L2 (line 517) | struct metric_L2 : public Metric {
      type traits (line 518) | struct traits {
    type metric_L2_Simple (line 523) | struct metric_L2_Simple : public Metric {
      type traits (line 524) | struct traits {
    type metric_SO2 (line 529) | struct metric_SO2 : public Metric {
      type traits (line 530) | struct traits {
    type metric_SO3 (line 535) | struct metric_SO3 : public Metric {
      type traits (line 536) | struct traits {
    type KDTreeSingleIndexAdaptorParams (line 547) | struct KDTreeSingleIndexAdaptorParams {
      method KDTreeSingleIndexAdaptorParams (line 548) | KDTreeSingleIndexAdaptorParams(size_t _leaf_max_size = 10)
    type SearchParams (line 555) | struct SearchParams {
      method SearchParams (line 558) | SearchParams(int checks_IGNORED_ = 32, float eps_ = 0, bool sorted_ ...
    method T (line 579) | inline T *allocate(size_t count = 1) {
    class PooledAllocator (line 602) | class PooledAllocator {
      method internal_init (line 613) | void internal_init() {
      method PooledAllocator (line 627) | PooledAllocator() { internal_init(); }
      method free_all (line 635) | void free_all() {
      method T (line 703) | T *allocate(const size_t count = 1) {
    type array_or_vector_selector (line 716) | struct array_or_vector_selector {
    type array_or_vector_selector<-1, T> (line 720) | struct array_or_vector_selector<-1, T> {
    class KDTreeBaseClass (line 740) | class KDTreeBaseClass {
      method freeIndex (line 745) | void freeIndex(Derived &obj) {
      type Node (line 755) | struct Node {
        type leaf (line 759) | struct leaf {
        type nonleaf (line 762) | struct nonleaf {
      type Interval (line 772) | struct Interval {
      method size (line 814) | size_t size(const Derived &obj) const { return obj.m_size; }
      method veclen (line 817) | size_t veclen(const Derived &obj) {
      method ElementType (line 822) | inline ElementType dataset_get(const Derived &obj, size_t idx,
      method usedMemory (line 831) | size_t usedMemory(Derived &obj) {
      method computeMinMax (line 837) | void computeMinMax(const Derived &obj, IndexType *ind, IndexType count,
      method NodePtr (line 858) | NodePtr divideTree(Derived &obj, const IndexType left, const IndexTy...
      method middleSplit_ (line 910) | void middleSplit_(Derived &obj, IndexType *ind, IndexType count,
      method planeSplit (line 968) | void planeSplit(Derived &obj, IndexType *ind, const IndexType count,
      method DistanceType (line 1006) | DistanceType computeInitialDistances(const Derived &obj,
      method save_tree (line 1025) | void save_tree(Derived &obj, FILE *stream, NodePtr tree) {
      method load_tree (line 1035) | void load_tree(Derived &obj, FILE *stream, NodePtr &tree) {
      method saveIndex_ (line 1051) | void saveIndex_(Derived &obj, FILE *stream) {
      method loadIndex_ (line 1065) | void loadIndex_(Derived &obj, FILE *stream) {
    class KDTreeSingleIndexAdaptor (line 1117) | class KDTreeSingleIndexAdaptor
      method KDTreeSingleIndexAdaptor (line 1123) | KDTreeSingleIndexAdaptor(
      method KDTreeSingleIndexAdaptor (line 1171) | KDTreeSingleIndexAdaptor(const int dimensionality,
      method buildIndex (line 1191) | void buildIndex() {
      method findNeighbors (line 1222) | bool findNeighbors(RESULTSET &result, const ElementType *vec,
      method knnSearch (line 1253) | size_t knnSearch(const ElementType *query_point, const size_t num_cl...
      method radiusSearch (line 1278) | size_t
      method radiusSearchCustomCallback (line 1296) | size_t radiusSearchCustomCallback(
      method init_vind (line 1308) | void init_vind() {
      method computeBoundingBox (line 1317) | void computeBoundingBox(BoundingBox &bbox) {
      method searchLevel (line 1347) | bool searchLevel(RESULTSET &result_set, const ElementType *vec,
      method saveIndex (line 1418) | void saveIndex(FILE *stream) { this->saveIndex_(*this, stream); }
      method loadIndex (line 1425) | void loadIndex(FILE *stream) { this->loadIndex_(*this, stream); }
    class KDTreeSingleIndexDynamicAdaptor_ (line 1467) | class KDTreeSingleIndexDynamicAdaptor_
      method KDTreeSingleIndexDynamicAdaptor_ (line 1518) | KDTreeSingleIndexDynamicAdaptor_(
      method KDTreeSingleIndexDynamicAdaptor_ (line 1535) | KDTreeSingleIndexDynamicAdaptor_
      method buildIndex (line 1554) | void buildIndex() {
      method findNeighbors (line 1583) | bool findNeighbors(RESULTSET &result, const ElementType *vec,
      method knnSearch (line 1613) | size_t knnSearch(const ElementType *query_point, const size_t num_cl...
      method radiusSearch (line 1638) | size_t
      method radiusSearchCustomCallback (line 1656) | size_t radiusSearchCustomCallback(
      method computeBoundingBox (line 1666) | void computeBoundingBox(BoundingBox &bbox) {
      method searchLevel (line 1696) | void searchLevel(RESULTSET &result_set, const ElementType *vec,
      method saveIndex (line 1762) | void saveIndex(FILE *stream) { this->saveIndex_(*this, stream); }
      method loadIndex (line 1769) | void loadIndex(FILE *stream) { this->loadIndex_(*this, stream); }
    class KDTreeSingleIndexDynamicAdaptor (line 1788) | class KDTreeSingleIndexDynamicAdaptor {
      method First0Bit (line 1822) | int First0Bit(IndexType num) {
      method init (line 1832) | void init() {
      method KDTreeSingleIndexDynamicAdaptor (line 1857) | KDTreeSingleIndexDynamicAdaptor(const int dimensionality,
      method KDTreeSingleIndexDynamicAdaptor (line 1878) | KDTreeSingleIndexDynamicAdaptor(
      method addPoints (line 1883) | void addPoints(IndexType start, IndexType end) {
      method removePoint (line 1906) | void removePoint(size_t idx) {
      method findNeighbors (line 1926) | bool findNeighbors(RESULTSET &result, const ElementType *vec,
    type KDTreeEigenMatrixAdaptor (line 1954) | struct KDTreeEigenMatrixAdaptor {
      method KDTreeEigenMatrixAdaptor (line 1968) | KDTreeEigenMatrixAdaptor(const size_t dimensionality,
      method KDTreeEigenMatrixAdaptor (line 1987) | KDTreeEigenMatrixAdaptor(const self_t &) = delete;
      method query (line 1999) | inline void query(const num_t *query_point, const size_t num_closest,
      method self_t (line 2010) | const self_t &derived() const { return *this; }
      method self_t (line 2011) | self_t &derived() { return *this; }
      method kdtree_get_point_count (line 2014) | inline size_t kdtree_get_point_count() const {
      method num_t (line 2019) | inline num_t kdtree_get_pt(const IndexType idx, size_t dim) const {
      method kdtree_get_bbox (line 2028) | bool kdtree_get_bbox(BBOX & /*bb*/) const {

FILE: include/scan_context/tictoc.h
  function class (line 12) | class TicToc
  function tic (line 26) | void tic()
  function toc (line 31) | void toc( std::string _about_task )

FILE: include/utility_radar.h
  type pcl (line 59) | typedef pcl::PointXYZI PointType;
  function class (line 61) | class ParamServer
  function pointDistance (line 293) | float pointDistance(PointType p)
  function pointDistance (line 299) | float pointDistance(PointType p1, PointType p2)

FILE: src/g2o/robust_kernel_io.cpp
  type g2o (line 12) | namespace g2o {
    function kernel_type (line 14) | std::string kernel_type(g2o::RobustKernel* kernel) {
    function save_robust_kernels (line 45) | bool save_robust_kernels(const std::string& filename, g2o::SparseOptim...
    class KernelData (line 75) | class KernelData {
      method KernelData (line 77) | KernelData(const std::string& line) {
      method match (line 90) | bool match(g2o::OptimizableGraph::Edge* edge) const {
    function load_robust_kernels (line 118) | bool load_robust_kernels(const std::string& filename, g2o::SparseOptim...

FILE: src/gps_traj_align.cpp
  function associate (line 28) | std::vector<std::pair<int,int>> associate(std::vector<double> first_stam...
  function read_topic_from_rosbag (line 96) | void read_topic_from_rosbag(rosbag::View::iterator& iter, rosbag::View& ...
  function main (line 111) | int main()

FILE: src/gt_adjust.cpp
  function main (line 24) | int main()

FILE: src/radar_ego_velocity_estimator.cpp
  function RadarPointCloudType (line 41) | static RadarPointCloudType toRadarPointCloudType(const Vector11& item, c...

FILE: src/radar_graph_slam/Scancontext.cpp
  function coreImportTest (line 7) | void coreImportTest (void)
  function rad2deg (line 13) | float rad2deg(float radians)
  function deg2rad (line 18) | float deg2rad(float degrees)
  function xy2theta (line 24) | float xy2theta( const float & _x, const float & _y )
  function MatrixXd (line 42) | MatrixXd circshift( MatrixXd &_mat, int _num_shift )
  function eig2stdvec (line 73) | std::vector<float> eig2stdvec( MatrixXd _eigmat )
  function MatrixXd (line 162) | MatrixXd SCManager::makeScancontext( pcl::PointCloud<SCPointType> & _sca...
  function MatrixXd (line 217) | MatrixXd SCManager::makeRingkeyFromScancontext( Eigen::MatrixXd &_desc )
  function MatrixXd (line 233) | MatrixXd SCManager::makeSectorkeyFromScancontext( Eigen::MatrixXd &_desc )

FILE: src/radar_graph_slam/bag_player.py
  class BagPlayer (line 24) | class BagPlayer:
    method __init__ (line 25) | def __init__(self, bagfile, start, duration):
    method update_time_subs (line 54) | def update_time_subs(self):
    method time_callback (line 61) | def time_callback(self, header_msg, topic_name):
    method play_realtime (line 68) | def play_realtime(self, duration):
    method print_progress (line 101) | def print_progress(self, stamp):
    method check_stamp (line 147) | def check_stamp(self, topic, msg):
    method play (line 165) | def play(self):
  function main (line 207) | def main():

FILE: src/radar_graph_slam/ford2bag.py
  function gps2navsat (line 19) | def gps2navsat(filename, bag):
  function mat2pointcloud (line 59) | def mat2pointcloud(filename):
  function main (line 71) | def main():

FILE: src/radar_graph_slam/graph_slam.cpp
  type g2o (line 36) | namespace g2o {
  type radar_graph_slam (line 53) | namespace radar_graph_slam {

FILE: src/radar_graph_slam/information_matrix_calculator.cpp
  type radar_graph_slam (line 12) | namespace radar_graph_slam {

FILE: src/radar_graph_slam/keyframe.cpp
  type radar_graph_slam (line 11) | namespace radar_graph_slam {

FILE: src/radar_graph_slam/loop_detector.cpp
  function R2ypr_ (line 5) | Eigen::Vector3d R2ypr_(const Eigen::Matrix3d& R) {
  function limit_value (line 21) | double limit_value(int value, int min_, int max_){
  function monoToRainbow (line 29) | Eigen::Vector3d monoToRainbow(int value){
  type radar_graph_slam (line 48) | namespace radar_graph_slam {

FILE: src/radar_graph_slam/map2odom_publisher.py
  class Map2OdomPublisher (line 8) | class Map2OdomPublisher:
    method __init__ (line 9) | def __init__(self):
    method callback (line 13) | def callback(self, odom_msg):
    method spin (line 16) | def spin(self):
  function main (line 31) | def main():

FILE: src/radar_graph_slam/map_cloud_generator.cpp
  type radar_graph_slam (line 7) | namespace radar_graph_slam {

FILE: src/radar_graph_slam/registrations.cpp
  type radar_graph_slam (line 21) | namespace radar_graph_slam {
    function select_registration_method (line 23) | pcl::Registration<pcl::PointXYZI, pcl::PointXYZI>::Ptr select_registra...
Condensed preview — 79 files, each showing path, character count, and a content snippet. Download the .json file or copy for the full structured content (543K chars).
[
  {
    "path": "CMakeLists.txt",
    "chars": 5425,
    "preview": "# SPDX-License-Identifier: BSD-2-Clause\ncmake_minimum_required(VERSION 2.8.3)\nproject(radar_graph_slam)\n\n# Can we use C+"
  },
  {
    "path": "LICENSE",
    "chars": 35149,
    "preview": "                    GNU GENERAL PUBLIC LICENSE\n                       Version 3, 29 June 2007\n\n Copyright (C) 2007 Free "
  },
  {
    "path": "README.md",
    "chars": 7797,
    "preview": "# 4DRadarSLAM\n## A 4D Imaging Radar SLAM System for Large-scale Environments based on Pose Graph Optimization\n\n[Paper (R"
  },
  {
    "path": "apps/preprocessing_nodelet.cpp",
    "chars": 24627,
    "preview": "// SPDX-License-Identifier: BSD-2-Clause\n\n#include <string>\n#include <fstream>\n#include <functional>\n\n#include <ros/ros."
  },
  {
    "path": "apps/radar_graph_slam_nodelet.cpp",
    "chars": 59427,
    "preview": "// SPDX-License-Identifier: BSD-2-Clause\n\n#include <ctime>\n#include <mutex>\n#include <atomic>\n#include <memory>\n#include"
  },
  {
    "path": "apps/scan_matching_odometry_nodelet.cpp",
    "chars": 34806,
    "preview": "// SPDX-License-Identifier: BSD-2-Clause\n\n#include <ctime>\n#include <chrono>\n#include <mutex>\n#include <atomic>\n#include"
  },
  {
    "path": "cmake/FindG2O.cmake",
    "chars": 3443,
    "preview": "# Find the header files\n\nFIND_PATH(G2O_INCLUDE_DIR g2o/core/base_vertex.h\n  ${G2O_ROOT}/include\n  $ENV{G2O_ROOT}/include"
  },
  {
    "path": "config/params.yaml",
    "chars": 2483,
    "preview": "radar_slam:\n\n  # Topics\n  pointCloudTopic: \"/radar_enhanced_pcl\"               # Point cloud data <!-- pc2_raw inlier_pc"
  },
  {
    "path": "include/dbscan/DBSCAN_kdtree.h",
    "chars": 512,
    "preview": "#ifndef DBSCAN_KDTREE_H\n#define DBSCAN_KDTREE_H\n\n#include <pcl/point_types.h>\n#include \"DBSCAN_simple.h\"\n\ntemplate <type"
  },
  {
    "path": "include/dbscan/DBSCAN_precomp.h",
    "chars": 2211,
    "preview": "#ifndef DBSCAN_PRECOMP_H\n#define DBSCAN_PRECOMP_H\n\n#include <pcl/point_types.h>\n#include \"DBSCAN_simple.h\"\n\ntemplate <ty"
  },
  {
    "path": "include/dbscan/DBSCAN_simple.h",
    "chars": 5405,
    "preview": "#ifndef DBSCAN_H\n#define DBSCAN_H\n\n#include <pcl/point_types.h>\n\n#define UN_PROCESSED 0\n#define PROCESSING 1\n#define PRO"
  },
  {
    "path": "include/g2o/edge_plane_identity.hpp",
    "chars": 3347,
    "preview": "// g2o - General Graph Optimization\n// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard\n// All rights reserved.\n"
  },
  {
    "path": "include/g2o/edge_plane_parallel.hpp",
    "chars": 4853,
    "preview": "// g2o - General Graph Optimization\n// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard\n// All rights reserved.\n"
  },
  {
    "path": "include/g2o/edge_plane_prior.hpp",
    "chars": 3952,
    "preview": "// g2o - General Graph Optimization\n// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard\n// All rights reserved.\n"
  },
  {
    "path": "include/g2o/edge_se3_gt_utm.hpp",
    "chars": 3087,
    "preview": "// g2o - General Graph Optimization\n// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard\n// All rights reserved.\n"
  },
  {
    "path": "include/g2o/edge_se3_plane.hpp",
    "chars": 3053,
    "preview": "// g2o - General Graph Optimization\n// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard\n// All rights reserved.\n"
  },
  {
    "path": "include/g2o/edge_se3_priorquat.hpp",
    "chars": 3091,
    "preview": "// g2o - General Graph Optimization\n// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard\n// All rights reserved.\n"
  },
  {
    "path": "include/g2o/edge_se3_priorvec.hpp",
    "chars": 3177,
    "preview": "// g2o - General Graph Optimization\n// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard\n// All rights reserved.\n"
  },
  {
    "path": "include/g2o/edge_se3_priorxy.hpp",
    "chars": 2826,
    "preview": "// g2o - General Graph Optimization\n// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard\n// All rights reserved.\n"
  },
  {
    "path": "include/g2o/edge_se3_priorxyz.hpp",
    "chars": 2833,
    "preview": "// g2o - General Graph Optimization\n// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard\n// All rights reserved.\n"
  },
  {
    "path": "include/g2o/edge_se3_priorz.hpp",
    "chars": 2868,
    "preview": "// g2o - General Graph Optimization\n// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard\n// All rights reserved.\n"
  },
  {
    "path": "include/g2o/edge_se3_se3.hpp",
    "chars": 4832,
    "preview": "// g2o - General Graph Optimization\n// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard\n// All rights reserved.\n"
  },
  {
    "path": "include/g2o/edge_se3_z.hpp",
    "chars": 3004,
    "preview": "// g2o - General Graph Optimization\n// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard\n// All rights reserved.\n"
  },
  {
    "path": "include/g2o/robust_kernel_io.hpp",
    "chars": 452,
    "preview": "// SPDX-License-Identifier: BSD-2-Clause\n\n#ifndef ROBUST_KERNEL_IO_HPP\n#define ROBUST_KERNEL_IO_HPP\n\n#include <string>\n#"
  },
  {
    "path": "include/radar_ego_velocity_estimator.h",
    "chars": 7079,
    "preview": "// This file is part of RIO - Radar Inertial Odometry and Radar ego velocity estimation.\n// Copyright (C) 2021  Christop"
  },
  {
    "path": "include/radar_graph_slam/graph_slam.hpp",
    "chars": 5966,
    "preview": "// SPDX-License-Identifier: BSD-2-Clause\n\n#ifndef GRAPH_SLAM_HPP\n#define GRAPH_SLAM_HPP\n\n#include <memory>\n#include <ros"
  },
  {
    "path": "include/radar_graph_slam/information_matrix_calculator.hpp",
    "chars": 2122,
    "preview": "// SPDX-License-Identifier: BSD-2-Clause\n\n#ifndef INFORMATION_MATRIX_CALCULATOR_HPP\n#define INFORMATION_MATRIX_CALCULATO"
  },
  {
    "path": "include/radar_graph_slam/keyframe.hpp",
    "chars": 2624,
    "preview": "// SPDX-License-Identifier: BSD-2-Clause\n\n#ifndef KEYFRAME_HPP\n#define KEYFRAME_HPP\n\n#include <ros/ros.h>\n#include <pcl/"
  },
  {
    "path": "include/radar_graph_slam/keyframe_updater.hpp",
    "chars": 2316,
    "preview": "// SPDX-License-Identifier: BSD-2-Clause\n\n#ifndef KEYFRAME_UPDATER_HPP\n#define KEYFRAME_UPDATER_HPP\n\n#include <ros/ros.h"
  },
  {
    "path": "include/radar_graph_slam/loop_detector.hpp",
    "chars": 3880,
    "preview": "// SPDX-License-Identifier: BSD-2-Clause\n\n#ifndef LOOP_DETECTOR_HPP\n#define LOOP_DETECTOR_HPP\n\n#include <math.h>\n\n#inclu"
  },
  {
    "path": "include/radar_graph_slam/map_cloud_generator.hpp",
    "chars": 841,
    "preview": "// SPDX-License-Identifier: BSD-2-Clause\n\n#ifndef MAP_CLOUD_GENERATOR_HPP\n#define MAP_CLOUD_GENERATOR_HPP\n\n#include <vec"
  },
  {
    "path": "include/radar_graph_slam/nmea_sentence_parser.hpp",
    "chars": 2620,
    "preview": "// SPDX-License-Identifier: BSD-2-Clause\n\n#ifndef NMEA_SENTENCE_PARSER_HPP\n#define NMEA_SENTENCE_PARSER_HPP\n\n#include <c"
  },
  {
    "path": "include/radar_graph_slam/polynomial_interpolation.hpp",
    "chars": 2767,
    "preview": "\n#include <ros/ros.h>\n\n#include <Eigen/Dense>\n\nclass CubicInterpolation {\n    public:\n    Eigen::MatrixXd q_via;\n    Eig"
  },
  {
    "path": "include/radar_graph_slam/registrations.hpp",
    "chars": 494,
    "preview": "// SPDX-License-Identifier: BSD-2-Clause\n\n#ifndef HDL_GRAPH_SLAM_REGISTRATIONS_HPP\n#define HDL_GRAPH_SLAM_REGISTRATIONS_"
  },
  {
    "path": "include/radar_graph_slam/ros_time_hash.hpp",
    "chars": 466,
    "preview": "// SPDX-License-Identifier: BSD-2-Clause\n\n#ifndef ROS_TIME_HASH_HPP\n#define ROS_TIME_HASH_HPP\n\n#include <unordered_map>\n"
  },
  {
    "path": "include/radar_graph_slam/ros_utils.hpp",
    "chars": 5910,
    "preview": "// SPDX-License-Identifier: BSD-2-Clause\n\n#ifndef ROS_UTILS_HPP\n#define ROS_UTILS_HPP\n\n#include <Eigen/Dense>\n\n#include "
  },
  {
    "path": "include/rio_utils/data_types.h",
    "chars": 5852,
    "preview": "// This file is part of RIO - Radar Inertial Odometry and Radar ego velocity estimation.\n// Copyright (C) 2021  Christop"
  },
  {
    "path": "include/rio_utils/math_helper.h",
    "chars": 3731,
    "preview": "// This file is part of RIO - Radar Inertial Odometry and Radar ego velocity estimation.\n// Copyright (C) 2021  Christop"
  },
  {
    "path": "include/rio_utils/radar_point_cloud.h",
    "chars": 2064,
    "preview": "// This file is part of RIO - Radar Inertial Odometry and Radar ego velocity estimation.\n// Copyright (C) 2021  Christop"
  },
  {
    "path": "include/rio_utils/ros_helper.h",
    "chars": 1972,
    "preview": "// This file is part of RIO - Radar Inertial Odometry and Radar ego velocity estimation.\n// Copyright (C) 2021  Christop"
  },
  {
    "path": "include/rio_utils/simple_profiler.h",
    "chars": 3435,
    "preview": "// This file is part of RIO - Radar Inertial Odometry and Radar ego velocity estimation.\n// Copyright (C) 2021  Christop"
  },
  {
    "path": "include/rio_utils/strapdown.h",
    "chars": 1828,
    "preview": "// This file is part of RIO - Radar Inertial Odometry and Radar ego velocity estimation.\n// Copyright (C) 2021  Christop"
  },
  {
    "path": "include/scan_context/KDTreeVectorOfVectorsAdaptor.h",
    "chars": 5436,
    "preview": "/***********************************************************************\n * Software License Agreement (BSD License)\n *\n"
  },
  {
    "path": "include/scan_context/Scancontext.h",
    "chars": 5992,
    "preview": "#pragma once\n\n#include <ctime>\n#include <cassert>\n#include <cmath>\n#include <utility>\n#include <vector>\n#include <algori"
  },
  {
    "path": "include/scan_context/nanoflann.hpp",
    "chars": 73146,
    "preview": "/***********************************************************************\n * Software License Agreement (BSD License)\n *\n"
  },
  {
    "path": "include/scan_context/tictoc.h",
    "chars": 956,
    "preview": "// Author:   Tong Qin               qintonguav@gmail.com\n// \t         Shaozu Cao \t\t    saozu.cao@connect.ust.hk\n\n#pragma"
  },
  {
    "path": "include/utility_radar.h",
    "chars": 10670,
    "preview": "#pragma once\n#ifndef _UTILITY_RADAR_ODOMETRY_H_\n#define _UTILITY_RADAR_ODOMETRY_H_\n\n#include <ros/ros.h>\n\n#include <std_"
  },
  {
    "path": "launch/radar_graph_slam.launch",
    "chars": 11824,
    "preview": "<?xml version=\"1.0\"?>\n<launch>\n  <!-- Parameters -->\n  <rosparam file=\"$(find radar_graph_slam)/config/params.yaml\" comm"
  },
  {
    "path": "launch/rosbag_play_radar_carpark1.launch",
    "chars": 1115,
    "preview": "<!-- This launch file loads rosbags and makes an octomap file -->\n\n<launch>\n\n<!-- <param name=\"/use_sim_time\" value=\"tru"
  },
  {
    "path": "launch/rosbag_play_radar_carpark3.launch",
    "chars": 841,
    "preview": "<!-- This launch file loads rosbags and makes an octomap file -->\n\n<launch>\n\n<!-- <param name=\"/use_sim_time\" value=\"tru"
  },
  {
    "path": "launch/rosbag_play_radar_garden.launch",
    "chars": 1190,
    "preview": "<!-- This launch file loads rosbags and makes an octomap file -->\n\n<launch>\n\n<!-- <param name=\"/use_sim_time\" value=\"tru"
  },
  {
    "path": "launch/rosbag_play_radar_nanyanglink.launch",
    "chars": 852,
    "preview": "<!-- This launch file loads rosbags and makes an octomap file -->\n\n<launch>\n\n<!-- <param name=\"/use_sim_time\" value=\"tru"
  },
  {
    "path": "launch/rosbag_play_radar_ntuloop1.launch",
    "chars": 1142,
    "preview": "<!-- This launch file loads rosbags and makes an octomap file -->\n\n<launch>\n\n<!-- <param name=\"/use_sim_time\" value=\"tru"
  },
  {
    "path": "launch/rosbag_play_radar_ntuloop2.launch",
    "chars": 1026,
    "preview": "<!-- This launch file loads rosbags and makes an octomap file -->\n\n<launch>\n\n<!-- <param name=\"/use_sim_time\" value=\"tru"
  },
  {
    "path": "launch/rosbag_play_radar_ntuloop3.launch",
    "chars": 923,
    "preview": "<!-- This launch file loads rosbags and makes an octomap file -->\n\n<launch>\n\n<!-- <param name=\"/use_sim_time\" value=\"tru"
  },
  {
    "path": "launch/rosbag_play_radar_smoke.launch",
    "chars": 644,
    "preview": "<!-- This launch file loads rosbags and makes an octomap file -->\n\n<launch>\n\n<!-- <param name=\"/use_sim_time\" value=\"tru"
  },
  {
    "path": "msg/FloorCoeffs.msg",
    "chars": 32,
    "preview": "Header header\n\nfloat32[] coeffs\n"
  },
  {
    "path": "msg/ScanMatchingStatus.msg",
    "chars": 189,
    "preview": "Header header\n\nbool has_converged\nfloat32 matching_error\nfloat32 inlier_fraction\ngeometry_msgs/Pose relative_pose\n\nstd_m"
  },
  {
    "path": "nodelet_plugins.xml",
    "chars": 615,
    "preview": "<library path=\"lib/libpreprocessing_nodelet\">\n  <class name=\"radar_graph_slam/PreprocessingNodelet\" type=\"radar_graph_sl"
  },
  {
    "path": "package.xml",
    "chars": 1868,
    "preview": "<?xml version=\"1.0\"?>\n<package format=\"3\">\n  <name>radar_graph_slam</name>\n  <version>0.0.0</version>\n  <description>The"
  },
  {
    "path": "rviz/radar_graph_slam.rviz",
    "chars": 17011,
    "preview": "Panels:\n  - Class: rviz/Displays\n    Help Height: 0\n    Name: Displays\n    Property Tree Widget:\n      Expanded:\n       "
  },
  {
    "path": "setup.py",
    "chars": 311,
    "preview": "## ! DO NOT MANUALLY INVOKE THIS setup.py, USE CATKIN INSTEAD\n\nfrom setuptools import setup\nfrom catkin_pkg.python_setup"
  },
  {
    "path": "src/g2o/robust_kernel_io.cpp",
    "chars": 3803,
    "preview": "// SPDX-License-Identifier: BSD-2-Clause\n\n#include <g2o/robust_kernel_io.hpp>\n\n#include <fstream>\n#include <iostream>\n#i"
  },
  {
    "path": "src/gps_traj_align.cpp",
    "chars": 10891,
    "preview": "#include <stdio.h>\n\n#include <algorithm>\n#include <iostream>\n#include <fstream>\n#include <string>\n#include <vector>\n#inc"
  },
  {
    "path": "src/gt_adjust.cpp",
    "chars": 4065,
    "preview": "#include <stdio.h>\n\n#include <iostream>\n#include <fstream>\n#include <string>\n#include <vector>\n#include <boost/algorithm"
  },
  {
    "path": "src/radar_ego_velocity_estimator.cpp",
    "chars": 11839,
    "preview": "// This file is part of RIO - Radar Inertial Odometry and Radar ego velocity estimation.\n// Copyright (C) 2021  Christop"
  },
  {
    "path": "src/radar_graph_slam/Scancontext.cpp",
    "chars": 13482,
    "preview": "#include \"scan_context/Scancontext.h\"\n\n// namespace SC2\n// {\nusing namespace radar_graph_slam;\n\nvoid coreImportTest (voi"
  },
  {
    "path": "src/radar_graph_slam/__init__.py",
    "chars": 0,
    "preview": ""
  },
  {
    "path": "src/radar_graph_slam/bag_player.py",
    "chars": 6356,
    "preview": "#!/usr/bin/python\n# SPDX-License-Identifier: BSD-2-Clause\nimport sys\nimport yaml\nimport time\nimport curses\nimport argpar"
  },
  {
    "path": "src/radar_graph_slam/ford2bag.py",
    "chars": 2722,
    "preview": "#!/usr/bin/python\n# SPDX-License-Identifier: BSD-2-Clause\nimport re\nimport os\nimport sys\nimport struct\nimport numpy\nimpo"
  },
  {
    "path": "src/radar_graph_slam/graph_slam.cpp",
    "chars": 14536,
    "preview": "// SPDX-License-Identifier: BSD-2-Clause\n\n#include <radar_graph_slam/graph_slam.hpp>\n\n#include <boost/format.hpp>\n#inclu"
  },
  {
    "path": "src/radar_graph_slam/information_matrix_calculator.cpp",
    "chars": 3231,
    "preview": "// SPDX-License-Identifier: BSD-2-Clause\n\n#include <iostream>\n\n#include <radar_graph_slam/information_matrix_calculator."
  },
  {
    "path": "src/radar_graph_slam/keyframe.cpp",
    "chars": 4738,
    "preview": "// SPDX-License-Identifier: BSD-2-Clause\n\n#include <radar_graph_slam/keyframe.hpp>\n\n#include <boost/filesystem.hpp>\n\n#in"
  },
  {
    "path": "src/radar_graph_slam/loop_detector.cpp",
    "chars": 20343,
    "preview": "#include <radar_graph_slam/loop_detector.hpp>\n\nusing namespace std;\n\nEigen::Vector3d R2ypr_(const Eigen::Matrix3d& R) {\n"
  },
  {
    "path": "src/radar_graph_slam/map2odom_publisher.py",
    "chars": 1095,
    "preview": "#!/usr/bin/python\n# SPDX-License-Identifier: BSD-2-Clause\nimport tf\nimport rospy\nfrom geometry_msgs.msg import *\n\n\nclass"
  },
  {
    "path": "src/radar_graph_slam/map_cloud_generator.cpp",
    "chars": 1645,
    "preview": "// SPDX-License-Identifier: BSD-2-Clause\n\n#include <radar_graph_slam/map_cloud_generator.hpp>\n\n#include <pcl/octree/octr"
  },
  {
    "path": "src/radar_graph_slam/registrations.cpp",
    "chars": 7718,
    "preview": "// SPDX-License-Identifier: BSD-2-Clause\n\n#include <radar_graph_slam/registrations.hpp>\n\n#include <iostream>\n\n#include <"
  },
  {
    "path": "srv/DumpGraph.srv",
    "chars": 37,
    "preview": "\nstring destination\n---\nbool success\n"
  },
  {
    "path": "srv/SaveMap.srv",
    "chars": 64,
    "preview": "bool utm\nfloat32 resolution\nstring destination\n---\nbool success\n"
  }
]

About this extraction

This page contains the full source code of the zhuge2333/4DRadarSLAM GitHub repository, extracted and formatted as plain text for AI agents and large language models (LLMs). The extraction includes 79 files (508.8 KB), approximately 143.8k tokens, and a symbol index with 453 extracted functions, classes, methods, constants, and types. Use this with OpenClaw, Claude, ChatGPT, Cursor, Windsurf, or any other AI tool that accepts text input. You can copy the full output to your clipboard or download it as a .txt file.

Extracted by GitExtract — free GitHub repo to text converter for AI. Built by Nikandr Surkov.

Copied to clipboard!