Repository: ART-Robot-Release/racecar Branch: master Commit: d304e2498627 Files: 521 Total size: 73.7 MB Directory structure: gitextract_j53mpcyy/ ├── .catkin_workspace ├── README.md ├── install.sh └── src/ ├── art_driver/ │ ├── CMakeLists.txt │ ├── README │ ├── include/ │ │ └── art_racecar_driver.h │ ├── lib/ │ │ └── libart_driver.a │ ├── package.xml │ └── src/ │ └── art_racecar.cpp ├── art_imu/ │ ├── CMakeLists.txt │ ├── launch/ │ │ ├── imu.launch │ │ ├── imu_test.launch │ │ └── rviz.launch │ ├── package.xml │ ├── rviz/ │ │ └── imu.rviz │ └── src/ │ └── art_imu.cc ├── art_racecar/ │ ├── CMakeLists.txt │ ├── README.md │ ├── art_rviz.sh │ ├── cfg/ │ │ └── imu.cfg │ ├── launch/ │ │ ├── Run_car.launch │ │ ├── Run_gmapping.launch │ │ ├── amcl_nav.launch │ │ ├── car.launch │ │ ├── includes/ │ │ │ ├── amcl.launch.xml │ │ │ ├── art_car_tf.launch.xml │ │ │ ├── default_mapping.launch.xml │ │ │ ├── ls01g.launch.xml │ │ │ ├── rf2o.launch.xml │ │ │ └── rplidar.launch.xml │ │ ├── ls01g_lidar.launch │ │ ├── rviz.launch │ │ └── teleop_joy.launch │ ├── map/ │ │ ├── mymap.yaml │ │ └── test.yaml │ ├── package.xml │ ├── param/ │ │ ├── base_global_planner_params.yaml │ │ ├── dwa_local_planner_params.yaml │ │ ├── ekf_params.yaml │ │ ├── global_costmap_params.yaml │ │ ├── local_costmap_params.yaml │ │ └── move_base_params.yaml │ ├── rviz/ │ │ ├── amcl.rviz │ │ ├── gmapping.rviz │ │ └── test_laser.rviz │ ├── save_map.sh │ ├── src/ │ │ ├── ESC_calibration.py │ │ ├── PID.h │ │ ├── art_car_controller.cpp │ │ ├── art_car_controller.hpp │ │ ├── lib/ │ │ │ └── libart_controller.a │ │ ├── racecar_joy.py │ │ └── racecar_teleop.py │ ├── ssh.sh │ └── udev/ │ ├── README │ ├── art_init.sh │ ├── car.rules │ ├── imu.rules │ └── laser.rules ├── ls01g/ │ ├── CMakeLists.txt │ ├── Y.txt │ ├── launch/ │ │ ├── ls01g.launch │ │ ├── rviz.launch │ │ ├── rviz.rviz │ │ ├── talker2.launch │ │ ├── talker_shell.launch │ │ ├── test.launch │ │ └── test_ls01g.launch │ ├── package.xml │ ├── rviz/ │ │ ├── kobuki_rviz_viewer.rviz │ │ └── slam.rviz │ ├── scripts/ │ │ ├── LS01A.py │ │ ├── create_udev_rules.sh │ │ ├── delete_udev_rules.sh │ │ └── laser.rules │ ├── slam_launch/ │ │ ├── gmapping.launch │ │ ├── hectormapping.launch │ │ ├── karto.launch │ │ ├── karto_mapper_params.yaml │ │ └── viewer_rviz.launch │ └── src/ │ ├── main.cpp │ ├── uart_driver.cpp │ └── uart_driver.h ├── navigation_tutorials/ │ ├── README.md │ ├── laser_scan_publisher_tutorial/ │ │ ├── CMakeLists.txt │ │ ├── package.xml │ │ └── src/ │ │ └── laser_scan_publisher.cpp │ ├── navigation_stage/ │ │ ├── CMakeLists.txt │ │ ├── launch/ │ │ │ ├── move_base_amcl_10cm.launch │ │ │ ├── move_base_amcl_2.5cm.launch │ │ │ ├── move_base_amcl_5cm.launch │ │ │ ├── move_base_fake_localization_10cm.launch │ │ │ ├── move_base_fake_localization_2.5cm.launch │ │ │ ├── move_base_fake_localization_5cm.launch │ │ │ ├── move_base_gmapping_5cm.launch │ │ │ └── move_base_multi_robot.launch │ │ ├── move_base_config/ │ │ │ ├── amcl_node.xml │ │ │ ├── base_local_planner_params.yaml │ │ │ ├── costmap_common_params.yaml │ │ │ ├── dwa_local_planner_params.yaml │ │ │ ├── global_costmap_params.yaml │ │ │ ├── local_costmap_params.yaml │ │ │ ├── move_base.xml │ │ │ └── slam_gmapping.xml │ │ ├── multi_robot.rviz │ │ ├── package.xml │ │ ├── single_robot.rviz │ │ └── stage_config/ │ │ ├── maps/ │ │ │ ├── willow-full-0.025.pgm │ │ │ ├── willow-full-0.05.pgm │ │ │ └── willow-full.pgm │ │ └── worlds/ │ │ ├── willow-pr2-2.5cm.world │ │ ├── willow-pr2-5cm.world │ │ ├── willow-pr2-multi.world │ │ └── willow-pr2.world │ ├── navigation_tutorials/ │ │ ├── CMakeLists.txt │ │ └── package.xml │ ├── odometry_publisher_tutorial/ │ │ ├── CMakeLists.txt │ │ ├── package.xml │ │ └── src/ │ │ └── odometry_publisher.cpp │ ├── point_cloud_publisher_tutorial/ │ │ ├── CMakeLists.txt │ │ ├── package.xml │ │ └── src/ │ │ └── point_cloud_publisher.cpp │ ├── robot_setup_tf_tutorial/ │ │ ├── CMakeLists.txt │ │ ├── manifest.xml │ │ ├── package.xml │ │ └── src/ │ │ ├── tf_broadcaster.cpp │ │ └── tf_listener.cpp │ ├── roomba_stage/ │ │ ├── CMakeLists.txt │ │ ├── manifest.xml │ │ ├── maps/ │ │ │ ├── lse_arena.pgm │ │ │ └── lse_arena.yaml │ │ ├── move_base_lse_arena.launch │ │ ├── package.xml │ │ ├── params/ │ │ │ ├── amcl_roomba.launch │ │ │ ├── base_local_planner_params.yaml │ │ │ ├── costmap_common_params.yaml │ │ │ ├── global_costmap_params.yaml │ │ │ ├── local_costmap_params.yaml │ │ │ └── local_costmap_params_2.yaml │ │ ├── roomba_lse_arena.world │ │ └── roomba_stage.rviz │ └── simple_navigation_goals_tutorial/ │ ├── CMakeLists.txt │ ├── package.xml │ └── src/ │ └── simple_navigation_goals.cpp ├── rf2o_laser_odometry/ │ ├── CMakeLists.txt │ ├── LICENSE │ ├── README.md │ ├── cmake-build-debug/ │ │ ├── CATKIN_IGNORE │ │ ├── CMakeCache.txt │ │ ├── CMakeFiles/ │ │ │ ├── 3.9.6/ │ │ │ │ ├── CMakeCCompiler.cmake │ │ │ │ ├── CMakeCXXCompiler.cmake │ │ │ │ ├── CMakeSystem.cmake │ │ │ │ ├── CompilerIdC/ │ │ │ │ │ ├── CMakeCCompilerId.c │ │ │ │ │ └── a.out │ │ │ │ └── CompilerIdCXX/ │ │ │ │ ├── CMakeCXXCompilerId.cpp │ │ │ │ └── a.out │ │ │ ├── CMakeDirectoryInformation.cmake │ │ │ ├── CMakeError.log │ │ │ ├── CMakeOutput.log │ │ │ ├── CMakeRuleHashes.txt │ │ │ ├── Makefile.cmake │ │ │ ├── Makefile2 │ │ │ ├── Progress/ │ │ │ │ ├── 2 │ │ │ │ └── count.txt │ │ │ ├── TargetDirectories.txt │ │ │ ├── actionlib_generate_messages_cpp.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── actionlib_generate_messages_eus.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── actionlib_generate_messages_lisp.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── actionlib_generate_messages_nodejs.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── actionlib_generate_messages_py.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── actionlib_msgs_generate_messages_cpp.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── actionlib_msgs_generate_messages_eus.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── actionlib_msgs_generate_messages_lisp.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── actionlib_msgs_generate_messages_nodejs.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── actionlib_msgs_generate_messages_py.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── clean_test_results.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── clion-environment.txt │ │ │ ├── clion-log.txt │ │ │ ├── cmake.check_cache │ │ │ ├── download_extra_data.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── doxygen.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── feature_tests.c │ │ │ ├── feature_tests.cxx │ │ │ ├── geometry_msgs_generate_messages_cpp.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── geometry_msgs_generate_messages_eus.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── geometry_msgs_generate_messages_lisp.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── geometry_msgs_generate_messages_nodejs.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── geometry_msgs_generate_messages_py.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── nav_msgs_generate_messages_cpp.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── nav_msgs_generate_messages_eus.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── nav_msgs_generate_messages_lisp.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── nav_msgs_generate_messages_nodejs.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── nav_msgs_generate_messages_py.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── progress.marks │ │ │ ├── rf2o_laser_odometry_node.dir/ │ │ │ │ ├── CXX.includecache │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ ├── depend.internal │ │ │ │ ├── depend.make │ │ │ │ ├── flags.make │ │ │ │ ├── link.txt │ │ │ │ ├── progress.make │ │ │ │ └── src/ │ │ │ │ └── CLaserOdometry2D.cpp.o │ │ │ ├── roscpp_generate_messages_cpp.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── roscpp_generate_messages_eus.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── roscpp_generate_messages_lisp.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── roscpp_generate_messages_nodejs.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── roscpp_generate_messages_py.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── rosgraph_msgs_generate_messages_cpp.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── rosgraph_msgs_generate_messages_eus.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── rosgraph_msgs_generate_messages_lisp.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── rosgraph_msgs_generate_messages_nodejs.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── rosgraph_msgs_generate_messages_py.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── run_tests.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── sensor_msgs_generate_messages_cpp.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── sensor_msgs_generate_messages_eus.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── sensor_msgs_generate_messages_lisp.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── sensor_msgs_generate_messages_nodejs.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── sensor_msgs_generate_messages_py.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── std_msgs_generate_messages_cpp.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── std_msgs_generate_messages_eus.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── std_msgs_generate_messages_lisp.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── std_msgs_generate_messages_nodejs.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── std_msgs_generate_messages_py.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── tests.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── tf2_msgs_generate_messages_cpp.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── tf2_msgs_generate_messages_eus.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── tf2_msgs_generate_messages_lisp.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── tf2_msgs_generate_messages_nodejs.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── tf2_msgs_generate_messages_py.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── tf_generate_messages_cpp.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── tf_generate_messages_eus.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── tf_generate_messages_lisp.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ ├── tf_generate_messages_nodejs.dir/ │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ └── progress.make │ │ │ └── tf_generate_messages_py.dir/ │ │ │ ├── DependInfo.cmake │ │ │ ├── build.make │ │ │ ├── cmake_clean.cmake │ │ │ └── progress.make │ │ ├── CTestTestfile.cmake │ │ ├── Makefile │ │ ├── catkin/ │ │ │ └── catkin_generated/ │ │ │ └── version/ │ │ │ └── package.cmake │ │ ├── catkin_generated/ │ │ │ ├── env_cached.sh │ │ │ ├── generate_cached_setup.py │ │ │ ├── installspace/ │ │ │ │ ├── .rosinstall │ │ │ │ ├── _setup_util.py │ │ │ │ ├── env.sh │ │ │ │ ├── rf2o_laser_odometry.pc │ │ │ │ ├── rf2o_laser_odometryConfig-version.cmake │ │ │ │ ├── rf2o_laser_odometryConfig.cmake │ │ │ │ ├── setup.bash │ │ │ │ ├── setup.sh │ │ │ │ └── setup.zsh │ │ │ ├── ordered_paths.cmake │ │ │ ├── package.cmake │ │ │ ├── pkg.develspace.context.pc.py │ │ │ ├── pkg.installspace.context.pc.py │ │ │ ├── setup_cached.sh │ │ │ └── stamps/ │ │ │ └── rf2o_laser_odometry/ │ │ │ ├── _setup_util.py.stamp │ │ │ ├── interrogate_setup_dot_py.py.stamp │ │ │ ├── package.xml.stamp │ │ │ └── pkg.pc.em.stamp │ │ ├── cmake_install.cmake │ │ ├── devel/ │ │ │ ├── .catkin │ │ │ ├── .rosinstall │ │ │ ├── _setup_util.py │ │ │ ├── env.sh │ │ │ ├── lib/ │ │ │ │ └── pkgconfig/ │ │ │ │ └── rf2o_laser_odometry.pc │ │ │ ├── setup.bash │ │ │ ├── setup.sh │ │ │ ├── setup.zsh │ │ │ └── share/ │ │ │ └── rf2o_laser_odometry/ │ │ │ └── cmake/ │ │ │ ├── rf2o_laser_odometryConfig-version.cmake │ │ │ └── rf2o_laser_odometryConfig.cmake │ │ └── rf2o_laser_odometry.cbp │ ├── include/ │ │ └── rf2o_laser_odometry/ │ │ └── CLaserOdometry2D.h │ ├── launch/ │ │ └── rf2o_laser_odometry.launch │ ├── package.xml │ └── src/ │ └── CLaserOdometry2D.cpp └── robot_localization/ ├── CHANGELOG.rst ├── CMakeLists.txt ├── LICENSE ├── README.md ├── doc/ │ ├── .templates/ │ │ └── full_globaltoc.html │ ├── Makefile │ ├── conf.py │ ├── configuring_robot_localization.rst │ ├── index.rst │ ├── integrating_gps.rst │ ├── manifest.yaml │ ├── migrating_from_robot_pose_ekf.rst │ ├── navsat_transform_node.rst │ ├── preparing_sensor_data.rst │ └── state_estimation_nodes.rst ├── include/ │ └── robot_localization/ │ ├── ekf.h │ ├── filter_base.h │ ├── filter_common.h │ ├── filter_utilities.h │ ├── navsat_conversions.h │ ├── navsat_transform.h │ ├── robot_localization_estimator.h │ ├── ros_filter.h │ ├── ros_filter_types.h │ ├── ros_filter_utilities.h │ ├── ros_robot_localization_listener.h │ └── ukf.h ├── launch/ │ ├── dual_ekf_navsat_example.launch │ ├── ekf_template.launch │ ├── navsat_transform_template.launch │ └── ukf_template.launch ├── package.xml ├── params/ │ ├── dual_ekf_navsat_example.yaml │ ├── ekf_template.yaml │ ├── navsat_transform_template.yaml │ └── ukf_template.yaml ├── rosdoc.yaml ├── src/ │ ├── ekf.cpp │ ├── ekf_localization_node.cpp │ ├── filter_base.cpp │ ├── filter_utilities.cpp │ ├── navsat_transform.cpp │ ├── navsat_transform_node.cpp │ ├── robot_localization_estimator.cpp │ ├── robot_localization_listener_node.cpp │ ├── ros_filter.cpp │ ├── ros_filter_utilities.cpp │ ├── ros_robot_localization_listener.cpp │ ├── ukf.cpp │ └── ukf_localization_node.cpp ├── srv/ │ ├── GetState.srv │ ├── SetDatum.srv │ └── SetPose.srv └── test/ ├── record_all_stats.sh ├── stat_recorder.sh ├── test1.bag ├── test2.bag ├── test3.bag ├── test_ekf.cpp ├── test_ekf.test ├── test_ekf_localization_node_bag1.test ├── test_ekf_localization_node_bag2.test ├── test_ekf_localization_node_bag3.test ├── test_ekf_localization_node_interfaces.cpp ├── test_ekf_localization_node_interfaces.test ├── test_filter_base.cpp ├── test_filter_base_diagnostics_timestamps.cpp ├── test_filter_base_diagnostics_timestamps.test ├── test_localization_node_bag_pose_tester.cpp ├── test_robot_localization_estimator.cpp ├── test_robot_localization_estimator.test ├── test_ros_robot_localization_listener.cpp ├── test_ros_robot_localization_listener.test ├── test_ros_robot_localization_listener_publisher.cpp ├── test_ukf.cpp ├── test_ukf.test ├── test_ukf_localization_node_bag1.test ├── test_ukf_localization_node_bag2.test ├── test_ukf_localization_node_bag3.test ├── test_ukf_localization_node_interfaces.cpp └── test_ukf_localization_node_interfaces.test ================================================ FILE CONTENTS ================================================ ================================================ FILE: .catkin_workspace ================================================ # This file currently only serves to mark the location of a catkin workspace for tool integration ================================================ FILE: README.md ================================================ # art_racecar # art-racecar V1.0 2019.01.30 # art-racecar V1.1 2019.07.17 完善手柄遥控功能 ROS racecar ************************安装************************ cd ~/ git clone https://github.com/ART-Robot-Release/racecar cd racecar ./install.sh 配置小车串口udev: cd ~/racecar/src/art_racecar/udev sudo bash art_init.sh sudo reboot **********************建立地图********************** 先安装电脑用户名和主机名配置主从机 a) 运行车 roslaunch art_racecar Run_car.launch b) 3.3运行gmapping roslaunch art_racecar Run_gmapping.launch c) 3.4运行键盘控制 rosrun art_racecar racecar_teleop.py 或者手柄遥控 roslaunch art_racecar teleop_joy.launch d) 3.5.本地电脑打开rviz 本地电脑打开: source 工作空间 source art_racecar/art_rviz.sh roslaunch art_racecar rviz.launch e) 3.6 建立地图 键盘控制建立地图,按键如下: U I O J K L M , . 加减速为W,S. 手柄控制: L侧方向键:上下为加速减速,左右为转向幅度大小调节 R侧摇杆:控制小车运动 f) 保存地图(地图直接保存在小车上) 在art_racecar文件夹下执行:bash save_map.sh 地图保存在art_racecar/map/mymap.pgm 检查无误后,修改mymap.pgm替换为test.pgm ************************导航************************ a) SSH连接小车(Ubuntu系统为例)sz为小车用户名 ssh sz@192.168.5.101 b) 运行车 roslaunch art_racecar Run_car.launch c) 运行AMCL roslaunch art_racecar amcl_nav.launch d) .本地电脑打开rviz 本地电脑打开: source 工作空间 source art_racecar/art_rviz.sh roslaunch art_racecar rviz.launch e) 4.5 开始导航 在RVIZ中设定初始坐标,设定目标位置,开始导航 *********************软件接口*********************** 1.启动底盘 启动底盘需要启动rosserial_python节点。 设置参考art_racecar/launch/Run_car.launch 2.发布地盘控制指令: 通过发布Twist消息控制底盘。 线速度:twist.linear.x,这里的线速度范围为500~2500(对应PWM脉冲为0.5ms~2.5ms),1500为静止,1500-2500为正向速度,500-1500为反向速度。 角速度:twist.angular.x,这里角度范围为0~180度,90度为中间值,90-180度左转,0-90度右转。 3.里程计数据: 里程计采用激光雷达和IMU数据融合的里程计。 需要先启动IMU节点和雷达节点,参考art_racecar/launch/Run_car.launch 然后启动rf2o节点,用rf2o生成激光里程计,参考art_racecar/launch/includes/rf2o.launch.xml 再启动robot_localization用EKF融合里程计信息,参考art_racecar/launch/Run_gmapping.launch # Steven Zhang # 2019.01.30 ================================================ FILE: install.sh ================================================ #!/bin/bash # Varibles rosversion="kinetic" # Install the ros if [ `id -u` == 0 ]; then echo "Don't running this use root(sudo)." exit 0 fi echo "Start to install the ros, http://wiki.ros.org/$rosversion/Installation/Ubuntu" echo "Update the software list" sudo sh -c '. /etc/lsb-release && echo "deb http://mirrors.ustc.edu.cn/ros/ubuntu/ $DISTRIB_CODENAME main" > /etc/apt/sources.list.d/ros-latest.list' sudo apt-key adv --keyserver hkp://ha.pool.sks-keyservers.net:80 --recv-key C1CF6E31E6BADE8868B172B4F42ED6FBAB17C654 sudo apt-get update echo "Install the ros from apt" sudo apt-get install ros-$rosversion-desktop-full -y sudo rosdep init rosdep update echo "Setup the ROS environment variables" echo -e "if [ -f /opt/ros/kinetic/setup.bash ]; then\n\tsource /opt/ros/kinetic/setup.bash\nfi" >> ~/.bashrc echo "source ~/racecar/devel/setup.bash" >> ~/.bashrc source ~/.bashrc echo "Install the rosinstall" sudo apt-get install python-rosinstall -y echo "Install the ssh" sudo apt-get install ssh -y echo "Install the ntpdate" sudo apt-get install ntpdate -y echo "Install the chrony" sudo apt-get install chrony -y # Install the dependecies for the project echo "Start to config for the project" #echo "Install the python dependecies" #sudo apt-get install python-numpy python-scipy python-matplotlib ipython ipython-notebook python-pandas python-sympy python-nose -y #echo "Install the eigen3" #sudo apt install libeigen3-dev -y #echo "Install the nlopt" #sudo apt install libnlopt* -y echo "Install the ROS package for art_racecar" sudo apt-get install ros-$rosversion-joy -y sudo apt-get install ros-$rosversion-move-base -y sudo apt-get install ros-$rosversion-mrpt* -y sudo apt-get install ros-$rosversion-geographic-msgs -y sudo apt-get install ros-$rosversion-map-server -y sudo apt-get install ros-$rosversion-gmapping -y sudo apt-get install ros-$rosversion-amcl -y sudo apt-get install ros-$rosversion-rviz-imu-plugin -y sudo apt-get install ros-$rosversion-dwa-local-planner -y echo "--Finish" ================================================ FILE: src/art_driver/CMakeLists.txt ================================================ # Created by Steven Zhang on 18-12-29. # art racecar cmake_minimum_required(VERSION 2.8.3) project(art_driver) ## Compile as C++11, supported in ROS Kinetic and newer # add_compile_options(-std=c++11) ## Find catkin macros and libraries ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) ## is used, also find other catkin packages find_package(catkin REQUIRED COMPONENTS roscpp rospy std_msgs ) ## System dependencies are found with CMake's conventions # find_package(Boost REQUIRED COMPONENTS system) ## Uncomment this if the package has a setup.py. This macro ensures ## modules and global scripts declared therein get installed ## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html # catkin_python_setup() ################################################ ## Declare ROS messages, services and actions ## ################################################ ## To declare and build messages, services or actions from within this ## package, follow these steps: ## * Let MSG_DEP_SET be the set of packages whose message types you use in ## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). ## * In the file package.xml: ## * add a build_depend tag for "message_generation" ## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET ## * If MSG_DEP_SET isn't empty the following dependency has been pulled in ## but can be declared for certainty nonetheless: ## * add a run_depend tag for "message_runtime" ## * In this file (CMakeLists.txt): ## * add "message_generation" and every package in MSG_DEP_SET to ## find_package(catkin REQUIRED COMPONENTS ...) ## * add "message_runtime" and every package in MSG_DEP_SET to ## catkin_package(CATKIN_DEPENDS ...) ## * uncomment the add_*_files sections below as needed ## and list every .msg/.srv/.action file to be processed ## * uncomment the generate_messages entry below ## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) ## Generate messages in the 'msg' folder # add_message_files( # FILES # Message1.msg # Message2.msg # ) ## Generate services in the 'srv' folder # add_service_files( # FILES # Service1.srv # Service2.srv # ) ## Generate actions in the 'action' folder # add_action_files( # FILES # Action1.action # Action2.action # ) ## Generate added messages and services with any dependencies listed here # generate_messages( # DEPENDENCIES # std_msgs # ) ################################################ ## Declare ROS dynamic reconfigure parameters ## ################################################ ## To declare and build dynamic reconfigure parameters within this ## package, follow these steps: ## * In the file package.xml: ## * add a build_depend and a run_depend tag for "dynamic_reconfigure" ## * In this file (CMakeLists.txt): ## * add "dynamic_reconfigure" to ## find_package(catkin REQUIRED COMPONENTS ...) ## * uncomment the "generate_dynamic_reconfigure_options" section below ## and list every .cfg file to be processed ## Generate dynamic reconfigure parameters in the 'cfg' folder # generate_dynamic_reconfigure_options( # cfg/DynReconf1.cfg # cfg/DynReconf2.cfg # ) ################################### ## catkin specific configuration ## ################################### ## The catkin_package macro generates cmake config files for your package ## Declare things to be passed to dependent projects ## INCLUDE_DIRS: uncomment this if your package contains header files ## LIBRARIES: libraries you create in this project that dependent projects also need ## CATKIN_DEPENDS: catkin_packages dependent projects also need ## DEPENDS: system dependencies of this project that dependent projects also need catkin_package( # INCLUDE_DIRS include # LIBRARIES art_driver # CATKIN_DEPENDS roscpp rospy std_msgs # DEPENDS system_lib CATKIN_DEPENDS roscpp rospy std_msgs ) ########### ## Build ## ########### ## Specify additional locations of header files ## Your package locations should be listed before other locations include_directories( include ${catkin_INCLUDE_DIRS} ) ## Add cmake target dependencies of the library ## as an example, code may need to be generated before libraries ## either from message generation or dynamic reconfigure # add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) ## Declare a C++ executable ## With catkin_make all packages are built within a single CMake context ## The recommended prefix ensures that target names across packages don't collide add_executable(${PROJECT_NAME}_node src/art_racecar.cpp include/art_racecar_driver.h ) ## Rename C++ executable without prefix ## The above recommended prefix causes long target names, the following renames the ## target back to the shorter version for ease of user use ## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node" # set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "") ## Add cmake target dependencies of the executable ## same as for the library above # add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) ## Specify libraries to link a library or executable target against #find_library(./lib libart_driver.a) #link_directories(./lib/libart_driver.a) target_link_libraries(${PROJECT_NAME}_node ${catkin_LIBRARIES} ${PROJECT_SOURCE_DIR}/lib/libart_driver.a ) #target_link_libraries(${PROJECT_NAME}_node # # ${CMAKE_SOURCE_DIR}/lib/libart_driver.a -lm -ldl # # ) ############# ## Install ## ############# # all install targets should use catkin DESTINATION variables # See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html ## Mark executable scripts (Python etc.) for installation ## in contrast to setup.py, you can choose the destination # install(PROGRAMS # scripts/my_python_script # DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} # ) ## Mark executables and/or libraries for installation # install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_node # ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} # LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} # RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} # ) ## Mark cpp header files for installation # install(DIRECTORY include/${PROJECT_NAME}/ # DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} # FILES_MATCHING PATTERN "*.h" # PATTERN ".svn" EXCLUDE # ) ## Mark other files for installation (e.g. launch and bag files, etc.) # install(FILES # # myfile1 # # myfile2 # DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} # ) ############# ## Testing ## ############# ## Add gtest based cpp test target and link libraries # catkin_add_gtest(${PROJECT_NAME}-test test/test_art_driver.cpp) # if(TARGET ${PROJECT_NAME}-test) # target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) # endif() ## Add folders to be run by python nosetests # catkin_add_nosetests(test) ================================================ FILE: src/art_driver/README ================================================ /*******************************************************************/ /***************art_driverr*****************************************/ /*******************************************************************/ 这是art racecar的底层驱动例程 这个历程订阅/car/cmd_vel的twist的消息,发送给底层单片机 具体可以参考art_racecar.cpp 使用send_cmd()函数向单片机发送指令,函数参数分别为电机PWM和舵机PWM. PWM范围为500-2500us. /*********************************************北京钢铁侠科技 **********/ /*********************************************Steven Zhang ***********/ /*********************************************2018.12.29**************/ ================================================ FILE: src/art_driver/include/art_racecar_driver.h ================================================ // // Created by Steven Zhang on 18-12-14. // art racecar // #ifndef ART_RACECAR_DRIVER #define ART_RACECAR_DRIVER #include #include #if defined(__cplusplus) extern "C" { #endif int Open_Serial_Dev(char *dev); int art_racecar_init(int speed,char *dev);//设置波特率和串口设备 unsigned char send_cmd(uint16_t motor_pwm,uint16_t servo_pwm);//发送指令(电机PWM,舵机PWM),单位为us. #if defined(__cplusplus) } #endif #endif ================================================ FILE: src/art_driver/package.xml ================================================ art_driver 0.1.0 The art_car package zn TODO catkin roscpp rospy std_msgs roscpp rospy std_msgs roscpp rospy std_msgs ================================================ FILE: src/art_driver/src/art_racecar.cpp ================================================ // // Created by Steven Zhang on 18-12-14. // art racecar // #include "../include/art_racecar_driver.h" #include #include #include void TwistCallback(const geometry_msgs::Twist& twist) { double angle; //ROS_INFO("x= %f", twist.linear.x); //ROS_INFO("z= %f", twist.angular.z); angle = 2500.0 - twist.angular.z * 2000.0 / 180.0; //ROS_INFO("angle= %d",uint16_t(angle)); send_cmd(uint16_t(twist.linear.x),uint16_t(angle)); } int main(int argc, char** argv) { char data[] = "/dev/car"; art_racecar_init(38400,data); ros::init(argc, argv, "art_driver"); ros::NodeHandle n; ros::Subscriber sub = n.subscribe("/car/cmd_vel",1,TwistCallback); ros::spin(); } ================================================ FILE: src/art_imu/CMakeLists.txt ================================================ cmake_minimum_required(VERSION 2.8.3) project(art_imu) add_definitions(-std=c++11) find_package(catkin REQUIRED roscpp sensor_msgs tf cmake_modules) find_package(catkin REQUIRED COMPONENTS) include_directories(${catkin_INCLUDE_DIRS}) find_package(Eigen REQUIRED) catkin_package( ) add_executable(art_imu src/art_imu.cc ) target_link_libraries(art_imu ${catkin_LIBRARIES} ) ================================================ FILE: src/art_imu/launch/imu.launch ================================================ ================================================ FILE: src/art_imu/launch/imu_test.launch ================================================ ================================================ FILE: src/art_imu/launch/rviz.launch ================================================ ================================================ FILE: src/art_imu/package.xml ================================================ art_imu 0.1.0 The art_imu package Steven Zhang Steven Zhang BSD catkin roscpp sensor_msgs tf cmake_modules catkin roscpp sensor_msgs tf ================================================ FILE: src/art_imu/rviz/imu.rviz ================================================ Panels: - Class: rviz/Displays Help Height: 78 Name: Displays Property Tree Widget: Expanded: - /Global Options1 - /Imu1 - /Imu1/Box properties1 - /Imu1/Axes properties1 - /Imu1/Acceleration properties1 Splitter Ratio: 0.5 Tree Height: 655 - Class: rviz/Selection Name: Selection - Class: rviz/Tool Properties Expanded: - /2D Pose Estimate1 - /2D Nav Goal1 - /Publish Point1 Name: Tool Properties Splitter Ratio: 0.588679016 - Class: rviz/Views Expanded: - /Current View1 Name: Views Splitter Ratio: 0.5 - Class: rviz/Time Experimental: false Name: Time SyncMode: 0 SyncSource: "" Visualization Manager: Class: "" Displays: - Alpha: 0.5 Cell Size: 1 Class: rviz/Grid Color: 160; 160; 164 Enabled: true Line Style: Line Width: 0.0299999993 Value: Lines Name: Grid Normal Cell Count: 0 Offset: X: 0 Y: 0 Z: 0 Plane: XY Plane Cell Count: 10 Reference Frame: Value: true - Alpha: 1 Autocompute Intensity Bounds: true Autocompute Value Bounds: Max Value: 10 Min Value: -10 Value: true Axis: Z Channel Name: intensity Class: rviz/LaserScan Color: 255; 255; 255 Color Transformer: Intensity Decay Time: 0 Enabled: true Invert Rainbow: false Max Color: 255; 255; 255 Max Intensity: 2666 Min Color: 0; 0; 0 Min Intensity: 2 Name: LaserScan Position Transformer: XYZ Queue Size: 10 Selectable: true Size (Pixels): 3 Size (m): 0.0500000007 Style: Flat Squares Topic: /scan Unreliable: false Use Fixed Frame: true Use rainbow: true Value: true - Class: rviz/TF Enabled: true Frame Timeout: 15 Frames: All Enabled: true Marker Scale: 1 Name: TF Show Arrows: true Show Axes: true Show Names: true Tree: {} Update Interval: 0 Value: true - Acceleration properties: Acc. vector alpha: 1 Acc. vector color: 255; 0; 0 Acc. vector scale: 1 Derotate acceleration: true Enable acceleration: false Axes properties: Axes scale: 2 Enable axes: true Box properties: Box alpha: 1 Box color: 255; 0; 0 Enable box: true x_scale: 0.400000006 y_scale: 0.300000012 z_scale: 0.300000012 Class: rviz_imu_plugin/Imu Enabled: true Name: Imu Topic: /imu_data Unreliable: false Value: true fixed_frame_orientation: true Enabled: true Global Options: Background Color: 48; 48; 48 Default Light: true Fixed Frame: IMU_link Frame Rate: 30 Name: root Tools: - Class: rviz/Interact Hide Inactive Objects: true - Class: rviz/MoveCamera - Class: rviz/Select - Class: rviz/FocusCamera - Class: rviz/Measure - Class: rviz/SetInitialPose Topic: /initialpose - Class: rviz/SetGoal Topic: /move_base_simple/goal - Class: rviz/PublishPoint Single click: true Topic: /clicked_point Value: true Views: Current: Class: rviz/Orbit Distance: 19.7761364 Enable Stereo Rendering: Stereo Eye Separation: 0.0599999987 Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false Focal Point: X: 1.2478348 Y: -3.33640909 Z: 0.00110054587 Focal Shape Fixed Size: true Focal Shape Size: 0.0500000007 Invert Z Axis: false Name: Current View Near Clip Distance: 0.00999999978 Pitch: 1.56979632 Target Frame: Value: Orbit (rviz) Yaw: 3.04539394 Saved: ~ Window Geometry: Displays: collapsed: false Height: 936 Hide Left Dock: false Hide Right Dock: true QMainWindow State: 000000ff00000000fd00000004000000000000016a0000031efc020000000bfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006100fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c00610079007301000000280000031e000000d700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d00650072006100000001d1000000b50000000000000000fb0000000a0049006d0061006700650000000000ffffffff0000000000000000fb0000000a0049006d00610067006501000002ab00000113000000000000000000000001000001a30000025efc0200000004fb0000000a0049006d00610067006500000000280000025e0000000000000000fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a0056006900650077007300000000280000025e000000ad00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000005160000003efc0100000002fb0000000800540069006d00650100000000000005160000030000fffffffb0000000800540069006d00650100000000000004500000000000000000000003a60000031e00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 Selection: collapsed: false Time: collapsed: false Tool Properties: collapsed: false Views: collapsed: false Width: 1302 X: 538 Y: 105 ================================================ FILE: src/art_imu/src/art_imu.cc ================================================ #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include extern "C" { #include #include #include #include #include #include #include #include #include // close #include // strerror } using namespace std; static int data_length = 81; boost::asio::serial_port* serial_port = 0; static const uint8_t stop[6] = {0xA5, 0x5A, 0x04, 0x02, 0x06, 0xAA}; static const uint8_t mode[6] = {0xA5, 0x5A, 0x04, 0x01, 0x05, 0xAA}; static uint8_t data_raw[200]; static std::vector buffer_; static std::deque queue_; static std::string name, frame_id; static sensor_msgs::Imu msg; static sensor_msgs::MagneticField msg_mag; static sensor_msgs::NavSatFix msg_gps; static int fd_ = -1; static ros::Publisher pub, pub_mag, pub_gps; static uint8_t tmp[81]; static float d2f_acc(uint8_t a[2]) { int16_t acc = a[0]; acc = (acc << 8) | a[1]; return ((float) acc) / 16384.0f; } static float d2f_gyro(uint8_t a[2]) { int16_t acc = a[0]; acc = (acc << 8) | a[1]; return ((float) acc) / 32.8f; } static float d2f_mag(uint8_t a[2]) { int16_t acc = a[0]; acc = (acc << 8) | a[1]; return ((float) acc) / 1.0f; } static float d2f_euler(uint8_t a[2]) { int16_t acc = a[0]; acc = (acc << 8) | a[1]; return ((float) acc) / 10.0f; } static double d2f_latlon(uint8_t a[4]) { int64_t high = a[0]; high = (high << 8) | a[1]; int64_t low = a[2]; low = (low << 8) | a[3]; return (double)((high << 8) | low); } static double d2f_gpsvel(uint8_t a[2]) { int16_t acc = a[0]; acc = (acc << 8) | a[1]; return ((float) acc) / 10.0f; } static float d2ieee754(uint8_t a[4]) { union fnum { float f_val; uint8_t d_val[4]; } f; memcpy(f.d_val, a, 4); return f.f_val; } int uart_set(int fd, int baude, int c_flow, int bits, char parity, int stop) { struct termios options; if(tcgetattr(fd, &options) < 0) { perror("tcgetattr error"); return -1; } cfsetispeed(&options,B115200); cfsetospeed(&options,B115200); options.c_cflag |= CLOCAL; options.c_cflag |= CREAD; switch(c_flow) { case 0: options.c_cflag &= ~CRTSCTS; break; case 1: options.c_cflag |= CRTSCTS; break; case 2: options.c_cflag |= IXON|IXOFF|IXANY; break; default: fprintf(stderr,"Unkown c_flow!\n"); return -1; } switch(bits) { case 5: options.c_cflag &= ~CSIZE; options.c_cflag |= CS5; break; case 6: options.c_cflag &= ~CSIZE; options.c_cflag |= CS6; break; case 7: options.c_cflag &= ~CSIZE; options.c_cflag |= CS7; break; case 8: options.c_cflag &= ~CSIZE; options.c_cflag |= CS8; break; default: fprintf(stderr,"Unkown bits!\n"); return -1; } switch(parity) { case 'n': case 'N': options.c_cflag &= ~PARENB; options.c_cflag &= ~INPCK; break; case 's': case 'S': options.c_cflag &= ~PARENB; options.c_cflag &= ~CSTOPB; break; case 'o': case 'O': options.c_cflag |= PARENB; options.c_cflag |= PARODD; options.c_cflag |= INPCK; options.c_cflag |= ISTRIP; break; case 'e': case 'E': options.c_cflag |= PARENB; options.c_cflag &= ~PARODD; options.c_cflag |= INPCK; options.c_cflag |= ISTRIP; break; default: fprintf(stderr,"Unkown parity!\n"); return -1; } switch(stop) { case 1: options.c_cflag &= ~CSTOPB; break; case 2: options.c_cflag |= CSTOPB; break; default: fprintf(stderr,"Unkown stop!\n"); return -1; } options.c_oflag &= ~OPOST; options.c_lflag &= ~(ICANON | ECHO | ECHOE | ISIG); options.c_cc[VTIME] = 0; options.c_cc[VMIN] = 1; tcflush(fd,TCIFLUSH); if(tcsetattr(fd,TCSANOW,&options) < 0) { perror("tcsetattr failed"); return -1; } return 0; } int main(int argc, char** argv) { ros::init(argc, argv, "imu"); ros::NodeHandle n("~"); name = ros::this_node::getName(); std::string port; if (n.hasParam("port")) n.getParam("port", port); else { ROS_ERROR("%s: must provide a port", name.c_str()); return -1; } std::string model; if (n.hasParam("model")) n.getParam("model", model); else { ROS_ERROR("%s: must provide a model name", name.c_str()); return -1; } ROS_WARN("Model set to %s", model.c_str()); int baud; if (n.hasParam("baud")) n.getParam("baud", baud); else { ROS_ERROR("%s: must provide a baudrate", name.c_str()); return -1; } ROS_WARN("Baudrate set to %d", baud); n.param("frame_id", frame_id, string("IMU_link")); double delay; n.param("delay", delay, 0.0); boost::asio::io_service io_service; serial_port = new boost::asio::serial_port(io_service); try { serial_port->open(port); } catch (boost::system::system_error &error) { ROS_ERROR("%s: Failed to open port %s with error %s", name.c_str(), port.c_str(), error.what()); return -1; } if (!serial_port->is_open()) { ROS_ERROR("%s: failed to open serial port %s", name.c_str(), port.c_str()); return -1; } typedef boost::asio::serial_port_base sb; sb::baud_rate baud_option(baud); sb::flow_control flow_control(sb::flow_control::none); sb::parity parity(sb::parity::none); sb::stop_bits stop_bits(sb::stop_bits::one); serial_port->set_option(baud_option); serial_port->set_option(flow_control); serial_port->set_option(parity); serial_port->set_option(stop_bits); const char *path = port.c_str(); fd_ = open(path, O_RDWR); if(fd_ < 0) { ROS_ERROR("Port Error!: %s", path); return -1; } int kk = 0; double vyaw_sum = 0; double vyaw_bias = 0; pub = n.advertise("/imu_data", 1); pub_mag = n.advertise("mag", 1); pub_gps = n.advertise("gps", 1); if(model == "art_imu_02a") { write(fd_, stop, 6); usleep(1000 * 1000); write(fd_, mode, 6); usleep(1000 * 1000); data_length = 40; } ROS_WARN("Streaming Data..."); while (n.ok()) { read(fd_, tmp, sizeof(uint8_t) * data_length); memcpy(data_raw, tmp, sizeof(uint8_t) * data_length); bool found = false; for(kk = 0; kk < data_length - 1; ++kk) { if(model == "art_imu_02a" && data_raw[kk] == 0xA5 && data_raw[kk + 1] == 0x5A) { unsigned char *data = data_raw + kk; uint8_t data_length = data[2]; uint32_t checksum = 0; for(int i = 0; i < data_length - 1 ; ++i) { checksum += (uint32_t) data[i+2]; } uint16_t check = checksum % 256; uint16_t check_true = data[data_length+1]; if (check != check_true) { printf("check error,please wait\n"); continue; } Eigen::Vector3d ea0((-vyaw_bias-d2f_euler(data + 3)) * M_PI / 180.0, 0, 0); Eigen::Matrix3d R; R = Eigen::AngleAxisd(ea0[0], ::Eigen::Vector3d::UnitZ()) * Eigen::AngleAxisd(ea0[1], ::Eigen::Vector3d::UnitY()) * Eigen::AngleAxisd(ea0[2], ::Eigen::Vector3d::UnitX()); Eigen::Quaterniond q; q = R; msg.orientation.w = (double)q.w(); msg.orientation.x = (double)q.x(); msg.orientation.y = (double)q.y(); msg.orientation.z = (double)q.z(); msg.header.stamp = ros::Time::now(); msg.header.frame_id = frame_id; msg.angular_velocity.x = d2f_gyro(data + 15); msg.angular_velocity.y = d2f_gyro(data + 17); msg.angular_velocity.z = d2f_gyro(data + 19); msg.linear_acceleration.x = d2f_acc(data + 9) * 9.81; msg.linear_acceleration.y = d2f_acc(data + 11) * 9.81; msg.linear_acceleration.z = d2f_acc(data + 13) * 9.81; pub.publish(msg); msg_mag.magnetic_field.x = d2f_mag(data + 21); msg_mag.magnetic_field.y = d2f_mag(data + 23); msg_mag.magnetic_field.z = d2f_mag(data + 25); msg_mag.header.stamp = msg.header.stamp; msg_mag.header.frame_id = msg.header.frame_id; pub_mag.publish(msg_mag); found = true; } } } // Stop continous and close device ROS_WARN("Wait 0.1s"); ros::Duration(0.1).sleep(); ::close(fd_); return 0; } ================================================ FILE: src/art_racecar/CMakeLists.txt ================================================ cmake_minimum_required(VERSION 2.8.3) project(art_racecar) ## Compile as C++11, supported in ROS Kinetic and newer # add_compile_options(-std=c++11) ## Find catkin macros and libraries ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) ## is used, also find other catkin packages find_package(catkin REQUIRED COMPONENTS geometry_msgs sensor_msgs joy move_base tf roscpp rospy std_msgs visualization_msgs dynamic_reconfigure ) generate_dynamic_reconfigure_options(cfg/imu.cfg) #catkin_package(DEPENDS CATKIN DEPENDS dynamic_reconfigure) ## System dependencies are found with CMake's conventions # find_package(Boost REQUIRED COMPONENTS system) ## Uncomment this if the package has a setup.py. This macro ensures ## modules and global scripts declared therein get installed ## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html # catkin_python_setup() ################################################ ## Declare ROS messages, services and actions ## ################################################ ## To declare and build messages, services or actions from within this ## package, follow these steps: ## * Let MSG_DEP_SET be the set of packages whose message types you use in ## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). ## * In the file package.xml: ## * add a build_depend tag for "message_generation" ## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET ## * If MSG_DEP_SET isn't empty the following dependency has been pulled in ## but can be declared for certainty nonetheless: ## * add a run_depend tag for "message_runtime" ## * In this file (CMakeLists.txt): ## * add "message_generation" and every package in MSG_DEP_SET to ## find_package(catkin REQUIRED COMPONENTS ...) ## * add "message_runtime" and every package in MSG_DEP_SET to ## catkin_package(CATKIN_DEPENDS ...) ## * uncomment the add_*_files sections below as needed ## and list every .msg/.srv/.action file to be processed ## * uncomment the generate_messages entry below ## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) ## Generate messages in the 'msg' folder # add_message_files( # FILES # Message1.msg # Message2.msg # ) ## Generate services in the 'srv' folder # add_service_files( # FILES # Service1.srv # Service2.srv # ) ## Generate actions in the 'action' folder # add_action_files( # FILES # Action1.action # Action2.action # ) ## Generate added messages and services with any dependencies listed here # generate_messages( # DEPENDENCIES # std_msgs # ) ################################################ ## Declare ROS dynamic reconfigure parameters ## ################################################ ## To declare and build dynamic reconfigure parameters within this ## package, follow these steps: ## * In the file package.xml: ## * add a build_depend and a run_depend tag for "dynamic_reconfigure" ## * In this file (CMakeLists.txt): ## * add "dynamic_reconfigure" to ## find_package(catkin REQUIRED COMPONENTS ...) ## * uncomment the "generate_dynamic_reconfigure_options" section below ## and list every .cfg file to be processed ## Generate dynamic reconfigure parameters in the 'cfg' folder # generate_dynamic_reconfigure_options( # cfg/DynReconf1.cfg # cfg/DynReconf2.cfg # ) ################################### ## catkin specific configuration ## ################################### ## The catkin_package macro generates cmake config files for your package ## Declare things to be passed to dependent projects ## INCLUDE_DIRS: uncomment this if your package contains header files ## LIBRARIES: libraries you create in this project that dependent projects also need ## CATKIN_DEPENDS: catkin_packages dependent projects also need ## DEPENDS: system dependencies of this project that dependent projects also need catkin_package( # INCLUDE_DIRS include # LIBRARIES art_racecar CATKIN_DEPENDS roscpp rospy std_msgs # DEPENDS system_lib ) ########### ## Build ## ########### ## Specify additional locations of header files ## Your package locations should be listed before other locations include_directories( include ${catkin_INCLUDE_DIRS} ) ## Declare a C++ library # add_library(${PROJECT_NAME} # src/${PROJECT_NAME}/art_racecar.cpp # ) ## Add cmake target dependencies of the library ## as an example, code may need to be generated before libraries ## either from message generation or dynamic reconfigure # add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) ## Declare a C++ executable ## With catkin_make all packages are built within a single CMake context ## The recommended prefix ensures that target names across packages don't collide # add_executable(${PROJECT_NAME}_node src/art_racecar_node.cpp) ## Rename C++ executable without prefix ## The above recommended prefix causes long target names, the following renames the ## target back to the shorter version for ease of user use ## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node" # set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "") ## Add cmake target dependencies of the executable ## same as for the library above # add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) ## Specify libraries to link a library or executable target against # target_link_libraries(${PROJECT_NAME}_node # ${catkin_LIBRARIES} # ) ############# ## Install ## ############# # all install targets should use catkin DESTINATION variables # See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html ## Mark executable scripts (Python etc.) for installation ## in contrast to setup.py, you can choose the destination # install(PROGRAMS # scripts/my_python_script # DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} # ) ## Mark executables and/or libraries for installation # install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_node # ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} # LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} # RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} # ) ## Mark cpp header files for installation # install(DIRECTORY include/${PROJECT_NAME}/ # DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} # FILES_MATCHING PATTERN "*.h" # PATTERN ".svn" EXCLUDE # ) ## Mark other files for installation (e.g. launch and bag files, etc.) # install(FILES # # myfile1 # # myfile2 # DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} # ) ############# ## Testing ## ############# ## Add gtest based cpp test target and link libraries # catkin_add_gtest(${PROJECT_NAME}-test test/test_art_racecar.cpp) # if(TARGET ${PROJECT_NAME}-test) # target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) # endif() ## Add folders to be run by python nosetests # catkin_add_nosetests(test) install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} ) install(DIRECTORY src DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} ) add_executable(art_car_controller src/art_car_controller.cpp src/art_car_controller.hpp src/PID.h ) target_link_libraries(art_car_controller ${catkin_LIBRARIES} ${PROJECT_SOURCE_DIR}/src/lib/libart_controller.a ) #add_dependencies(art_car_controller art_car_generate_messages_cpp) ================================================ FILE: src/art_racecar/README.md ================================================ # art_racecar # art-racecar V1.0 2019.01.30 # art-racecar V1.1 2019.07.17 完善手柄遥控功能 ROS racecar ************************安装************************ cd ~/ git clone https://github.com/ART-Robot-Release/racecar cd racecar ./install.sh 配置小车串口udev: cd ~/racecar/src/art_racecar/udev sudo bash art_init.sh sudo reboot **********************建立地图********************** 先安装电脑用户名和主机名配置主从机 a) 运行车 roslaunch art_racecar Run_car.launch b) 3.3运行gmapping roslaunch art_racecar Run_gmapping.launch c) 3.4运行键盘控制 rosrun art_racecar racecar_teleop.py 或者手柄遥控 roslaunch art_racecar teleop_joy.launch d) 3.5.本地电脑打开rviz 本地电脑打开: source 工作空间 source art_racecar/art_rviz.sh roslaunch art_racecar rviz.launch e) 3.6 建立地图 键盘控制建立地图,按键如下: U I O J K L M , . 加减速为W,S. 手柄控制: L侧方向键:上下为加速减速,左右为转向幅度大小调节 R侧摇杆:控制小车运动 f) 保存地图(地图直接保存在小车上) 在art_racecar文件夹下执行:bash save_map.sh 地图保存在art_racecar/map/mymap.pgm 检查无误后,修改mymap.pgm替换为test.pgm ************************导航************************ a) SSH连接小车(Ubuntu系统为例)sz为小车用户名 ssh sz@192.168.5.101 b) 运行车 roslaunch art_racecar Run_car.launch c) 运行AMCL roslaunch art_racecar amcl_nav.launch d) .本地电脑打开rviz 本地电脑打开: source 工作空间 source art_racecar/art_rviz.sh roslaunch art_racecar rviz.launch e) 4.5 开始导航 在RVIZ中设定初始坐标,设定目标位置,开始导航 *********************软件接口*********************** 1.启动底盘 启动底盘需要启动rosserial_python节点。 设置参考art_racecar/launch/Run_car.launch 2.发布地盘控制指令: 通过发布Twist消息控制底盘。 线速度:twist.linear.x,这里的线速度范围为500~2500(对应PWM脉冲为0.5ms~2.5ms),1500为静止,1500-2500为正向速度,500-1500为反向速度。 角速度:twist.angular.x,这里角度范围为0~180度,90度为中间值,90-180度左转,0-90度右转。 3.里程计数据: 里程计采用激光雷达和IMU数据融合的里程计。 需要先启动IMU节点和雷达节点,参考art_racecar/launch/Run_car.launch 然后启动rf2o节点,用rf2o生成激光里程计,参考art_racecar/launch/includes/rf2o.launch.xml 再启动robot_localization用EKF融合里程计信息,参考art_racecar/launch/Run_gmapping.launch # Steven Zhang # 2019.01.30 ================================================ FILE: src/art_racecar/art_rviz.sh ================================================ #!/bin/bash #for open rviz and set ROS master ip #Steven.Zhang #2018.03.09 function get_ip_address { ifconfig | fgrep -v 127.0.0.1 | fgrep 'Mask:255.255.255.0' | egrep -o 'addr:[^ ]*' | fgrep '.8.'| sed 's/^.*://'; } #export ROS_IP=$(get_ip_address) export ROS_IP=`hostname -I` export ROS_MASTER_URI=http://192.168.5.101:11311 ##source ../devel/setup.bash #rosrun rviz rviz ================================================ FILE: src/art_racecar/cfg/imu.cfg ================================================ #!/usr/bin/env python PACKAGE = "art_racecar" from dynamic_reconfigure.parameter_generator_catkin import * gen = ParameterGenerator() gen.add("yaw_calibration", double_t, 0, "Yaw Calibration", 0, -10, 10) exit(gen.generate(PACKAGE, "art_racecar", "imu")) ================================================ FILE: src/art_racecar/launch/Run_car.launch ================================================ ================================================ FILE: src/art_racecar/launch/Run_gmapping.launch ================================================ ================================================ FILE: src/art_racecar/launch/amcl_nav.launch ================================================ ================================================ FILE: src/art_racecar/launch/car.launch ================================================ ================================================ FILE: src/art_racecar/launch/includes/amcl.launch.xml ================================================ ================================================ FILE: src/art_racecar/launch/includes/art_car_tf.launch.xml ================================================ ================================================ FILE: src/art_racecar/launch/includes/default_mapping.launch.xml ================================================ ================================================ FILE: src/art_racecar/launch/includes/ls01g.launch.xml ================================================    #设置激光数据topic名称    #激光坐标    #雷达连接的串口 # 设置为true探测不到区域会变成最大值 # true:探测不到区域为0,false:探测不到区域为inf # 角度制,从angle_disable_min到angle_disable_max之前的值为0 # 如果0度方向在串口线的方向上设置为true ================================================ FILE: src/art_racecar/launch/includes/rf2o.launch.xml ================================================ # topic where tu publish the odometry estimations # wheter or not to publish the tf::transform (base->odom) ================================================ FILE: src/art_racecar/launch/includes/rplidar.launch.xml ================================================ ================================================ FILE: src/art_racecar/launch/ls01g_lidar.launch ================================================ #设置激光数据topic名称 #激光坐标 #雷达连接的串口 # 设置为true探测不到区域会变成最大值 # true:探测不到区域为0,false:探测不到区域为inf # 角度制,从angle_disable_min到angle_disable_max之前的值为0 # 如果0度方向在串口线的方向上设置为true ================================================ FILE: src/art_racecar/launch/rviz.launch ================================================ ================================================ FILE: src/art_racecar/launch/teleop_joy.launch ================================================ ================================================ FILE: src/art_racecar/map/mymap.yaml ================================================ image: /home/art/racecar/src/art_racecar/map/mymap.pgm resolution: 0.050000 origin: [-100.000000, -100.000000, 0.000000] negate: 0 occupied_thresh: 0.65 free_thresh: 0.196 ================================================ FILE: src/art_racecar/map/test.yaml ================================================ image: test.pgm resolution: 0.050000 origin: [-100.000000, -100.000000, 0.000000] negate: 0 occupied_thresh: 0.65 free_thresh: 0.196 ================================================ FILE: src/art_racecar/package.xml ================================================ art_racecar 0.1.0 The art_racecar package Steven Zhang TODO catkin geometry_msgs joy move_base roscpp rospy std_msgs visualization_msgs tf sensor_msgs python-serial dynamic_reconfigure geometry_msgs move_base joy roscpp rospy std_msgs visualization_msgs tf tf sensor_msgs python-serial dynamic_reconfigure ================================================ FILE: src/art_racecar/param/base_global_planner_params.yaml ================================================ GlobalPlanner: allow_unknown: false # default_tolerance: 0.5 #路径规划器目标点的公差范围 # visualize_potential: true #指定是否通过可视化PointCloud2计算的潜在区域 # use_dijkstra: true #如果为ture,则使用dijkstra算法。 否则使用A *算法 # use_quadratic: true #二次逼近 # use_grid_path: true #如果为true,沿着栅格边界创建路径。 否则,使用梯度下降的方法。 # old_navfn_behavior: true #如果你想要global_planner准确反映navfn的行为,此项设置为true。 # lethal_cost: 25 # neutral_cost: 50 # cost_factor: 3 # publish_potential: True NavfnROS: allow_unknown: false ================================================ FILE: src/art_racecar/param/dwa_local_planner_params.yaml ================================================ DWAPlannerROS: acc_lim_th: 0.1 acc_lim_x: 0.5 acc_lim_y: 0.0 max_vel_x: 0.5 min_vel_x: 0.0 max_vel_y: 0.0 min_vel_y: 0.0 max_trans_vel: 0.5 min_trans_vel: 0.1 max_rot_vel: 0.2 min_rot_vel: 0.0 sim_time: 1.5 sim_granularity: 0.025 goal_distance_bias: 30.0 path_distance_bias: 20.0 occdist_scale: 0.01 forward_point_distance: 0.5 stop_time_buffer: 0.2 ####### scaling_speed: 0.5 ####### max_scaling_factor: 0.2 oscillation_reset_dist: 0.05 # vx_samples: 20 vy_samples: 0 vtheta_samples: 10 rot_stopped_vel: 0.01 trans_stopped_vel: 0.01 # xy_goal_tolerance: 0.2 yaw_goal_tolerance: 0.1 latch_xy_goal_tolerance: true #如果目标误差被锁定,若机器人达到目标XY位置,它将旋转到位,即使误差没有达到,也会做旋转 ================================================ FILE: src/art_racecar/param/ekf_params.yaml ================================================ frequency: 30 sensor_timeout: 0.025 two_d_mode: true transform_time_offset: 0.0001 transform_timeout: 0.025 print_diagnostics: true debug: false # Defaults to "robot_localization_debug.txt" if unspecified. Please specify the full path. debug_out_file: /path/to/debug/file.txt # Whether to broadcast the transformation over the /tf topic. Defaults to true if unspecified. publish_tf: true # Whether to publish the acceleration state. Defaults to false if unspecified. publish_acceleration: true map_frame: /map # Defaults to "map" if unspecified odom_frame: /odom # Defaults to "odom" if unspecified base_link_frame: /base_footprint # Defaults to "base_link" if unspecified world_frame: /odom # Defaults to the value of odom_frame if unspecified # The filter accepts an arbitrary number of inputs from each input message type (nav_msgs/Odometry, # geometry_msgs/PoseWithCovarianceStamped, geometry_msgs/TwistWithCovarianceStamped, # sensor_msgs/Imu). To add an input, simply append the next number in the sequence to its "base" name, e.g., odom0, # odom1, twist0, twist1, imu0, imu1, imu2, etc. The value should be the topic name. These parameters obviously have no # default values, and must be specified. odom0: /rf2o_laser_odometry/odom # Each sensor reading updates some or all of the filter's state. These options give you greater control over which # values from each measurement are fed to the filter. For example, if you have an odometry message as input, but only # want to use its Z position value, then set the entire vector to false, except for the third entry. The order of the # values is x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. Note that not some message types # do not provide some of the state variables estimated by the filter. For example, a TwistWithCovarianceStamped message # has no pose information, so the first six values would be meaningless in that case. Each vector defaults to all false # if unspecified, effectively making this parameter required for each sensor. odom0_config: [false, false, false, false, false, false, true, true, false, false, false, false, false, false, false] # If you have high-frequency data or are running with a low frequency parameter value, then you may want to increase # the size of the subscription queue so that more measurements are fused. odom0_queue_size: 5 # [ADVANCED] Large messages in ROS can exhibit strange behavior when they arrive at a high frequency. This is a result # of Nagle's algorithm. This option tells the ROS subscriber to use the tcpNoDelay option, which disables Nagle's # algorithm. odom0_nodelay: true # [ADVANCED] When measuring one pose variable with two sensors, a situation can arise in which both sensors under- # report their covariances. This can lead to the filter rapidly jumping back and forth between each measurement as they # arrive. In these cases, it often makes sense to (a) correct the measurement covariances, or (b) if velocity is also # measured by one of the sensors, let one sensor measure pose, and the other velocity. However, doing (a) or (b) isn't # always feasible, and so we expose the differential parameter. When differential mode is enabled, all absolute pose # data is converted to velocity data by differentiating the absolute pose measurements. These velocities are then # integrated as usual. NOTE: this only applies to sensors that provide pose measurements; setting differential to true # for twist measurements has no effect. odom0_differential: true # [ADVANCED] When the node starts, if this parameter is true, then the first measurement is treated as a "zero point" # for all future measurements. While you can achieve the same effect with the differential paremeter, the key # difference is that the relative parameter doesn't cause the measurement to be converted to a velocity before # integrating it. If you simply want your measurements to start at 0 for a given sensor, set this to true. odom0_relative: false # [ADVANCED] If your data is subject to outliers, use these threshold settings, expressed as Mahalanobis distances, to # control how far away from the current vehicle state a sensor measurement is permitted to be. Each defaults to # numeric_limits::max() if unspecified. It is strongly recommended that these parameters be removed if not # required. Data is specified at the level of pose and twist variables, rather than for each variable in isolation. # For messages that have both pose and twist data, the parameter specifies to which part of the message we are applying # the thresholds. odom0_pose_rejection_threshold: 8 odom0_twist_rejection_threshold: 0.75 imu0: /imu_data imu0_config: [false, false, false, false, false, true, false, false, false, false, false, false, false, false, false] imu0_nodelay: false imu0_differential: false imu0_relative: true imu0_queue_size: 8 imu0_pose_rejection_threshold: 0.8 # Note the difference in parameter names imu0_twist_rejection_threshold: 0.8 # imu0_linear_acceleration_rejection_threshold: 0.8 # # [ADVANCED] Some IMUs automatically remove acceleration due to gravity, and others don't. If yours doesn't, please set # this to true, and *make sure* your data conforms to REP-103, specifically, that the data is in ENU frame. imu0_remove_gravitational_acceleration: true # [ADVANCED] The process noise covariance matrix can be dgit@192.168.1.102:zhangnan/art_racecar.gitifficult to tune, and can vary for each application, so it is # exposed as a configuration parameter. This matrix represents the noise we add to the total error after each # prediction step. The better the omnidirectional motion model matches your system, the smaller these values can be. # However, if users find that a given variable is slow to converge, one approach is to increase the # process_noise_covariance diagonal value for the variable in question, which will cause the filter's predicted error # to be larger, which will cause the filter to trust the incoming measurement more during correction. The values are # ordered as x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. Defaults to the matrix below if # unspecified. process_noise_covariance: [0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.025, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.04, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.08, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.05, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.015] # [ADVANCED] This represents the initial value for the state estimate error covariance matrix. Setting a diagonal # value (variance) to a large value will result in rapid convergence for initial measurements of the variable in # question. Users should take care not to use large values for variables that will not be measured directly. The values # are ordered as x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. Defaults to the matrix below #if unspecified. initial_estimate_covariance: [1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9] ================================================ FILE: src/art_racecar/param/global_costmap_params.yaml ================================================ global_costmap: footprint: [[-0.305, -0.18], [-0.305, 0.18], [0.305, 0.18], [0.305, -0.18]] footprint_padding: 0.01 transform_tolerance: 0.5 update_frequency: 10.0 publish_frequency: 10.0 global_frame: /map robot_base_frame: /base_footprint resolution: 0.10 rolling_window: true width: 10.0 height: 10.0 track_unknown_space: false plugins: - {name: static, type: "costmap_2d::StaticLayer"} - {name: sensor, type: "costmap_2d::ObstacleLayer"} - {name: inflation, type: "costmap_2d::InflationLayer"} static: map_topic: /map subscribe_to_updates: true sensor: observation_sources: laser_scan_sensor laser_scan_sensor: {sensor_frame: laser, data_type: LaserScan, topic: scan, marking: true, clearing: true} inflation: inflation_radius: 0.1 cost_scaling_factor: 8.0 ================================================ FILE: src/art_racecar/param/local_costmap_params.yaml ================================================ local_costmap: footprint: [[-0.305, -0.18], [-0.305, 0.18], [0.305, 0.18], [0.305, -0.18]] footprint_padding: 0.01 transform_tolerance: 0.5 update_frequency: 10.0 publish_frequency: 10.0 global_frame: /odom robot_base_frame: /base_footprint resolution: 0.10 static_map: true rolling_window: true width: 10.0 height: 10.0 resolution: 0.05 track_unknown_space: false plugins: - {name: sensor, type: "costmap_2d::ObstacleLayer"} - {name: inflation, type: "costmap_2d::InflationLayer"} sensor: observation_sources: laser_scan_sensor laser_scan_sensor: {sensor_frame: laser, data_type: LaserScan, topic: scan, marking: true, clearing: true} inflation: inflation_radius: 0.1 cost_scaling_factor: 8.0 ================================================ FILE: src/art_racecar/param/move_base_params.yaml ================================================ # Move base node parameters. For full documentation of the parameters in this file, please see # # http://www.ros.org/wiki/move_base # shutdown_costmaps: false controller_frequency: 10.0 controller_patience: 3.0 planner_frequency: 10.0 planner_patience: 5.0 oscillation_timeout: 10.0 oscillation_distance: 0.2 clearing_rotation_allowed: false ================================================ FILE: src/art_racecar/rviz/amcl.rviz ================================================ Panels: - Class: rviz/Displays Help Height: 78 Name: Displays Property Tree Widget: Expanded: - /Global Options1 - /Imu1/Box properties1 Splitter Ratio: 0.5 Tree Height: 528 - Class: rviz/Selection Name: Selection - Class: rviz/Tool Properties Expanded: - /2D Pose Estimate1 - /2D Nav Goal1 - /Publish Point1 Name: Tool Properties Splitter Ratio: 0.588679016 - Class: rviz/Views Expanded: - /Current View1 Name: Views Splitter Ratio: 0.5 - Class: rviz/Time Experimental: false Name: Time SyncMode: 0 SyncSource: LaserScan Visualization Manager: Class: "" Displays: - Alpha: 0.5 Cell Size: 1 Class: rviz/Grid Color: 160; 160; 164 Enabled: true Line Style: Line Width: 0.0299999993 Value: Lines Name: Grid Normal Cell Count: 0 Offset: X: 0 Y: 0 Z: 0 Plane: XY Plane Cell Count: 100 Reference Frame: Value: true - Alpha: 0.699999988 Class: rviz/Map Color Scheme: map Draw Behind: false Enabled: true Name: Map Topic: /map Unreliable: false Use Timestamp: false Value: true - Alpha: 0.200000003 Class: rviz/Map Color Scheme: costmap Draw Behind: false Enabled: true Name: global_costmap Topic: /move_base/global_costmap/costmap Unreliable: false Use Timestamp: false Value: true - Alpha: 1 Autocompute Intensity Bounds: true Autocompute Value Bounds: Max Value: 10 Min Value: -10 Value: true Axis: Z Channel Name: intensity Class: rviz/LaserScan Color: 255; 255; 255 Color Transformer: Intensity Decay Time: 0 Enabled: true Invert Rainbow: false Max Color: 255; 255; 255 Max Intensity: 402 Min Color: 0; 0; 0 Min Intensity: 2 Name: LaserScan Position Transformer: XYZ Queue Size: 10 Selectable: true Size (Pixels): 3 Size (m): 0.0500000007 Style: Flat Squares Topic: /scan Unreliable: false Use Fixed Frame: true Use rainbow: true Value: true - Class: rviz/TF Enabled: true Frame Timeout: 15 Frames: All Enabled: true IMU_link: Value: true base_footprint: Value: true base_link: Value: true laser: Value: true map: Value: true odom: Value: true Marker Scale: 1 Name: TF Show Arrows: true Show Axes: true Show Names: true Tree: map: odom: base_footprint: base_link: IMU_link: {} laser: {} Update Interval: 0 Value: true - Alpha: 1 Buffer Length: 1 Class: rviz/Path Color: 25; 255; 0 Enabled: true Head Diameter: 0.300000012 Head Length: 0.200000003 Length: 0.300000012 Line Style: Lines Line Width: 0.0299999993 Name: Path Offset: X: 0 Y: 0 Z: 0 Pose Color: 255; 85; 255 Pose Style: None Radius: 0.0299999993 Shaft Diameter: 0.100000001 Shaft Length: 0.100000001 Topic: /move_base/NavfnROS/plan Unreliable: true Value: true - Angle Tolerance: 0.100000001 Class: rviz/Odometry Covariance: Orientation: Alpha: 0.5 Color: 255; 255; 127 Color Style: Unique Frame: Local Offset: 1 Scale: 1 Value: true Position: Alpha: 0.300000012 Color: 204; 51; 204 Scale: 1 Value: true Value: false Enabled: true Keep: 100 Name: Odometry Position Tolerance: 0.100000001 Shape: Alpha: 1 Axes Length: 1 Axes Radius: 0.100000001 Color: 255; 25; 0 Head Length: 0.300000012 Head Radius: 0.100000001 Shaft Length: 0.100000001 Shaft Radius: 0.0199999996 Value: Arrow Topic: /odometry/filtered Unreliable: false Value: true - Acceleration properties: Acc. vector alpha: 1 Acc. vector color: 255; 0; 0 Acc. vector scale: 1 Derotate acceleration: true Enable acceleration: false Axes properties: Axes scale: 1 Enable axes: true Box properties: Box alpha: 1 Box color: 255; 0; 0 Enable box: false x_scale: 0.400000006 y_scale: 0.300000012 z_scale: 0.300000012 Class: rviz_imu_plugin/Imu Enabled: false Name: Imu Topic: /imu_data Unreliable: false Value: false fixed_frame_orientation: true Enabled: true Global Options: Background Color: 48; 48; 48 Default Light: true Fixed Frame: map Frame Rate: 30 Name: root Tools: - Class: rviz/Interact Hide Inactive Objects: true - Class: rviz/MoveCamera - Class: rviz/Select - Class: rviz/FocusCamera - Class: rviz/Measure - Class: rviz/SetInitialPose Topic: /initialpose - Class: rviz/SetGoal Topic: /move_base_simple/goal - Class: rviz/PublishPoint Single click: true Topic: /clicked_point Value: true Views: Current: Class: rviz/Orbit Distance: 17.7873268 Enable Stereo Rendering: Stereo Eye Separation: 0.0599999987 Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false Focal Point: X: 1.2478348 Y: -3.33640909 Z: 0.00110054587 Focal Shape Fixed Size: true Focal Shape Size: 0.0500000007 Invert Z Axis: false Name: Current View Near Clip Distance: 0.00999999978 Pitch: 1.56979632 Target Frame: Value: Orbit (rviz) Yaw: 2.95539427 Saved: ~ Window Geometry: Displays: collapsed: false Height: 809 Hide Left Dock: false Hide Right Dock: true QMainWindow State: 000000ff00000000fd00000004000000000000016a0000029ffc020000000bfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006100fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c00610079007301000000280000029f000000d700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d00650072006100000001d1000000b50000000000000000fb0000000a0049006d0061006700650000000000ffffffff0000000000000000fb0000000a0049006d00610067006501000002ab00000113000000000000000000000001000001a30000025efc0200000004fb0000000a0049006d00610067006500000000280000025e0000000000000000fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a0056006900650077007300000000280000025e000000ad00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000005160000003efc0100000002fb0000000800540069006d00650100000000000005160000030000fffffffb0000000800540069006d00650100000000000004500000000000000000000003a60000029f00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 Selection: collapsed: false Time: collapsed: false Tool Properties: collapsed: false Views: collapsed: false Width: 1302 X: 519 Y: 235 ================================================ FILE: src/art_racecar/rviz/gmapping.rviz ================================================ Panels: - Class: rviz/Displays Help Height: 78 Name: Displays Property Tree Widget: Expanded: - /Global Options1 - /Status1 - /ekf_odom1/Shape1 - /rf2o_odom1/Shape1 Splitter Ratio: 0.5 Tree Height: 775 - Class: rviz/Selection Name: Selection - Class: rviz/Tool Properties Expanded: - /2D Pose Estimate1 - /2D Nav Goal1 - /Publish Point1 Name: Tool Properties Splitter Ratio: 0.588679016 - Class: rviz/Views Expanded: - /Current View1 Name: Views Splitter Ratio: 0.5 - Class: rviz/Time Experimental: false Name: Time SyncMode: 0 SyncSource: LaserScan Visualization Manager: Class: "" Displays: - Alpha: 0.5 Cell Size: 1 Class: rviz/Grid Color: 160; 160; 164 Enabled: true Line Style: Line Width: 0.0299999993 Value: Lines Name: Grid Normal Cell Count: 0 Offset: X: 0 Y: 0 Z: 0 Plane: XY Plane Cell Count: 10 Reference Frame: Value: true - Class: rviz/TF Enabled: true Frame Timeout: 15 Frames: All Enabled: true IMU_link: Value: true base_footprint: Value: true base_link: Value: true laser: Value: true map: Value: true odom: Value: true Marker Scale: 1 Name: TF Show Arrows: true Show Axes: true Show Names: true Tree: map: odom: base_footprint: base_link: IMU_link: {} laser: {} Update Interval: 0 Value: true - Alpha: 1 Autocompute Intensity Bounds: true Autocompute Value Bounds: Max Value: 10 Min Value: -10 Value: true Axis: Z Channel Name: intensity Class: rviz/LaserScan Color: 255; 255; 255 Color Transformer: Intensity Decay Time: 0 Enabled: true Invert Rainbow: false Max Color: 255; 255; 255 Max Intensity: 2390 Min Color: 0; 0; 0 Min Intensity: 3 Name: LaserScan Position Transformer: XYZ Queue Size: 10 Selectable: true Size (Pixels): 3 Size (m): 0.0500000007 Style: Flat Squares Topic: /scan Unreliable: false Use Fixed Frame: true Use rainbow: true Value: true - Alpha: 0.699999988 Class: rviz/Map Color Scheme: map Draw Behind: false Enabled: true Name: Map Topic: /map Unreliable: false Use Timestamp: false Value: true - Alpha: 1 Buffer Length: 1 Class: rviz/Path Color: 25; 255; 0 Enabled: true Head Diameter: 0.300000012 Head Length: 0.200000003 Length: 0.300000012 Line Style: Lines Line Width: 0.0299999993 Name: Path Offset: X: 0 Y: 0 Z: 0 Pose Color: 255; 85; 255 Pose Style: None Radius: 0.0299999993 Shaft Diameter: 0.100000001 Shaft Length: 0.100000001 Topic: /move_base/TrajectoryPlannerROS/global_plan Unreliable: false Value: true - Angle Tolerance: 0.100000001 Class: rviz/Odometry Covariance: Orientation: Alpha: 0.5 Color: 255; 255; 127 Color Style: Unique Frame: Local Offset: 1 Scale: 1 Value: true Position: Alpha: 0.300000012 Color: 204; 51; 204 Scale: 1 Value: true Value: false Enabled: true Keep: 500 Name: ekf_odom Position Tolerance: 0.100000001 Shape: Alpha: 1 Axes Length: 1 Axes Radius: 0.100000001 Color: 0; 0; 255 Head Length: 0.300000012 Head Radius: 0.100000001 Shaft Length: 0.200000003 Shaft Radius: 0.0500000007 Value: Arrow Topic: /odometry/filtered Unreliable: false Value: true - Angle Tolerance: 0.100000001 Class: rviz/Odometry Covariance: Orientation: Alpha: 0.5 Color: 255; 255; 127 Color Style: Unique Frame: Local Offset: 1 Scale: 1 Value: true Position: Alpha: 0.300000012 Color: 204; 51; 204 Scale: 1 Value: true Value: false Enabled: true Keep: 500 Name: rf2o_odom Position Tolerance: 0.100000001 Shape: Alpha: 1 Axes Length: 1 Axes Radius: 0.100000001 Color: 255; 25; 0 Head Length: 0.300000012 Head Radius: 0.100000001 Shaft Length: 0.200000003 Shaft Radius: 0.0500000007 Value: Arrow Topic: /rf2o_laser_odometry/odom Unreliable: false Value: true Enabled: true Global Options: Background Color: 48; 48; 48 Default Light: true Fixed Frame: map Frame Rate: 30 Name: root Tools: - Class: rviz/Interact Hide Inactive Objects: true - Class: rviz/MoveCamera - Class: rviz/Select - Class: rviz/FocusCamera - Class: rviz/Measure - Class: rviz/SetInitialPose Topic: /initialpose - Class: rviz/SetGoal Topic: /move_base_simple/goal - Class: rviz/PublishPoint Single click: true Topic: /clicked_point Value: true Views: Current: Class: rviz/Orbit Distance: 17.5254555 Enable Stereo Rendering: Stereo Eye Separation: 0.0599999987 Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false Focal Point: X: 0.00508546829 Y: -0.0301897526 Z: 0.0989120007 Focal Shape Fixed Size: true Focal Shape Size: 0.0500000007 Invert Z Axis: false Name: Current View Near Clip Distance: 0.00999999978 Pitch: 0.3878344 Target Frame: Value: Orbit (rviz) Yaw: 5.83341122 Saved: ~ Window Geometry: Displays: collapsed: false Height: 1056 Hide Left Dock: false Hide Right Dock: false QMainWindow State: 000000ff00000000fd00000004000000000000016a00000396fc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006100fffffffb0000001e0054006f006f006c002000500072006f0070006500720074006900650073020000019b000001b500000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000002800000396000000d700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d00650072006100000001d1000000b5000000000000000000000001000001a30000025efc0200000004fb0000000a0049006d00610067006500000000280000025e0000000000000000fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a0056006900650077007300000000280000025e000000ad00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073f0000003efc0100000002fb0000000800540069006d006501000000000000073f0000030000fffffffb0000000800540069006d00650100000000000004500000000000000000000005cf0000039600000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 Selection: collapsed: false Time: collapsed: false Tool Properties: collapsed: false Views: collapsed: false Width: 1855 X: 65 Y: 24 ================================================ FILE: src/art_racecar/rviz/test_laser.rviz ================================================ Panels: - Class: rviz/Displays Help Height: 78 Name: Displays Property Tree Widget: Expanded: - /Global Options1 - /Status1 - /Grid1 - /LaserScan1 - /Axes1 - /Axes1/Status1 - /TF1/Frames1 Splitter Ratio: 0.5 Tree Height: 490 - Class: rviz/Selection Name: Selection - Class: rviz/Tool Properties Expanded: - /2D Pose Estimate1 - /2D Nav Goal1 - /Publish Point1 Name: Tool Properties Splitter Ratio: 0.588679016 - Class: rviz/Views Expanded: - /Current View1 Name: Views Splitter Ratio: 0.5 - Class: rviz/Time Experimental: false Name: Time SyncMode: 0 SyncSource: LaserScan Visualization Manager: Class: "" Displays: - Alpha: 0.5 Cell Size: 1 Class: rviz/Grid Color: 160; 160; 164 Enabled: true Line Style: Line Width: 0.0299999993 Value: Lines Name: Grid Normal Cell Count: 0 Offset: X: 0 Y: 0 Z: 0 Plane: XY Plane Cell Count: 26 Reference Frame: Value: true - Alpha: 1 Autocompute Intensity Bounds: true Autocompute Value Bounds: Max Value: 10 Min Value: -10 Value: true Axis: Z Channel Name: intensity Class: rviz/LaserScan Color: 255; 255; 255 Color Transformer: Intensity Decay Time: 0 Enabled: true Invert Rainbow: false Max Color: 255; 255; 255 Max Intensity: 2319 Min Color: 0; 0; 0 Min Intensity: 2 Name: LaserScan Position Transformer: XYZ Queue Size: 10 Selectable: true Size (Pixels): 3 Size (m): 0.00999999978 Style: Points Topic: /scan Unreliable: false Use Fixed Frame: true Use rainbow: true Value: true - Class: rviz/Axes Enabled: true Length: 0.5 Name: Axes Radius: 0.0500000007 Reference Frame: Value: true - Class: rviz/TF Enabled: true Frame Timeout: 15 Frames: All Enabled: true Marker Scale: 1 Name: TF Show Arrows: true Show Axes: true Show Names: true Tree: {} Update Interval: 1 Value: true Enabled: true Global Options: Background Color: 48; 48; 48 Default Light: true Fixed Frame: laser Frame Rate: 30 Name: root Tools: - Class: rviz/Interact Hide Inactive Objects: true - Class: rviz/MoveCamera - Class: rviz/Select - Class: rviz/FocusCamera - Class: rviz/Measure - Class: rviz/SetInitialPose Topic: /initialpose - Class: rviz/SetGoal Topic: /move_base_simple/goal - Class: rviz/PublishPoint Single click: true Topic: /clicked_point Value: true Views: Current: Class: rviz/Orbit Distance: 10.5115833 Enable Stereo Rendering: Stereo Eye Separation: 0.0599999987 Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false Focal Point: X: 0 Y: 0 Z: 0 Focal Shape Fixed Size: true Focal Shape Size: 0.0500000007 Invert Z Axis: false Name: Current View Near Clip Distance: 0.00999999978 Pitch: 1.06979573 Target Frame: Value: Orbit (rviz) Yaw: 2.66859388 Saved: ~ Window Geometry: Displays: collapsed: false Height: 773 Hide Left Dock: false Hide Right Dock: false QMainWindow State: 000000ff00000000fd00000004000000000000017000000279fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006100fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000002800000279000000d700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000279fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000002800000279000000ad00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000054300000040fc0100000002fb0000000800540069006d00650100000000000005430000030000fffffffb0000000800540069006d00650100000000000004500000000000000000000002b80000027900000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 Selection: collapsed: false Time: collapsed: false Tool Properties: collapsed: false Views: collapsed: false Width: 1347 X: 152 Y: 136 ================================================ FILE: src/art_racecar/save_map.sh ================================================ #!/bin/bash rosrun map_server map_saver -f ~/racecar/src/art_racecar/map/mymap ================================================ FILE: src/art_racecar/src/ESC_calibration.py ================================================ #!/usr/bin/env python import rospy from geometry_msgs.msg import Twist import sys, select, termios, tty import time msg = "" def getKey(): tty.setraw(sys.stdin.fileno()) rlist, _, _ = select.select([sys.stdin], [], [], 0.1) if rlist: key = sys.stdin.read(1) else: key = '' termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings) return key def vels(speed,turn): return "currently:\tspeed %s\tturn %s " % (speed,turn) if __name__=="__main__": settings = termios.tcgetattr(sys.stdin) rospy.init_node('racecar_teleop') pub = rospy.Publisher('~/car/cmd_vel', Twist, queue_size=5) run = 0 try: while(1): key = getKey() twist = Twist() if key == '1': twist.linear.x = 1500; twist.linear.y = 0; twist.linear.z = 0 twist.angular.x = 0; twist.angular.y = 0; twist.angular.z = 90 print "vel = 0" elif key == '2': twist.linear.x = 2000; twist.linear.y = 0; twist.linear.z = 0 twist.angular.x = 0; twist.angular.y = 0; twist.angular.z = 90 print "vel = +Max" elif key == '3': twist.linear.x = 1000; twist.linear.y = 0; twist.linear.z = 0 twist.angular.x = 0; twist.angular.y = 0; twist.angular.z = 90 print "vel = -Max" else: twist.linear.x = 1500; twist.linear.y = 0; twist.linear.z = 0 twist.angular.x = 0; twist.angular.y = 0; twist.angular.z = 90 print "stop" pub.publish(twist) if (key == '\x03'): #for ctrl + c exit break except: print "error" finally: twist = Twist() twist.linear.x = speed_mid; twist.linear.y = 0; twist.linear.z = 0 twist.angular.x = 0; twist.angular.y = 0; twist.angular.z = turn_mid pub.publish(twist) termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings) ================================================ FILE: src/art_racecar/src/PID.h ================================================  #ifndef PID_H #define PID_H /***********************************/ typedef struct PID { //结构体定义 double SetPoint; //设定值 double Proportion; // Proportion 比例系数 double Integral; // Integral 积分系数 double Derivative; // Derivative 微分系数 double LastError; // Error[-1] 前一拍误差 double PreError; // Error[-2] 前两拍误差 }PID; void PIDInit (struct PID *pp); double PIDCal(struct PID *pp, double ThisError); #endif ================================================ FILE: src/art_racecar/src/art_car_controller.cpp ================================================ /* Copyright (c) 2017, ChanYuan KUO, YoRu LU, latest editor: HaoChih, LIN All rights reserved. (Hypha ROS Workshop) This file is part of hypha_racecar package. hypha_racecar is free software: you can redistribute it and/or modify it under the terms of the GNU LESSER GENERAL PUBLIC LICENSE as published by the Free Software Foundation, either version 3 of the License, or any later version. hypha_racecar 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 LESSER GENERAL PUBLIC LICENSE for more details. You should have received a copy of the GNU LESSER GENERAL PUBLIC LICENSE along with hypha_racecar. If not, see . */ #include #include "ros/ros.h" #include #include #include #include #include "nav_msgs/Path.h" #include #include #include "PID.h" #include "art_car_controller.hpp" #define PI 3.14159265358979 int start_loop_flag = 0; int start_speed = 1560; extern PID pid_speed; L1Controller::L1Controller() { //Private parameters handler ros::NodeHandle pn("~"); //Car parameter pn.param("L", L, 0.26); pn.param("Lrv", Lrv, 10.0); pn.param("Vcmd", Vcmd, 1.0); pn.param("lfw", lfw, 0.13); pn.param("lrv", lrv, 10.0); //Controller parameter pn.param("controller_freq", controller_freq, 20); pn.param("AngleGain", Angle_gain, -1.0); pn.param("GasGain", Gas_gain, 1.0); pn.param("baseSpeed", baseSpeed, 1575); pn.param("baseAngle", baseAngle, 90.0); //Publishers and Subscribers odom_sub = n_.subscribe("/odometry/filtered", 1, &L1Controller::odomCB, this); path_sub = n_.subscribe("/move_base_node/NavfnROS/plan", 1, &L1Controller::pathCB, this); goal_sub = n_.subscribe("/move_base_simple/goal", 1, &L1Controller::goalCB, this); marker_pub = n_.advertise("car_path", 10); pub_ = n_.advertise("car/cmd_vel", 1); //Timer timer1 = n_.createTimer(ros::Duration((1.0)/controller_freq), &L1Controller::controlLoopCB, this); // Duration(0.05) -> 20Hz timer2 = n_.createTimer(ros::Duration((0.5)/controller_freq), &L1Controller::goalReachingCB, this); // Duration(0.05) -> 20Hz //Init variables Lfw = goalRadius = getL1Distance(Vcmd); foundForwardPt = false; goal_received = false; goal_reached = false; cmd_vel.linear.x = 1500; // 1500 for stop cmd_vel.angular.z = baseAngle; //Show info ROS_INFO("[param] baseSpeed: %d", baseSpeed); ROS_INFO("[param] baseAngle: %f", baseAngle); ROS_INFO("[param] AngleGain: %f", Angle_gain); ROS_INFO("[param] Vcmd: %f", Vcmd); ROS_INFO("[param] Lfw: %f", Lfw); //Visualization Marker Settings initMarker(); car_stop = 0; } void L1Controller::goalReachingCB(const ros::TimerEvent&) { if(goal_received) { double car2goal_dist = getCar2GoalDist(); if(car2goal_dist < goalRadius) { goal_reached = true; goal_received = false; //ROS_INFO("Goal Reached !"); car_stop = 100; } } } void L1Controller::controlLoopCB(const ros::TimerEvent&) { int count = 100; geometry_msgs::Pose carPose = odom.pose.pose; geometry_msgs::Twist carVel = odom.twist.twist; cmd_vel.linear.x = 1500; cmd_vel.angular.z = baseAngle; if(goal_received) { /*Estimate Steering Angle*/ double eta = getEta(carPose); if(foundForwardPt) { cmd_vel.angular.z = baseAngle + getSteeringAngle(eta)*Angle_gain; /*Estimate Gas Input*/ if(!goal_reached) { if(start_loop_flag++ <= 10) { double u = getGasInput(carVel.linear.x); cmd_vel.linear.x = start_speed + PIDCal(&pid_speed,u); start_speed += 4; if(cmd_vel.linear.x > baseSpeed) cmd_vel.linear.x = baseSpeed; ROS_INFO("baseSpeed = %.2f\tSteering angle = %.2f",cmd_vel.linear.x,cmd_vel.angular.z); } else { //ROS_INFO("!goal_reached"); double u = getGasInput(carVel.linear.x); cmd_vel.linear.x = baseSpeed + PIDCal(&pid_speed,u); ROS_INFO("Gas = %.2f\tSteering angle = %.2f",cmd_vel.linear.x,cmd_vel.angular.z); } } } } if(car_stop > 0) { start_loop_flag = 0; if(carVel.linear.x > 0) { cmd_vel.linear.x = 1300; //反向刹车 pub_.publish(cmd_vel); // for(int i=0;i<20;i++) // { // pub_.publish(cmd_vel); // sleep(0.1); // ROS_INFO("cat stop cmd_vel= %f",cmd_vel.linear.x); // } } else { car_stop = 0; cmd_vel.linear.x = 1500; pub_.publish(cmd_vel); //ROS_INFO("cmd_vel= %f",cmd_vel.linear.x); } } else { pub_.publish(cmd_vel); car_stop = 0; //ROS_INFO("car run cmd_vel= %f",cmd_vel.linear.x); } } /*****************/ /* MAIN FUNCTION */ /*****************/ int main(int argc, char **argv) { //Initiate ROS ros::init(argc, argv, "art_car_controller"); L1Controller controller; controller.PID_init(); ros::spin(); return 0; } ================================================ FILE: src/art_racecar/src/art_car_controller.hpp ================================================ /********************/ /* CLASS DEFINITION */ /********************/ class L1Controller { public: L1Controller(); void initMarker(); bool isForwardWayPt(const geometry_msgs::Point& wayPt, const geometry_msgs::Pose& carPose); bool isWayPtAwayFromLfwDist(const geometry_msgs::Point& wayPt, const geometry_msgs::Point& car_pos); double getYawFromPose(const geometry_msgs::Pose& carPose); double getEta(const geometry_msgs::Pose& carPose); double getCar2GoalDist(); double getL1Distance(const double& _Vcmd); double getSteeringAngle(double eta); double getGasInput(const float& current_v); geometry_msgs::Point get_odom_car2WayPtVec(const geometry_msgs::Pose& carPose); void PID_init(); private: struct PID *speed_pid; ros::NodeHandle n_; ros::Subscriber odom_sub, path_sub, goal_sub; ros::Publisher pub_, marker_pub; ros::Timer timer1, timer2; tf::TransformListener tf_listener; visualization_msgs::Marker points, line_strip, goal_circle; geometry_msgs::Twist cmd_vel; geometry_msgs::Point odom_goal_pos; nav_msgs::Odometry odom; nav_msgs::Path map_path, odom_path; double L, Lfw, Lrv, Vcmd, lfw, lrv, steering, u, v; double Gas_gain, baseAngle, Angle_gain, goalRadius; int controller_freq, baseSpeed; bool foundForwardPt, goal_received, goal_reached; int car_stop; void odomCB(const nav_msgs::Odometry::ConstPtr& odomMsg); void pathCB(const nav_msgs::Path::ConstPtr& pathMsg); void goalCB(const geometry_msgs::PoseStamped::ConstPtr& goalMsg); void goalReachingCB(const ros::TimerEvent&); void controlLoopCB(const ros::TimerEvent&); }; // end of class ================================================ FILE: src/art_racecar/src/racecar_joy.py ================================================ #!/usr/bin/env python import rospy from geometry_msgs.msg import Twist from sensor_msgs.msg import Joy import sys, select, termios, tty import time msg = """ CTRL-C to quit """ global run global speed_add_once,turn_add_once,speed_mid,turn_mid,control_speed,control_turn,speed_max,turn_max,speed_min,turn_min global last_speed_add_once,last_turn_add_once def callback(data): twist = Twist() car_twist = Twist() global speed_add_once,turn_add_once global last_turn_add_once,last_speed_add_once if (data.buttons[6] == 1 or data.buttons[7] == 1): twist.linear.x = 0 twist.angular.z = 0 print("STOP!!") else: if(data.axes[5] != 0): if(last_speed_add_once == 0): speed_add_once = speed_add_once + data.axes[5] * 0.1 last_speed_add_once = 1 else: last_speed_add_once = 0 if(data.axes[4] != 0): if(last_turn_add_once == 0): turn_add_once = turn_add_once + data.axes[4] * 0.1 last_turn_add_once = 1 else: last_turn_add_once = 0 if(speed_add_once > 1): speed_add_once = 1 elif(speed_add_once < -1): speed_add_once = -1 if(turn_add_once > 1): turn_add_once = 1 elif(turn_add_once < -1): turn_add_once = -1 twist.linear.x = data.axes[3] * speed_add_once twist.angular.z = data.axes[2] * turn_add_once control_speed = (data.axes[3] * (speed_max - speed_min) * speed_add_once / 2 + speed_mid) if(control_speed > 1500): control_speed = control_speed + 30 elif(control_speed < 1500): control_speed = control_speed - 200 control_turn = (data.axes[2] * (turn_max - turn_min) * turn_add_once / 2 + turn_mid) #print('speed: %.2f, turn: %.2f'%(twist.linear.x,twist.angular.z)) car_twist.linear.x = control_speed car_twist.angular.z = control_turn print('speed: %.2f, turn: %.2f'%(control_speed,control_turn)) pub.publish(twist) pub_car.publish(car_twist) def vels(speed,turn): return "currently:\tspeed %s\tturn %s " % (speed,turn) def getKey(): tty.setraw(sys.stdin.fileno()) rlist, _, _ = select.select([sys.stdin], [], [], 0.1) if rlist: key = sys.stdin.read(1) else: key = '' termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings) return key if __name__=="__main__": settings = termios.tcgetattr(sys.stdin) speed_add_once = 0.25 turn_add_once = 0.5 speed_max = 1600 speed_min = 1400 speed_mid = 1500 turn_max = 180 turn_min = 0 turn_mid = (turn_max + turn_min)/2 control_speed = speed_mid control_turn = turn_mid global pub rospy.init_node('racecar_joy') pub = rospy.Publisher('~/cmd_vel', Twist, queue_size=5) pub_car = rospy.Publisher('~/car/cmd_vel', Twist, queue_size=5) try: while(1): key = getKey() rospy.Subscriber("joy", Joy, callback) rospy.spin() if (key == '\x03'): #for ctrl + c exit break except: print "error" finally: print "finally" twist = Twist() car_twist = Twist() twist.linear.x = 0; twist.linear.y = 0; twist.linear.z = 0 twist.angular.x = 0; twist.angular.y = 0; twist.angular.z = 0 pub.publish(twist) pub_car.publish(car_twist) termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings) ================================================ FILE: src/art_racecar/src/racecar_teleop.py ================================================ #!/usr/bin/env python import rospy from geometry_msgs.msg import Twist import sys, select, termios, tty import time msg = """ Control Your racecar! Reading from the keyboard and Publishing to Twist! --------------------------- Moving around: u i o j k l m , . For Holonomic mode (strafing), hold down the shift key: --------------------------- U I O J K L M < > space key, k : force stop w/x: shift the middle pos of throttle by +/- 5 pwm a/d: shift the middle pos of steering by +/- 2 pwm CTRL-C to quit """ moveBindings = { 'i':(1,0), 'o':(1,-1), 'j':(0,1), 'l':(0,-1), 'u':(1,1), ',':(-1,0), '.':(-1,-1), 'm':(-1,1), 'I':(1,0), 'O':(1,-1), 'J':(0,1), 'L':(0,-1), 'U':(1,1), '<':(-1,0), '>':(-1,-1), 'M':(-1,1), } def getKey(): tty.setraw(sys.stdin.fileno()) rlist, _, _ = select.select([sys.stdin], [], [], 0.1) if rlist: key = sys.stdin.read(1) else: key = '' termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings) return key def vels(speed,turn): return "currently:\tspeed %s\tturn %s " % (speed,turn) if __name__=="__main__": settings = termios.tcgetattr(sys.stdin) rospy.init_node('racecar_teleop') pub = rospy.Publisher('~/car/cmd_vel', Twist, queue_size=5) speed_start_value = 70 turn_start_value = 50 speed_mid = 1500 turn_mid = 90 speed_bias = 0 turn_bias = 0 speed_add_once = 5 turn_add_once = 2 control_speed = speed_mid control_turn = turn_mid speed_dir = 0 last_speed_dir = 0 last_turn_dir = 0 last_control_speed = control_speed last_control_turn = control_turn run = 0 try: while(1): key = getKey() twist = Twist() if key in moveBindings.keys(): run = 1 #print "key =",key speed_dir = moveBindings[key][0] if(speed_dir!=0 and speed_dir + last_speed_dir == 0):#Reverse control_speed = speed_mid last_speed_dir = speed_dir control_turn = turn_mid print "Reverse" else: if(speed_dir > 0): control_speed = speed_dir * (speed_start_value + speed_bias) + speed_mid elif(speed_dir < 0): control_speed = speed_dir * (speed_start_value + speed_bias) + speed_mid - 140 else: control_speed = 1500 control_turn = moveBindings[key][1] * (turn_start_value + turn_bias)+ turn_mid last_speed_dir = speed_dir #print " " #print "speed_dir = ",speed_dir #print "control_speed = ",control_speed #print "control_turn = ",control_turn last_control_speed = control_speed last_control_turn = control_turn elif key == ' ' or key == 'k' : speed_dir = -speed_dir #for ESC Forward/Reverse with brake mode control_speed = last_control_speed * speed_dir control_turn = turn_mid run = 0 elif key == 'w' : speed_bias += speed_add_once if(speed_bias >= 450): speed_bias = 450 else: last_control_speed = last_control_speed+speed_add_once run = 0 elif key == 's' : speed_bias -= speed_add_once last_control_speed = last_control_speed-speed_add_once if(speed_bias <= 0): speed_bias = 0 run = 0 elif key == 'a' : turn_bias += turn_add_once last_control_turn = last_control_turn+turn_add_once if(turn_bias >= 80): turn_bias = 80 run = 0 elif key == 'd' : turn_bias -= turn_add_once last_control_turn = last_control_turn-turn_add_once if(turn_bias <= 0): turn_bias = 0 run = 0 else: run = 0 print vels(control_speed,control_turn) #print "speed_dir=",speed_dir,"last_speed_dir",last_speed_dir if(run == 1): twist.linear.x = control_speed; twist.linear.y = 0; twist.linear.z = 0 twist.angular.x = 0; twist.angular.y = 0; twist.angular.z = control_turn #print "control_speed =",control_speed pub.publish(twist) else: twist.linear.x = speed_mid; twist.linear.y = 0; twist.linear.z = 0 twist.angular.x = 0; twist.angular.y = 0; twist.angular.z = turn_mid pub.publish(twist) if (key == '\x03'): #for ctrl + c exit break except: print "error" finally: twist = Twist() twist.linear.x = speed_mid; twist.linear.y = 0; twist.linear.z = 0 twist.angular.x = 0; twist.angular.y = 0; twist.angular.z = turn_mid pub.publish(twist) termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings) ================================================ FILE: src/art_racecar/ssh.sh ================================================ #!/bin/bash #for run artrobot #Steven.Zhang #2018.03.09 ssh sz@192.168.5.101 ================================================ FILE: src/art_racecar/udev/README ================================================ #添加ART_Racecar的USB设备,使用如下指令: sudo bash art_init.sh 然后重启电脑 ================================================ FILE: src/art_racecar/udev/art_init.sh ================================================ #!/bin/bash sudo cp ./car.rules /etc/udev/rules.d sudo cp ./laser.rules /etc/udev/rules.d sudo cp ./imu.rules /etc/udev/rules.d # exit 0 ================================================ FILE: src/art_racecar/udev/car.rules ================================================ # set the udev rule , make the device_port be fixed by arduino # KERNEL=="ttyUSB*", ATTRS{idVendor}=="1a86", ATTRS{idProduct}=="7523", MODE:="666", SYMLINK+="car" ================================================ FILE: src/art_racecar/udev/imu.rules ================================================ # set the udev rule , make the device_port be fixed by sanchi_imu # KERNEL=="ttyUSB*", ATTRS{idVendor}=="10c4", ATTRS{idProduct}=="ea60", ATTRS{serial}=="0001", MODE:="666", SYMLINK+="imu" ================================================ FILE: src/art_racecar/udev/laser.rules ================================================ # set the udev rule , make the device_port be fixed by ls-lidar # KERNEL=="ttyUSB*", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6001",MODE:="0666", SYMLINK+="laser" ================================================ FILE: src/ls01g/CMakeLists.txt ================================================ cmake_minimum_required(VERSION 2.8.3) project(ls01g) find_package(catkin REQUIRED COMPONENTS roscpp rospy std_msgs sensor_msgs ) catkin_package() include_directories( ${catkin_INCLUDE_DIRS}/src ) add_executable(ls01g src/main.cpp src/uart_driver.cpp) target_link_libraries(ls01g ${catkin_LIBRARIES}) install(TARGETS ls01g ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} ) install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} ) ================================================ FILE: src/ls01g/Y.txt ================================================ Stop the scan command: rostopic pub /startOrStop std_msgs/Int32 "data: 1" Stop the motor command(Stop the motor will stop scanning): rostopic pub /startOrStop std_msgs/Int32 "data: 2" Start scanning(Drive motor, and then open the scanning): rostopic pub /startOrStop std_msgs/Int32 "data: 4" ================================================ FILE: src/ls01g/launch/ls01g.launch ================================================ #设置激光数据topic名称 #激光坐标 #雷达连接的串口 # 设置为true探测不到区域会变成最大值 # true:探测不到区域为0,false:探测不到区域为inf # 角度制,从angle_disable_min到angle_disable_max之前的值为0 # 如果0度方向在串口线的方向上设置为true ================================================ FILE: src/ls01g/launch/rviz.launch ================================================ ================================================ FILE: src/ls01g/launch/rviz.rviz ================================================ Panels: - Class: rviz/Displays Help Height: 78 Name: Displays Property Tree Widget: Expanded: - /Global Options1 - /Status1 - /Grid1 - /Axes1 Splitter Ratio: 0.5 Tree Height: 765 - Class: rviz/Selection Name: Selection - Class: rviz/Tool Properties Expanded: - /2D Pose Estimate1 - /2D Nav Goal1 - /Publish Point1 Name: Tool Properties Splitter Ratio: 0.588679 - Class: rviz/Views Expanded: - /Current View1 Name: Views Splitter Ratio: 0.5 - Class: rviz/Time Experimental: false Name: Time SyncMode: 0 SyncSource: LaserScan Visualization Manager: Class: "" Displays: - Alpha: 0.5 Cell Size: 1 Class: rviz/Grid Color: 160; 160; 164 Enabled: true Line Style: Line Width: 0.03 Value: Lines Name: Grid Normal Cell Count: 0 Offset: X: 0 Y: 0 Z: 0 Plane: XY Plane Cell Count: 26 Reference Frame: Value: true - Alpha: 1 Autocompute Intensity Bounds: true Autocompute Value Bounds: Max Value: 10 Min Value: -10 Value: true Axis: Z Channel Name: intensity Class: rviz/LaserScan Color: 255; 255; 255 Color Transformer: Intensity Decay Time: 0 Enabled: true Invert Rainbow: false Max Color: 255; 255; 255 Max Intensity: 0 Min Color: 0; 0; 0 Min Intensity: 0 Name: LaserScan Position Transformer: XYZ Queue Size: 10 Selectable: true Size (Pixels): 3 Size (m): 0.01 Style: Points Topic: /scan Unreliable: false Use Fixed Frame: true Use rainbow: true Value: true - Class: rviz/Axes Enabled: true Length: 0.1 Name: Axes Radius: 0.05 Reference Frame: Value: true Enabled: true Global Options: Background Color: 48; 48; 48 Fixed Frame: laser_link Frame Rate: 30 Name: root Tools: - Class: rviz/Interact Hide Inactive Objects: true - Class: rviz/MoveCamera - Class: rviz/Select - Class: rviz/FocusCamera - Class: rviz/Measure - Class: rviz/SetInitialPose Topic: /initialpose - Class: rviz/SetGoal Topic: /move_base_simple/goal - Class: rviz/PublishPoint Single click: true Topic: /clicked_point Value: true Views: Current: Class: rviz/Orbit Distance: 15.7352 Enable Stereo Rendering: Stereo Eye Separation: 0.06 Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false Focal Point: X: 0 Y: 0 Z: 0 Name: Current View Near Clip Distance: 0.01 Pitch: 1.5698 Target Frame: Value: Orbit (rviz) Yaw: 3.14858 Saved: ~ Window Geometry: Displays: collapsed: false Height: 1056 Hide Left Dock: false Hide Right Dock: false QMainWindow State: 000000ff00000000fd00000004000000000000017000000391fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006600fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000002800000391000000e200fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000391fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000002800000391000000b800fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000078000000040fc0100000002fb0000000800540069006d00650100000000000007800000033b00fffffffb0000000800540069006d00650100000000000004500000000000000000000004f50000039100000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 Selection: collapsed: false Time: collapsed: false Tool Properties: collapsed: false Views: collapsed: false Width: 1920 X: 0 Y: 24 ================================================ FILE: src/ls01g/launch/talker2.launch ================================================    #设置激光数据topic名称    #激光坐标    #雷达连接的串口    #设置激光数据topic名称    #激光坐标    #雷达连接的串口    #设置激光数据topic名称    #激光坐标    #雷达连接的串口 ================================================ FILE: src/ls01g/launch/talker_shell.launch ================================================ ================================================ FILE: src/ls01g/launch/test.launch ================================================ #设置激光数据topic名称 #激光坐标 #雷达连接的串口 # 设置为true探测不到区域会变成最大值 # true:探测不到区域为0,false:探测不到区域为inf # 角度制,从angle_disable_min到angle_disable_max之前的值为0 # 如果0度方向在串口线的方向上设置为true ================================================ FILE: src/ls01g/launch/test_ls01g.launch ================================================    #设置激光数据topic名称    #激光坐标    #雷达连接的串口 # 设置为true探测不到区域会变成最大值 # true:探测不到区域为0,false:探测不到区域为inf # 角度制,从angle_disable_min到angle_disable_max之前的值为0 # 如果0度方向在串口线的方向上设置为true ================================================ FILE: src/ls01g/package.xml ================================================ ls01g 0.0.0 The ls01g laser package yutong TODO catkin roscpp rospy std_msgs roscpp rospy std_msgs ================================================ FILE: src/ls01g/rviz/kobuki_rviz_viewer.rviz ================================================ Panels: - Class: rviz/Displays Help Height: 78 Name: Displays Property Tree Widget: Expanded: - /Global Options1 - /Status1 - /LaserScan1 - /Axes1 - /Axes2 Splitter Ratio: 0.5 Tree Height: 727 - Class: rviz/Selection Name: Selection - Class: rviz/Tool Properties Expanded: - /2D Pose Estimate1 - /2D Nav Goal1 - /Publish Point1 Name: Tool Properties Splitter Ratio: 0.588679 - Class: rviz/Views Expanded: - /Current View1 Name: Views Splitter Ratio: 0.5 - Class: rviz/Time Experimental: false Name: Time SyncMode: 0 SyncSource: LaserScan Visualization Manager: Class: "" Displays: - Alpha: 0.5 Cell Size: 1 Class: rviz/Grid Color: 160; 160; 164 Enabled: true Line Style: Line Width: 0.03 Value: Lines Name: Grid Normal Cell Count: 0 Offset: X: 0 Y: 0 Z: 0 Plane: XY Plane Cell Count: 10 Reference Frame: Value: true - Alpha: 1 Autocompute Intensity Bounds: true Autocompute Value Bounds: Max Value: 10 Min Value: -10 Value: true Axis: Z Channel Name: intensity Class: rviz/LaserScan Color: 255; 255; 255 Color Transformer: Intensity Decay Time: 0 Enabled: true Invert Rainbow: false Max Color: 255; 255; 255 Max Intensity: 65122 Min Color: 0; 0; 0 Min Intensity: 1 Name: LaserScan Position Transformer: XYZ Queue Size: 10 Selectable: true Size (Pixels): 5 Size (m): 0.01 Style: Points Topic: /scan Unreliable: false Use Fixed Frame: true Use rainbow: true Value: true - Class: rviz/Axes Enabled: true Length: 0.15 Name: Axes Radius: 0.05 Reference Frame: laser_link Value: true - Alpha: 0.7 Class: rviz/Map Color Scheme: map Draw Behind: false Enabled: true Name: Map Topic: /map Unreliable: false Value: true - Class: rviz/Axes Enabled: true Length: 0.2 Name: Axes Radius: 0.1 Reference Frame: base_link Value: true Enabled: true Global Options: Background Color: 48; 48; 48 Fixed Frame: map Frame Rate: 30 Name: root Tools: - Class: rviz/Interact Hide Inactive Objects: true - Class: rviz/MoveCamera - Class: rviz/Select - Class: rviz/FocusCamera - Class: rviz/Measure - Class: rviz/SetInitialPose Topic: /initialpose - Class: rviz/SetGoal Topic: /move_base_simple/goal - Class: rviz/PublishPoint Single click: true Topic: /clicked_point Value: true Views: Current: Class: rviz/Orbit Distance: 30.5779 Enable Stereo Rendering: Stereo Eye Separation: 0.06 Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false Focal Point: X: -10.6774 Y: 1.87741 Z: -0.740706 Name: Current View Near Clip Distance: 0.01 Pitch: 1.4998 Target Frame: Value: Orbit (rviz) Yaw: 3.14359 Saved: ~ Window Geometry: Displays: collapsed: false Height: 1028 Hide Left Dock: false Hide Right Dock: false QMainWindow State: 000000ff00000000fd0000000400000000000001820000036ffc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006800fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c00610079007301000000280000036f000000e600fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c0000026100000001000001170000036ffc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a0056006900650077007301000000280000036f000000be00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073f00000044fc0100000002fb0000000800540069006d006501000000000000073f000003a700fffffffb0000000800540069006d006501000000000000045000000000000000000000049a0000036f00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 Selection: collapsed: false Time: collapsed: false Tool Properties: collapsed: false Views: collapsed: false Width: 1855 X: 5 Y: 14 ================================================ FILE: src/ls01g/rviz/slam.rviz ================================================ Panels: - Class: rviz/Displays Help Height: 78 Name: Displays Property Tree Widget: Expanded: - /Global Options1 - /Status1 - /RPLidarLaserScan1 Splitter Ratio: 0.5 Tree Height: 413 - Class: rviz/Selection Name: Selection - Class: rviz/Tool Properties Expanded: - /2D Pose Estimate1 - /2D Nav Goal1 Name: Tool Properties Splitter Ratio: 0.588679 - Class: rviz/Views Expanded: - /Current View1 Name: Views Splitter Ratio: 0.5 - Class: rviz/Time Experimental: false Name: Time SyncMode: 0 SyncSource: RPLidarLaserScan Visualization Manager: Class: "" Displays: - Alpha: 0.5 Cell Size: 1 Class: rviz/Grid Color: 160; 160; 164 Enabled: true Line Style: Line Width: 0.03 Value: Lines Name: Grid Normal Cell Count: 0 Offset: X: 0 Y: 0 Z: 0 Plane: XY Plane Cell Count: 10 Reference Frame: Value: true - Alpha: 1 Autocompute Intensity Bounds: true Autocompute Value Bounds: Max Value: 0 Min Value: 0 Value: true Axis: Z Channel Name: intensity Class: rviz/LaserScan Color: 255; 255; 255 Color Transformer: AxisColor Decay Time: 0 Enabled: true Invert Rainbow: false Max Color: 255; 255; 255 Max Intensity: 4096 Min Color: 0; 0; 0 Min Intensity: 0 Name: RPLidarLaserScan Position Transformer: XYZ Queue Size: 1000 Selectable: true Size (Pixels): 5 Size (m): 0.03 Style: Squares Topic: /scan Use Fixed Frame: true Use rainbow: true Value: true - Alpha: 0.7 Class: rviz/Map Color Scheme: map Draw Behind: false Enabled: true Name: Map Topic: /map Value: true Enabled: true Global Options: Background Color: 48; 48; 48 Fixed Frame: map Frame Rate: 30 Name: root Tools: - Class: rviz/MoveCamera - Class: rviz/Interact Hide Inactive Objects: true - Class: rviz/Select - Class: rviz/SetInitialPose Topic: /initialpose - Class: rviz/SetGoal Topic: /move_base_simple/goal Value: true Views: Current: Class: rviz/Orbit Distance: 11.1184 Enable Stereo Rendering: Stereo Eye Separation: 0.06 Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false Focal Point: X: -0.0344972 Y: 0.065886 Z: 0.148092 Name: Current View Near Clip Distance: 0.01 Pitch: 1.5698 Target Frame: Value: Orbit (rviz) Yaw: 5.66358 Saved: ~ Window Geometry: Displays: collapsed: false Height: 626 Hide Left Dock: false Hide Right Dock: false QMainWindow State: 000000ff00000000fd0000000400000000000001950000022cfc0200000006fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006400fffffffb0000001e0054006f006f006c002000500072006f0070006500720074006900650073020000019b000001b500000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c00610079007301000000280000022c000000dd00fffffffb0000000a0049006d006100670065000000028d000000c60000000000000000000000010000010b00000294fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003300000294000000b000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004a00000003efc0100000002fb0000000800540069006d00650000000000000004a0000002f600fffffffb0000000800540069006d00650100000000000004500000000000000000000003240000022c00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 Selection: collapsed: false Time: collapsed: false Tool Properties: collapsed: false Views: collapsed: false Width: 1215 X: 503 Y: 227 ================================================ FILE: src/ls01g/scripts/LS01A.py ================================================ #!/usr/bin/env python # -*- coding:utf-8 -*- import serial import math import time from array import * import rospy import numpy as np from sensor_msgs.msg import LaserScan d2r = (2 * math.pi) / 360.0 r2d = 360.0 / (2 * math.pi) pack_len = 1812 class ls01c: def __init__(self): # default parameters on parameter server self.angle_min = rospy.get_param('~/angle_min', -math.pi) self.angle_max = rospy.get_param('~/angle_max', math.pi) serial_baudrate = rospy.get_param('~/baudrate', 230400) serial_port = rospy.get_param('~/port', '/dev/laser') ScanPub = rospy.Publisher('scan', LaserScan, queue_size=5) ScanPub2 = rospy.Publisher('scan2', LaserScan, queue_size=5) angle_range1 = np.arange(0, -math.pi, math.radians(-1)) angle_range2 = np.arange(math.pi, 0, math.radians(-1)) self.angle_range = np.append(angle_range1, angle_range2) rospy.loginfo("laser is connected through port:%s and baudrate is %d" %(serial_port, serial_baudrate)) rospy.loginfo("min angle is :%f and max angle is %f" %(self.angle_min, self.angle_max)) rospy.on_shutdown(self.shutdown) header = [0xA5] ender = [0xE1, 0xAA, 0xBB, 0xCC, 0xDD] cmd_control = [0x3A] cmd_start = [0x2C] cmd_scan_continue = [0x20] cmd_scan_once = [0x22] cmd_stop = [0x21] cmd_stop_rot = [0x25] self.cmdstr_start = array("B", header + cmd_start + ender).tostring() self.cmdstr_control = array("B", header + cmd_control + ender).tostring() self.cmdstr_scan_continue = array("B", header + cmd_scan_continue + ender).tostring() self.cmdstr_scan_once = array("B", header + cmd_scan_once + ender).tostring() self.cmdstr_stop = array("B", header + cmd_stop + ender).tostring() self.cmdstr_stop_rot = array("B", header + cmd_stop_rot + ender).tostring() try: self.device = serial.Serial(serial_port, serial_baudrate, timeout=0.05) print("port opened successfully") except: print("Port failed open.\n" "Are you sure device is connected correctly?\n" "Please press (ctrl+c) and restart it after checked!" ) return time.sleep(0.2) #self.device.write(self.cmdstr_control) #time.sleep(3) self.device.write(self.cmdstr_start) time.sleep(0.2) #self.device.write(self.cmdstr_stop) ## make sure no data is sending #time.sleep(0.2) self.device.write(self.cmdstr_scan_continue) time.sleep(5) rospy.loginfo("lidar is ready!") print self.angle_min, self.angle_max cnt = 0 try: while not rospy.is_shutdown(): laser_distance, laser_angle = self.resolveData() rospy.loginfo_throttle(30, "return data length is %d --->> " "this message appear every 30s to check driver" % len(laser_distance)) if (cnt% 2== 0): self.ls_scan_pub(ScanPub, laser_distance, laser_angle) else: self.ls_scan_pub(ScanPub2, laser_distance, laser_angle) cnt += 1 rospy.sleep(0.01) except: pass rospy.logwarn("keyboard interrupt---> rosnode shutdown is requested!") self.LaserStop() def LaserStop(self): self.device.write(self.cmdstr_stop) time.sleep(0.2) self.device.write(self.cmdstr_stop_rot) time.sleep(0.2) print('Laser is stopped to send data and thread is stopped') def resolveData(self): buffer_len = self.device.inWaiting() if buffer_len >= (pack_len * 3): print("need to empty buffer") self.device.read(pack_len * (buffer_len / pack_len)) data = self.device.read(pack_len) cnt = 0 while len(data) != pack_len: cnt += 1 data_memst = self.device.read(pack_len - len(data)) data = data + data_memst print("timeout %d times to read data from laser" % cnt) if cnt >= 50: raise IOError # print "go" if (data[0] == '\xA5') and (data[6] == '\x81'): # print "found" print ord(data[1]) / 15.0 data_final = data[7:pack_len] pass else: while 1: data_check = self.device.read(1) if data_check != '\xA5': continue else: dat2 = self.device.read(6) if dat2[-1] != '\x81': continue else: data_final = self.device.read(pack_len - 7) print ord(data_final[-4]), ord(data_final[-1]) if (data_final[-4] == '\xAA') and (data_final[-1] == '\xDD'): break else: continue laser_distance = [0] * 360 laser_angle = [0] * 360 for i in range(360): laser_angle[i] = -(ord(data_final[2 + i * 5]) + ord(data_final[2 + i * 5]) * 256) / 10.0 * ((2 * math.pi) / 360.0) laser_distance[i] = (ord(data_final[3 + i * 5]) + ord(data_final[4 + i * 5]) * 256) / 1000.0 return laser_distance, laser_angle def shutdown(self): # Always stop the robot when shutting down the node rospy.loginfo("Stopping the laser...") # self.dev.LaserStop() def ls_scan_pub(self, pub, laser_distance1, laser_angle1): # distance data is from -pi to pi laser_distance1 = np.array(laser_distance1) scan_msg = LaserScan() point_num = 360.0 scan_msg.angle_max = self.angle_max # LS-lidar rotates clockwise, which is disobey right-hand rules for coordinate system scan_msg.angle_min = self.angle_min scan_msg.header.frame_id = 'base_laser_link' scan_msg.angle_increment = 2 * math.pi / point_num scan_msg.range_min = 0.15 scan_msg.range_max = 3.0 scan_msg.header.stamp = rospy.Time.now() # print("begin to select") if (self.angle_min > 0) or (self.angle_max <= 0): range_part = laser_distance1[(self.angle_range >= self.angle_min) & (self.angle_range <= self.angle_max)] scan_msg.ranges = np.flipud(range_part) else: range_part1 = laser_distance1[(self.angle_range >= self.angle_min) & (self.angle_range <= 0)] range_part2 = laser_distance1[(self.angle_range <= self.angle_max) & (self.angle_range > 0)] p1 = np.flipud(range_part1) p2 = np.flipud(range_part2) scan_msg.ranges = np.append(p1, p2) scan_msg.intensities = [255] * len(laser_distance1) pub.publish(scan_msg) if __name__ == '__main__': try: rospy.init_node('LeiShen_Lidar') rospy.loginfo("Leishen node is initialized!") print("Initialize node %s with Node_URI %s under namespace: %s" % (rospy.get_name(), rospy.get_node_uri(), rospy.get_namespace())) if rospy.get_namespace() != '/': rospy.logwarn("This node is contained under namespace %s, be careful" %rospy.get_namespace()) ls01c = ls01c() try: rospy.spin() # pass except: pass # rospy.logwarn("keyboard interrupt---> rosnode shutdown is requested!") except rospy.ROSInterruptException: rospy.logerr("Leishen node initialization failed!") ================================================ FILE: src/ls01g/scripts/create_udev_rules.sh ================================================ #!/bin/bash echo "remap the device serial port(ttyUSBX) to laser" echo "ls01g usb cp210x connection as /dev/laser , check it using the command : ls -l /dev|grep ttyUSB" echo "start copy laser.rules to /etc/udev/rules.d/" echo "`rospack find ls01g`/scripts/laser.rules" sudo cp `rospack find ls01g`/scripts/laser.rules /etc/udev/rules.d echo " " echo "Restarting udev" echo "" sudo service udev reload sudo service udev restart echo "finish " ================================================ FILE: src/ls01g/scripts/delete_udev_rules.sh ================================================ #!/bin/bash echo "delete remap the device serial port(ttyUSBX) to laser" echo "sudo rm /etc/udev/rules.d/laser.rules" sudo rm /etc/udev/rules.d/laser.rules echo " " echo "Restarting udev" echo "" sudo service udev reload sudo service udev restart echo "finish delete" ================================================ FILE: src/ls01g/scripts/laser.rules ================================================ # set the udev rule , make the device_port be fixed by ls-lidar # KERNEL=="ttyUSB*", ATTRS{idVendor}=="10c4", ATTRS{idProduct}=="ea60", MODE:="0777", SYMLINK+="laser" ================================================ FILE: src/ls01g/slam_launch/gmapping.launch ================================================ ================================================ FILE: src/ls01g/slam_launch/hectormapping.launch ================================================ ================================================ FILE: src/ls01g/slam_launch/karto.launch ================================================ ================================================ FILE: src/ls01g/slam_launch/karto_mapper_params.yaml ================================================ # General Parameters use_scan_matching: true use_scan_barycenter: true minimum_travel_distance: 0.3 minimum_travel_heading: 0.4 # 0.2 #in radians scan_buffer_size: 67 scan_buffer_maximum_scan_distance: 20.0 link_match_minimum_response_fine: 0.15 link_scan_maximum_distance: 6 # 6 do_loop_closing: true loop_match_minimum_chain_size: 5 loop_match_maximum_variance_coarse: 0.4 # gets squared later loop_match_minimum_response_coarse: 0.4 # 0.6 loop_match_minimum_response_fine: 0.6 # Correlation Parameters - Correlation Parameters correlation_search_space_dimension: 2 correlation_search_space_resolution: 0.05 correlation_search_space_smear_deviation: 0.05 # Correlation Parameters - Loop Closure Parameters loop_search_space_dimension: 10 # 2.8 loop_search_space_resolution: 0.1 loop_search_space_smear_deviation: 0.05 loop_search_maximum_distance: 4.0 # Scan Matcher Parameters distance_variance_penalty: 0.3 # gets squared later angle_variance_penalty: 0.35 # in degrees (gets converted to radians then squared) fine_search_angle_offset: 0.00349 # in degrees (gets converted to radians) coarse_search_angle_offset: 0.349 # in degrees (gets converted to radians) coarse_angle_resolution: 0.0349 # in degrees (gets converted to radians) minimum_angle_penalty: 0.9 minimum_distance_penalty: 0.5 use_response_expansion: false ================================================ FILE: src/ls01g/slam_launch/viewer_rviz.launch ================================================ ================================================ FILE: src/ls01g/src/main.cpp ================================================ #include #include #include "ros/ros.h" #include "std_msgs/String.h" #include "sensor_msgs/LaserScan.h" #include "uart_driver.h" using namespace std; bool is_scan_stop = false; bool is_motor_stop = false; bool zero_as_max = true; bool min_as_zero = true; bool inverted = true; string laser_link = "laser_link"; double angle_disable_min = -1; double angle_disable_max = -1; io_driver driver; void publish_scan(ros::Publisher *pub, double *dist, double *intensities, int count, ros::Time start, double scan_time) { static int scan_count = 0; sensor_msgs::LaserScan scan_msg; scan_msg.header.stamp = start; scan_msg.header.frame_id = laser_link; scan_count++; // scan_msg.angle_min = (angle_disable_min < 0) ? 0 : angle_disable_min; // scan_msg.angle_max = (angle_disable_max < 0) ? 2 * M_PI : angle_disable_max; scan_msg.angle_min = 0.0; scan_msg.angle_max = 2 * M_PI; scan_msg.angle_increment = (scan_msg.angle_max - scan_msg.angle_min) / (double) (count - 1); scan_msg.scan_time = scan_time; scan_msg.time_increment = scan_time / (double) (count - 1); scan_msg.range_min = 0.1; scan_msg.range_max = 10.0; scan_msg.intensities.resize(count); scan_msg.ranges.resize(count); if (!inverted) { for (int i = count - 1; i >= 0; i--) { if((i >= angle_disable_min) && (i < angle_disable_max)) // disable angle part { if (min_as_zero) scan_msg.ranges[i] = 0.0; else scan_msg.ranges[i] = std::numeric_limits::infinity(); } else if(dist[count - i - 1] == 0.0 && zero_as_max) scan_msg.ranges[i] = scan_msg.range_max - 0.2; else if(dist[count - i - 1] == 0.0) if (min_as_zero) scan_msg.ranges[i] = 0.0; else scan_msg.ranges[i] = std::numeric_limits::infinity(); else scan_msg.ranges[i] = dist[count - i - 1] / 1000.0; scan_msg.intensities[i] = floor(intensities[count - i - 1]); }} else { for (int i = 0; i <= 179; i++) { if((i >= angle_disable_min) && (i < angle_disable_max)) { if (min_as_zero) scan_msg.ranges[i] = 0.0; else scan_msg.ranges[i] = std::numeric_limits::infinity(); } else if(dist[179-i] == 0.0 && zero_as_max) scan_msg.ranges[i] = scan_msg.range_max - 0.2; else if(dist[179-i] == 0.0) if (min_as_zero) scan_msg.ranges[i] = 0.0; else scan_msg.ranges[i] = std::numeric_limits::infinity(); else scan_msg.ranges[i] = dist[179-i] / 1000.0; scan_msg.intensities[i] = floor(intensities[179-i]); } for (int i = 180; i < 360; i++) { if((i >= angle_disable_min) && (i < angle_disable_max)) { if (min_as_zero) scan_msg.ranges[i] = 0.0; else scan_msg.ranges[i] = std::numeric_limits::infinity(); } else if(dist[540-i] == 0.0 && zero_as_max) scan_msg.ranges[i] = scan_msg.range_max - 0.2; else if(dist[540-i] == 0.0) if (min_as_zero) scan_msg.ranges[i] = 0.0; else scan_msg.ranges[i] = std::numeric_limits::infinity(); else scan_msg.ranges[i] = dist[540-i] / 1000.0; scan_msg.intensities[i] = floor(intensities[540-i]); } } pub->publish(scan_msg); } void startStopCB(const std_msgs::Int32ConstPtr msg) { Command cmd = (Command) msg->data; switch (cmd) { case STOP_DATA: if (!is_scan_stop) { driver.StopScan(STOP_DATA); is_scan_stop = true; ROS_INFO("stop scan"); } break; case STOP_MOTOR: if (!is_scan_stop) { driver.StopScan(STOP_DATA); is_scan_stop = true; ROS_INFO("stop scan"); } if (!is_motor_stop) { driver.StopScan(STOP_MOTOR); is_motor_stop = true; ROS_INFO("stop motor"); } break; case START_MOTOR_AND_SCAN: if (is_scan_stop) { ROS_INFO("start scan"); int res = driver.StartScan(); ROS_INFO("start: %d", res); is_scan_stop = false; is_motor_stop = false; } break; default: ROS_WARN("Unkonw command: %d ", cmd); break; } } int main(int argv, char **argc) { ros::init(argv, argc, "ls01g"); ros::NodeHandle n; string scan_topic = "scan"; string port = "/dev/ttyUSB0"; ros::param::get("~scan_topic", scan_topic); ros::param::get("~laser_link", laser_link); ros::param::get("~serial_port", port); ros::param::get("~angle_disable_min", angle_disable_min); ros::param::get("~angle_disable_max", angle_disable_max); ros::param::get("~zero_as_max", zero_as_max); ros::param::get("~min_as_zero", min_as_zero); ros::param::get("~inverted", inverted); ros::Publisher scan_pub = n.advertise(scan_topic, 1000); ros::Subscriber stop_sub = n.subscribe("startOrStop", 10, startStopCB); int ret; ret = driver.OpenSerial(port.c_str(), B230400); if (ret < 0) { ROS_ERROR("could not open port:%s", port.c_str()); return 0; } else { ROS_INFO("open port:%s", port.c_str()); } if (inverted) { ROS_INFO("This laser is inverted, zero degree direction is align with line"); } driver.StartScan(); ROS_INFO("Send start command successfully"); double angle[PACKLEN + 10]; double distance[PACKLEN + 10]; double data[PACKLEN + 10]; double data_intensity[PACKLEN + 10]; double speed; int count = 0; ros::Time starts = ros::Time::now(); ros::Time ends = ros::Time::now(); ROS_INFO("talker...."); while (ros::ok()) { ros::spinOnce(); if (is_scan_stop) continue; // ROS_INFO_THROTTLE(2, "talker"); memset(data, 0, sizeof(data)); int ret = driver.GetScanData(angle, distance, PACKLEN, &speed); for (int i = 0; i < ret; i++) { data[i] = distance[i]; data_intensity[i] = angle[i]; } ROS_INFO_THROTTLE(30, "ls01g works fine!"); ends = ros::Time::now(); float scan_duration = (ends - starts).toSec() * 1e-3; publish_scan(&scan_pub, data, data_intensity, ret, starts, scan_duration); starts = ends; } driver.StopScan(STOP_DATA); driver.StopScan(STOP_MOTOR); driver.CloseSerial(); ROS_INFO("Keyboard Interrupt, ls01g stop!"); return 0; } ================================================ FILE: src/ls01g/src/uart_driver.cpp ================================================ #include "uart_driver.h" #define NO_SCAN 0 #define START_SCAN 1 #define STOP_SCAN 2 static pthread_t id; static int m_dFd; static pthread_mutex_t g_tMutex = PTHREAD_MUTEX_INITIALIZER; static pthread_cond_t g_tConVar = PTHREAD_COND_INITIALIZER; static double g_angle[PACKLEN]; static double g_distance[PACKLEN]; static int creatPthread = 1; static struct basedata *g_pcurr = NULL; static double g_speed; static int IS360; static int g_start_scan = NO_SCAN; //static struct wifides pack; #define DEBUG 0 #if DEBUG #define ALOGI(x...) printf( x) #else #define ALOGI(x...) #endif static int RestartGetData(void) { int wRet; char wificmd0[] = { 0xa5, 0x3A, 0xe1, 0xaa, 0xbb, 0xcc, 0xdd }; char wificmd1[] = { 0xa5, 0x2C, 0xe1, 0xaa, 0xbb, 0xcc, 0xdd }; char wificmd2[] = { 0xa5, 0x20, 0xe1, 0xaa, 0xbb, 0xcc, 0xdd }; ALOGI("--------start scan----------\n"); wRet = write(m_dFd, wificmd0, 7); if (wRet < 0) return wRet; usleep(5000000); wRet = write(m_dFd, wificmd1, 7); if (wRet < 0) return wRet; usleep(3000); wRet = write(m_dFd, wificmd2, 7); if (wRet < 0) return wRet; ALOGI("-------------end------------\n"); return 0; } static int Uart_parameter(unsigned char *data, double *angle, double *dist, int len) { int i, j; unsigned char *tmp; rplidar_response_measurement_node_t *curr; ALOGI("len = %d, data[] = %02x %d\n", len, data[len-1], IS360); if (data[0] == 0xA5 && data[6] == 0x81 && data[len - 1] == 0xdd) { //pthread_mutex_lock(&g_tMutex); //pthread_cond_signal(&g_tConVar); tmp = data + 7; g_speed = data[1] / 15.0; curr = (rplidar_response_measurement_node_t *) tmp; for (i = 7, j = 0; i < len - 4 && j < IS360; curr++, i += 5, j++) { ALOGI("%d ", curr->sync_quality);ALOGI("%d ", curr->angle_q6_checkbit); if (IS360 == 720) { //720 if (curr->angle_q6_checkbit != (j + 1) * 5) { if (curr->angle_q6_checkbit == (j + 2) * 5) { angle[j] = (j + 1) * 5 / 10.0; dist[j] = 0; j++; angle[j] = curr->angle_q6_checkbit / 10.0; dist[j] = curr->distance_q2 / 1.0; } else { break; } } else { angle[j] = curr->angle_q6_checkbit / 10.0; ALOGI("%d \n", curr->distance_q2); dist[j] = curr->distance_q2 / 1.0; } } else if (IS360 == 360) { angle[j] = curr->angle_q6_checkbit / 10.0; ALOGI("%d \n", curr->distance_q2); dist[j] = curr->distance_q2 / 1.0; } }ALOGI("j= %d\n", j); if (j >= IS360) { pthread_mutex_lock(&g_tMutex); pthread_cond_signal(&g_tConVar); j = 0; pthread_mutex_unlock(&g_tMutex); } return j; } else { return 0; } } static struct basedata *creatlist(void) { struct basedata *head; head = (struct basedata *) malloc(sizeof(struct basedata)); if (NULL == head) return NULL; head->flag = 0; head->start = 0; head->end = 0; head->curr = 0; head->next = NULL; return head; } static struct basedata *initlist(void) { struct basedata *head, *p; head = creatlist(); if (NULL == head) return NULL; p = creatlist(); if (NULL == p) { free(head); return NULL; } head->next = p; p->next = head; return head; } static int InitPackageSize() { if (1812 == PACKSIZE) { IS360 = 360; } else if (3611 == PACKSIZE) { IS360 = 720; } else { return -1; } return 0; } static void analysis(unsigned char *buf, int nRet) { unsigned char tempbuffer[2048]; int i, j; int clen = 0; if (nRet > 0) { if (!g_pcurr->start && !g_pcurr->flag) { for (i = 0; i < nRet - 6; i++) { if (buf[i] == 0xa5 && buf[i + 6] == 0x81) { break; } }ALOGI("i0 = %d\n", i); if (i >= nRet - 6) { memcpy(g_pcurr->data, buf + nRet - 6, 6); g_pcurr->flag = 1; g_pcurr->curr = 6; } else { memcpy(g_pcurr->data, buf + i, nRet - i); g_pcurr->start = 1; g_pcurr->flag = 1; g_pcurr->curr = nRet - i; } } else if (!g_pcurr->start && g_pcurr->flag) { memset(tempbuffer, 0, sizeof(tempbuffer)); memcpy(tempbuffer, g_pcurr->data, g_pcurr->curr); memcpy(tempbuffer + g_pcurr->curr, buf, nRet); clen = g_pcurr->curr + nRet; ALOGI("clen=%d,nRet=%d\n", clen,nRet); g_pcurr->start = 0; g_pcurr->end = 0; g_pcurr->flag = 0; g_pcurr->curr = 0; memset(g_pcurr->data, 0, PACKSIZE); for (i = 0; i < clen - 6; i++) { if (tempbuffer[i] == 0xa5 && tempbuffer[i + 6] == 0x81) { break; } }ALOGI("i1=%d\n", i); if (i >= clen - 6) { memcpy(g_pcurr->data, tempbuffer + clen - 6, 6); g_pcurr->flag = 1; g_pcurr->curr = 6; } else { if (clen - i < PACKSIZE) { memcpy(g_pcurr->data, tempbuffer + i, clen - i); g_pcurr->start = 1; g_pcurr->flag = 1; g_pcurr->curr = clen - i; } else if (clen - i == PACKSIZE) { memcpy(g_pcurr->data, tempbuffer + i, clen - i); g_pcurr->start = 1; g_pcurr->flag = 1; g_pcurr->end = 1; g_pcurr->curr += clen - i; } else { if (tempbuffer[i + PACKSIZE] == 0xa5) { memcpy(g_pcurr->data, tempbuffer + i, PACKSIZE); g_pcurr->start = 1; g_pcurr->flag = 1; g_pcurr->end = 1; g_pcurr->curr = PACKSIZE; g_pcurr = g_pcurr->next; g_pcurr->start = 0; g_pcurr->flag = 0; g_pcurr->end = 0; g_pcurr->curr = 0; memset(g_pcurr->data, 0, PACKSIZE); memcpy(g_pcurr->data, tempbuffer + i + PACKSIZE, clen - i - PACKSIZE); g_pcurr->start = 0; g_pcurr->flag = 1; g_pcurr->end = 0; g_pcurr->curr = clen - i - PACKSIZE; g_pcurr = g_pcurr->next; } else { memcpy(g_pcurr->data, tempbuffer + i + 1, clen - i - 1); g_pcurr->start = 0; g_pcurr->flag = 1; g_pcurr->curr = clen - i - 1; } } } } else if (g_pcurr->start && !g_pcurr->end) { for (i = 0; i < nRet - 6; i++) { if (buf[i] == 0xa5 && buf[i + 6] == 0x81) { break; } } ALOGI("i2=%d,nRet=%d\n",i,nRet); if (i >= nRet - 6) { if (g_pcurr->curr + i < PACKSIZE) { if (g_pcurr->curr + nRet < PACKSIZE) { memcpy(g_pcurr->data + g_pcurr->curr, buf, nRet); g_pcurr->curr += nRet; } else if (g_pcurr->curr + nRet == PACKSIZE) { memcpy(g_pcurr->data + g_pcurr->curr, buf, nRet); g_pcurr->curr += nRet; g_pcurr->end = 1; } else { clen = PACKSIZE - g_pcurr->curr; if (buf[clen] == 0xa5) { memcpy(g_pcurr->data + g_pcurr->curr, buf, clen); g_pcurr->end = 1; g_pcurr->curr += clen; g_pcurr = g_pcurr->next; g_pcurr->start = 0; g_pcurr->end = 0; g_pcurr->flag = 0; memset(g_pcurr->data, 0, PACKSIZE); memcpy(g_pcurr->data, buf + clen, nRet - clen); g_pcurr->start = 0; g_pcurr->curr = nRet - clen; g_pcurr->end = 0; g_pcurr->flag = 1; g_pcurr = g_pcurr->next; } else { g_pcurr->start = 0; g_pcurr->end = 0; g_pcurr->flag = 0; memset(g_pcurr->data, 0, PACKSIZE); memcpy(g_pcurr->data, buf + nRet - 3, 3); g_pcurr->start = 0; g_pcurr->flag = 1; g_pcurr->curr = 3; } } } // else if (g_pcurr->curr + i == PACKSIZE) { if (buf[i] == 0xa5) { memcpy(g_pcurr->data + g_pcurr->curr, buf, i); g_pcurr->curr += i; g_pcurr->end = 1; g_pcurr = g_pcurr->next; g_pcurr->start = 0; g_pcurr->end = 0; g_pcurr->flag = 0; memset(g_pcurr->data, 0, PACKSIZE); memcpy(g_pcurr->data, buf + i, nRet - i); g_pcurr->start = 0; /* no start*/ g_pcurr->flag = 1; g_pcurr->curr = nRet - i; g_pcurr = g_pcurr->next; } else { g_pcurr->start = 0; g_pcurr->end = 0; g_pcurr->flag = 0; memset(g_pcurr->data, 0, PACKSIZE); memcpy(g_pcurr->data, buf + nRet - 6, 6); g_pcurr->start = 0; g_pcurr->flag = 1; g_pcurr->curr = 6; } } else { //(g_pcurr->curr+i > PACKSIZE) g_pcurr->start = 0; g_pcurr->end = 0; g_pcurr->flag = 0; memset(g_pcurr->data, 0, PACKSIZE); memcpy(g_pcurr->data, buf + nRet - 6, 6); g_pcurr->start = 0; g_pcurr->flag = 1; g_pcurr->curr = 6; } } else { if (g_pcurr->curr + i != PACKSIZE) { g_pcurr->start = 0; g_pcurr->end = 0; g_pcurr->flag = 0; memset(g_pcurr->data, 0, PACKSIZE); memcpy(g_pcurr->data, buf + i, nRet - i); g_pcurr->start = 1; g_pcurr->flag = 1; g_pcurr->curr = nRet - i; } else { memcpy(g_pcurr->data + g_pcurr->curr, buf, i); g_pcurr->start = 1; g_pcurr->flag = 1; g_pcurr->end = 1; g_pcurr->curr += i; g_pcurr = g_pcurr->next; memcpy(g_pcurr->data, buf + i, nRet - i); g_pcurr->start = 1; g_pcurr->flag = 1; g_pcurr->end = 0; g_pcurr->curr = nRet - i; g_pcurr = g_pcurr->next; } } } if (g_pcurr->start && g_pcurr->end) { //pthread_mutex_lock(&g_tMutex); //pthread_cond_signal(&g_tConVar); Uart_parameter(g_pcurr->data, g_angle, g_distance, g_pcurr->curr); g_pcurr->start = 0; g_pcurr->end = 0; g_pcurr->flag = 0; memset(g_pcurr->data, 0, PACKSIZE); g_pcurr = g_pcurr->next; //pthread_mutex_unlock(&g_tMutex); } } } void *Uart_creatPthread(void *data) { unsigned char buf[1024]; fd_set read_fds; struct timeval tm; int nRet; while (creatPthread) { FD_ZERO(&read_fds); FD_SET(m_dFd, &read_fds); tm.tv_sec = 1; tm.tv_usec = 0; nRet = select(m_dFd + 1, &read_fds, NULL, NULL, &tm); if (nRet < 0) { printf("select error!\n"); } else if (nRet == 0) { ALOGI("select timeout!\n"); if (START_SCAN == g_start_scan) { printf("timeout----\n"); RestartGetData(); } } else { if (FD_ISSET(m_dFd, &read_fds)) { bzero(buf, 1024); nRet = read(m_dFd, buf, 1024); if (nRet > 0) { //ALOGI("nRet = %d\n", nRet); //printf("nRet = %d\n", nRet); analysis(buf, nRet); usleep(30000); } } } // usleep(30000); } return NULL; } int io_driver::OpenSerial(const char* port, unsigned int baudrate) { int ret; struct termios m_stNew; struct termios m_stOld; const char* addr = port; const char* addr2 = port; m_dFd = open(addr, O_RDWR | O_NOCTTY | O_NDELAY); if (-1 == m_dFd) { //perror("Open Serial Port Error!\n"); m_dFd = open(addr2, O_RDWR | O_NOCTTY | O_NDELAY); if (m_dFd < 0) return -1; }ALOGI("start init serial\n"); if ((fcntl(m_dFd, F_SETFL, 0)) < 0) { perror("Fcntl F_SETFL Error!\n"); return -1; } if (tcgetattr(m_dFd, &m_stOld) != 0) { perror("tcgetattr error!\n"); return -1; } m_stNew = m_stOld; cfmakeraw(&m_stNew); //将终端设置为原始模式,该模式下所有的输入数据以字节为单位被处理 //set speed cfsetispeed(&m_stNew, baudrate); //115200 cfsetospeed(&m_stNew, baudrate); //set databits m_stNew.c_cflag |= (CLOCAL | CREAD); m_stNew.c_cflag &= ~CSIZE; m_stNew.c_cflag |= CS8; //set parity m_stNew.c_cflag &= ~PARENB; m_stNew.c_iflag &= ~INPCK; //set stopbits m_stNew.c_cflag &= ~CSTOPB; m_stNew.c_cc[VTIME] = 0; //指定所要读取字符的最小数量 m_stNew.c_cc[VMIN] = 1; //指定读取第一个字符的等待时间,时间的单位为n*100ms //如果设置VTIME=0,则无字符输入时read()操作无限期的阻塞 tcflush(m_dFd, TCIFLUSH); //清空终端未完成的输入/输出请求及数据。 if (tcsetattr(m_dFd, TCSANOW, &m_stNew) != 0) { perror("tcsetattr Error!\n"); return -1; } g_pcurr = initlist(); if (NULL == g_pcurr) return -1; if (InitPackageSize()) return -1;ALOGI("finish init seria!\n"); return m_dFd; } int io_driver::StartScan(void) { static int scanflags = 0; int wRet; char wificmd0[] = { 0xa5, 0x3A, 0xe1, 0xaa, 0xbb, 0xcc, 0xdd }; char wificmd1[] = { 0xa5, 0x2C, 0xe1, 0xaa, 0xbb, 0xcc, 0xdd }; char wificmd2[] = { 0xa5, 0x20, 0xe1, 0xaa, 0xbb, 0xcc, 0xdd }; char wificmd3[] = { 0xa5, 0x50, 0xe1, 0xaa, 0xbb, 0xcc, 0xdd }; g_start_scan = START_SCAN; ALOGI("--------start scan----------\n"); // if (scanflags == 0) // { wRet = write(m_dFd, wificmd0, 7); if (wRet < 0) return wRet; usleep(5000000); wRet = write(m_dFd, wificmd1, 7); if (wRet < 0) return wRet; // } usleep(30000); wRet = write(m_dFd, wificmd2, 7); if (wRet < 0) return wRet; usleep(30000); wRet = write(m_dFd, wificmd3, 7); if (wRet < 0) return wRet; ALOGI("-------------end------------\n"); creatPthread = 1; if (scanflags == 0) { scanflags = 1; pthread_create(&id, NULL, Uart_creatPthread, NULL); } return wRet; } int io_driver::GetScanData(double *angle, double *distance, int len, double *speed) { int min = 0; int i; unsigned char buffer[PACKSIZE]; pthread_mutex_lock(&g_tMutex); pthread_cond_wait(&g_tConVar, &g_tMutex); min = len > PACKLEN ? PACKLEN : len; for (i = 0; i < min; i++) { angle[i] = g_angle[i]; distance[i] = g_distance[i]; } *speed = g_speed; pthread_mutex_unlock(&g_tMutex); return min; } int io_driver::Reset(void) { char buf[] = { 0xa5, 0x40, 0xe1, 0xaa, 0xbb, 0xcc, 0xdd }; return write(m_dFd, buf, 7); } int io_driver::StopScan(Command cmd) { //unsigned char buf[] = {LSLIDAR_CMD_BYTE, LSLIDAR_CMD_STOPSCAN, LSLIDAR_CMD_STOPSCAN_END}; char stop_scan[] = { 0xa5, 0x21, 0xe1, 0xaa, 0xbb, 0xcc, 0xdd }; char stop_motor[] = { 0xa5, 0x25, 0xe1, 0xaa, 0xbb, 0xcc, 0xdd }; g_start_scan = STOP_SCAN; if (STOP_DATA == cmd) { usleep(50000); write(m_dFd, stop_scan, 7); } if (STOP_MOTOR == cmd) { usleep(50000); write(m_dFd, stop_motor, 7); } return 0; } void io_driver::CloseSerial(void) { struct basedata *tmp; creatPthread = 0; g_start_scan = NO_SCAN; //sleep(2); pthread_join(id, NULL); tmp = g_pcurr; free(tmp); g_pcurr = g_pcurr->next; while (g_pcurr != tmp) { free(g_pcurr); g_pcurr = g_pcurr->next; } g_pcurr = tmp = NULL; close(m_dFd); } ================================================ FILE: src/ls01g/src/uart_driver.h ================================================ #ifndef __UART_DRIVER_H #define __UART_DRIVER_H #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include "math.h" #include #include #define PACKSIZE 1812 #define PACKLEN (PACKSIZE/5-2) #define LSLIDAR_CMD_BYTE 0xa5 #define LSLIDAR_CMD_START 0x2c #define LSLIDAR_CMD_STOP 0x25 #define LSLIDAR_CMD_SCAN 0x20 #define LSLIDAR_CMD_END 0xd1 #define LSLIDAR_CMD_RESET 0x40 #define LSLIDAR_CMD_RESET_END 0xe5 #define LSLIDAR_CMD_STOPSCAN 0x21 #define LSLIDAR_CMD_STOPSCAN_END 0xc6 enum Command { STOP_DATA = 1, STOP_MOTOR = 2, START_MOTOR_AND_SCAN = 4 }; struct ture_data{ int ture; int curr; unsigned char data[1024]; }; struct wifides { int start; int end; int flag; int packsize; int packcurr; unsigned char buf[1024]; }; struct basedata { int flag; int start; int end; int curr; unsigned char data[PACKSIZE]; struct basedata *next; }; #pragma pack(1) typedef struct _rplidar_response_measurement_node_t { unsigned char sync_quality; unsigned short angle_q6_checkbit; //角度 unsigned short distance_q2; //距离 }rplidar_response_measurement_node_t; struct scanDot { unsigned char quality; float angle; float dist; }; class io_driver { public: int OpenSerial(const char*, unsigned int baudrate);//it means fail if return -1 int StartScan(); int GetScanData( double *angle, double *distance, int len, double *speed); int Reset(void); int StopScan(Command cmd); void CloseSerial(); }; #endif ================================================ FILE: src/navigation_tutorials/README.md ================================================ # navigation_tutorials Tutorials about using the ROS Navigation stack. See: - http://wiki.ros.org/navigation_tutorials - http://wiki.ros.org/navigation/Tutorials ================================================ FILE: src/navigation_tutorials/laser_scan_publisher_tutorial/CMakeLists.txt ================================================ cmake_minimum_required(VERSION 2.8.3) project(laser_scan_publisher_tutorial) # Find catkin dependencies find_package(catkin REQUIRED COMPONENTS roscpp sensor_msgs) # Call catkin_package catkin_package() # Add catkin_INCLUDE_DIRS to the include path include_directories(${catkin_INCLUDE_DIRS}) # Build the laser_scan_publisher executable add_executable(laser_scan_publisher src/laser_scan_publisher.cpp) # Add a build order dependency on sensor_msgs # This ensures that sensor_msgs' msg headers are built before your executable if(sensor_msgs_EXPORTED_TARGETS) add_dependencies(laser_scan_publisher ${sensor_msgs_EXPORTED_TARGETS}) endif() # Link against the catkin_LIBRARIES target_link_libraries(laser_scan_publisher ${catkin_LIBRARIES}) # Mark executables and/or libraries for installation install(TARGETS laser_scan_publisher ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) ================================================ FILE: src/navigation_tutorials/laser_scan_publisher_tutorial/package.xml ================================================ laser_scan_publisher_tutorial 0.2.3 The laser_scan_publisher_tutorial package William Woodall BSD http://ros.org/wiki/laser_scan_publisher_tutorial https://github.com/ros-planning/navigation_tutorials https://github.com/ros-planning/navigation_tutorials/issues Eitan Marder-Eppstein catkin roscpp sensor_msgs roscpp sensor_msgs ================================================ FILE: src/navigation_tutorials/laser_scan_publisher_tutorial/src/laser_scan_publisher.cpp ================================================ /********************************************************************* * * Software License Agreement (BSD License) * * Copyright (c) 2009, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of Willow Garage, Inc. nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. * * Author: Eitan Marder-Eppstein *********************************************************************/ #include #include int main(int argc, char** argv){ ros::init(argc, argv, "laser_scan_publisher"); ros::NodeHandle n; ros::Publisher scan_pub = n.advertise("scan", 50); unsigned int num_readings = 100; double laser_frequency = 40; double ranges[num_readings]; double intensities[num_readings]; int count = 0; ros::Rate r(1.0); while(n.ok()){ //generate some fake data for our laser scan for(unsigned int i = 0; i < num_readings; ++i){ ranges[i] = count; intensities[i] = 100 + count; } ros::Time scan_time = ros::Time::now(); //populate the LaserScan message sensor_msgs::LaserScan scan; scan.header.stamp = scan_time; scan.header.frame_id = "laser_frame"; scan.angle_min = -1.57; scan.angle_max = 1.57; scan.angle_increment = 3.14 / num_readings; scan.time_increment = (1 / laser_frequency) / (num_readings); scan.range_min = 0.0; scan.range_max = 100.0; scan.ranges.resize(num_readings); scan.intensities.resize(num_readings); for(unsigned int i = 0; i < num_readings; ++i){ scan.ranges[i] = ranges[i]; scan.intensities[i] = intensities[i]; } scan_pub.publish(scan); ++count; r.sleep(); } } ================================================ FILE: src/navigation_tutorials/navigation_stage/CMakeLists.txt ================================================ cmake_minimum_required(VERSION 2.8.3) project(navigation_stage) # Find catkin find_package(catkin REQUIRED) catkin_package() # Install launch files install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) # Install move_base_config files install(DIRECTORY move_base_config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) # Install stage_config files install(DIRECTORY stage_config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) # Install the rviz files install(FILES multi_robot.rviz single_robot.rviz DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) ================================================ FILE: src/navigation_tutorials/navigation_stage/launch/move_base_amcl_10cm.launch ================================================ ================================================ FILE: src/navigation_tutorials/navigation_stage/launch/move_base_amcl_2.5cm.launch ================================================ ================================================ FILE: src/navigation_tutorials/navigation_stage/launch/move_base_amcl_5cm.launch ================================================ ================================================ FILE: src/navigation_tutorials/navigation_stage/launch/move_base_fake_localization_10cm.launch ================================================ ================================================ FILE: src/navigation_tutorials/navigation_stage/launch/move_base_fake_localization_2.5cm.launch ================================================ ================================================ FILE: src/navigation_tutorials/navigation_stage/launch/move_base_fake_localization_5cm.launch ================================================ ================================================ FILE: src/navigation_tutorials/navigation_stage/launch/move_base_gmapping_5cm.launch ================================================ ================================================ FILE: src/navigation_tutorials/navigation_stage/launch/move_base_multi_robot.launch ================================================ ================================================ FILE: src/navigation_tutorials/navigation_stage/move_base_config/amcl_node.xml ================================================ ================================================ FILE: src/navigation_tutorials/navigation_stage/move_base_config/base_local_planner_params.yaml ================================================ #For full documentation of the parameters in this file, and a list of all the #parameters available for TrajectoryPlannerROS, please see #http://www.ros.org/wiki/base_local_planner TrajectoryPlannerROS: #Set the acceleration limits of the robot acc_lim_th: 3.2 acc_lim_x: 2.5 acc_lim_y: 2.5 #Set the velocity limits of the robot max_vel_x: 0.65 min_vel_x: 0.1 max_rotational_vel: 1.0 min_in_place_rotational_vel: 0.4 #The velocity the robot will command when trying to escape from a stuck situation escape_vel: -0.1 #For this example, we'll use a holonomic robot holonomic_robot: true #Since we're using a holonomic robot, we'll set the set of y velocities it will sample y_vels: [-0.3, -0.1, 0.1, -0.3] #Set the tolerance on achieving a goal xy_goal_tolerance: 0.1 yaw_goal_tolerance: 0.05 #We'll configure how long and with what granularity we'll forward simulate trajectories sim_time: 1.7 sim_granularity: 0.025 vx_samples: 3 vtheta_samples: 20 #Parameters for scoring trajectories goal_distance_bias: 0.8 path_distance_bias: 0.6 occdist_scale: 0.01 heading_lookahead: 0.325 #We'll use the Dynamic Window Approach to control instead of Trajectory Rollout for this example dwa: true #How far the robot must travel before oscillation flags are reset oscillation_reset_dist: 0.05 #Eat up the plan as the robot moves along it prune_plan: true ================================================ FILE: src/navigation_tutorials/navigation_stage/move_base_config/costmap_common_params.yaml ================================================ #This file contains common configuration options for the two costmaps used in the navigation stack for more details on the parameters in this file, and a full list of the parameters used by the costmaps, please see http://www.ros.org/wiki/costmap_2d #For this example we'll configure the costmap in voxel-grid mode map_type: voxel #Voxel grid specific parameters origin_z: 0.0 z_resolution: 0.2 z_voxels: 10 unknown_threshold: 9 mark_threshold: 0 #Set the tolerance we're willing to have for tf transforms transform_tolerance: 0.3 #Obstacle marking parameters obstacle_range: 2.5 max_obstacle_height: 2.0 raytrace_range: 3.0 #The footprint of the robot and associated padding footprint: [[-0.325, -0.325], [-0.325, 0.325], [0.325, 0.325], [0.46, 0.0], [0.325, -0.325]] footprint_padding: 0.01 #Cost function parameters inflation_radius: 0.55 cost_scaling_factor: 10.0 #The cost at which a cell is considered an obstacle when a map is read from the map_server lethal_cost_threshold: 100 #Configuration for the sensors that the costmap will use to update a map observation_sources: base_scan base_scan: {data_type: LaserScan, expected_update_rate: 0.4, observation_persistence: 0.0, marking: true, clearing: true, max_obstacle_height: 0.4, min_obstacle_height: 0.08} ================================================ FILE: src/navigation_tutorials/navigation_stage/move_base_config/dwa_local_planner_params.yaml ================================================ #For full documentation of the parameters in this file, and a list of all the #parameters available for DWAPlannerROS, please see #http://www.ros.org/wiki/dwa_local_planner DWAPlannerROS: acc_lim_th: 3.2 acc_lim_x: 2.5 acc_lim_y: 2.5 max_vel_x: 0.65 min_vel_x: 0.0 max_vel_y: 0.1 min_vel_y: -0.1 max_trans_vel: 0.65 min_trans_vel: 0.1 max_rot_vel: 1.0 min_rot_vel: 0.4 sim_time: 1.7 sim_granularity: 0.025 goal_distance_bias: 32.0 path_distance_bias: 24.0 occdist_scale: 0.01 stop_time_buffer: 0.2 oscillation_reset_dist: 0.05 forward_point_distance: 0.325 scaling_speed: 0.25 max_scaling_factor: 0.2 vx_samples: 3 vy_samples: 10 vtheta_samples: 20 sim_period: 0.1 xy_goal_tolerance: 0.2 yaw_goal_tolerance: 0.17 rot_stopped_vel: 0.01 trans_stopped_vel: 0.01 ================================================ FILE: src/navigation_tutorials/navigation_stage/move_base_config/global_costmap_params.yaml ================================================ #Independent settings for the global planner's costmap. Detailed descriptions of these parameters can be found at http://www.ros.org/wiki/costmap_2d global_costmap: #Set the global and robot frames for the costmap global_frame: /map robot_base_frame: base_link #Set the update and publish frequency of the costmap update_frequency: 5.0 publish_frequency: 0.0 #We'll use a map served by the map_server to initialize this costmap static_map: true rolling_window: false footprint_padding: 0.02 ================================================ FILE: src/navigation_tutorials/navigation_stage/move_base_config/local_costmap_params.yaml ================================================ #Independent settings for the local planner's costmap. Detailed descriptions of these parameters can be found at http://www.ros.org/wiki/costmap_2d local_costmap: #We'll publish the voxel grid used by this costmap publish_voxel_map: true #Set the global and robot frames for the costmap global_frame: odom robot_base_frame: base_link #Set the update and publish frequency of the costmap update_frequency: 5.0 publish_frequency: 2.0 #We'll configure this costmap to be a rolling window... meaning it is always #centered at the robot static_map: false rolling_window: true width: 6.0 height: 6.0 resolution: 0.025 origin_x: 0.0 origin_y: 0.0 ================================================ FILE: src/navigation_tutorials/navigation_stage/move_base_config/move_base.xml ================================================ ================================================ FILE: src/navigation_tutorials/navigation_stage/move_base_config/slam_gmapping.xml ================================================ ================================================ FILE: src/navigation_tutorials/navigation_stage/multi_robot.rviz ================================================ Panels: - Class: rviz/Displays Help Height: 78 Name: Displays Property Tree Widget: Expanded: - /Global Options1 Splitter Ratio: 0.5 Tree Height: 510 - Class: rviz/Selection Name: Selection - Class: rviz/Tool Properties Expanded: - /2D Pose Estimate1 - /2D Nav Goal1 - /Publish Point1 Name: Tool Properties Splitter Ratio: 0.588679 - Class: rviz/Views Expanded: - /Current View1 Name: Views Splitter Ratio: 0.5 - Class: rviz/Time Experimental: false Name: Time SyncMode: 0 SyncSource: "" Visualization Manager: Class: "" Displays: - Alpha: 0.7 Class: rviz/Map Color Scheme: map Draw Behind: false Enabled: true Name: Map Topic: /map Value: true - Alpha: 1 Buffer Length: 1 Class: rviz/Path Color: 255; 149; 0 Enabled: true Name: "Robot 0: Global Plan" Topic: /robot_0/move_base_node/TrajectoryPlannerROS/global_plan Value: true - Alpha: 1 Buffer Length: 1 Class: rviz/Path Color: 0; 0; 255 Enabled: true Name: "Robot 0: Local Plan" Topic: /robot_0/move_base_node/TrajectoryPlannerROS/local_plan Value: true - Alpha: 1 Buffer Length: 1 Class: rviz/Path Color: 255; 0; 0 Enabled: true Name: "Robot 0: NavFn Plan" Topic: /robot_0/move_base_node/NavfnROS/plan Value: true - Alpha: 1 Class: rviz/GridCells Color: 0; 0; 255 Enabled: true Name: "Robot 0: Inflated Obstacles" Topic: /robot_0/move_base_node/local_costmap/inflated_obstacles Value: true - Alpha: 1 Class: rviz/GridCells Color: 255; 0; 0 Enabled: true Name: "Robot 0: Obstacles" Topic: /robot_0/move_base_node/local_costmap/obstacles Value: true - Alpha: 1 Class: rviz/GridCells Color: 0; 255; 0 Enabled: true Name: "Robot 0: Unknown Space" Topic: /robot_0/move_base_node/local_costmap/unknown_space Value: true - Alpha: 1 Class: rviz/Polygon Color: 255; 0; 0 Enabled: true Name: "Robot 0: Robot Footprint" Topic: /robot_0/move_base_node/local_costmap/robot_footprint Value: true - Alpha: 1 Buffer Length: 1 Class: rviz/Path Color: 255; 149; 0 Enabled: true Name: "Robot 1: Global Plan" Topic: /robot_1/move_base_node/TrajectoryPlannerROS/global_plan Value: true - Alpha: 1 Buffer Length: 1 Class: rviz/Path Color: 0; 0; 255 Enabled: true Name: "Robot 1: Local Plan" Topic: /robot_1/move_base_node/TrajectoryPlannerROS/local_plan Value: true - Alpha: 1 Buffer Length: 1 Class: rviz/Path Color: 255; 0; 0 Enabled: true Name: "Robot 1: NavFn Plan" Topic: /robot_1/move_base_node/NavfnROS/plan Value: true - Alpha: 1 Class: rviz/GridCells Color: 0; 0; 255 Enabled: true Name: "Robot 1: Inflated Obstacles" Topic: /robot_1/move_base_node/local_costmap/inflated_obstacles Value: true - Alpha: 1 Class: rviz/GridCells Color: 255; 0; 0 Enabled: true Name: "Robot 1: Obstacles" Topic: /robot_1/move_base_node/local_costmap/obstacles Value: true - Alpha: 1 Class: rviz/GridCells Color: 0; 255; 0 Enabled: true Name: "Robot 1: Unknown Space" Topic: /robot_1/move_base_node/local_costmap/unknown_space Value: true - Alpha: 1 Class: rviz/Polygon Color: 255; 0; 0 Enabled: true Name: "Robot 1: Robot Footprint" Topic: /robot_1/move_base_node/local_costmap/robot_footprint Value: true Enabled: true Global Options: Background Color: 48; 48; 48 Fixed Frame: map Frame Rate: 30 Name: root Tools: - Class: rviz/Interact Hide Inactive Objects: true - Class: rviz/MoveCamera - Class: rviz/Select - Class: rviz/FocusCamera - Class: rviz/Measure - Class: rviz/SetInitialPose Topic: /initialpose - Class: rviz/SetGoal Topic: /move_base_simple/goal - Class: rviz/PublishPoint Single click: true Topic: /clicked_point Value: true Views: Current: Class: rviz/Orbit Distance: 10 Focal Point: X: 0 Y: 0 Z: 0 Name: Current View Near Clip Distance: 0.01 Pitch: 0.555398 Target Frame: Value: Orbit (rviz) Yaw: 2.73721 Saved: ~ Window Geometry: Displays: collapsed: false Height: 756 Hide Left Dock: false Hide Right Dock: false QMainWindow State: 000000ff00000000fd0000000400000000000002090000028cfc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005600fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000002540000011a00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000004c0000028c000000dc00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f0000028cfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000004c0000028c000000a500fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004fc0000003efc0100000002fb0000000800540069006d00650000000000000004fc0000020b00fffffffb0000000800540069006d00650100000000000004500000000000000000000001e20000028c00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 Selection: collapsed: false Time: collapsed: false Tool Properties: collapsed: false Views: collapsed: false Width: 1276 X: 4 Y: 22 ================================================ FILE: src/navigation_tutorials/navigation_stage/package.xml ================================================ navigation_stage 0.2.3 This package holds example launch files for running the ROS navigation stack in stage. William Woodall BSD http://www.ros.org/wiki/navigation_stage https://github.com/ros-planning/navigation_tutorials https://github.com/ros-planning/navigation_tutorials/issues Eitan Marder-Eppstein catkin amcl fake_localization gmapping map_server move_base stage_ros ================================================ FILE: src/navigation_tutorials/navigation_stage/single_robot.rviz ================================================ Panels: - Class: rviz/Displays Help Height: 78 Name: Displays Property Tree Widget: Expanded: - /Global Options1 Splitter Ratio: 0.5 Tree Height: 485 - Class: rviz/Selection Name: Selection - Class: rviz/Tool Properties Expanded: - /2D Pose Estimate1 - /2D Nav Goal1 - /Publish Point1 Name: Tool Properties Splitter Ratio: 0.588679016 - Class: rviz/Views Expanded: - /Current View1 Name: Views Splitter Ratio: 0.5 - Class: rviz/Time Experimental: false Name: Time SyncMode: 0 SyncSource: LaserScan Visualization Manager: Class: "" Displays: - Alpha: 0.699999988 Class: rviz/Map Color Scheme: map Draw Behind: false Enabled: true Name: Map Topic: /map Value: true - Alpha: 1 Class: rviz/Polygon Color: 0; 0; 255 Enabled: true Name: Robot Footprint Topic: /move_base_node/local_costmap/footprint Value: true - Alpha: 1 Buffer Length: 1 Class: rviz/Path Color: 255; 149; 0 Enabled: true Line Style: Lines Line Width: 0.0299999993 Name: Global Plan Offset: X: 0 Y: 0 Z: 0 Topic: /move_base_node/TrajectoryPlannerROS/global_plan Value: true - Alpha: 1 Buffer Length: 1 Class: rviz/Path Color: 0; 0; 255 Enabled: true Line Style: Lines Line Width: 0.0299999993 Name: Local Plan Offset: X: 0 Y: 0 Z: 0 Topic: /move_base_node/TrajectoryPlannerROS/local_plan Value: true - Alpha: 1 Buffer Length: 1 Class: rviz/Path Color: 255; 0; 0 Enabled: true Line Style: Lines Line Width: 0.0299999993 Name: NavFn Plan Offset: X: 0 Y: 0 Z: 0 Topic: /move_base_node/NavfnROS/plan Value: true - Arrow Length: 0.300000012 Class: rviz/PoseArray Color: 255; 25; 0 Enabled: true Name: PoseArray Topic: /particlecloud Value: true - Alpha: 0.699999988 Class: rviz/Map Color Scheme: costmap Draw Behind: false Enabled: false Name: Global Costmap Topic: /move_base_node/global_costmap/costmap Value: false - Alpha: 0.699999988 Class: rviz/Map Color Scheme: costmap Draw Behind: false Enabled: true Name: Local Costmap Topic: /move_base_node/local_costmap/costmap Value: true - Alpha: 1 Autocompute Intensity Bounds: true Autocompute Value Bounds: Max Value: 10 Min Value: -10 Value: true Axis: Z Channel Name: intensity Class: rviz/LaserScan Color: 255; 255; 0 Color Transformer: FlatColor Decay Time: 0 Enabled: true Invert Rainbow: false Max Color: 255; 255; 255 Max Intensity: 1 Min Color: 0; 0; 0 Min Intensity: 1 Name: LaserScan Position Transformer: XYZ Queue Size: 10 Selectable: true Size (Pixels): 3 Size (m): 0.100000001 Style: Flat Squares Topic: /base_scan Use Fixed Frame: true Use rainbow: true Value: true Enabled: true Global Options: Background Color: 48; 48; 48 Fixed Frame: map Frame Rate: 30 Name: root Tools: - Class: rviz/Interact Hide Inactive Objects: true - Class: rviz/MoveCamera - Class: rviz/Select - Class: rviz/FocusCamera - Class: rviz/Measure - Class: rviz/SetInitialPose Topic: /initialpose - Class: rviz/SetGoal Topic: /move_base_simple/goal - Class: rviz/PublishPoint Single click: true Topic: /clicked_point Value: true Views: Current: Class: rviz/ThirdPersonFollower Distance: 43.5168953 Enable Stereo Rendering: Stereo Eye Separation: 0.0599999987 Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false Focal Point: X: 0 Y: 0 Z: 0 Name: Current View Near Clip Distance: 0.00999999978 Pitch: 0.710398257 Target Frame: base_link Value: ThirdPersonFollower (rviz) Yaw: 2.82039738 Saved: ~ Window Geometry: Displays: collapsed: false Height: 723 Hide Left Dock: false Hide Right Dock: false QMainWindow State: 000000ff00000000fd00000004000000000000016400000274fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006400fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000002540000011a00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000004100000274000000dd00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000274fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000004100000274000000b000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004fc0000003efc0100000002fb0000000800540069006d00650000000000000004fc0000030000fffffffb0000000800540069006d006501000000000000045000000000000000000000027d0000027400000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 Selection: collapsed: false Time: collapsed: false Tool Properties: collapsed: false Views: collapsed: false Width: 1276 X: 2 Y: 24 ================================================ FILE: src/navigation_tutorials/navigation_stage/stage_config/maps/willow-full-0.025.pgm ================================================ P5 # CREATOR: GIMP PNM Filter Version 1.1 2332 1825 255 LZͱ|[(9ͥƫۊW͢z|Ѿ˿ͳͶcj͈X͵糿jn͋niͭyx͞mѭnͧ&ܹͣdԭ6Ҷ+9Vޱɬ<Ꞵ)͖ꈛͶGFM͎ͳ&ͧ͘Ι\ͻƳ˶8Ĺͥ-|͋͸̈́ʹ͛y~Xͬ~ʽ̈́i̧͉O.ڭsiOBbʶͼ͡jJۺaͳƆ`敇ІG͵ױ؍̕颶ܱImͰэF]Y&aͥͿJ5 v`s~z隁ӆN΋ןFѻu.dⴿc͵tr9ͮ̀ nrͽ͹lKBša{~˳ղsçf멡âЯoi͍гť͕YͤS͙[醧0CDemoF\эs綬|~׸²ES/ʤzPT$ʉ̀s3zaƺͯn{.y{멬һѦ]ŨCąɹՄ|i|"{ӡfǓ͓voCmѵūȫͬE]ɱ9̯і*ͦʚiS>3 TxJ5 ¬̓lW͸;ʹƪx͇M׈$Ͳ?wɐͺRͺW<@ٚͮpͽCoF rG}j(:^;f%Fr3?, -MvȰ͓gͪͨ͟Ⱦ͝ub͹͌lΈr͠zοÖs͹gC˳ g͆ñ.͹͟cͳ͔ͩ?ƎʖD̟tb̳.o$l7赎n\ƍډtmO:$Dsq\F0TwV?=z_uNrͅelYhUkaa]K6kzhŒܚLϘqҵǜ͘B͹ͼk͊grͷ3E^]ͨ ͙漠똊mqhW`͎ڵ̈́Qv|]]Kiʵ(pa놯jfVqyůy|mFE^L]V>3\v{oijZrF[­Q{ۙξ{JӃȝsͷɊts{x͈b̵ͦ͠r޾OϭF'Q͚ɩ͑g̘}wNQQƑcӚeͲ斈幵ӸÒR $eA{źVA9,ݵa*WD7zZ[ˤͅexɰo{xhz`{g|هwQO➷~Ѓ(ͻFZx2QC;xsM/䗪մ|^ٟqe9/n͋Ў)RݺͶkw͖p͡e͹ȻmͺdNy_| vjǽϛưͯ͋iɹͰ%EHSkǷ\sjwo?謡b@؄OԤш@;Ġd͒ұҷ4#ycW͑]G1ͿS>(Xmu`Jq ]lWA+mogxbM8" TpHG"C.\LѦآB͒Vy%۽ŁҙͺϦkmͧͧhH̀Ͷͽr͠걡͇a̎NӳX6W|fgY͚XF`C+Ewͱ͡F΅"ͱҚ຃|tģͼ~øͳɍIfʈȘ͆ͳ͠_]ѕڹͲØߺ֘،ҫ{IڐSݼ̈́dR,1bRΌ JĤňvBUTA`͸ʦS3ȷJ厝ũ͝k邨ƴ;q˩ؗأ͡¾-~ڢ~aOcͽzтW׵cλeͭTt3 AcFu\ͱzReȗ{M2nf \ͧiͮ豦ԽΜ_ͥ]-ᄩQXzۖ|ͺ͡}͊Q͓vͫ~͗P˵ĒK)о؃ϟͽκ͢͜Ľbio_ͽot;k2D᳂ܢ}eqlٙŻ^Cd۫iNɫd?ͭ*}Ͳ;iK״ͮeͮ҇O~=(D_Z͖;̶V0ͿmuҧA:bg?Î_ʉ?rǢͿi"kأڶ,l6͓Űͻ()rr}ņٹƌXɵZq̬o5f=ooXbYd8ͮ|G# DWwaBZ'4fdN9# ͽͼխߣ͌«遌͂ÿͶ¶vدפ)ʧ.mzǥڳǻީ͎ߨͻ;ړHoȄq\F0 9r9{'|aqt4ybVkwͷĺdz͚n{w͵^N͋ͣΟ2;Ͱ1tڧmol}ƾͷe֖ǬڨТϸ#Aڟr۷ʨ̅RmL*>%vVrl'8W͆͟BԽͱ͎`cí͹͚c͍ͼͷތk*sܸ쪶i4Fƿ;hӌ?Y`!ɴؾyͦ{ͧ͘rըil;QsB}DvӑOݬͫKkbͮԩڰW׻5սDL4'Wxj粬zu˧ۑ}a媨tzf`oͮM֑GBϒvMo޾ZoHɍT@˵92 ֭ۢeLWodt㯚|HαJ-|⯽˚iϣj#ƳWͦѴQxܘRͫ1Ac'͖urdʁ~оӾ |թ;p%"<59r{ǚudr~0㊣<ʹȩ#ͳ㕸~[}Mi۰K͖剙>{B͒Ȧ͓+Fw9͊ͩt^J~qL$=,srߒ}͖͙ͬuWȝͼʾY͹oƑʑ⸡ͮLQgͪLh .hƛrNZtD.͵fyݽͶoͻͿu͔Esҡͽm͵c}\ݨ^яXZͦK ͞[1=ͧͬA7iӤOݿڨ͇́tE[`l{|ϱ6A5t蠪ZsVaMDsͼĥͼඖwl7ntͱ)͏`ͥǙͯ ʞӾϨNyͷ~͆rrn4˄ 8棥t͌h/2oUY>͊>ͥݦͣe՟ܒ͵Zi͍wͰ}̈́͝ͼͨwѶ5 (jЇͷ&ΠHߍbDڝ@`Qg<<#o+՞u:Mͭ7ͥuͽ:߾6yYͿ#٧`eBeSֳУێ˷r^өk͸i͇3ffPٶ#L(˄$q4꾩޿;L객͸l*ʄµ?ɩگqxt]̡H̪jzQ͝~B&:͠DzǠͷ6ڮG;y< 镵֮`cͪpұ;͢"ͮsr`͞rȭ♬Ll͋ŧ3̜RϝYjͶRZ X蒤͖jڸͪͣjȨټ;͉ذ#K(mQ٦>ã˜wAܛr̀pͺTҠ>͞`Lͯ.ԙ{ͱ]Ͱ4ͽm°o͑\ Lͫ͒ʢrͶ[aJu$ͪvT˲H);yҶjz5͆xcϰc.b̓߼z?M4̎Lͪ͐ڸUۂ_̅G>ͻҪ|ͱeXƼg A݊篟ˬʹͼe(ḳQͳ¢ğ͉М? ͗mɰͷzo栕෻jy' u\Ϳ͑͗U#8K3`UgXͳ!ҿuPvby]nLš=ٝ̀ͿcD3koޤ5=CxLϸrtwuŹ̈́Y><ŎЭ׉OT&Z*»͵|U~ͧO{Ab8ͭ{{ľ+d̀ͤgd2ҟqf̝ ɡŎ⯹^ 8ͼ:{IܤQ͵˦{GuMyw̕Uy` Ah暻՘KQͷd%,٢@gͦij͎jpqcK|oySQYbiS͂T hyZ*j'ߚlR~̻͋͋ͭҐʹ;͎La|q:ͱ?#Īηiͅόͯ͗ͷͤ2嵰͗Kƻ왩z仞ƪ湺SҮʿ }BeͪL3=ٍWB_TCĐ}gQ<&0$Sf2͹cflUGl͚LS}Б͓mYRf+ͶS^hi4-~͎E͛ Ljˌͪ͌XguVѥrs+Ͳkrڤɽ跽v_̾ ڬ͸нæʻԵ[q笶PЊ寎zP͵4g͞Qą~;6Si͸̺Κʤ͋r䌛͑ܤN7͹oڨ9nw#G5jY觮e"͹Ƴ׳Б1Lԯ]Ftųt͹Ѩ3Dۧsy4͖8OuM̽ռ9͒~͒vؐ[ƞK@ͿϠ5x˽͐Aص͠IͿuIii.߇{ꌇ߬ͽlʹuH ٚ`vkS2~͵͈ⷵVͷڤ֭w)4ۧHͺ)ݱ͇[>zrz͜<ͿmͅXps)ε߫Bٿꞷ]qvҀͱ-͛͞WïGz!_☚?{d,Ͱ+{͸{q ͹㵂d;fߏþi͐Kl5yx͟@ɲpzJLyt͛mѵ;1̦ͥ?$oͯκ͓f▙ͼ?d˺͢?Nي݆SFamOͬG̫ͿO˫ꩧ̈́z߾O%ድͨJ_q|Sp֜W΅6ۧѲ)͔ӝ`s;ϐȬͻū}ꆯǟlIsͱүԢcMͶ͂,Ȑt釐M=ܭ|԰hjԅͿm͘eЌܪͳn?[ϵ^S9]`͘LֆϦPjբ˺ͳ~CSѾͪ6r5νJ˶Ϳ=糾h*+ݍİ肆͊ͮhͼjUÖͭ ͉0oZbˎx7Ȁj9ra'pܜ1ޜU_ͿlͶصssߨp朏㮱{DZZbʥuP X:́/Ϫ?Z?@6ͿPŬڭSתY &r͚҇z֑ͨZSսʼ> 0͵TVtڶԫg^Ҍ{ˮT$ݝ!Pssh̪R0͹!PO^ׄͬ'a~͜SfΥK8E1y䱙n37{߿܂ο^{֩-͍Y6ۉ6Cʤ~v5^1~ܕ׿C; 3֤_/[t$ ׹rVG@ʏͰSdͳx՘͎ZپW͠{nͯ/ڟ͸*k$[HϽ͢gHϜe?Png93t4Ba͹߯ՠI$0;^oQwbGHmăͿɿ뵕޺;mgptdP͵΀y$_yҫHр*Y68B6G2ԍS]mѻͪIͳBZͫӝIaŗCEu͏O'}g}Wϧ}f^H̛Qķ֗̎/͹(9D!MaOپO\Έʮ͙JzJƍɖ-խa˯Ў\اmҢͤˮKbְ̬F͓Ϳ G͖͊G2j͡6řεP˲Uze͉sz컠ʴߩڕcєaNPÚȰEQ߼քkBJ~> enTӝ̹́͵͹Io[ʊA{I{+SŵƦ ן축rYX譺rxrit=qz[Tͤ$r͙kͽͣyOԬscB‰d͂0ͪͿ̬lOlbžťɫͷTʔf۶IkaǸiӔzM$vv^qLcq͋?|H![y[WHq1sxVSz{wp̵ƧÖÿ󹆫"Gziͤli.晨[矵NƠb6f_lӵ͚ObúAͿ̋PͲ֌dͼ̓JվۺçǬP֝ȵڼjSsӸi̬f˾͢8qהԮ«ԳQ9=ǻó俥g Ǐ͸;Tͺͽͭܨ-wͩ-Gι\YZў˼r#Ǽ@.\Efe}͝pɴѭľȱб᠗صњrϻiEʹXYg%a;ͽ>nצ͠Ohşcz׿JPͽ)kMͱIÖvT͏Ҋԩ,ɬxīˬƶ̎;ìȲʔɸŜxbyvۏdzЫ]?nͽ_Xɘik&0 ~hR=7ʴͮ窋p͙&bȝ\cϻ-nۖF1nVAG}٠|͙riùʚ{sήؽ4ͩLݯӳŹЌĬcrQןdX{Y),Q0]ҧr_x,]Q5K-::)b|Jì;ҕnXdzVtͭͅͰͽd3C͎jé׻̶̀ͻ}jѮ袥y"፽(ƟܸڿtnͿ橪ͫɳǡ|_?䧴扎ye^Tzz֌Jԧޣbοbڰζ׍ߐߒ@|§+BkҵĺH:zs{ڸʖkXZTt{ŗXZxL1Bzkи߶jpѿceԲ)摐߹ͲbeǛHe\t<|ڹiݿ/{gΌ೽2YʯF{|”γ`ĖŦװΫι㽎dЮںɬDگM2!ͥ씛/1㞎氭ĘͤijmȅgӲlғ-Źɋڂݰ͵۾ٰ״̶Αؼ塵>QڲGyɴё!ۛt鲤۲Ǚݡs~ܮøݲ߫ɰȮɶpȐkuPͭǜͰқQfM͜媚ʑzݑѶѳԇөѢۗ豩ׁ `ڹwkksa س̓׏͖msऒʰoTqó9鞣ͩͱd[:~̼аƢ[RӘ~QĻT]tРٻڒе$0݁f͝xǾː$ўгү⨹ȹÿ㻿͹ntۺV8bM_ڌ[gػժşJHͰȳҴ߽ƭƻĸԑȬhXkϘÿVۼNͰPɽҶǼj~FզϿݰױ͟ʼݿӳɴi}ͥһYl۴Ьȳ檝dҸ԰táʺԥ㿲˓Ļ˪ʝӴ~ǾӯŠָ뼱ײ̟Q\ⷥջ݋0!eNܧͰʸߜ3|o;GƭʵԹ;f⿩Ͷiͪ1^sͪZyꂑlۖFYʹ{mⱷͼ(y̯q͘q󋈳ⴽQͽ¬;Xq4WȺdʹ6QQ>n]BQC˺_{S_Y2͌֯㱚4-촸e͎ӵ?ͩק ȭ5͉^̙s庞W)j PŠe}Ͱb/$ͶBwʹ姵ͅ"lc˫ώȸ砀ͯ/Pµ]滩͢oԗTd_cL͟ ̀vs;fSWɵ_E>v"ͽ5Ͼ,Uc[͞ޝ׀͵ͮ͘pWgBͮͲ}Њ[H% Ozͮʹ͞ Έͧ{fo~7lӗ˞|͢DŽ'ݥ%˶͹͟ߜe̲VJC;͚i׍˰{`|qͿ3O@]9Ofyݢ#>Si͛oʒVpuT^d̿s7: ͺk=osz3#&B_"!]fd_͏, ԐQ{XͷͷCMǯ,iտͥ0Kͫqkl`乕uGKYͺdVzVﳜӯYMͿypcuͱ`{a@й&5\ʹ1$MY^!܀bǫϪ9yv]$5ëd+ʹ̀Ϳ;yʹc|xhvhΠ.uƢDܧ͑bV۫%4ɶܣYŸɰ榍͛I >Z_3)mvUͭLѦ?͢(d崝͸ |Ųkdzmڿ̬䧫h͈JͭrȨzϐ dn0t%ͥ͛DgmzjGoКnaȓ_ř}ʹŴȪʭóRZؔūOmlǷůͤ9t]Oϊ͒tỐz]YYXSѫoh_oO͎0gc]JSstaronыϠh6՗f{z즒˔v.˘MOoږ;|{ӋvAviFP´׊$OÃjG'칺ՑZΐzyr|â}5͏Z͠Wͺ({t'tkp/]͋[xaWgo2ܺؽxH؀QZ2vKͩ7䚙0DtSpK`tG׌V$^f`TZRWdگͧ>̢ʏ?ͣF~ֈ桫jȸ㯅o\b؍͔CʩԬ͗Cʢʦ͹ӻͰprDWNrٰ|ͨi3yెƯԾ[ANr¿XxfR=dk@t(4hbBNfֿ͟YZqVp|fŵ2kiī|a˼ͧ𘂩·ɿg}.ͷͫU7o}͚͔̓tͦҫ/^ߩͳp񨇯!|[Qbz²R-, Cȡ͞bpʶ>uvඬ[Z]qt˺tzGǵ}ܴ?H|jdk%BY}:&I^ܮ?dϡы/U䱕dȍuG飼i˺Ӿ䄩ͷ冟Y|Ϳܮͅkįl1Ć͕lͭxpUͮҡmCZQZî͗v:\0Ḻˡߢm ȷ8Y_ʫٹʩe k͹wnƱg|ˏԘ~>Cͦ[\q͵hݱčհˤNͮܤ׷J͛m꾞hRzss Tu:[1η͒ͼQ0ƼLāxRըlյOT͹(ٳ-{/l|PL2U>ʴœz2h]ҡ:~µZnB͹NuqƖg־6Tk2G]%;͌h\̂*͑en$xժw|qqvvƑ^͍ēc(pE.ͫ~ɵ7gZ ^ӼꬼϷĊvmИy2}:8}VUs|F04G)o)ڑ1F(_޽|iyjbQ2ȳX%MTᕐ!P\.ֶofny`|䶦r\Ű9d˳gǔlrnvXw@klbƮCsͺͤʹͬͬؖaVƠtҳğ蹃r⯐ƱYĊəu)yqwʤ%μ>K仼u7F車ͤpǂcS%ڐ`~쩠ͭͽym4œpɝBp¦׉˃_rjzxmʯx|xi|KSqIy0C{W#/fo8$pY JHC9Ŵ{Uͣ/͑i˵с®s6̥ڕ֙km{ᵵM^oՂgOww5@]Wq9^XFkF f8/lֲ5IsYHy؂LhE봤u8υ͠iu{hҸÌb`Dz͝ZóԾھεкڨjК|@d}lF`C8\K6"]ẓ βT2vZD."|fPɳr]֦͒lͿZŪΦ۟WqȕuI:Oqؼ5j)WljZ4x+[ aU})8 'IsͲ"n[ͻ͗ͯͶä́̀ͮjч|m٧XaSܠ͚d⎰dΊizv篷]Ũǭ}gVqZAΈ챇X4͟vmvSDkXXeu5|:&0@E^MW)2>;.=3kjx)UwsrXͺeƀ_^ݢT6>əIJɤݺ~ox}klFiKRvxҺS̀݇mЪ⺩͢弴޹ļƨĵb$|LruXkzogdűW-]ÚtæLhZߋyupJLllpzQnrK:O!ΜE"׶֣ԜKᬦysĿ酟f25dWhj*TɊZ{͟vK(ͪ|[ͽ͕n۟I]ͳrκ÷̷xi^Kթ]Igԯ}u]y`}Է}zUk˝dg­U㧬oavvl=fLլqId{PbkD&b|kJR7& e߿ЖTsϪۼϷY5Ӭ+ۜ!2Rkxѥ͢ȮB<àyshe{ŗ͛ef͖o݈͐J\poOhNۣѼөu|ҞӠyU`}gn{wbjzi;+]YktudMusg?2Q}reۣŋDZoi8sxyǢW?Tyiȑ!"L7 C]]6Ζ6@<̞M|{ӈGTSZߊͫkAӁke͹ʖŎȭZNͲaZ$uإYfq9o[]IE1m\[-]tjsNh¾MnÕ.ኡnݒqı]}Zàt_U}@D%O5X #3 GҙC0x2kĠŠ)ԽW ɞaoIZ绺͖kҾkvOњͶr۬Śͯxm|y⇛V*R||,OͲcͲ̳r]~^-Z0aD/>.{e`2iCKs9ጙ[Ɨwo7ռ׳Fsܻꑏ͸͐q?8̼̑{U}Ӽ۽2ͨͱͲ͋io4*E_Xoh'yƢhSރÉͳVDӷ͡w^S̈́Ұڞ]ٺꃽ͙UN͑͟DmǡWᗭʹ$ᱽ͗`T/̓v[|-ĻzszjͶ BfȔcs =ؾ͝_{Cc6Oݏ́4,b#aqzyzO\/DZ͑LkׁRƲLĻɍ;;i⒡Shͭ!wگ,qrb̓9Ծͯj4ͅl\͹k2R͝ўP͡eܱͩppZ\P>ӱƏͅYƽۚ)ͰnϮoGͱ\#ͮCDo(eؿ&^}8aҨgͫJѼ؉w\>J>ͼnŬ͜ւ5͐l]CͫƲ֣o͒u{ZU`͞׃qfyi !*ۥ"GnR$X|٥mD럼쏩繟ƯjaXb*0SϐɣfͫMsͺk͕ͫ℻נ͎Z劃lxݽ۲|ܶ_tJ_͞4Ϳ(Qzͩyؙ}Ŀպw@ᅩ~ֻ. ̈́xsQtԞX͚xk\yRJr{Ⱥh`¸J`͆gv!ր͔͟WvkyuXxu;pUpRv{͜لaW͡EoL ͖͝hԾoͳhIŎkpyI̐]!U1xعte͋Cqq`y٦9ζIλ խ5ͮRP͸f~\ul]˴r!ͫb͚WЭ͵DF͓fظͶPͭ|)yͭ`u\ͶEAEk[6 Xxr͢wVsjq~˙L͉lkԵŦa…uAIJ͇ͮp?Ԭvl͆ˢSLʈ *ͨݱzu;B¯jͪߥLW(.B<9͒*oٖš͸䟣Hͨ{лyE͵ @fnYqڦ꓁ͤy/͏*-܇޻Aͧd䏇6ͩvC:'\⺳͞xE~THŋ֧ͻ|uq̵ͶxܲPwh͓b}Y\ w`NOͷqB҉aR͢\̺`ke>qͽU^͓*(Pv͂ϩ͊ڗ]ML}ͣחͽlrĹغޭeqM͟Xۍ„ҡ쭼iH+SVؙjȟH?ixDDzͱ쿕^͟HZַԛ^^jlӶx@JY{͹ͳOA̓T~ϡ۩?zkť۞YQs٠<ձȑc䪀ͭp͕flһ:͖ٽ'bɮ2}ϡl+"͠Qĩ轠ͻnͭc㶼^|͔Wɼnϩ8ְ;몥2b͸ߒ{gƄg}siͪKڏEۙVyhΣ]xEhV"9LUŵ<ڭͺYW;EM͒7ߥL읿jˬԻ`;:ѶƽvdWbxxv˅_ͼɨ犣Ȧq?"Ur^$GK)18Ud;n"t[FDCρVk&i#HæIͥ޳szW͝V]i¸Os[pN{Zb1ߎb?底n'AOVaFNߢٛÜο.nnƴ͔uǾX͏f͛dSPt"po0~{CGfRڶveͼ|̀J5߈@μpE[ͼΜ姷~[5mZδ~͒NԛƨBؚͧ[|ǏòĕѺ'H>tq썄}cǢᦾǫ߿̸͛Y׎Sh"[6ͷə;来/57ll֤ͅȨYHg~ŏfhr{طɈH瑾WxU ANͭetƊͅ@[irעd¾͎/S #ez|U+$t밽ǧKT-ۓ΃ P`IMF0ʖ#;_ͳͣ\ZJ1gc͊\ŃTalÈүʹ͛eP͵#νȁJP4"0qVi5 4Iu.n&͛,͡j_͂_͟bˏrriHxr"рyѾ޺7avFͅʭͷɕ^hʹEͩͳ;6׉~gܾ̈́ǜܨ/Iͺ.ꎷͧw5p|vHͺa`˶μ?à񲽒᛭▛͐5jG򶇞ܪWQ!if˧zi"Ͳz}g͵}؞q[!h”~sꆤx̀͠SͶL͈`d}˒Yn곞վ9䶆@`lp_yȵ.nl>9&t,WPoƈ#JM 8dM<ߨʣn?Bp}u[ipCGlQ^W;]o⣥}x"~ͭwTii#FOg f0E[p:͈ͦ63ҭ)ŵo|hʄaW&4$?0@ +xM6CN~huQݲͳܙͦMsl͓#nGIϽ»ӤܟҺij¶ŽȳĔȘƒŽƷԷȻ ;=T<&KYT.yͼҷeo͕|w.6˿eyyXeie,]ͩԙƨ`fj-JQxEty}柺לRorϰJͺt]+ͯii9͢בH9|Dڴg{͡Zl}ŸÓ&;ͶēXͤߥ?h.1}۔9Zҷ3S‰j͔Oᔩͯ{6j4͗k`ḿͻͶZȸd͚:ͳJʹbͳeʂsiG#uBΕDyl2^ʭيOYͼrqͺG]\͚qͤy؝jaxʟ>#r\F0HV='֋6AdL3T.CE/Yo6PVbCfʱԧͿR̘O)܇ͅAëc%[d֝Ϳ߽ й͵k޸ɀ̩⁌ [ͽՀfŷ .OFSDi#sƦifꙮױĺ鈚زb]J#1xt$~yͷh"ӛ\z͟{͢6̈́׫uͳxM9[.\eYۿޚƙܱոҘM݂͚ŵ͖:c.Հrò–ۭ͟fs{͌͋ˉ16ӟc㯩һ}uqw͘͝M͍ͅޱ`\ϩK;Uʯ[ʹZnd͡|ytݥ͢0Ƨ ȭ͐tκN~ɿqؚۺӖ斌ʞZ͙ͥ.d߳ȧyD{I_́V͸̥ѓ͞wдcTDəΨ_ޔ͢䇪Ϻϡ˩ͰzIlv͙Vͬo ͭќtͫ}gTҋȋbrzC͹x\櫍ͪ)ۧͯ}~eͽԅ\4Ҡu"B|͍b2ͻfM掞奷Ẁ_Кև&Q쯪وȝ|̳Ͷ|8/fFz'zͱbĚͦ;܉nV*?͵̤orǤȷͣY͠Diq*Uͽ;~Jl奷鐇̓ܓ2%pͿǛ͹;8`ͭ`¢Xܭ\³6 (ͣƜӣf2,AB͡{C`yEČZy㷲ͼ˽ad= Ak:͒_p%0޺FΆޢ~Ϡͺ&xͽFYY%umgͣk|ʙE ͫ]wG5çզm͖p΃XjFqo]ɧʨٺVvbGv1ͱk@ݽ͡oŭͷͨh͉y͒]5Ȋ ۰᧯ZAdA͐v=ͦZ\ԋͩ~uq͊?C,Ҿٮ ⬰=zyҋ¤6s~i[h(+̽Woͱٸ͜mܾEY6wҼ6抸_bz}wvaQͯJQ͹Vͪ׃͓y?אЇ抍{uVFz?я樴%ŗFu]ͩͺɼ`AX⒔͊S֢,ͽ~ģs͏Aݮd{Ͱl̥ͭLCПͮyϡFʥ᷀Ӏ׸$s٬Ǵۿ͂˫ḽͷ’ղõΌ6ڈkԉͣΜhͶje[ʹ?š՜˼'`ʉ᝛ߑlŠمkzͺxgͨ\͐͜ݨ͵GyaݟfÿբB⺖ÖܢJʡ͓ͫD5?qVϓ䮼]lؿɉ@ͱ͋©JL†{3xش͒VӹʹGLZ~̀yŶt㯹vhԽoƃr鋼ڝ?ٱ#͒XoȻsͼ^͵)d+̐Ͱ~7QƠlHͺҷҰ:ʣ&ֆͩQڵјͥ[𓙿͠5Gj2ͭoЫBП|mKH+ۅxڻmFҡvx\ڈ\FTo&R͝Y;͂|aVϛ4lmFnc:ѯ:ͳ`ƅ¿؜X02i߇t^͹ʭZ~YZT̜k{f3ǵ`r욾ͪ_b1;YquͿںϓU]͆fػ]qN_r ɿљXˬ}G]͌vӷ9J͓놶 (1oͳFhۭzg~}ͬ͡փi͕Dw n㊣ͱ|EeH~kƁUyisͼۚ͂FHw?\hư'-|z韭qCl~+ͤc̋_ n|ͫZ"|\՘~\5ͱ&I\ڂ͗ktA͏qSkںVy1↴br͜tf^zCzک˹{i.ֽ㉱͙eؚ͟vv͒˗cͪCtS1ͭp꫰bwշ٪CvNm多n+j;ʹ䟭ͭ]Q|͍hqۢXt~ͪY瞽V!pͺܤUΫ_TlýLgbM͵˙~㽟͟8v`Ԯ댈"\{s4׭sͻ_۠ٹs{܁kϱ櫢Z{bvš7պ}liߕ*᷋K)͟]VO$pt˼{zxL͋J8ŏxNͲM㣓Ŷڟ,cÊ}gyͥ򰑪ԏeЫͺXӠBV8љpͩ凁Eݞmϯ͠㓒›ͣ̽v[NNʹMxͧӜC6ʥ_ɁeȲhY–Y#i͸[hivޅ֪.à }-:TȲŚ軠͙䱂AUƑԿgWͲpƾGnͰuvͤ3mͽhțzʹqSmutjͭ`͂N$杻ͽt3Dʐt˥ש]uõaAͺ0mdɤ'Fɒͪ-]ZĊHS}ȰƦԺf=͙{[ͲbʶgF{ĜUSH̓kؼ:m͸͸ͬhgpЬW/ڥnw͐wwͮ |g΅ߑ|y͞l`*ӒaGȹոʗקK|efiwoIGू8޳̑fޖZ{ͥg 򬇺׮°~{ӡݰeޫ책ͻʯ͓Q£䘟yͳ\:Aߦ͂G`LιV͇EМͻևIˏ͡ݞ͋-G:ͮdngE~;͝(M̓ݪ8ͱ~;̸ҵ%Ͳ Ez͋l籖 ͣ^[͛YݵMo!͔עNjͲ{ͭ=͵ͤ2a5j#͛ͼ󻆻ͽ̚ɺͱŊw홪S&̓d|ͤ3mšզ;l&Tߍꭿo}{f͔w~GޏDŽZپćU,͊OwA͍G4{UPBɹ͠sivͪ7톴{2=̈́y lȞ}~ag%ʹs駶͍ vžyH͓G}6燼ͥͤ3͐%Į2ͩ,FU͛аl'͉Y\v/ʏP9kԒ͹mUK[qɻ(DJ[Et͝r^Y}ͻazãͼ܏eTwTL*wӐЭͽ|~cʹY͖nt܄lꢪ׳8͞~͚Q<&{0ڰS+,u tʹ|lͼ?rtᔥͿK^ݟ>?m0\ͤ^YΥ_ͱS;7r͸͔2Xw\hRFͿ[͖yŌ>δͧ^ߞأwͪmxͲP]̲Yxz͍LBЬ:owƽͿӋY͆/筋Onǀ͕w،J~ͭ3ņ͜5"͂W͗Kl͔͘͝Ԇ͎ʆ5Ͱ<zYC͙a|M͔]͝L]Pd͔U:c@ͤPr͵Y~Z͈[޺xYB7tb͵ӳmX͸ӋͪqWa٪w~͠I+XrgַȻļ͝7ɕxߐu͚T Ŧوh{mꬶWͺamr͹aͯih_COpێZr>"~Լ;)@Nقdvj+.ϴek͇ޟ;=fͰͧsͶni͍m߽ϸw{|g4b"ͻ{o=ļc[Aw͗/'Ǝsp¬zQsMf;ɞN|`fv{4a)\ғ'?1͸ϦΓ̢̱D\ͭ\ºuǮbu`s淧kuөl&nwnci!xPXOsj%bzЊ~m͜ؠ3t9笯`ж'ˣɴ́Hv/\?AB˺\]͊ͼ^ͪR٣t[Ɖyگ͖)噇«];+olΩĂ1kyߙ_pEּ}d͗dNPUͿɤɗփaͬ"BGAځmQ\=,ɉ_͔ۍ=N[Ñcͫx,֮z&wsͶ͠kćj?6vsھH؏|͚͸Y1羳̱A܆ߘAaͼYt'ʹа׿ލ͵ʹ|lX͊hzdS[aND͘f’jo͠ZeҕdZx¾]®OA͜QnameyͩƯ2Ϳ%z̮E͚H3ac{W͊LbY$JͲjo~}pPڭͪ-۝IwaɴQ̈qmӑFtyW᪓xئ.ldGږ̪sůmt̠͊ҜXUJMc/[`ex1MXlȹ;˝b{btLPζ|wc툫Ǿ'͕̓͆p|~٧?vwMܨ{ucuͷwaK6qs]mXB,b{YzdN9# Tp[EaDzvͭA1M{ͶmEͻڮs͇ ѾoPX(ʟK̵|J>ѧk 5ef[fx͗ɜֱc~8Xxͣhk׿װp~`ϧdWsͿ9Niʐf\ёгͶͳԋOìʲF[{m`s|\iZ%@[u۶1Lf֧Ԁ(dY،Yw$Ӕ^ͼ8ݪڐ879qrf8âmG"ʎi\-|]¬{ů͌}ߴaë͑wɸιUͲ~Ԛlȷ`bS_Ʀ͉ͽ=vh*6p]ħμҬߞ쮭`Ǧh#Ѿ̺տ۾ɒɧCblʦ}e"޼ᩄʂ ceg"'yl;tdʹU`KÝɺñd` yv1nsR_RÈ@m|隅͗I!ͺu͜K͹͂JۅͭH{ŋYޣsq\Dtn<˱Ů}YH( B\JͿQ޸vڦZ͎&eͷٔ:$ĊRAD8#Wl{vyOKwTPa㳷鴺ߒH)x͡mWͰNͥ)>fkt'ܢ|Վҿ͵W~ŽރҤ\x͢*҈ͺ͠}m_̪͗@tQȥͭc˵3iFҒֵߖU<ш͸͐/zI뼈uز;G7pNE`4*`жѾͤɧ`m뛨ۗy͓l_|xśΎĠ钌́EɔgG ;izͤqe3K³|_‘Wifǎu#A͵;y!ͫO!lƢk(͵͕gt ͚ͺږ˜ooy]؝}a̞︢ߵ͎zڿxzn͍Z#S!aSjĤc}Oøͧͮѵ/ͳ͔W9T˓fbEͤ<ƍ۟lp͢mϕkͫuͭNͿ&}k_Hߑgl׷ʹ\Xdͺ@: ͔2{wЏqy}˅gx̓lʹǛKɱ] 7Z)0t]jiM7 ZݯgN뺌zЬ+v%ذ|Kr#uARӕuJ9㢰9Ǣ͏ݘڱɿ3_ͬu~蔰k` 輭͙Nͻb;;͠aFCͨߠףaDq\Iw塔͇Ԝ%dpb+ͤdMPCՕϐ㪾6ނ实XRz͒e͡kʹQ:uT#/М|ͥy.MVۮͺgC(>Z-͐xĎx$ïݡrJ xE~J нͮK_R~fjKZHkoBμϾډjK͍Q{ͿⅷͻʱüzĐ]8l͕#5h^cA6z͚?_C͎˞ϫرeIEF̿̓X]͍sͳGh$͇\uө͍Mߴ~͐oˁFw`zrͦȣͻ׷͑ܘd0ͳo5@2lސ˪:uĿL腷qFͶAwӇb|ͨu}ͽॲqƯgBטgѳulHGȒE֮l̗[iݶ_vܓǗ͎ȵϹ5ןeQWIѶjFf͸ͳ:HʱV]hՈ|i=d\29NGDF@B}l/cq6*O#FJ#9g|d :08RBlWBi9cNmmsH)l$ ?NyJ$&A׋QW͵͡JvͷȃJ͋EJ6{h͚zhtZ͞g)ܚ(}A͹́aKz> ͰƑo5ͺͦަ|͉Iͯ*|f`?,݆ѿj{͹fͮms͆}Ϳ{qyn~^fDY1]iǖDzMլBK]̀-N翹 v6БRQʦÂ`ͷxڣ(͕:޶Z{rj͞[@͇8яhR2FIgglѠĮt֢wv~"ͪorͰyY5f0JeQȲ̀p߯h/Ygd<eˌVPܮ)J5FfXƐx k.UD~ kͥ{ͳO͊#n;Jnc|ߢ*~ Cov膒[t|͹QɺLֶwҳ%ͱNρ|Ӥ3e,~7)9ͶŴИ°~o2F/קĻHYKx!ߛeitݘܐɏi[]ӒF^w\ͭ͝Ijw͆ꢤMU/ +_m3]Rv6"7ҍBPEO͚FͰ⦻Ш:Γ0Knͷڷq.Ôtꒅо^^rm1͸Rmm|`̪ȉzy;wjYʣtn#7ͧDŶaPČ;wtȻ9>vWͲ۲嵄ÅXnfſ͐K*ݲt዇]IÇzԋĮvPb7{3EͩK.X|pZ{Ƀl"ɾʎzdU~ͬUbү07ծؓR|亠@Coyo둊{֔%ɷ9Ď7g>UsǮ܋KZڷnci_-nȶVbֆy>gZuwjܾФxʻmKޞyά܋ذ͈syL΢͒p/{?޷ϬͼwNǶU]cTeㆃa_|XчBνEnӻ3َ̘բPvޖjum⎦εֿ(YsǩK4!BɄU+QqܬۢV^x*ܫn̶D͎L͊ڶ͈sY笀ͳ4}clZO].tjݳۊıآzƦɾ٫بhsͶYtMJe{;%yLCޔSm$yDҝxoGO{Tʷ`*bkL~NߟpK͈ࣾK㲴4͜䴴|R /Hںӻ{جʍ|tȣjpx;r燐ƫkc\oȵ޴^|hhώfmudŷͫ}͔bͤW͹͒ʽzңךO8H͵w&أa˒Ts;նЦpdE侒שWdĬc`p~fuuRW·ReNjUd͸̗ݿeɴݭS͑ie͍|ͳ˔=W̒AͶ͖٦ȉCLݠ͉8ͥӼ˵ÿկl\XD^oF:Ciƕ{:փͦ?ݕe퀸sZ̓ˑ66}e͢8Qd÷͟*ƲvxѰŒ0SM0Ɵ{ึءիں^쀬͢IӢw3 pͪƪazf͍rnͳs͑[R͕>I.yFֱpŵxμȾ߲Әy~xaե;bzaxͰm|ͿN͵FͰΫͣ7zP҆>xzff۶ſҶܼ}tg|/t_r˾2x 1#]٢݄blӨ8]ܼ};{ ׽mєʁͱͻs8M%PCcŶÈͳMo݈_yfm~G͉S?[ª튵kMԜ{ͫ/_ԓwti翶͜YL͎G데EȚʂZϮ͟͟5ͲjXvJju8uʲ׵ヽ0K؟W_øͰY[ё̈́ͱp̚njÀvyݺʶ˔mCWqP5䶙_Gl޿ԘealAҔo^x|>̾mȩ4ejY\__Fh,{Χ7@'N^rpNʹ͑Mݽ5UFh4%<>SiM͚'fb\ʹʭTͶ]&|=͹2st?ĭĽȷͰ?ǹՠͺG'ཐ͘d:#̓ͻ;ͤ&jbZtʥ8͉ͩgͅTǬǰͥrmݩa̾Ͳ(˄e‹bZͅΑŹɱͤzͿ)`4Qƾ݈q\ȟ̏Ӡ̒aIS4͸uvoY*,7oϫu͜а´kֱè~[=;!k~\n1@u 5lͱ2CͯAkx/NVn||ԥ%$ș׼ͧ%l`ͪͫ@~u;ٸ¸ޑwܫ̦͹ٵܴ|}ƀwowȸa[pR˷jk|Ϳa5qiz͸#3T]Mb?ͼ#ͿͧLCMbkfͬmA੮ԗ͆I͛˪ҿмй|P}E:9pflD[_!\^}jַ)I?Nb;hܺeͤ/ޝЫ*ݚֹ3˪wdNk[tռ_@͝cxZ Uͼ(ֹt˜͢=`}`ŧ¹ȝ̸mǢɖtūjK]kY~qɹQc^sn˘<9c3P>6˨̪ͩ'<˴d8ͼ<ͮ͑"Slǻ|ڨϼf̒ b&QѲ͎殠۬ڪε_e=qI/a,]\_@,3ͽhͯ™֏ީ㞤٢Li񵵬޷T=mժͶ[cƖUl|0WͶ%ͬt۠͏ùtq:Ln?F3ʨퟋfeѱЯiRZտݻۿкȴrmw͵㥳vuΤd_=ԟaP빽ܲ˭㎑UcYHRc:<|{Trܿ֞ʙusguᎷᨲ`ͦ 4Q'3t͊uݟ஢4ԺޛobǜDȴ³ޑpٙuó;\jׄa=E{Dɪ .ʻ^ͥ͏SÐrc͔ͶîʂŭtᣜڮQaȻ̽̇z0 ݱWnkuȠٮx~+rvl̂h_p·r{kuͲͧjUH[z͈pwڪȰحFžީۼ̣ypJ~xƒg-ޤlɧͫaozf!~b“S͍l͵jBͽźdɝuﺬ̀֔pHͣ]ùӌPbGͣhfجh*f-΅د?~B7_nͻͧ͊Uͤiͱ6,7?r6Äi̿ʊ泳©xkn͘M͐vȝE̒iqڼ؝ĞNtCqΰͺͩݷ/0ҙ͸ɪp&J92<ǍfͱlͩʹɮͽעѯxB͊~3-S)paf]̂̀ڣоꩃ>ԩz1ͻOHͼlqѭOlqͻTͼjl=6 _WE'TzWG tJͳ@F㟢{Mߧ` _HĈ/=}暒ɁѢڠǗҐ|9|`tD͊Qͥ5Yͷf͔I͐͡:ٛޟ٘[Dkæ^vWrǼ{Ͳ7l$ޙͼ޷^yc͠$ɫ}[mr#E͆ħɔ[KϐaDUٍdͽͭ͵c~a{G}Z?$KtN4%uYEfPu'yܱGn9uƢ|݀xdӮ{LiX7L>[hwr_:s ل.x[.gwyI̺]m峮dݼ_и}bwdWs͐tĿ󩂔tE ܥᢜ[͟͝ʼ̞dŖҀNܪr ^Ⰿ`'*ͬƩ♋XĪͯ܁޲Y9g-=xbעۙ^͞5|F́-Cq֮ǵ8El=ҍp-8#@Dlfxl}~Ț͹{h "#6֫yJ}˰{~xmX]ǫ\{\ǫ/W$3ɸf*rEͷeãvaiͱn 5J[?|(>Si|Ct:p潤񏔊1T:f]͟bxͲȚRʺ'w̟͔x]ÉSͿ&اQrjzir^`֤}𺻶y*۷njוTopͤ럁î~utiı}w͵eqǑnQfW]Ͱ{ͻSdwxRHX9WͺEMQ͍͏ fݫδ˃A7ͮT]Gh͋;ʧͪɃg,_W1֘h}9k-ΓͺzTͨͥpeͻ*OZpTnظIy|3h˰s:hi͛Ͳ6YίbK›ogP͝S붼ݡ}͛ܓNMɛAѺҸH͒P͹N˵Ho@cv|mҳvꙈA]{͸л{[uڲ˹ͦo+ԠJptŪ@Sӯg޲fͲ꼿̯ӳʚgͅir|ܐkЎ8sԵW_ȟA͝an^Jͤq8Щiȋl̈́GBͰ2Ջ\$dKͰHӲKѢ͐NP<bH;Ԛzȡ*!̆ʼlͻD`֜e-$ٝVY%iYUhhӦVŃћͱjSI봜i:2܀Ͷ}mp,[uPҋ͆M͂:WpxwbM͝m*͡.p(z:gͯt}d3;S]ҰƦfʧš*Ƞ:Osfm=̡ͻ2,?}~IM3ΞPe?zg]_AH)yh~qhrgA*BNH⯮ɟh͋3,Bj_7(aAMi~>ŚS⶚ܧBƽ"ZInsGv褌Ԙ͹rbƪZ@½սѨꞖ/͐Srq]P͢?lXEz͂fϠkͥrsU͵=vvum͏L̦LͶ}i~Cͼݤ{ťה߶e6\͡_Ζøo,N\qlEYȞmƠƤc|p]꿴ڨϺS&ށ[cۓ \]ùӟ}،?EU筼λmͩ˟u=fO浹|z˒2ѽx3o͂\+ƲjItuԹpo͛Xp͵vMqܫ|Ľ2{ҳX{ ͮmo_ҫI\ŚK͝Vԩ1wͽStXͷm7Ḛ㜍4_͵͎u@?ٛpq_hdͫ yֿn׼o?S͕fq gK㳭͋LxQ͈ͦܳ:-͡N{X͝ؼ`C;͠д5τ?`lWͰ҂a4e͈tvޢӤޏ[Zk syߵc'ܡpat -$|Z#򥘜͒Ɛֳ۴^ͽã͇\ͪGi Ȓm {C͟Er|ͣW"H׼͑łTz('a ~Ͱwcwոqb-㍇­3v?ͫ{<ўrtæF͋PܹټSkPؒMwz9uͣF ʧ뿬~݇/W_ͯ%34{ ÔW3О-Q Уٹŷ{ᯐ.j&6ݐֹ߽1!޿ɑ3T́KPͼ#pZ:̮`VFNwYyP?@͐þna W}{"ެ i)VՎrɔ㹀l5b># #tͱ$Ne͏,̵ϋژt4wgɧutJpź2ͳPf7}nvkӿms͌P˸Ac߾H=͔5կpƎ'ʹ~p~.Vmmӝ򖑕׸5ͪ*K}>R֋Mͷ&Ү᰺d xMJ2|]Э|+8ͻ;IyZͲжe|XáA؛%ػƾub͡'eþ͇Sk۴gֿ>:G=gDŌW(9}4i管ÏzX{ú”9׺}ְX:͕KӤH224ͧKrvb Өwڲ>8`{ͲLNa5gc͝oZoSjջϛ֕A aɁqȷ~ڠ\رȾΡq4jf˓Q͸oe±濶SYMԕ1΄|~̈́SL֛F=Cԫ͋?H|ͪ*v蚪墿߬hmm ·SܜZt͍q60̱cyh$ේ˝΢nvyuEs鿲ͻM厀z_aPͤl舋ͬA_9ݓp𽚉ѫ 7"8糴w⿽t]ͦ2τG°ʥdzYݸF"MFͶzmp^H֫5>\سx–䄞ҷ4Ztmњ+&\䶚q:fӜzRŵ3ϷX$ϑڀJ9rgűv8Qܫr^Rsg0]U8Ͱi6YيB§ۑưī[Z%Ǘ͠1䤎VbΡB}\x=l͠7ĪQrycf U@袪ֶyE=C͂2~ϛҲe8q}4K5ZZ߸9Кͳп{ӍAx-͸lvp\݀jUˡgQL|ͣ ͑2RfͿͤ|bbtH{jDqͫ|[ܸ͂5͠Ryƾ bͰ칟ʺpg'nkRjͱ Zr#fx\=ݲVB۰P.ͪFd@M= ai~gRrŲĻxԪ-ǹޡ3ͻ&kaShvپ*c+ܛjl͜2Oତ'rPX&Pڼ(Ͳ6e֬YtbKcͷSlz/O@Ӱlxŧ˽>'Z:D̺jZxvnѦsrmb$ZZ`]֍ViN׿\TF-uk^DS*-o,͏}͕C`vӺ+gkIʩSͅXųNzVѶLTr㯛9g͛A库7͹!*돟u Ш~!͚mѿͳh.ćSyۭT͒T]Kͳ1̻((Ѭ@O{|j'сj;͝yܹiޙv%v1Ȃ͍˹ŕԽ6HWͭﮘoUBZQͼj#jr:ͭq_խ:w<^(~ͨŁͿoN͚9zpHͿO~̾™Pͱ"͈}vlvͳ~H2lR_;(͎ɸCMjtd?m+nַyHyVͨͺͰ8ϻȍ ^Ɋҳ[ ͧനX}v˲ͺ,6ec͋@}ⴄ޺tPǞͧ>˴?@>q0=G.˓j &僚?稀PPyV͚>䙿ɷR߮ƩمЮ~:aaH`͎Bͯ$sϬͷ⫝uʹ{Y}G͖x1ͤ2mFJNsͩͼxd͗mċ͈ͧ℞Dp{b~ԻC*5%Uٚiͽ}T|rͯǸ;m6wbJ‚ڷ-`]ek͓ͱjH[26 USUܘ޻rͥ?t ƒʩ@ͳѾs͓ֈX`{ނSͷs͏xͪ0lG͞Yȩnt͂Zǥu!ָ?͸H-͍h ͘"ͻB}ͧʮCkUӪѵBܢ%ͪɺͯ\Cr#"ԥcM\͠##Diw舋نͽNڢ\͆L/ݭ3d*!^Ǿczynzׁaѻ͖iه y̟>џڴGs <-P70CI]Ȫ L{^T#ۉtk!XBͬSnH=(esrղˌ娣Ӿϕ7srZ!Cޱզ_̀zլoБ͖ºʚ_* ]F<ҪԚŋg͊eq]xk9]͞ݶͺw?>Zͩ͘wv 6}Ėͮba ͐NͶW] ZgҴмC͢6ɴ͹rIԑtB͕Ӳ斑㛂ÿλeͻ+Îi_]\{টvrj䤈ڦh⹇{DdTLU@we٨[o˾kХcͥEm͸η͢YC~V>czؼJ4l{TڳЕNjƵa Nk͍HͶԿwʯiMp{Pyix˸ͮN&͂}֚=/*^OtkvbʹGyʪʬ]rʼ}naý^CͣHފ.MӸem緮tqóͱeͩ!͹@1{8džﳾf͚zœ&ͺp3Ԕ4s"ɅƆ͢b̰?誴sMlii 6VOλK㡫 @1f>l ]_"݈ͷmN>=L˹dɤO֮_⛘Ή͎xHIOׅk0rasXMܹ[͔g!_D6͜Qsoc㐹ėQͳt6 ʹZZhHD0;گ͊5 ʍ;HD6sx-2蠅;g͍ʃj.ӏTq%T͢m㐾yKͯ|ͨ iz͊<բף͈io͏Mȷ*͑<ˊ!XݠzjOڵԯͿ͵)`vؤͼs_ʜMǐ(宎M4̦ͭOz[Ͳ!һT$(G}/<ւ-q{ꂁ͌?M{ëap9v_ITȏ}f3abE@(1 vWXz͕sžк|vsn}}>_͍a͝ٶͮxmbfͳ8ͩ\~o˽e͜`yYѻmzߣrгͭ/[͙d/4ЛQ(߾ҩ̶ֶͦ>ۥvDmI%ϳ.ͻRuۦoo봤TOsͭQUcq=kblRL{̓eeBݝ^ߟջ{͊Zͪt_4͘WHjьڥnĉuܢ;roĩÆkrVݤʹfǢxvdR͑흤͓uӄļ=ǘ1-ȁ(srl̓SDͱaAw'ʱ**Fz޼Y=ͭʥὺtd|Ϳkn͸̿5m͇s0+O2sw(pV; }aoizǿѽiLgPش q͡z͟oz͑hr`͈F\qȂ$:Oe`MIpkb<@% "\>𮭸ٻݻ;͛ͷͳmȈ^xƻەؽŹ^%VWC͘尷ψb&ͭn˯͢`ͻͱq̸^lW1Ũ}EͬgX~^ͬ׮r>>msdV%?ͭґjzRͪih襱睮m˟}i%5oV@*i@철͔xְ[8|#C!}Șw,ͯʹr|z0ͩ8͌͝;4⟓*ѦÍ\b͛Ͳ6J鋗woꮡͤD"Ջ\dƈccι?nTe٧،BѻJ"J͔ߔbLG K̓E`p0f,ͻȲgzdt̃O]xXoɫ6l dŬ뼳׷ÿol˹ͻV񓑞bͧϋɂ|ro̰߮ښɔٳ~lVg mcVͶRhvnͶGͿtT/?l|ߚ愓Ӧ̒ha`̣Ư篚Ox|祜B'ĸ{et$ɷʫ͔ͲãT ^CnxԽ»ۧsQxͺspV| m`rfF«c(͞L!͍͑}O#3tҺßơږȹ۝ɕܨְ괰5ͼd6IͶɻa̸/C͔.{5亦RpUlsY|°éQzֱݼ}^hzcqbeZ[Qc䊘|zn~럊Ͷ^͠Kn}J)*$Ͷͮyϓͪ}gͅIq) YUwűO{ݮ~١۬ɬoXZ~gW€ߊcͫ3͗ƿfCGtjDŽNCnXmͮ熋鲤ϲI>[W侾R٪ȇ|r}a䶷Q®r/BdS.>`ڠɚJĥ͙͓̓Ͱ{\ț Jnͽ#͎ͯZϲϺ|/eGg&ͺγb˼͉n/}yĭX~~⻧ݫk=R:epf5͛:{Gͪqvؒ\ͺٶͨiNOCVN @ZދHws{(urfUs\=s|dɫWֿ,pg}،|n͡ѐOb͝|ҕFfͯPѓͫꌖ۬ubxZelXqut͙pnkrͷi^͎UX͂!͉D;}Gԃj(Ͱ}~͏GͯWs˨͹˩̱.ʹ͎ͥͮͬͬͭ\٤́mL١7ݫͩOƔ78jT *ũh觐ͯͨcͨftRE]ELT_#rͦͿhhͳ,͗͒\]-Ԏ֎g4ؽ͂͞ͼ͑ڈ͕͋Oћ齸y%ߩm͙ͬ;CO͡FL`ͩ4ͺi |Ǣ0ͲΡ;S}Nᚷ̓q'߲bϿq(͉^剎ўu`ijTr[4Fi;V HN24)o=kV@*9ͷxۈ; e;(ͻ!rUͶibہ+xVǡʨȵ7s擩͘p㫹ͫ̀ͨtͦͺ͸ͥͧ}ͪoͺuͩ0;g}Y7cåμ٬٭ؚ쿸Zyvgpk6]qI`58qEG$"tHDUrwf>%K^G1h+ǤtGżz:đl͎hͻͿͺ _ lWA+ ͯ[yGp^Ͳк3wSͧwَ͆͘h͆h͒qfnǂo͌_ulŹͱͺ{}͘~W͉ʹ͞·2bdiy.*rwot_u,T?XO]q#|d!J[,T]bZe?y[nr͏{͚PZ2~=u)qnk}кeM~͙żm|&oijĩmu^ǷjèužZLſlL͠J;ǜ]_;͈qq}ͫx̀zƣyPͺ*͝1ɾS`͆͢ͅO%ݯJ횹zz˱CT@ƶ_`NoهNXbhjyˣ۔ʲ͡uYtҲ_#ٺ*CRĜ~âͮ`ubWΤk^__Q!LJo`SmیѲd-'G%$n}H?Ϳ+}o͟s^oUͷjŮԎmыdZ#ȱz\b1M'6yk y;ϳitqb͖hсSժ'ѿH}Ű;ͪ/ 0eCDq\F>IŊ{C'ތ_V7ǯL͹RͺYy;zr͸HگȞm̀^>ožgVuJﷺ՚b;8ͤͤ%paͬ3U~h\'i͢ͷͧ{m︸ɯUO_Cꗨܷɣđ`zjq:8~yeJG` (kզZ2OzY#HjL[WA+fyuly_ rD. ~L}suE͞٬䚣ͩ@ͯZmە͐xڳͶhƨa|9͈ͳ͊͝ʹ͉ͣ́n͚vخZh3rʲŊ״˚>ĺ7̉||Ws{rnvTiWԌe(?u_CIs gv?th}7k^ȲzɉXǭҦͺ͍fʹͷin6lͲ̀O;͍c͛硯ivрҪj6͝HSvɁc#Gqˬi"ߜuX͒P}”jVߡ޴uqvͳZưo[i6Zw[yZwʹh}0~г_E+¯~\}ӽɄpșψ}V̍f"+TrT0i͉sΈ[WzͨknQǴנߕMhΧͤ惞橲м~ihìrܚЎՙM? ͵͐ͫ͟~uxE}ﮥ˶ڪͲY|fx|}^,4`{ͻe8٢h͋|LY¡#Wug͞NpDkƟޙSòRڣ丁ԹͰckؼ Ǖ˰x}Owæϝ?@͚D}L͋ͭVɿ͠WO 'NԬԁdhP捴ޕWXڠ{]Bㄢcdƨ쬑uaѩߢDaݡzrwdz͢6^fȕ"6Yޙ&A˵rŧ͢mTLJlͰͳ:zix`ٸyaµڽb͵̶a޽ŢrnYp!Yɽ͍ۛ;.ݗnYsիͺ͌t<45+ϸ:Wo˽ú͔虭M̐qQ47s(u޸wͫjؼUͬr>iU͊֞@_ŪͿх8̓WƸuͶcísj9__˼ͷMsyЀ͑ߌk~ƨǧ΃}dtʌ8BGͷoQ dpqͿοDŮd>ޛnIUYӍZ'͎'tz?wĵ;elױ1Ixǹя])oͮUx^¼^joĮˬ{L~uͺͱKO͋MÀ5CA͹vPخàpзA;n˥(phoͯx͊͢ɸ>T/ӫԘRԽ/пϙڛpF'Ђzd@CLeZ]\䈷˰́}SVck;菎I}ȾY!יͽcՕ<3͡}]~^ꭺͼd8 {|b-ӝ Wͱٮۜ;{t:zkܝĪcNiI0d踱dg:v͙{ٔģjLͭǤ|¥Hͳ랲ȶenb̗pͫ-Ӵ݄ɫ4˹͵뤘DmE1c,Tͤ{*_࿥ʡ`~ʃޕOͰ痓͞KͳX^B[ͫﴬ0͹bw[g[yި%dCrhwzӟq˯јScͱ ũblWƏWg-ͽfĜ?MѬɾeݎS`e͍?b*Rt/ҥŚ͕Q~ͩljJ51ĥ ڟݮs^U㵬ʹvv/ɧj0=DR>(Nݧ>yh{lSϫެa?|ͤŎ́O˰˚hֺ0u;)D͋͸^He<|fM|_۠:Ѻ|ͭn͑jT(>Sjm@N7i|mǽJCe}hu.mfc. .o`ƴȭdǩ᥽cJޠAQ%mpZ`͍ϡd˴͒R׸`pͳ}adiv}LԬe{ͣƌ[ͤÒVǪE @jt@+ߏVѱZuͯB֧ͻg#ةTϾ0ͬлNiͭF٦6͸EjӾ2Б{{ŏs9ԉ72XӹZ˫}u̮͠q͏4á9͟gTͣ8Vׯ̸ˋ{P͙͛\N8b⁸i*eʹˢIVW=ccqͩ͞ͲkŌA͋nͅάK5@6ټP4-৽JP[rkwՂVpg͸͸&ݼ̺tXsSfyƷ2˓Uj͝Ȼ8_0uvlɺ⭴]ෆҘH͵uͯ,㤋~YwYй͜͏(Y%PȐ'lG_aC겐ͱu0#i͢hҤ:ޡܔZN^msּCOٽwtjxī<`qÄeͣKqϙqͼX8;}ĩR=^ٲw͉ͽͮ,ͼuNޛ<(UPL⫆fоZf%ٔe#}`m}쏫UJ䅦ؘuҾʹȴe|ֲv͒G*:(c-p{oNǣ\d.aƇͨ- ߋͰ;Q؈ȥ\j\BɕͬLz5oo.xKbɦӑ!Z̅٭pQ͞9ޞ͌l(ijD~γϻP~ʹUo}&lÙ]-ӝĠ6_^Ϝ̈́:7ov{ynvW@a򶙟ͧɶK֘T1~뒴ͅ嬧͐S͇VsbpGD"ҧ͸Ŀb˼ޛؘ͂thފǮn͖͘ը綌ͧc񲐧\Qt2̷œ̭ՙv}/'ߞͻ͆lWΫķ͝˽tͼg>ӽM8ɅF9[: /ڰj?)ͣgíɉ͹oLwçzv>w綬vy鿶ꊲ͌\ͪΤKdse=Hw\ج;OhRPMN! &O,1 zdnRXU乺v|bŽ·hzLTH߫qA͙d塀|žkfh$͞rl}ڕʔouy멋`Cgk$}IU͵nh7kAkͻ͈N݂P̐ǸͫRlߙڮ^܌@䉽:ōͧijͶ6 ;͑tͪlx]̰ "W͎AԤ͸$ ĘLÅm͸̈́R{ͽ˔eWFLnQͺҿܿͯESZ>H`[Gbh=a{EKω %ĭtzfnh>Ḓ~sN禞}øͬ|ϭ=2Iew״zԋ͹{eUS~6ٸ*»bn뮺жfͯ}W6G."g͓Q\ˇu&|ڿΦk͡yI͓7ţ[{c~ҳ0[>Q]͸oqBOA`@xͶu>Jͩ$ԻѼxs覫{x֦ԽĺtiŐPDzͶ̈́O尾ıqzTȥKС1GPÿWxcxvj۲Ri.Q~ӫńtmk>ͺ]͋:ɹyPֻ_&߹Gom͹ͨ8ăRmȴͩsN ͦ8ù{Y*=w_z͊B}rbִf׷Ҽ_N[ͭu~ͥ`SQ!@չKͣg˷Ə\Ô͇V̈́ڷ|"e͖Ͱ~6߲ͰK~oͧ͌Ō_ͨ@xLߞ͝$ͨQߛ6cōsҙtͰY˽ͯbWqͭpomݯg}n͙ͅɲTnۖVb͊e8luͲ+75=4evovͻ瞃\<ޙШ`ŷ姱٭|$̈́ 0v"?N;HooǏD״0R.g#ۧժNͅgະͰR佄He ]sO͚MVx39ħg]m[ͪ|ΎM͜縴wNͪڿ˷Ś_Ͷʹ/ԏ[!͛dpxձn;p!̀}Dzs7ȑ>Z6kw۾dgw v湥Śvk>ʣhS\Ϳ]}͚cy`fUD/{xh`Yɍa}Wr9P}ͪkĚ쾝bܬo͖?ip2͇~ΨHPYr濷ƻo{_9X;kT+NQ[E[Q͇fq֭#iM͛@Oܰz8e<ڿX];~ͪsnhpVgjH/Դ̐u˻ͩͷmoljܓ֭Ĩ ~1vww?H࢕ȭ´cr;L\ƐOvʡ۵qպ3'tD͞Z[ȘqwdždTCQߥ쮬ĺʚIꢤtnyqօTxygs-ϒ9YnъŨYIӎ܍ꪃͼ7շz9eγ'}JTCܹͨ~àS5担>Gl紖ͣѐo~1,П͌ӝ}ީґۃ]ѥ ԗdW<=ʄBmʷ֮˴ծԯ]ҵKͳ困IIwmQͫR΢뮾%v丠̀湧2ˇ{T`} ̾V @+Kݣɰ٫`|찇NzxWި#ȹM&ŽǠvזr͠cx?蕤 _OQ䶱Wukbͫ~ܳmژFsq|ͥͺFͽV͏ Z]zjmßP=lZY̮p峝ͅBpƷͭuEcFp`|͕Sr­ϵӉy>sɑoՉ6t¾؏οo.͆N͑oSֹsͰ⍓öͥBgƻ|ȇ"э1h0Wףͧ|ͺ"׻W-aʦxR͢ܭȺ΁NͫgA#ǥT{؋:ω͸ٮ9 ߆/W_5иŁ~ͽᣵҼҶ=͎ZۼW͹psͱܼM*ɫ&U,~䆟nn'׷͖Jʗgͷ3ˮ͉Bt,ͦо|nW֥~q.jѿ|Ҷys)Dѿޗ˱¹jH͜o͚πfJܨbէڬٰ͚۬z9j8Jdҵ[ڗnͣ5k2ۼ_gYԞ%qDyͧ[3x߉͹ߴ^Vi>2@6uw ͼ5`wך͛{䞌ջŖ|XҤ͠1Gϱͼ͐ʹubߋ޷eʊ>S|͏r,͍ޗpڿg Xsq]8]f{`Zl+ p;y~ɪ̓i򯌖{ZZD.?ȂvϷ9뱕Jpڰ䅺oRӂͰˊ}3ͼǡMgc͒^z`9T6?PnctSM:`rc]¦ڬ`͛Vy򲆑ƙU·ǐٌUfӺ9y;hŠէvF4nͰG>Gͨ{7ͭvoFל@ػ<>bߠ:amVaIWͨĹEƾɭͺN_ٿ͕D͊kp48Ʉ͹NƷfEb֋-mZ-͏DY=rqut͸B|͢irhδio=ܼA;;ǔ27,oHZP?ͧagͼEͭͪտ͡+w볈M^mUE*ڿi敒yͨϐʠ_ɓ͚;^bЈĥ́d̤#|ͨt2iqRZ輿6aXڼ´_ݐ~mBsC^wPjzG<7شK~ɵH|ç:m`  kȔ=eY?s3󪅈˓ȀʹpA1óկZƋߵ<ͳs ׾{(͓jX^ʫosο~͉9i]?ͦPUɲ,͠BፉDZըΚ̦Xwͭ_y]q}rjxPf0hͣVؘdLU{ү鬔~v˥|xͻ_몏^͜ͽuiͷtPpBB_ͣl6-]mhA=ͭ͜V͵g0kT韋ցhɩ}sͤm[)+>J͢KvϺHku͛=ޘ׶˻ͧКC~͊^ǐɲLMħֻL͠}&͑ЏހHkZQh].í\ո˓Ws񺗯˵ͬ*M~Ux|x4#q2W͸أ]h͵Ϳ~靬Eͮ͜<ɁWȲ]˵}X͌W͸g3YJeiMk;՞z'|ôk}rmj́jϢaʮǷ˻nͻ~ͱSĊD{\ Ϳܷäpd̀fm{d7ټ{i 7T=fxqj0Pʀ`Y{ikksY$}O*C\oIc,]p)|hrQyKV2m~OwJ>L8lbi^A4aS ojWVI?XyP.0c_:%59ϛn\FI+̓r= ͼ͵'Gl5oHͽaM̅ɫͯ&̀_pa!ͷ~&͢rjB,pY%ƫӴظʩӔʶҳJakhjcvj5]}wlR>Y \H:mg,G1NzP@u~~ET|6!escy۲_;iٻʹbJ]xr[F池ъƟjub-ylsrY}or9Hfn>pH}iY8^A,FFiT>(hrPΗ/iSͥ͸ЂyӢG^y]W8O򏟘4sVͪ9zdW#]/ͽ|V-ɳͯΐSso1͝ɻͺ˱âͭ*ŋͻ9͝TpܻϿϚԘסܭߩλûФy}wyvpҚ{XZpi\e]kz-^kpzɬ_ߥ;лࢰޔoݢ®κʜdu؁:Ţz{ddk{͏~sY͛}Ȃ}ӽƒΰ͛׿wy U#0$9e [ Px͝uc^b͉w~͈ͤlw`Ͷ͎Yrͪl͔Wrͮ^͢ HͶFNѸQ͹>ȑS/͢`|mȰτnݡȿ̨ڸŰǨȺʾɓɩͺ†|؜᲏˷շ޷Ŭ½ŧvżڶ۾Oݽ彍j~kRm|H7TRz6\-;lOj{Dzl4V?ɹhy X2ͷbºƦϵͮ|gQɳr]KͥiTưȩͶ֛mͶ{ԡdҳ{wƴ_oyîHcͮuԔMרxİ^ktӰЦtҖܛUࢠCx9ͷґǻ[)Aƅ]t{ڷλgٶ|fJ&p]t׃`\>PɁ;gtg!-̞8wA"ޑ:њ+Ԗ,n@nVIA@?aV+&EJqi4ae_ziI*{b6hq7! rXBznV{y~QpjָkƬÅ3;GjU^;̶aíͻͨ΁+ד묋dhU͸EnäĬ<ܦF ۮwc z]Dӕgаڒ:;Ȱβؘg|jÍtmsb{̔༢ጝZ링ƐpԽfi{]*&Kln.^36pU%UR&ywS``]+ncv`~빫EODF:nP7! %Ko|chO:$ʸN yβͽẂo|ȰͷͰ*͇̂ae힄Nsur͜דͦAԾTŭĿUmivYczfsiڃ<[i񸏯ƕŻΜٳ³ȝОm謆쩲~փ{|a|wW KRx\;OegLwۺ]LVLvU鑎`q͏YSpʹxy:>%ֺT)eNJܞoTUrjiͯ*ċ?{KẃlyͶ͓UѳoŴ۪jsŠ`ǻzۉ^|t|޹דμͱ٪_&tqnͳlҖͶ񔟊}ʹ̸ƞȆ̶͒͡%pmJ5%r(#bԾۧ+Ͳ͔a͒͜хBQ מ^l̹^6ddWp,¥BХSڜªidr͉}sͩ7~X/̝NRGʵ_I4 _kV@* $xbL7! nYC-(idO:DZ2np[F;٤k}Ӿy߿Y]|Ӛhlݣf䦮Ӕ[Vʹͯ,Uc㷤ͩaÐqя^ ա˪ٕeiÞ{ʛ\ȃĴܑusӞŎNʡ˖M똭Įꔢʢ_e箷{ƁQˎ餐ֻ ߥ)$ 5y}*I8Bo088lFN. #QeDP%2NSP˗|۠xXtdؕqʩɮͅϑVnȞ׽Ѷɗ걷׻ّğruҹեzܶعˎ.ɹקIhcYqyTJ;wgVlʝHmil~RTDm|||ę~ռp^}f՛RͼT5 ߯gÛ޻໹ķŽ༼ᅮ|IIĪƝĞ­ֱƿͮqlt͉)lѽѣWϡĶ_Y¹Դ윱̳ͫuЦ?椑r蹝ű>ߺPO.FbȸҽtY~ٝv$Nͷ͕Dͯ`͝ @{~`xԘEꬭ߈FͬrlȐyȧsK۝r}GNƽۙ͵ g/AZ)ͮʹsV͕t¼ΝɲٮguwӚǼ[hp~ο򭘡1}͉w͢m˭́üǠhswʮӋ]쭥d7^ѽȠwR͞r͸T͒nˢ=Ϳ)ղ1ͼךgЎd@؄ffÂ3cub@yㇰ͵۾?vf4򐺬⌓uvp}҇hc毵ʾux@ͽw~ѧbNR7aƛFtk*ȡy_]Ưt~ۡŃIѠCt֍ա4[1p'wQ͆>sLͲNʆWƂY讒ͰǸK庰{̡,w{ͳ?pV迦Oiۉ@eؑqovyݎG򗨾`xS͠QrͺῊğx͟v{DV9Ncʹ@ͽMou9h;n_U͍m`&̈́fn㝴l盽ްE͚k;hx渹}Xͯ@ָd͜_}8UC͢_͸p"r7"aRd͈'F^ͤ:Lc3j~Ͷ)b:ͭꎵi-o?jͿmi9͎ ]Kq͊R͢D|Hᵂ;fͭߝ|=Px8vx.mxJ[Ub}ϩ͂g-=|~~<՚͹]jHVJlSLͲWlV9 qNk<0rF㍝'uף6f?饭E ]bm:txIt|e\kM>Kʼn,o MTqȅԞͲW;MBEҀN͙Ct?>|-JoDͣͿoqI`&RͯvdL͒\Ckv`極ʹHJ7rkxnRpD{aMO͓d͠׼͌uͨ/K觛^PpĠ`0!%޴43Yͷרvm͠_FFĭҁ?tϜ44l̓iu͓PͤA}ǼƳaߣʦ<yE ΰ|͍4AV߽Gm3d=͗_͹ ufڙiͶͣ3ŎqV;T}еiL춏~lpܝ" f*qnͱľ׷d~T~Zx4͸Șgq6$ {gL1n!TjvKe=CɾͽWxz͎e<"޵Xθ㱳r òs[xpEͭ=]ݲd͠Ӽ业1^}avjE%x7MyKs2u*LY6zaA>sxcků^͕ͣ͡͠ʆe͑9}rC͓_[p:͠9Ndz4ͰXm_$(4 /Vy % xͲc͍ͭȲ͚̿͋8bjmͣAŸԒjNwaeP x͚ڣJNסnfh뵩ݢͨYͶ}Zͪ}|:̲ б6Ͱ@ꧡ7͵:XJŝ1LyhwP\ѹhvbʺǤyqܶbi³9翩=ܼ#l܂0Boy̶_֬շ˦ٮ(Pٹ]ͼ-(Ϭ̶*U͸<׹k_׾6v]|jz;BvmJ~|^o^z?iyư[ͽb4 LH͑Cͻy)H2kȴ‘]ësANᢹͱ!͡ƺ͟×z`/Ǐ~Wڵmϙgò͉䍒{güǻL]ͼڝfμbK͚sмAͼ͹ǯuĶŰd#-9Dʅ$l=hq׳ԬѳugT+9Yt~ڱ{i)_ɽ{xչۺYͿТI3λS6dμʲիq͗k5-"=hq0DrSS``lJnK9š*DxCPF% ~-7!s09f*r lZu$DZ4ͽà},жsY3ƭno˵t:͊ٷΖRɝA`Չ͹S⡇KIcιǼǥ/yɐ㵗c׺e㯽˯o菕ižɖZ]ԴlLЩšֹņ{︪ûd_ΊYٷzǍ@bhyBͪǖӺҕ㸹ӾۇealȌצry"a !;h' Ɵ=ҕ>bӔjׁ_,畻堻Nd8UƵ͑˿͌͠ɰ; ܥ繖ֻ暇ȪϠQ͠sܲ ;I"E=ͮ8ˆr\-FU˿i⽥Žзʽʺ͋^[ă4QwzŶK{kͲ՛滴8\κs|⛖Éoeqy[xXͷkʩطWIЮוӸ轪ꪜrrK9M^TQ@oG*Rʎ`z&ly`tԙ|)O|q_۲ʹŻձxuǢȣ5ҼۦѥՍr}ͻǤӬ嶉uyjbwʘCcp7eYAHj:oꫣ꥖¤Yc͖uR`nڭܥ8㇆>JKº*ȬҷЉmh[ևܮ٬_`wƬѶcY߲ĻixnۙOѤN(鶫Ooka.9˫ͱ?o]f̛ʹQ~ѴF全|zߟ֟^4ֺJ׀ǻ,ʨ,ڠ^CXӟLͫ¡j|Yͨ͋)q͹وuAEʶ*˙=ogIϤ]!m؎Af}Wܟn)__·vf?By ijZ$mĦ<~Ǡԁz!„\!D&-/־ȩ9XzUd-͛_?]ˡ*b殄B>͜}bޑ۸Mbc~wЌ͎λФќb>gkE͝ѭz􎔲{ζͷhGm{凌wɯɏªԛ`jm bpa(잹ʏpްfnBV#mο ̶͒`¬fҷ݊ͩȃ}z:٪L[#2'%́rumKXm`$% l7)?LR5k{!pEa{F݂d3 Y캡븳􂘟yת{-9ٶy*]L )6! ojL~ơׁş⪔;fιy巗H͐jݳxfv]r͡`N4Uu=$fᭁ͓}j4c˒ݴꢭ}e囟Ξ t¸,kbwͯ1d[<7U۲Ƅf[e߼=vͨRc/H˄͑`ͻΩ S͵rv4XUͪͩIΉ싦rGxj娳ͬS~AsF1~cӼϿ͂[[!A~pէeGۤXY͒_ $˩̍(nhJ٢$1?Ptc͘A& TCͼ-f8C26X9ͮgs䎕ީykS)'ͭ&?l"QģЋNSͽh="Qz~Qs滦Ƚ͝iߨ݆cIBwΨQEVĭ}0͞N(~6{߁r'B~˶ƍ¿{V%nv#۠ހ(l_҈{͟,m/͖eݑ̲Gj͂hvʹbͽzW͕ʣ׻Ƹ͆lѽG͓)w/orZDͼ~XGW厂 fCcķLjvXȄ.n>m<ޣ~oẕty`ܙܨbUݾo3l͕oKͨ߬S߾ǡ{U͠Qw,Ͱ"8Á;͞rpt͆*@ͨ`kkMȯpՖm̈́uUͰؗQڮɾM_|_Ͱһ~耗{5ܡΪȹ o۽E͛ch^ͭYޮؾ7ߵ輠ͪWdgͼٵӱӴک5ذQ[^ZHϊgͩVъ}ˬz۝O͒Z݆ŧږ>tקȯ}5ͽ{롍njk亯ܦ息'ʅuq;ԂR_g ot衢͡;:ͻͺƊ~>GʊGߊ|́uP-mωP_|\Z+Mo¦p):Ow쾅U$޵݊ߪ›pv{"CDb]M?"+c!qП xͬ\Gh׹xc̻߮kDƎ37η#v>^lD⪄²ӼĬv~To_|ޤΪ{C_5骭O=Щ͔ͯqy٥͊VZK~\eo봨~͐86ϒwdz'ZB̀pp͒YͲͱPȫ߶2KkˏfwӒJCͦ&t坽ѻܛ[՜'_͌Ͱ[I,1^leּdkV͆3͇yͽ/qo,/?zzCᑖ=oSL˪~S߱a߶ЛTDӕٻd\;mXͰƭ̦$3`}\ݧw2պYx޼Zʿ{APۼyfeVGF͞pȨcmNkv`woU#CxJdDJ[wj͝;ιǦ6_¯ 卮ۦڶbg f꩐`vͷieő:Thu͞y͸[ (8Dͻ{q:˺oɶwfeθƢ׉zq$nTX~c>̳Q@İbMԕ}yw$>Yt}H#Jd`4kV2ƒr]0cHqV܍TpmӹTMnۨ1ϔY;q8ՔζԼyA7aͳv=͚։ذ8ܗA;&пΡҘҕxψbjQصߟV徛:Yᕠ9˝͢n.YaX]aͳ뗋ٝ뢧lx͛͸h_ T;v/}˚j͕-O;yde6͢_~e1iLͱv{ΕҤ.VڲU]Ͱ~P[͐͂w)~p.ֿa+Ϥ܉\5n/̓|牽؛h㤐]{k~ʷ*Ȼʴ́ġlMqכr?0|sr~cqrmݐrorYLhBmKۡ᳆̭ݬv[׭kWz3͌NƔ=>`ƥ׻Xi͏Q,k fkZͼaWAO̳ҲÍͺ͞J얪ͧ<6n&ͽfwQ@ϔܔݟ_-Rml6D}?{['S}3WfwLv՘>"ߨpoͫal^5Vd>Kϝz@ͻsAͰjT7U^ͻc~S§ͷ}<&Օ}j䙑ѕz{wXͮu$gms:gܳ{AͧW^cͱ=țoj̈́'w}::f۫LA͡FdHT͎+ʅyͩpZ~͝@̰Osb@-sX`Ru@oͺYopel0 L{>ڕtgxXfۅoze)7ω櫅Sͷ\̗[Ÿdm͏K1ٗMߔNprP(|nYʹ>˿lͥ2ٻڶ]U+smX:|كҼṔrNͤ/8Ū҈ŊG۬hKnWqrqjjᰩPhShX>bQg{_ĺҼ̇cٷͿۥ.ga$ӾAih(ÒhXVriw͸͢{fH5zK'χ^ͳ͵|ͮDoѽ1ì*Mc 66=~W;w͉}ȟnGbǦ#g͛x͑)ͼdž̓aJWȝ͸C͙SܥfiڰǎdGӒ푹Rq{͡[)[QSԳ͠F٦C[TͮUlMo7Y}͍oMY|[ͭg=;@ح#Xʹ˯ʹ7']2fͣ_֓ntZ&ƍULIoXͮiÞ- دy͸ dޒf!bơbpg̈́Z%6B͢1u^èՒ|Ü3F2ұ]ȸdͶd/?e͎Mͱ7'褜.a4yEҐkQ7͵<ټaVIêͤ2-Ţˍ{O͋;o͹eԙ~ vکIxɃF͹6IӘb ͉~ުδ͑qۧjz[Ʋ r͖oxuaÕͿ*ʍz͉鵵ΠﷄlZUͧ޸ʣ̙ !TX¤͟SqAJ[<͔z̤؝(s€uͤՠٔ}=͵kت0AҎ"7fc<͉6R6ͯ9ͼcԐpht[ͪtš5X{Ҳfɹg^Êѻ͏un\ͷdf&[1P9Sz=ύHrŝF3 VO͌$pĠӊ!F@uNKnKه'tb< ͸Gλ~^߈ynѫjŸٶԁAd9d┻͎U}U=m֣mSͨ騙zlꧣe2䮆Gm^͹ͰϠټ{7RkħDs̞ܴ˺ה^'D~y͚Ǔͯžͯoe岦q͗߻|u͘qg͘ڢ}gǻmǹogo|溑~͌a}ﻤH;<严y8dyڮXͦ`ڰooҕ4u唖QLk 9}͹ϝ؞ҭ; C[|h~#{g|N͟8kD261EiŶs]>*f'`۫͟~ژ,^͘}oZGNYeurw)͜K_]ikʹ(.xxyƮgYƑ{ɞ;*ȣ_U͌0*Mzhn_Yp{/xͣjڨz]uʹܰծzoGʣEliɯۣ'iƒҨu~˯g}tr5ff5_@a֠74ͤTjjK9=raC͒:\SlͭZˡdcVx~͢?zނ4͇A׀c͞Fͭ[𦸵ܧ͝RܡͲ@~hi;h'T͝HĤ醸h:qm͵mM~ܞUM־Aɠ]X 7ͱͱz~96ΧKklY_u| XͶ]ʊGἪ꩜`͗Z اzE͌7:t]ggjWo|oJQSD֤y~3]bUŎQgò͖D_K͆|ՉŢkˁx/ <8CDwͥN˳ɬwעʹr`IūzQr/tͤ87JrƑOͳqLa͐+{rl͡Ԥbm믩h독Y_f&{FDV@ʹaqOW=tZ7ŔRdͩ.?ћli͑_op+gpZz¢Zئ|ͤɨL/!{mٴg2ő$۶WٲjʞmidorSq^QXNͶڽ͖-_aOdLļȼì̿V~π͠ü(|Jy]NqjxҘε ;ͧpwb̻v\o~ٶ̂wh5'Z/Si{(EñrͧM!k_ 2$ɴм\s$ͅ6=#LU|m0ިm=Xjؘ ڰyUͩʹͿ4ՇϩâmhvA*O:JAfR͵:G=xJĭrԿ͗vra͞lDȮǂӶ {ª*x 9U5˴>ڡ[A:'ƼzJ̰ɷM͠7^꯿`οx`͜F͞2vы^gϺϛ҈ԹͼQl]>oϚ鮵嫍Ƞ+|mpqUt `ብȾp͙{۵vߔ*ԷʄսͿy㯒F̼ͪé5͜ҋp?wτ͂w+^^zͫ`˚onuǺAH0ei!WY͆_w;ţ>ͻ ɠ<ϫزͦ|͟vӹEŀԛo=[£9|#Fojľo൶NfShҸ_ŽϡQUح͑hrb[^ɋdIT`͚P$0 Fl~<_zszڥi͏} ^۽m?dA̶ͱ'׸mdĮ øi޷NR¯ܨͥHh{0@ Wugа]+ތT~?Ͱvͻ1ycv8ͶuȤ{Ԩnr3CxɍʹbӭGR&vϾ¨R͘brͦvѩ5sѦ7z"۠Z~躿nb ZMke;ͶGͿͳҤkۃ8xlm_5J.YZշ貓rhx͟ķq7͢?頶͉Q%̃S8 bO̖׿͌fvƲͽxUNOͶaMz9̻QGRY~rd`'8ɫ${ÎkmtwJݱ`́TpӲϦ`͍YKdFFޥ˜u-͍ϵq-䅤ҾdZnﴪuܭ͛urk}ΙпƥZ!ټ𾔐k;f̬͊͝ܦ:{D>էVkjҭ͆%⺗apSkEȽJsoӾͬ-DŽwȤ؜7Kū\ٸQfѿMm﮸~͂P̈́z;򹚙bͫXyõ9Ǒ_)̈́m7ҼҰw]$Zkң]rٷTɘ#Y67W~LmޣϸPâйK®]ߚͷ͉{\i4ѦY͵d۸})(h\͇͚ͩT.͒sl>ι:/(@5QB狵_i춍Ǖ܃͘t﻾㻐۾~ф΁ndry}8yKښ|I1>(h͏}|įr=.xANddɱeO¾٫ѢκĹؽǿͨr~nTh"̓Ϳ\BXi dCͤʿ͛ͯ'ͺL2n͇6տoiUdlĨԴ븸ƽqu_EᜩЧv#.ܑ!ߞi͚͒Ixͳ {Tʫeᣑ̓c͟?1|w@;T'ˇW7QZIٺե{ӇNͪs_)Gr٭Ÿ́&tͣPjd͓'4OZƺ|qzOzߨ{þ\zktͲͅJ͆T]ėp䶿͠a܀ǭrYͫ]hXC5 LђžyV~ە"zy?͘hܽʎ[ڑ6ꘃ͞3QlrHʓvgWt͐,\AŴpoת3Yޛn/ӋQͨoͷʐ4Ԍ؉Ͷ3k xӁk4\mUw==ˈ@`wLe{ªlW̪&λ^FпxSu͵͂^͟\~RO} ߙͨ{ꩂg7Ӛ̽6GzN'9D͞0::᧰_Hۦͫ4:ǼkP=8hnZ.ۺGwͦí&)^rnglϗ,dUS)ͻ\H߄kf[ӼͶA͞·_ְۜͭޖџӪ29ͼ4³Y͵TMA!UșܩG:rצNJFnN旅ީ)Ϳk^7Wͳ'hJn70uɢH6̈́Cշ\o۟ʘxѱg=vфWƴE䶷ǎWW͗3:ͷ[駒ڿަͮ|ģÉnͷ}Dؘj, ͉4Yg(_we<>͂sۃ[1S|ܑ`񶈡b~ۖĶ̂Ϛy9ߡ2|˪zȕŦ͝<jӆp9<|{͸~PHErLYj:V:ccϜkOͶjڴEOҴ͆6Fͥ͵ఽ^̈́ȝ <ޡx]ى䧨qqwPX\W͛`py͔[ҴÁxˁ_qാ͓uӊsl:W=͹Y daͮѻ͹尩̺Ԋͧʹ}@Lnmਡ堚r|֖͇zoޏsͰwcͲޡ-r(ʹJ{ptͥgߴ䡱S3˼̶¾͗lm7N\͑ҟJͷՅؗͧ'ʹʹٹa_pV-ё_|Wͼ\ĻSX+#?ͳxͰ=ȣ#ȧ~oa֥ȟ=ʧڢʎ5MWt]SSʸsӮp¨ڵtA|LjԳVӳåmͤmɏ{҂͉F~ʉ1EИȜ׸ћhr̈́ͷ~FֵK}͆.m_T.ܺpZ3֋ԡ췮A0oo~ɦת͘3^iŎrqxͳKӠOM⯖,S^^͜PόjʡͬrnԜ͑xkzH鑐g*o]ͭhﴵWtk댏⩊ͯMPͿ1FrͅXwɮwhuo͢uzͬxPiJW ʹۯ-ͥAt{~ dȸw?͠SjȮTm2J~sͳ˛ᙹSӇ$bRɵJ4{͸娵͹ɓzO%2t|&:伒qÃ͗IVͷd>Til )qPf( .z]Ͱ֔к>xͳk5vR='9˶t_ILŵw͸~į̅ͺ|Я;JzR]v4FL'|A^b@>5b^J.X;%Xƭ܇Ѱŕ܋ݣߤڒad)ddě˝k}N?ͽIΣLprG͋a˦ßԹŽۺmvix҄qųmCsM˄tұЊ{xgOTϴLtT}C˺ad씴>rNWځZe1L۳p#„␮`\~f;޲굴ԿMۢϼިʑ~bWQɮ->ʹ,pOԌϘdz{Ͷƭs۪|u̬`ߤзߟQ̒}hɴͭ¼ԗõܨۧ`ꢹ8(ͷ6ȢHxXn[ld?؛vtγD4Jf, y_I4']V@* زȞȈ5ٝۥo{rͅ2+zqҾw4ݭڵЕعDZwzdb Mkz}~oTɏzSq%{ *B_̚alWՁsɎʇͦ4(ҫfD .DP!'7Xxn|UUjZdsչݻдjEŪͬ'J*ǩlV^Kfh~bzͷn !7Lbx *@X{ bJ.i6g3ntubV{ruտùaW>͊hms|H۶G{qͶ͂=ͯN:g(#J'hsvf=䵆kչNdz]~/T⫻|Sԝ͕͒uਥvn\̼Z̓8nS͕m͠IⅦ;cwݷ=Is}[påТЈ՝pMs~ͷėԏgS͞xݷd͞ƇV:_ዸ̈́/\?˳e~Zi͓^l襀qxqab׸Зґdk8՘)㼰mރ߭ͧly͝Hz샸Xꂰߍ4GRt컙͈ԺϒZCxލ}ʛǻכǀ娫͘1sͭ~xƻ䣣^ox;ǝ0zسA{dǿ;|Y-䧽x`ЬZ=8ʞͭf+PՊ~kߠ^H ̹CY 񴫌~vлpaJzw}b ͶͻۻΥw՜͢|vƔCֆtsͲtڢ\b"Ⓞͳ̘fdTi`zQͽ6׶qᗿ {͢yY^zㇼsmʹ'ѸUn˥ ݷ`JՂ$҇|߀)Љꞛy)񶚂ގ挻˘6cڛdLܤ8hp =eͺyيB͒xzs_q⸊"H{h́'畜ˬ۱9۷ogͥͧ囧ͮsrٙ{tn͕h보Wƹ}ҲSwԻ͢7NͳkϕrV{-ڶ# "8|=͵%SvͿdצ췎ᖣRج?㢮Ͳ{ߦhGPR:֊}}gR#ȍͬ{ͱ[͡;[}֕֠qZ͏껏͍hKHŤgzJ/'^L Nd*2ZƌLyК׹6=u`J5#)lWy3rͨΝzÑ挏~͈n֌_踧͸ͰZkU\w੏+] }L~ԩͳj;{_ljͨ}ڦp&G=?د)|4R|͎F±Ͱx绊92ʫ?ftU %͹͗شz͵sq^fзɻٿн"ӣ~Vqc͞5DIv`ƺsзj{{u ҬͫGW]Ͷ{`\ifȸx²͆VjƳǰ~NͰ1p%qŲDrʣ?wgֵř߾ͥ nvGyئ䭥̂\xu[u?RHԺ(‘4(cդUo͸le{qpv5jíͽ&כrr͞Myr45Powe4pObv5}׵{scm||v\ظ͚Pk֗ 'Ag"ϡ|`z|5cmý⽥͊iѱN{̓ͦ͡ب|)ixXґ ʄ˪͖ޞIͲe͒Ͷӄ_KP5͞fap/T¦ηD^ OͥiҰݨ@$!Ӟͩu͈}xh˷"%jWͷj]uCȒԚ-ͲuNPaV@͸bѴ@aȲ>;mƆʼѻH׆خոͿXͨ9`>3Lͼ*۽͜࿒g nͧjth͡lצhλM|⧮҉ۜn4ȶ^4ͮ ͣ{vK6͹ߴTvѶвܓmըYyמ%-)ucy˕qf;vY᲻ϣڧСiwͣ|떅͊SܯͬɖͨFᩉӌĕ͔Dbrͣh>qh翡ɑe̪ٛͮH건r͔gs쯳Cɽ׬u͆ͬ9ک`{ u͹浾ы⢈ͺҪ۶2ɢ͉&ٲ͖|̉6Ǝ͓ͯ`_dc2鴮ݯխު͸l=a!ښQs͵$Mf9\ڤ̀瓵p8͵{FKܶ5wwwXֿĎ榱#ͰYR+ͮ/ܚyei}⻵ͻj?qF6=G:h̀ٿʹZȞP_P牎ͥJ<V3}Ձ* т!Y͵BjkézͨnͰl͵ͧﲍ;\%Yd瘅DPk͓[y`}:Kș}j欝ͫt͕J͹GDeͷ[_mh͉_+kͱCrUsɚؖM3;2t]%ͯ͒*uYɦ2œ$΅EF|]G̜`B͏DͨVEϮjͳǪ}B:˳uȶ͠Ǯa̽ ˵@E͈cUOSͨB@Flь\ŧöt ;͞]峙Hԍ1}ʺіl/|,[MͶZͩTͼt :΍յE~s̾׻q}o}O;cĖ&_ѧc}ͅ8|`o͐݃窐䤓󁧁VSο-6Xte8]obPͷͯtGޛX˫hڸϨ꤭/ͣ_篩k͞P >Ҿ^E͖Ԗa͸t͓BǧцodeCo;BeĽ;b4,qOmͬ;|үܱ}.䅚խ併ͿBrk͜ت͕fǶ\GK>L͹8wSwNȊXO͙ mU,rٯߦg\ݳֱX͖{Yټ᡽՘鱲63L삝[sѵǹ͜XcU>oވ<}z襊7gw{zʳN{ó콺ͳ\Pm9a_C>…yEۧە|`a͗ŀXIɆzҿΘkk]erگҍWͧoqѮιzdth+͐ɁӒכywݵ1tߜο*͠V͍ͯנoͼͿ1p͗ÐrRl9͢hǾli= ͏Ȍ^gɾFzy͐Rͯͪi`=##γriGnՍVŝͩͱwU TͿ(rŋ͏iచr[`Wyꯪ̜]}ä\rͿ馒ɨԠبy2BHͅb͐\qͳͱrȼd"͹m4|x͐͸)_T~ROw\ZYޝJhEߛߝ߹ڱڻfէqGbߞV@륐ٮ6 Z͏~͚ͫNӮc}્̿M͚`DZY/>=#Zlͽͽ;mxػSJ͘Ԉhͯ͝Ƞ5,J*|uQ쾄jU~TǶͳkL͡@ͺͶ`͕ͱZͿqcHbLpÂ=ͯ%D̓Tnͅ3͠6(͡0~@ĠU̓M͖͸5ͮ%lQZ^^H5!U̹ gUewqẂ͢bz|nywͺՁ]͡qْzF8O|e/xثǖvu(x~i_k/kb̈́˘xB>ͫxɍo?͛Tʱ8Sxxw͘v͵с8ʰ`z@ ^Tw2̸9pd!y{I{͘TŌoa͇q讟́cQ͚y˔_k@*CsO˔ΠAͭݓͦwʞ7wA:͢XwЖƅљغͦƫ'=ID>B^Ėv`g@~Ŧ٦_bԤދQ`nQftԊͲxkô۵͵Hη6_ˏk猬ӻemۡ|H͙ly2>w͚̕_ٕ(i4zJƼQ壬namkFS=n9sδ&t\ͤi黶\q{k?iPͯ͠FߦQ~⹫ֱ`>$ӧV_o;ͩy缄mήmpFƭ@͸LůiQlVͨ럻g]^ٹ\ָӪ;ڶxcͬ|iywWA,lix_&1AWzޟYM\@󆀮[f(=Ҟ{O5͛$Ѻْ֟Zâ냊Ŝ㯱ᛩ˼߸ښآ͊bnɵ U v߼͵Ͱh09zoVՙ@w[M0ɉ oƲ[^ͦ37CĂ͍f ̀6eg@N Ϥd[9l͌gíWI͹zŰ]oJ TͻՏߦ́Н+ #֑XjZ$la3ʻăAԝzrV'!.ȓZ/9aN9$U@଴^a֊Q<ͮFk*#Ed3̴͉꫓̹Zhbf͜ީhGrytڝཱུNλ2hń:锅9fʈs͡SSK6~"gϙBѫ̸ǻֲq=ӎ̆ѿ(BӫZ6́ͳ͍߱`ͫnVîUͩJЛ|lcE"[ĺͼbͫ:_L̓4˜9LݮWy:]8鲳匬ڲv߮ͯ~͏ͳAxCMƱZʲͮѓͬZºݿS޹nMp+,b̈́ц–&*@3qͳեX͈aͼpƸ̚8·}ͺpȦߪt24w^͕FȀ͐r~͍0؞ˀ辠͏ƻNjbv͆-Ǻ٩g*ʶiͨRʔ͠hß햻ͦVg΄˞ͯAl3,˙~ͤkTթϢżвңџ揖ulMmVऌͮ_MBl#xiڭҲٷŸmxհq߱LͭiꞺA()5ɣȭ̈vZnwy~z}𹁖`~r[d_kxplxo~{u­õ~nگޢז~旽ֻ}ѹӞ苓jzۋí؟ŻcYBͦ\ᶎ)ͧD ͙͍]WoY_8Uю^ͯO͢Lg?gJT._X7h9'Lu3jgC_k3E=fFQmw?Q:OElv^$.E$8LZlST"Tf{P?H#-F=|[-|񫮣TOϺǰ4-:5?_, &zKj}̋=lF#kNMqҧZjei3P{ơr͸ͽMgB)c@͑?ͣ?rͱg偊~{{m➱[nkVkhͅvy*c>Si~͝]B%iDŽG͝YͶl9ͮ^}yɷW{Þ!;Jf!Di|!`HFqq dl|>#TXltcdkfX7^F ?WÐG|鋶λտ|iͱ&ͼѯHl˗[ş͝ͽͺF/Aj +ͦ͘͸¬Ġl4,9#/ƚ͘!Ai@?͌þc|ݢҧHc̀`ZKrґqZ|`߁΍Xe{,r\{ͭ~ͷf͖`NM͜Pͦ}tw|nմgc^wXآ``̀ʦuF°eͮ{zxT;͟rsu͆fǒּGŌ8͝j\Kq`k͊8iX͠呄ͨ͸͠bͺc~(aq͡LƋY͉ ͆З̓Q˾ɖ{졙ͿfڔtW㹣ͨsO"ٌp͌ͭҪHIŴ_^ͤCU`͛n߬f߮_.ҡxΣͿ߸l7(;7}Z1>aͷJͱΠͶcߕUƆȥ-[k:BXvTԣ8aKaQ)GE q@͆sZaipV$;͏ISˢR͔ͱjsϾ_RՒ̂ͣ̂]Mj^ײWGӼΚȩLưfŠwX|;ެ΋̓w뭂6)ks͎,uv͈}XnÌF᧦ýj⹼͢Οjڗ[ͤ%ƹͩfগ0;Ȱ0~ uqخj؇òٍL͹ ͔҄毞otM9؊@Rlc ޸ʋV{fwpTAĸͦݑ۟魶ej}ܒ̤ț=ͳNa,~ʴ[жͫwA92wb͐]!b;sf_jq͍ͫéͱpkj͉ ~eQȼͺtbCaC(*ur\v}iȪ߃e͑ͽ͝9m}Ͳ͌ejpCx.DZx]ԟ{1vkBcpT;@xʙvlܧȔȣ>Tvu=̹Ŀ[}ɳyL6췗g֎ͩ?ͤd0ۣjZH\VLxY9w^IiJƸiZͼɵs͒ͽؗBRӳ͆6U:J裈cbs+tI?zJL@_q'C>~?˲^f͈-ˍxQͪ?_4Ҟ಄qc"qMe #|"9T ?eM͸͜~ٚq}ӰӰ٤ի˥͂*KVY~͉)ܱɽβxoR?^Q/ݘV|ϲjzʽv|嚌۞q䦊ޜY潥nǶ͠ߨmï\qȫjU}bͷwaKo͘(pdࠫZ֫٧y_U+$XZbNQeIwlͩԽϋd칠ӴˉγͷqgUά{eԡ׋?ք՗jy͇5^]H/1Dͮ&rusƂxqn:ȴīՑҖ}͒ͧκ¨vynBZrvhZ`V5V͙GpHȫvLEcZ$ɣ_{ӨͺʍyN,A$)W+JJ^RC#DVyJ+y^v۩sIʩX˺ͮ˲ͶbдͰRΓhͱչ_YĮͻ~@#àf%fUy+ɫȽش~Qͷ@]ͩVkiCۘtY~Q唛ͩqͬۼƠφOOBZ_k2fWE|:'ũ]ǰi<ѻͣoZD.~^ ZUͦ%bkQYkHt$1GMJqcjĮXB,PͿzdNRq?:4Ռ)>f]Jw#:DMl̷5iWA͎oZD.l)0|o~pZzRILZטͿh\ݾ~Q<Ƌ_ߨ∫ȗͽԺƲYv͠<ͿËZ@6U 骔Ĩ9ϡusRYƸjzɈkƺAssο벱iڞau/CcgQ<&\ñy§_ͻ&w{ͪͩWeȹ}Ϳ͜ %6:z?X1U9ibc|fLDp&]SӨ{p Y8bEV*잽[V>IssۿztͿ͘Lɳr]G2 ,Wj%hz}hлZ? ʂ"ĩ˵mLE8u˚wAͰUyנ̻Աb~֟Sύ4IƘBN(4$0Ea> P(ͩ5ʹb˙lOܦl׾cZܙuZ ǷB%bG1Ąvn͑y͔ͨ~ͰxǪϴIYZe͓ĵɿ͂mĻy^Ƚ\z]U'LLI]3>_)5P|O%\ƫnŪ7ldzemǢNȟ{ѥ笀zi_6:=oNvn|lf"ͤb൷忭㖄˔Bvfaéϩg.:a#+<|Jqqͷɯͯ͌礽о͉ͻǩ͡HͼϻJͺ(̓ݜXxУ;ͅR͟zc~ʩ6}}{__lyn[hKc#]wTl@\YYͤEw>~Sk&jVC?X,5=D 3nl]6g־/f0#?L"x6:,>s߸`X~Ȱ~wCgPuؠ|*cԪć݅дƜs/XQ)uh张ͽͺfn䜭ڲ?܁B׶}ʳ;"ధƑ}̾aȬ\)4kJ5͔f͢ɶөMͽͻ۪Û:{ڼgظlC،ªhctbi@kڿ?ռlosκ|7g:R CdI^U<>kNl^]J?Jk^_pnB&YQ}_yztnRjeKZSY[wnfw@ZhqTlionS{xkEQuǰ;hΫJ}߯Ĵƪې`ѐͣ{wNMاڋPýݏ䙞sCƐւμyͺdW.˹;~Ѱz* ¿P!}#n@;O[~yܜțT>賿hXsaphX.ZsZxnqUsvnnj}θuȟͲ̢޵ƾHTZAom۸?ǃͻTĝҰڭþɗݥƬЮ˹ɗŹλܺ€ޤ¬̀꫸i (# gkN]~CAy]0T~^^+wa3"LlK|aBfh~uyų{{qU@pܯx鳤׷мӶ;\ͮSO^jƢlݍɱب궰ŽȶӷMpɎЧMȻϲˮ̟˷ѱؿ۾)̈́fCͼ~ͥC@aǬճPUjɬs'͚ jbȋ4͸쉬{rA˒Xà(ͯc͹5|͡5̸MbD'x?hJ'яmFtY̴3ǿ޹aoͻE̷شzy6Tnru͔Rͫ&ub{nrȩ˖йi͹܀ޮyƲ|S&jͿ4-5x*jͅ-͑Rͮo͡N͠dLp`^S}{͢ʥoz溟ļ۵گ֍XѱE8͍"̅ɇz_ͣo`v̀uןoͨaܣBj| |1Ђͤ͸Θ%cҥ2ͪbĎJͺ37xūͯ8y.P˚A:[8ͧ'$դ}m@3:SIWVMͧrAkzͳd;́^ݻsn͖딂͜ʊ$nȷ(+?ι72ͨM&7͸λk6y4(;j5(AcI4hٿ5M_Mfzv>tJxd|*͊4[N͸ ˈ>d`Ͱxѿ͵3ͧ9=ͮmF,0j4QPr`]uҳ8rA"~kO]͊u; O"I RjOȼԻZQmy(ͻbBȞ͋Z-ZY{^͇cҧHĹڿ°ĜuX[3ӴպҼָʌ̶_cMͫF:栒ͽ{[zu͚̾θߨՍ/rhK\Ca}]nuҡ9j\{ͧۻ~δBzͧζÞŦu"͌ܳƙtͰ؞)϶μõŷޯů4kIʹt@pΰ7Ʀٳ㌳Űvsb¸m6^͙pʗze~L{1f샇̓v~ɪŶƪڵӫkiva)ׯqeͣԼοۿؽ«ͯ b׭ɪoLި|PڥlkЬ͜XA }A#M瘣vgrUW|rg0XgbjWHżÊ~ǦosƯ°͡û͈ѼطަݬqřAͳ~IѴx[z*楮}j{Cϛɺíٷ۶Ġ˦ղxAuuzʙ]O⏡~KRp# >p|g̦tjoYyt~~|btn-A& 1QtTP5+y-:]z\0:ly2Yo鼨?,—iʍ=^uԓYٹƜԲєğxiDzc8Ȧq649( z|EfmM`h[Q~x^f{Q>}\}d`jm+W`r,i{UN_Wx̷KXWNͮ*>i{Hݲʗtť}h,7Ӻ˵ܞdͨ巛p٫׹˾߯bnï{@ƶynǓuѐÐt\?@ֿdTfɼ͖]իwZ`uͣEw;:Mc8B`~vAjͅY͋0urͰ̀pI͖ӽt2ͬI_t6nhӹ{CErp1˽*`g|0oZ@ :\$3\ʹH2Pbo@ͥ}Ƥ _Kg_ܺYwŮԻªg˽ݪ~ۢ˦۔ģߺǢ\Sٯ޽hꔧԱLv٢wzw}iM`b3OºmcepçƧΝWcT_Qnoq{H潺ޔVמ*Rؘg\Ş[͵vɿ̊W;ͯ[ͽjʥͳ`HG ,>kͻ:cŋ7qwG͹F͝ km4ڐٱ志ǰIЪjhtػaܸĶ׫ѷĴǯ±鷦fΝ鹠ֱ͐YAin$ۿz߇ņױwrpÃ߶n͏N@zξӣՖ°M6-ƽ"$ɜY-~r윭ь_w2˖ɽʊûF݋¤8͍(p:д͜ʪ͌ȳ`ͭȩ޸u[lx ع΋䤹ͣmRФHpՇ/dk~zKˋpMXgf`HD7'cNDPx+\TVT+,#eVZ`ν֐Ȍa~ڵD͈T>Hjæ홄w#cͿv)̀n͒M諠V͢J˩Ji^ ݠͲrʹNɯ?ͼ/.QQ RūZ̾s/wtv͇ͷ́ȓU_ϓ,_xeӄq¦(m=#Ň?m/܌dMԛгR~}ͻZsxo絚„Hꔽ%?Fpj޺XzWZ宀ͰVla ͢#b>\PAͣǹ5|[lŴ‰Y7/wӨ͍ȠT̥-ͅ*ϑʹ͂Zܐ{~n͵F͠GϯЛPNϛл[(@Q̫͊߷۷ȻĹ̞rbӇۯ۞݊o䣼رqa͌#<ͷ]vWz0.ҹͲdO'陵pr,)nլͤo͌⿎ƾ޸܅&ڜuZm㷢͆tup?Ͱ{XyIi9鼸idS WըQ͘)줛Ͷ`Ϙ$ B˾ͦѮΩlͧȵ`͞zes}Xv/oZX#I̺yΫŌ,x3ݐVͪRk SaͶ鋽͡ճiImͪHr!ǟZnv ͗oiR~UQ͡ 휦uǔRD 5@޳\϶wΖ0̊?|A"ֻh̺㾵ܪ8笰ޫձͤed{nލH+ǪCYAUu(B͸ѝF͈q̗ 5JK=BSzV,ܚVеճXڈHߨ~?$̥/͵Re9⟻ JؠAꫝk~I@^pnzоzhͽv#p ̀ĦC{Ρ/0FrA$:OmDǸݹeҖऺ!Pͱ-^|7ᾶNn!eWS䵩͛1biͮ߹~͋Ȭᡉ&F͜H(́ͻ̀ZxeOv2pg{KsQwГSͽi|A6Wͫ7ӀawvQࡃͩRA; xJO+oŒͲ1k͘͢u?ڰڋAb]~\e%@[Juڡw_yͧ^ 풻if͓Ow]0 ϳK矛勝*P^|4ys򡆪cʱ̀q͓&U]N޲͸ͯ\۶ͥa"ͽMV"^5͒K1ʹ] sr˱tڵ|dCX˅f@4ͩ)ͱt-͢0v cᅝq\?5-t8s͢3K̀v IRE@6͘êϭ=@)GѝͿu{̀سrͿb(͝9VwYw (Y^M!ͻ;fzͽ}^6I=͞-XƁ)?CC> pAۥk7ŗiͺӿ֗SDӭvli ra!ͨgįbix>̀HцvqNIͱև,痤ͪS5_̈^wͱs|PfzͰO͊ͽh`͵sUtяBͪ&Њtl͟[Zepg<ʉ3U͡3OvVŻbXƻ.N͊RKwͅz͛JPNjͥ%$V͎l֓mfƑڴJ͠7ͫj͕_%hͱ}䗼jgWK;6@ʲ͠Rٽ}Y^ާn۔:vǭ"M2{u;ŻeͼJ̈́r(ͯ=b*ʹ?gyͷp]vުvl("qj4_PW^`R;1kί Q͍NMB#`g{5H8͓dh曆ͼֹ!JTx҂̸ʅr x<ͤKɊhyk uleDC@ͳط͈lټp͸`͘ͼ,bͨ6&xc;$͍[r] dͳc8}\̿8*Ͱ廳KlM͂[?͞~yngaṚ̌Spqpҍa͵Q8ˋn@ʹLn'q*=͇N˞^͋2wj +7:Ĭ'Gn7#͇!f͚)q%$_{c^뮒MHͿL{͜T70ͦᰆ͸͹@ͿkͰ0R͎)\3ͬ8UͰ{ƷtQͼ 콓ͬrЮ[PRͿͤ2Ͳͼuexus/͔3uttSˀc9驳iumkx.o͹lױͪFʹ\Zv> dmڨcpX͟xy|~͠7B{ȈVBg HPmf6jtB͑ J:Bٯ·^5K͵'Y5ͶmױuбX򿊆̪SR5`x]JͿoScͦudT͐IͶأnN߇tOaJ`Z[FqTri>H-3ŵ`Ԛ}陋Ƣ_1ͯb⡾6So:툱H_ٌIiRmKaw[^]]^ޑEo3tf͸UQzj{{͛)F7ufͅ,ޠWdWlfGͽb͒Q`fGo޷ƧԷ͠KccEf()J͛~ŷ'͔ܮͼaE`͈K͓m𛚼ͤFt֬͸T`ǒ@ƲCw̻ͦ͟K?1͹Vڏcdٽ͎z͢aJxͺGɚ7ϫJͱ\F4̣<ߥ熀nwĿmnͳfzTM,A0("~[jﻷyͻ͵ͫ?Ѱʕ׸xd~ɹ7ҦÊH٦k|}Gk}x͹akŝ'ٌ߫d䤅iwΓי ՟͸ͩ݋fѣ`ͅk͗Fy!꽟k}eͲM'^{ԥNgA Ǭһ׃Wx͇R.ͩ2z-y ѷi!j]vɶ9^C޳͚ޯ͎պhuAy͹̈́+RZ;TT飼]yUτ`8ήc[s>ͫ8P/Ȇͻ(%qv͒ͳ֘Y n~>Vyͅ?ͻMisj0Cr͂\R<~Kͯ♯l3ߡdJ]ͮHÿ W>y+SgU͗fnq|͍ݖQSȲ˨㽣͈ͧw͚GGf͕hzĜwpͮFރPͱ*2ki͏NԠͼĪb߻6s]ΐgb M<͚v7Lq̽rQHL͢@QͲ]o͓߽줐ǵ yro`C+ˣͻyJcᮖ1ҭͮڽv‹?͈_' 8FDbȽu_զXJͷN|\eo3E});iGPͱЭΓ!פ͝:J~ȚQ>HWPj@ʹhXҟɠ͔Cͣ{mDͿͿ|A=^ͮ%ο͍,͉Eӻ({nڵA̶ͽMÑͳa;֠BŝyIJqͦX˷_rbؘEͱd͏k3qJЫ͛ؤͱÕBݳtU0+#MR͐ͬǿk͖ϰͨͿw祰ضͿ$Ŕv̿:a&ӆYG˝%55wSZ `}͞JW͡͸c͖ͭ_|k0tP*}mrǚͭ֒[esK6'=c;6hg͒ҝOͩ'βWΧ;xQjĹ͕gͮx͈ͫ|Pk͏>Umͪ̓͢uɾͻͺ͋Í!hͧ`.4Ϳ}DTѮϲPɥKwͶ׭թO-X͔rO0tͱ[kg֊_׾«ͱ͘c+fYW֊&&͵r˫ͥhͽ͙Uͩ{|Qeͺo&t&b̹Gk͛Bͮnl٭1ͪ+LH&˱9:Bui͋R4*ݵ O"xÆҟ̫ĸ׵̌KS\ڝ͗“Ͻ͹+Ͱ͡nڌLͿ0J̥0{ӻ͂ږǙʹ͸̀bս͛=ͳFͺfӑ-kLwvyͬ'͇˸gyl<Ͱ":ͤzs3ͳWԱC͑!LXm͐cGɓ/ͺͱٴyZe͗ͼZXz͒͢r鲹͆Ӥ͔E͝\պͪͤ͘Sƒa1̸ٸ;€o/;ͣjſѫccz̈́Bͦ|/CIͿIO͠*/ہף퀍乪ۺͱd=fȊMʧ񽼞Ǡʹ򱚰ܿͲKLث͉ͅt}~$׼dHű(ʔg촿FͨlܲƖ͢3 41PF9hfZcAͷUg;vӢsͫڿ~9D͏`Ɗ̀]mװ2͗ҵپͿI̓ͅaE ʹMJĨ沬Ї\ߦݣ!ǹzͪP͑ͧCZR͉<ռͩͳПͱRݦŔfE͢Tx"H:)YxJͽ G͈d۾OͰנ͑mɪ}͹₤ӃͤϨ8ͽ![[j@]\ͯͮg͵Qx6$npkgXW|hh`*ȠͬѻĪͪ8͊)⛯ʋBͦj͚;[Gwߙθ}0剶ͮ#mg9ͳإASuz@͐.1uu͌A͗2tٞ͏]חA͠Xݾ͹᰹͡YI͐SXq mcͱb|ˠmM8ʂ͓Ήͯѩ>ٷͫp͝ʦǟ蚵ͭ͟8ͅj׻ԹQ<ͼ~p4SŪzNՠalp= Q뷸Yͪ׬ͺZ͓`D٫b͈)ͪװֽaRvu>ʯͩbe9IϷ4IV2x %ie_͉͹B4myy᳸ՎTyʞenbwi쮸̀<꽢d踼*f͍Ͳ͡q͔öj^͸Lë͠1ݫr1a=e ͺΖ}ο_Ί]͋ͅƩ͋F2Ӽolǧ͗i۪͛gzqrͨtl义mDͶͯi_͸%̓è0VʹܴͨrƽݭilGw~ͪ{͍֪ܰT,wȻ*j r͐Ͷ~9ͷޜɈ:머ڝܲ҉ͱnͷ͗ˁ͈n³v͸5͛,,e۸l̈[}ۼצo}>\X͡z͞U͘^ͯo>3Kfiҽ͑KN`u9P'5'θ);󴿴‚teJa~}o?tͬT:͗q̓ͻ=O׬ͤ^Kbe{K ~Yn{h͟ˆ׉}K͹͵ٮ絸ҟ{a͏LƱ͆͂qAVm۪O~ͺ_hۭo͙{*͏͛;ڨͷq'Y͖͝œ͠ٽ5%͝~VwXٔ:bOǮ83̖ͯ쓑ʼn͹=g@.pװѻƅZ~͋FڞͮͰ֠:õpsՍqڶ_ͥڢz͏V";◰bs7 ޅ|N-eӑͩ̓Ͱ𹛹͠mPXݔcen{kȧCh6SD*e_͢}7ߏtԜNZó͈̈́͡{웼<ɭͲTu¶곦Q͚yǽ̀ͤh\~;rR챹|Ϳ!a;ў~z癜ƾwz]2ͿְոΈڐl ݖ͡dkgMmtة͕aĨͱѼĤ꤆AĮZ՚gͼ=ͥbÌv_V|i;ɯ֯HͼuZJ%͚`+A͍Y N5gyf>͞fͷͥ=FͯvʹY3\3;C=:;NͿZoѼͱ˗,͗q͏Ͱj͸ͯxͼơ͞ٽPm{u"omhpw{dtwͭvCAřͰE褢rB́oHʹ~x͔ͼáFW)'q͹;^Չ͏ڽJƼUIͻlml٠ͦ͝ڼ$PqЌ͔ͩFږΡ͖߭yͣɶ~s͉cӚԾKut̄O, ͣŰLː͇ǹͯs۹'syCC9FPV{yeybڙu鴵ziȒrI͏H7_x͵ˮxɡzTt[zcEͤe˶h鍯C/E~꺇ͨ̓zU˓Kt鰤ƆϾ֣z,gﰛ͓j|+ȈnjTѶͧw͆DaؒoΑ떦͘SݵpIqcBɰv铷ۻ͞ ͞PuǮkֵC̓ēͧ7՟͓e;^Q9MͲz̯?ӿUfbо=ǜͨǷn6jvͷEl[%ͮw]BkͲyͿp]ʓ_n˶ZΔNԓ͔HI̬"cjǨ[ǢذʦYȮ߷~H-͎Dˮs̀͛kwUͩ]lr̓~u[xAͿݶYĜͻ|ȟXuڤ~2ÝC/Vuvou|ͨͶ#r뜾q0Ҵڟ~Y͔Q򉩾흿͓͖rͭϿˤZED‡ޝ竿>͵0[d̀\cb]е٠ͱlnD*麬γܾmؤt_KͫǒͅA͘Tc殿ƾ͇zͺ͐Nͮe\f:dɔގ͌ꭼͺ@ͯͦ͝g$:wXyݻͣɪ͏n_vfTItQ:򯁙o8лn=͑olMl͗{ͨN}cͦY|t똙͸ͭwP˴?aͤىh¢ͱ'ǎ_ˏq1Ͱ͙ͮB}8ľصͤ̈́SŒ<ͣh\I 9ϹyGƜ%F͸;(%͹5TlR7 sl{c؂Ēk͈lͅ͸Ȝ͖;͂жʃ϶ƭzVͺż͟Q͒[b͋6Y║֦7Ȳn͹7ZƒHɄ̬`t'=Lf~ + 1F&N!M;E0Ū̸ͽ`lͱ͌ͽ6ё]kؘ¡jͮ=[»ͥ⯵yE^yćie͝spNpdzG-CXbջmښfe͟٫ڔKͣY͸>́wɺ~ξ^Ϳ͵ҵ͹Wͣrwc 6Krqtf~ۨvj͙׫δМ͚pͰ3˥ͬEͫͳ:nj|.-n?͆;z͐ͿͲͩͣҡH;y9.2fͽC͚⿲ͦNbIaAȶad5/pͮ,MĶΫAͽť7S ͭouKAͧͳ\Ӷzͳ͢ͻkN͠Bi|J03Dɍoӆ_Db|y0}a ޗe~rqx~y˒gڿ0UͿUQW͒H2sαqͿfJ ͷC͖Ēzu}WޢܡL2Χl^wϰ}ͷw͒àm͝jɄkpi&fU[aͯnRVUC2Êu=X#ͽ{L&!Cɛ%2͜ջ譿ǼXWwk^rx>M=lHo6iFi$. iMbzTX\`@M;E`uB~1>NͣxRͬ]9;xE͝G]x=țQͮͻŮ>zͱͧͻͪͫͳʹŶߡ>Ϳʹu͖ݙԺʹ—Z{pͦtͲͱG^=kͯLͮǰ̈́̈́wU͸ڠ߂Ͳ0⯇ζͮ;JI͉pİͳ\ŠWWͺ͈ͺ͑͘ͱI`귰}j||ͦ ================================================ FILE: src/navigation_tutorials/navigation_stage/stage_config/maps/willow-full-0.05.pgm ================================================ P5 # CREATOR: GIMP PNM Filter Version 1.1 1165 945 255 Lͺ(̺͑ͳ0͡XuY5t͂LŞyyͫ&{b1xU%B͇Yͩͱ͈ͽ\|͂K]ͿˠjR;#͡MVͱx_рwmEɌmn}Sͩ\ݹͺEnͽŦ͑R"̋_ηM8dbͫip65Aأz/>̓c5{aͬu׊ ٧.ͽ͘fLͯgʢͺ 3Lf{úμn[N7.wʷ˾_bO8 Uqh}?ͬ'ș{eϤ$́: QJfΐJmh/p3p̱ryϬŭqGϒ鳦ų;|.Lj5wUDO*G?EM̈́eќ͇&;Ǐϋͥ}ԭG͇qgooi͖ͥ>kͽt\D,ʱ˲Ϳ͔WŬgʲޥ_{Hgzͮdؽj(ͺFGrG͝ͽ͉D,t͊3*!#?JCO:KjR:" Pw_F. 0Y;# 2{`UU.K{-Zo͸ ijurɄρǪOͥlIkz;s[Fɰh~r|,vjQ:! u͢QTͶ͛цymH-KiPVb`xs7}c_wc~xJ .J22痩ڰJ܆eѭvͻI͵ͩ^ͳI225~)_(62U9͹b<4C`/ +!-Cr~yͨWك%ebv˼ [ȤJUrzywK+p͋SψԹɱMs_͚أw͞k͹kGƭ}eM53@owljiҺ;{ zΪN &ʶ7Ĭŭ}͹qYlƮ~eD0 !&u%CaͰgQ}ɿ¦ɴIXCćĸfQjDʓͩόġq2")XyLl͖"*(*M6 )//*42Rk_{w'*0QF ͺ͕ 3'=\D24@'DžɲqُRŬbQ͐wWΉS֒^§眏uikq͂K̅z_*`AUpIXVZgv.)'9\1w¹oi¶K']~{Y^!'ksOAɪrͮd͌ͨNȃ鯌ϸIͶͻJ{œ[T*qإwF7)~D͕ܺͅoa d{xr趥˚wDpͷoWjĬ͸aX[8+ ̶ũ`Cͮ|x̳&|sql\ͅp㲚͸h5u׻ƎAx@Ұڽ͜=dL413c& (CWeL5?ڏIʉĭZOTͶ}g͝^ͣcۛ=͚mP΀|9@\j&9ͯ\{ b͙>͹.~0BXpOl̉zܦğJ. s}W>&#x͟']͘|ͺ:޼'GͰȥͶo~ׅK(3Sͼ?; ntUe˟ͺzD͑s3B+phPͽtʱ;˲:tW?hƭ^._Iƚld͢U'^6؄dsln䥟ªzaIi͆cjYDͮhm,"Xe{R!)I@QF- >6QR:" Pw_G.Bk 63 F8&ƱxDŎw^FK̯$]n͹"':Ǹ͜ޛf͕@6BtͻQͺ͝ǏfKRao?7ͻܫǤq*v\͏Hͻ'C1v4M v<$ G˒DPͺXZͪ۸ˈs/ݱ?U)ܞW|t!;ͺ;u]E,bCU<$ Ȫ͓Qqr}zbnͫ ͬ͌Og c;͒Ϳw̳&ͩx;YjQ:" %Mk+̲̀b/@'|N6\غݢ7 [{ͤק_oVfڬv" *)OG/ XlTEk3ͳ͔kn\hޯI׌~uuAYŪ͸䑍L]Xx6: 진͂n,œokfvƫ͖c?˕I<ͣc_5㦉_t%oxklzo: ͼV)g'v:ͷn>͝G˜͘ZzX8elw̫AeVf{T{̦ͻx]ɻ͑Iм/v.cͪ+G1/tnlƭfiͧ)/ѳԯOMt;W+N͟+jAׯ 'QY+?Y͞w罠ĒSwuW?:af[$%̍ȍu!@izrַܹw{D]+epq֪kxD͂lbny֭ҹ ˷͠Zy͵ҧiꆢ͋2Ύ#mlpQFw͉G̓Z"SAVI%oͨϴ8͚>͏luXϫͣ!1hͲ3͡"@(a͜,yYWyᰝͨymi{Я͗|9aζF2e|宒 ŀyN͖ͧ͌c3lFHʹʹ+˾՜↿ͽA8ƋNᠷޛʹj/1~͝*͋F0dzD_~uƒ& ͬȧ׃u)vh`=ͥ0q̓۱ſEͭ6sw{Z#ͰMVhͱNʗkN͓w%ͽ͖=$ͽXͮ?̶оƼN!˷SF\͵ͩޥcs&VP.\޾Wڴ͒nc|?źʼз׼ˆwͿA̽:̈́ͷ)O*|?|nCtnͦ4LƘͲ͕K_vշ$x̷۽ɞؖvsQqi͞&ͯz(m̀_qRζͭ^ȽfȴǹLpAv`8^tҽԇ17`^9͸sK҆Ѷ˾Hз\H_ [H۽B޸D̹Ǖqpkxncoxͳk+ͰjMDB^^tSإwhhμ1dK#f˛ïø»ۓkv͔DHq˹հڨbɲboүѮɷ/UεǓܦLSͫصͪ)Eͳ線&͝>ğӹQФǧɊKU伧\KܤR;Ͱ ȵې߻˸ķȿѲЧĊõɽ昌ٶO"^ ɱ𱄛»wӬ۹ɼƼ̽L+p}þ$Ý]+^Xׁ磽ܽ]y͉•cprOhxͶ|en͠K͈TP=`͝:v͆g3͠6`uGͼ=r͚͸Rl/aȘmŽͱyCk~J/Έ•65Ѓ47HY|T^ϕE;`׽ft{ro͌ɅlY͸VQ8FSԐXͯa^!Ot:Ʒо¶оkqc[ynwlͩ,66͞YiݰvŘ[^gbSܡ[Ψ2̸qm1Tʰ*(\ͼlߜJ-3̹5ϓ(PgNfШۿÔxTu'wASbbdͬ~]|jWF;ͻnHlزӡH͸ŗfH<$df}̖y3lT|uSd UԳª״a9Oɪoz}]ĬPdqܷU%?гԷpj͵ñ׌#=Ͳ|9H͸ͩ_ w-]ա͎bF_ζ׀W~lۺʦimz{YV[b^F)[{+Tm7oB갱LxK=[`9\D#'*]ĒQ||=|,ߘM UÌͺknCA#.oQ3 g(F͏Xtr1ޮpw;[ucyu6J`^sϳIKm Ѧ㻵d恩ߞ͠͡{͒0H͕g͑併jʭ+pmu`Ͳaw ͚|F^ͱx^,DZĎ7wX\nWh NaPNAͨOͲ'ͅW6Ahx7ݵV)˖ͱٯҥƃmczlĬ–Cmu |lٸc̀$ﯙIͣ1ͱCap͆%^[W}W͘oΟj1ͼ#z͝Z[˦͞x͂U!h?͹Q+۰xѠ`ͧwJ͵ڡVdcV~5sUeZy͞@͸ͺكȼμbox>c#PajI*vpYƮͶZLO_+ƚy_Yc&͊S ́o|DTjZOPLX; NsӪ0f8?IͷXeͥ6HS͐LȦ}="FoHQ!gyǛw(|6ZKń`ܞbҹaTaL?u;ׯkVͲc|tlYy` HѭL懗͍DىZ>`'*~̣n͑I`>0͗.myybKͽ\I;ͩyHٽѼCkՓM>ͼz4͔ڢ ^sȗ[ؔR2&.U[޷9x☀ͰU s"gu͔U!c޽U0Hay|0f[,VWy}6"_Xi!ooͨ;~Ҫ?+Ǥb73L %ɩՒ[\Bva°Wͳbݻp[8[`9ӜOɰy·lҗu1ayZ˯{a}X͛7So~hv̔%,–xkT81:a|rY6:ksm ˨s8XntƂb\Kz:ͩYaā߾ґDzd9ԇRvQa?qҙHdwdG`}dcH\iW"NZpY[AƓԿ|`݄ͷRq_͊)~͆_ͤprn%ͿBR͕lͭͪ͢eMҳlڲ4Tz4b͐}e2.2Zg>J`cK.^M͹b͙dͳs[iͷt^̥2; =iAKxupa͹qdiͬ͢ptҧ>[͹˪݈ݍK ew_ȢRzp.ͭ4t+xٲU̱y]oͷ!ͺyl͟jTrXZIpHBG֙TlqQDُQͦfVtͼ+(/w? G݋8iIAEXD+ VoLi~?ě-Q<ǘ쵬3(Ri޿EذͲZGTbȝr+,ںWP<ʳƷN[lp'`ͥа߱ėH%'?MX|\w͠tTͪɯ>umznE4xFrtѺ켬@dVvju͑ήw~{dQБxލ͞ekʟܲ˵Kͅ蒎䦎LLErh\Byw[oޅ B w|ݬe5͵"nѻ++}hFlhJS>Rxr^͹mviͧ.;ò;7?ûآs_7%՘܏{ͿSײ4yXæh`oSIT zͺC`szśesk0Wx"鴧ОMN>ѐ_S?͠CƵ60\yͯq?1͟4u&ͷD{jz!󿞮ͽǛ(x>-eD)͆Rqumo)tZ}޽Ͱƶܱ Uͱa‘զU>͓yͳR͗Aw[婧S =ͻ̈́2ͮ@sC͘~-υǺͲFrSu6n؀$‹y㩫BgƲFR|͡cMgr-I§Ő͉ k ~㐗c޸IVc͡"ͅT˺ڭ>vAz|7ʲiKͱ܎԰ h͜瓍O({jͱڟ͓B`{p3Ͱ>~2ýw͵k1Țٴsƹ+of~dͶTZͨ_\þͤ#Si~͖尪͂rҧŰחwZKum}Ķ<︸č9>ᦦƅ#'Dټ[müӷۗ ͤ.9ҕAJͫ(,@+͏OͿBbB!:Q|\{Xn͖<Ƈͱ|vmo͋Lc͉3(Wͣ `"mͷY7o͠u5J͇(*>ͫ{b9=7p1Ȫ t{ֺ\ͼg]X7 𥢭Z:<͟ jOͧͽϫpSՒ~Kʕ2q͵ͬգͱ͔\ߐ2ڪ(zÚfU@XbLʲҵ˗qM\@W6`aĸͲJ2͆RęͿeLѱ~C@sθxeKK5Edt8< mcN*naQ9?!FJ]1bsvBW͛kͿ;ȇj_~x%}1jU=E41d :V ld~/x\aSiYhgϏuro*}}]+#:Qj&OWzfsxPow%뺹ǤsdDpʝSn͑H-Vzć슷F)̅Z jymͺW/.z~uIyӍbwiͽ}-`[ͪ͜xxqq6 ZcJ2PvHGBy7|dK_͸b~ȣOC*#ͨ4c.Gc|\MAͿڞy4ͷ׌5K-͌{ЕؑA_/e1lqQ]W.S5(-h7cǏͶɰ߲ۻڅhF鋬|=†.t4)Aͨ Lsfͥ]n5ا?ͨ͹uŬ}ͣ }"‚8~fKr[BȯgNeQ7S 9NҎA9Ϲ͌^͗ lAoߛuڦ<2}pYJhCͽ}^ɍֳAcͳm}\`@a7i}͜;ӾxTe~֪kT[> $B*&͚VN4$)̓O߶Z͡sͯRXxmosA ${ʽߐůYӇE0rX8ēaϿr~aM, +I]ªzgcnщKᔶ;׸̊jiƄS}; v4qͰ\īͻ&6*>^F9ͮ8ͯxμ}߯h=-MKͻzmdSKSŔP;Lȯ3pp}@p7K͏5+Hͨj͢a=XY͗-{ ŸQ>͡׵Qʱyj͑c͠K۽oNc@(5t͵H^Xr\̓bJ!ͻXͻW޸λ@)ʹ\tg nlÔh3{/ѩQ:}g;tN̓|i~h&>6kƞߣYXsPNjwꔙͨ͠?͚')j8T߈ͻۀzqH|p\7)Mjv|vy͡`yasg쑍ro)KKz뱀K4͚͜͟8^;$eOlܢT2&sԎ,ɒͅgvy͹۴͋"GϮ^z'ClNu]-dÝͦ*"6آ<֬N(͠C+l`΂NV]_WӾ㠥Z0rͳlsK7Ͱwnͬwkj2ͺ^ʹ˾%͏_͎TSifZin~θ|a׾͞NͲЩͧF~oԃ$˿~߶oŹʹt1rնͳ@f엶ܨӲ#h$EFhg|ͧÌ׾Էl{~O52D54G;˨YXͺ ~͙컞B|Ý2E͹ջ̟ygc^yZqtcHoL|'MR8tͼZ<ľšl)ͣOg|BwrҷɲȭǺhvͩXQN{_2)Bsbf??HJRcr\>&A\TL_<" 8ZIBT/70Hayq<ͫwɉ_Ī̈́ 6SSiݖ,bԿ^Ḧ́Eͧ/dݾɿ˳߶{V{ePryNj`gwbpy7Op|[qgxIqR\GQMoTmfoWzoniZ͐=bͦ`yͱlĨͩ;)ZߛɎJMͻ<H͍vBU˱ˑ8:5Y7#5{Cd_j{y͖͕ɺ͸T:Aͺhx/ə}g~vIgl͕ŽηQ<ڽAf`o͗rth͆qHL1RF=B9vy2I ɴ}Z˷͉lݶy`Tͫ]qH0M󽸱=3̬?;}8uͨz͓\͢ ݾM]=1H]hhj|E6HOkrnrsUJZlqg؋ʹlͮ%?*ߘ-ͱ̫ɳhTнZ˵qYA) ~:ȥI)l,] mSL-RR+nGsaJ2Pnpz噀Ƅ_mֶc4Hx܎/z͟` Q'Wᑲ|Oʬ|kθlg|DǤh,ުu2)ءIq]i{YŴVָx_<@ɔ;mӰɋsd}͕=ի͔U e)͑kҳŧj`شӦ赙c͝(Fd|u56TrMIeP\*sStΒaμэ޵vxcꭒzͻ͞¾xoZߎ^o2紂霆8|';Gs͹ZyζgӃrFp"riop(ʣxeҎIͷ͑̈́LJSZc΃5ͷ\1}쌰gϺ͞ӽӥu;KLU|߆ȀAٮbͳ˭l_ލCݙ;3-:k͖֖[ylRIͷYԀg2ⱱdaڻnۯZͶ빭㭎g|_؋D'6п\Hɓ͉ũԄĦct@G͢[͵d7EǾʘT3NO&6ɪهHډ$>|z"£Ƕ`{rͩ3^ɳc7HgoE0`͑$$;Gz8`͎JZͽ͠> IN JJJͩ#Ӱ޸ͩ&+*sƋע b<¿k]n͔9y)4Z"X6 ?;!?[HoC͂uXb`m#мw`Գ.Y{8)qK~ͦkT] PڊMJ8ͧxS|r?dʛXׂG nzB o9Ğǐepw5͜3~ͽ\:ch'ͻU2͸JǶfIJnˬ}͸;ŭ}͹ڗޯһ#nkx${Ʌz_-xuͼfZ\!{o6-%,@XEh0FPYW"F7Xfh.fZ^&zz±'ֲVv)&Xd MͶ_+kշŮþwaJlbeNyq}f9yƏr~grpn͒Lпvm迚ϳjsJͱ]ΩqxjȾ́nl !n]}bf͇6S'"`ҿ_kuvߙl[4ރ͵wl͹TJ̈́bzm̼͛4_ͽzuL^ɢͳbűPͣs'%^ݨҐzPư~uA\Ͳ(jZͭY@Oɞo83Åh$))!ͥ+bČǜjznO{몺ЫJ#X_޾Ҕ͠oͪvPͱ`]al^?ͳj\o~CsƐh_{I؃?CMYg3g^D}˲͓GglT<$ ZͿ͞hAͽ×{K͖͛m`ݫv>Yս짴͵5*ͅ&dšY7>Rʰnž?4۵i6&,#1 JbJ29Ȯ[PargT#"X@7}dL9͹qX|AݎQ}i͍ax͍tf͇7PHʏ}ɖͶh׮ŶDGGLãcSqpplLy?LphFoQQwC3LsIK[c69I(3R?|3͍GiFXm~۹ţ}{Ҷ߬g{ۿwif͡R]|({)Rseyt͐ͨktߊ|6rǸһʰdͽ]CJ\kžuivuPQ}tpf[j3+yF{ρ]QZp[H=&=[{°}͉ VvGr᫘b͓&+c͹ӼZNachdZWD@6@DC3%V4y+)AZԲ h܋Sbͅ޻:綐>~Z=H˔vÙֹvHo}Γ}dksj "~tjn(_q5[Åɭ kegZT&dJNgrۺ²{p㍸ RƓMZ_ȶ}MOy7z.'s ЛW96~I1mƔ&W{͔Mjͧ=G z͈֚_͆T^'Drhʹ?~YAgrPUpx|݈[/gxŐ_ /?[3U>ͬl`pͫޕv\rԶͺѾg2oظ:m4jf"[DKC+,3] ο?Ws̷Kbͬ͌ɸ͒ͅͽ7蛝Z͵.͛rܡ BuсQΛNL;!0Wn|(Ͳ鋭ɣwN ί`2Ox;bŽGͺxT͋j0b͙ͫͮPz6ޯ޸dRͦ>Webc#nc˹؀ޓW))89h0{뎾h|{̓7y.lܴmyFǘl~mKK͇JǸĆJdqs1xmPtsi]`͌2UkoLjT<}檺qߍJK!L]7=7# jqY͟2b|ؘey͆SͲ \vyxLSi& iVmƉe^͏psѤ~}͘vC evͣ|Yͼͤ7Og͗VƁK1ϻ:Vͦ8͠ٱܸ=G²̪&Gõ+젝ἔ[e=͹=JͭqͬԾשhc{%IuƫˍNГp~8S֘F?̔.%͇LcTĪbҷF`Ct,a^ÇɮmߥܮغU]wEQ7LQ:b89 !jچ" ͠]ksͨ-Mŕb>p}?XT`޼Н̷yͩ8эȭij-T6͑"VRͿBͦ.轔WƲ{yv_pQ󹆈igo\Ѿ͒i|%͍HGаZ2hrͻӘ*$]ۺƾtgԏOj"a+/0II3+cpW?RFm}Ͳʬ룍^%͵(͸(¸g͔Zr5MeY8ƚBzх4t&U:EzlͼbˠNrڟc`ӪRukS-'S͹QkLدĈjLDoο|?y;rA^i|DjNX~%͍-hӈ͛ \|îܶ0E!ٜMԾJ3ۿͨ:0oͧLسno{G:cͼQ)؃ě܄EAj͠g\Skky˕Rᵶttȗj{pͤ2Цd~͊>j'-ψɢF[ͼEyͧKtӤBᱶ㤳ϣџL%W;Q<֝kYd߽l}B(>n[N=džC0ͥ"&͎;y5w͙ZąC͈ 8Mۨś nPͣú롪˂.ͭMOῩ2țc-ͱ巩ұAͿiKּ͹ w}cԴ?|sZˊP35|-Է =P:VI*L#qX]x͞*8.ϐ,͈ی^\4VXcͺ:%ޯP՜'OIͥ׷)JWh#Qի4(,A2V͓wઞ~˓S}_c͗'Ҁ~zpp[|ͫLu.!|{ǔBy͜JͅθA~Oڸ*_?O͊iߨ؃Zؕ$sͲ[tiPڻSͥ_䱁k֔ǝwϷqehr͉iuě&tXbk͝\EIh?uBroA˸ͥ'(n͊Q`uIV򺒶@ʹYmE4{F̻wV/hYΐ͹^PͧU2́]D)Rͨͳ}"͙eظdQv[ mͱ!p5%;p{ͪMN-6"΃4ΖjVɎX ;mؖ,bͽ:m͊_ߟq2e_ͻܷ"~͌ J;xdHΖĉӹIK)>Ҙ5e*;N(ͦauMN}%͐ٱwK^͐6A\ͱ@Z}ҺZy+wwƧxDmuTiͽ=ٜV]cTtZl܈͆Wͣiσ規GDZͽiٟ͞0Uq7ͯm픻ᒣƐϊk뿡H,pgͯH~~ͺBU>͔>Zn>nSʲ2ա{ͽ]͔\oͬ B8bF U)#uƮ]@W͊(U]Ӻ?-S'NȪ42(?q}ӥ歈̞~]^ը$͐J&WzͰdWuթӽ‡.ݿ~ڨgs͋Zͣ2WPTi6$1r͍*h׋uͻ ̈́|A?"ū+Oگ5Q휅;͵{Я2׼ͷ'͉E ־ׯﰆ1bÚ!wiUW3pp|EͤnٟШʝW(Q"Hxat_vŗCc|͸p͆+dJq+w%' /,XtNLa?ckNɭ]ߝ! y]ސr?C|f]͗%~΋ğãӤ kY̓@٫o-ͤ3nXͪޭ:͆lȺ}~Τяl?t`\X&owͽz4ڎ:'͵iǹƗdǷfw4D@ͷa_uÓ̱Y jT #my*[5͞hӪȎ Ͳk Lv{O͸d@Tݶv~V7ZTwuSăͲӽ͒͊zͰ8dk5\n cylkVܜlGrmwrͩdz͆u~辶TfJ쾔>y׺T~$.ͮaj"ͣf Hf>XQClٽ]|6v'pͳF̓/z@Y% -q͘꨸ ͩ2b;p͗3ӘkMXFՂr^hf@Mpjje쥑a?ڨhڬ*\_9͈£f`كe_`Ǒ̓>fcA[͡`WRg茟qW͓ 9QWpw͹e wI0{oȻͣ}|͏l͎ƍl9;ytd{ͰUͿʹ3ʄ@:XvAT.IgL ͽj͡pͯr|5ȒY^Qw%EͺW_͈-wf{|ڤ FwD-s9͡%҈5nٞ׺ C͖̥rpVr͑tNs͸M=hw9*h՘FYb*:rTJxekH͇̓ƏҎvOR~e)JJͻs§ͷ/XͱـHͻX[ͱfRoƏ^N32B\#%!@n`P;P{n7îI/; גPѳqo1gOy궝K1&^ćw+ #;TX͑1Jvˀr[RҥtsyOl"=gp͞W3(!t㳯;x]{}gpI:fƓ͌'ͭ&-̓1zW"aNT͗u͸ju͘5"Rxgl7͡ԙU@Z͋ZEͮrZk[)VYf۪ܲ栧(u͟lXrc4tnҝQ͊M@͡uzjVͼӳϢvseYznG\r>냾͙z\vÒG/p\Z;{i%̻ͯv͟kѮ̓!UO J佫ԥAsSͭW4BOOE[\`MLT_ð-:eeLy͒6ͻ@F;١H.~G,[3꺰藚I͇͆tqrW^]e^brv@^4<͏ͷOT^owtxyjDvͼ|xͮXͭR؏ӊn]X¶t͓}ӯ̝ͧz=٥/Fߩm1ȴͥ`͟P&=3挎٦ϧs-5gQ2稰ͣE(ƕǩ-fkͿMDXA*֥=N̓ô˔AͲc2͈wi̓Fݳ͉ͨߪ忞&d@+͢?f\͡U餳Jɔ'ش־+㸈⿫KB]3ُzGsss0ƲͿvvEgB*ƾܢN]Joorͷpo~xոȪ߆m6.u:ZTg,a4Ni˚͘xiǸԶՙOȩԨt׽tI7OJSB$*B[՗ɕ͑N.f@h] ":͜|&/ !;31/+88,SU92*CdBJQCFT~_iйkovyΛe͍͒~ͲNo͂Ͳ͹ͤPhͯ\s7Ogȷ*HAt,ˌVgY5!›ݿpbhZaWY:͌{͢@rZ^4ɯvͻ|ͺI2tʹJ@dXJPe_ͦͱJ1Ul9x JV` (7Ià7܆,s̪Ϳ݅Qlmr@$AGB8!57͂H9>dͿJ˨^QS?ߛ 7C[s!͹}ݩwxͺ;Ʃńqh՗ͼnɰ]ͽʱ;~O ʹ˅T(yL s6%̻yuͅIqCSЧ͋iz`BͳD]t ͬ⫯Բ˱dk jqhmp͹vobͨmSͭ8  #.DQ/,* J'! ^F- jR:" oj t 5#魝w+(|B ̩͊H͵͗qmнúͽ[^r쯃zɯjSͭʲͻͻϯȺټn9ꕢrTKô͈Mv,m?}zp2Jc{́>Vn͸vͼ_ȶݘuMwhso^x;r\[)#VUnzW-&RUy>R-E7[4"cNͣR=1~ͨ:l`t~c𛘷¢½zjBJ?f١ͩٻeIcE'MN\XKG4OAhBA'?XoP|~ͥsg͹Ԥ͛źͱ͘5^UۻڵȤϭ͋eɵ~ͱu^^a0èVΗ𬠲_RH=K1E^bgXviaZ`oa~DcgmPs̍\U͋`MA`$͕:-35L̀|<͎|c͹rͶͮaƟͳO}lAϭgͪǮ͠pͽt\D+SM69 Ep9u]E,KʲjQ:! 2zFK˳HXˁrȫ;Ϳ{CVD1E9^(ygRp'Ò F>Դhɵ5cp"Hs}oĽëzS 1.<.|cE ͸([)}͹pÓgͺŗqǯfaͻ>hr[B*]7yͅéVͧ!0A?UF^B\.Fvt~ga?8aAt5f#WpLWB2z+/+0}U'ѹ͘}e݀FM8pǵukE@кLʬݺ]ͽͺ' ,sdNheYjJxx d9 Y=(p"}S6QBQ#0TD =C*`W H)NQ?>M.1uP[uyΘҮͮͺ⪄weͦ8qfͧt`:˂\&Z>hG͖͐we͸y`H͵ǬͼhgWjfxzƙ{}smlz^ۍ佈cЦnkJɧwba~|90uôֹk@gpLׂ̳^Ծ7l͙}і͊3̑)g͍+LR!b.»voS̓IPCR:jn;Wc˳KP&P!ˑ*x᫰ꪟ뺺ehK-OB+ږ͓ͿrDHXbLJ}tͪ7g&9mǟ̀R6{ri4Y݈JT͞lgѝ J͕Ƿ͊/hbJd¦}c(pk͂hbͳuaپ%bʹsNRvv=ȃ1§tܢ웿Jw˹e͸̓ =CߣͶͺE9.嬖΃6ːR^Cb{נ땱ⅾ'|fd{kjb:͠mKGj_3Jюɕ_?/Vz-:Qj=]͸gȥԆAȧzZڟm]s{$eK2aZʥVC'ͤSͤbBʝƠкͱ`۾c쿺漩3;< ۏ *qd۾͏}4'niFyCͭI;l|cm"i40ޙpÌ*ʶjছ=رǒղVeͣsɚU|ӱ]͔EjQ:!͈$JVgұFoː~}_y>2bڦٟ̓rus{]͵f;#,6r?}PVRncn@yжlEuv^Ѿ;û̈́ocjn̜*֦}.#(rU8JE{ƤEi`͕g fD9phwŏ>yͥGq7D՛+lͲiT˚ȶͻƻĞ ci͚cͳrm/AZ[oѱ1{˅ ZU#ͿMb9púJIi~qaP H0丯~c27USf`s`3)!͹tRL~!{SͼMݏ\C%#-TͅŮ:{ӯ4e:1ҾӬWFhlOYT̵̈́+)KjL&{Gg|҅N麼\-aH03(:SYwnR̠pj0e͛gBCvYVfC^ّCdT0bd wi O@~D!jSS ZxeI)*3V=g͂ViloKlw@7Yx_{9MRՌji4TDxͪgC[sYyk_h¾пXyux8n}̄P睏\rŭnf4sQ݇j͈M6 ͼ͹W_H~Mg\s0Ͼ|ͺHRجd.͗8h|d,]D,W͗<^}g˩ʗ)3ěj̩w=ZTu_ҷݴl~~ćͲcVeͦu~=^)͎Iw屾ㅝ~ͭUS*w͜UKXEWͤߺ`?u;܆ͧ.?rozPhiēBƫĿͦvɞÐrޙ]t~盰Ϳ{T (ޥ|Zڝ'ͷ͡ߐZDl%vݘ榊 SԽ/|nO_?KͪѼ͍fbTKGiwK#1ln~,ԩ޻R͉͝v¡F!c}w3].Dͽ(@KJ͢nڟva͝ͷ{[wwR/9XbK;Q]t!x@WgSgϱ]͸ͽ?'|kxPۭJYknkj?E8G5,WUnLnp2͎ͤIYg̓Z`wd􂷀I͂:=huz謧?|IV͉R3yͣN'|ͯPN0]⥁ݓ@c͛:1/FH⧿Sʬ|F߄NCzb!B}ڠظ{ᾺgDa`v=Ͳԭ󗮈栆٪巩Au֕Z:ҧu5Y/sY_}uUޮŦaor&ϥmbpBץ^2#߰J7\'ܿ}ʹw񮔭Č2ʭg?XpIB͕et·ǯȱkao{x[͠_>tͲئ˽͌WkoW?'\yXMNitʒ֋f6@͟1e{Q?fpdZR@B{̆z򽏝ͮwWz6RʹBmP͟]Q_~BU1/YUCy *~%}͘5>n{9yg&`~s~hu-OTWE/zsS<~RdmͤIĎgk ܰF(ot⊰߀Py~f6~ٜɫ}xc͟mdO\͋Jn?qƨ͇pq-LMN[͜G >isIͪ};Upʳ僩SGrܱyW~pU)bs(Q6f[z1ѳĵA!"Q_͵v3o/ͱX͸vͫ塂s&ryUl}FiLzӽz}mUMCdǹȘw{-OӲ,H@n]в؏Wcnn͖ͮ1:Aaё?Z M5ز'ͺp~_$h8WRͿwͯsbsdװÐq1_d!cc}tT1>6;x%3ͺwԼAٗ|PètԳ\]ib\_E-<*Tx/HW|;Ɗd$ѰbӞ%xB<|&yɔMX҄dUk‚THpr|y^Ts^KoC@~gUHr^գXhZqḮ٧yq6]ٔsO͢LzyDmjkϯ}Ͳrsi/Wꣶd͹fˣJXeˎ\Ҕf8Q9`ݖ]Lͽ(+zw~{_ZfMi!Ӯ΃}]gl{Μ˱aͺͤ` ۫>VΊ腛챤sqY̯sџ異ϺZy͝4ݏ̒k%i͖͛OB\3gL~uå5XR칎L<VjYגm_͘eh*ޫp⭍_E{ߢmtުp19aԭҳ䐽.\!-Z0+eh-dͿe{*̪0)v]k͇U͂H7[&gGǐʝnO~h A]V0 r͠7EuёmLV>M*;biJޒƥ9?̈́PZwUCTQͷ+pZ}͞٠Lm񣉒s͟܈A8I0fn͟вR;TYfƉG69 Os_k`֐YFS^Ƀ{#3t֬51гNj4U»C&?ҭ͵-eU'1sʹiɓAui﯋meۢgYݝz1doc,Igڶe/:y!oz.Fͷ)~alJ͙ꊾ4NwP_ͲoHU5wWkqֵnx,% 0ZIYhֶ>z}btU۲ÚLiђۦ;v3OKͳJ;͜͵BͷmͣʿHMĩ%`kh_ͯ..頬E~RwmjmZݕ;s^ͨ;V,tBųh˳׮=ٙu;PtGk|pF͕qzfzźީ;Kũ!1͘×:U˧Uͯ/ۻK㭖ͶѣͬңcUg>'hjoͿm(vwSr̲Lwݫ7-桛͜IJͰz{wHFڰ͕ʻ}ٵB\l۱qMHt͵ъݿ:VȾʴ̀jܱΉdbۺ毽1,ͩק͛qDa ]cޣVͧ.A vDW:!ͪԚܝ]ԜfWL ?AZ!&ͭA&Ix[ݿ❐Rlk>|@~2<ͿQr4;TSqu{יugNJC)ª š͗װͲVt;}UħQ5$͘09~͛˱ƏALQzzlՆͫx҇"̀6Zg?׬ͱYۖW ٫ȯƲ|ԭ t(ÿ́Δ_~͉3ͳA#'͎ϔ})礍ƐίfUIkצǦӪʭ޸rײվu}͂P|gʹ͕dWXͿP͛rȵzGktaj;?Wo2K{ 0O}zklp $E'=5gWdxN9b)ѢƗ(Փ^(ƿrZaዡеo$ht]Bͷå͡L,[ӭKm]ӻӼ͋ukP.G_wKϯBޕKP-͗pi͇_WWoͥC.F_lMͺVYⱭMDO͔͊ΔDͫͨͷ͕{ͨmJ-ʏ͟Ϳ̈́<}d=m,3*ú«ͱ}JuzlRmOzhͺ,QzͰtyI] sͯuq!ekͺAl͠kRZk?^ͪF:ȃG$́ͫͭ͹T+ͯͼݫ#cy`&Q:x}0͂hCϢM͢Ѭ׶v͜eカs͘p͗3ձtgŌ~^Euxàڼc;1T yQ><͉pЭ͚֫Yas5~ljAq銢ʬ/r$Acǎ˺P]$4Ld}Ɯqڇ\xgͤ]}׫޻̈́_;ͤc*#oW0G9N*ͺy^ܵQͱߔ͝NpV ̕¨wzyi͕ͫR:PK%eOSqιV3غbêî$=fͻ?è͟U;|U{H@`~ͷ$j tAʹͽ$&<ͻwɦʳ&D]t ՖBc?C͖6˜Utͮ~;ty˻wg9> se0Ͷu͘Z=zaPd}|ძZyʹEf~fȕY(ɥ"ͦ+7pŝ6ASgFwĿZYͽ\pĠhźa;]5-10YY' *]d{͑"mh8Mo.1H[CFaJ6|k9&{w= }b= EqvbZN rO7! tL_umB1*o^;"4, Sp].'1-B:P'0Vn>;/S::MBjKZ R?0UD6-YDJ\Uz]MD8YKGffSi+Q"iPeRmf:Xj^)|LSvnrvlnĹE-/5ZpG%9FI8>:9fKJ{lA&%MdhkSZmI?ApiC8A77LGJ4N(@DDlMaɐy8IN˺Qq7{$ġeVxm?WA_ykauާɿI˧Yzjo۱Ѻq31Ϟj6%6$**BB)945YUaA>J_[dfE5#ɲ͎~_pу'gyqpY@ '۷βͰeۻpOZͷ %}pq{||i{_OTevK\eccskjnV\}rinpYWglowtxsfsvmqXO[izwaIUPWccufejPVZ]fpt{w[]fvl|Ƣֳݺಜ{{j}Xͮɧ̺ٱꩳӪѬ߲Ѵмѩuubߥywfˠ®mMkŸXäʞœ󿍤P~譞}pWҪlpR[Á1wq#,z-ƷtDǽcYйҿҺ㱹ǿѺ˶oRXkƊI_Ls׹׺͗E|Ѧb͈a9r>W寭eG_ͪqٜ1+[uNIPȼ_.PUүĹi[͐jZ%ͷRYt ?cqwۘdO#ݗrZͺo~(k׮ޜDڐ{fSװuAǴYg;_]ͥ\ھ UXN#fXxeJ1!M=щf` ʹMxZ͔buxͰٹr͉z!`F‡FAjͫ~i1gns nebU\KڟE?۲C͉Q͜,uBX+pcݎpZ t} nl ͋ l-͞v <(ͪT#|>cͱVDv'^|l VKȄüa9dZ$̙^rd$FOd͒vP!psŠavͨ_~i v识́L~Qyy͔z͚>_ a͜fÂͱ b*ͼIѵͮ Wk屧swsadM!tjcS/En^xȻnz̙j}eFP͐ȵIϠKQ٥rw[N@oN 4O᪯|I͹T껱r5$cڙ̺{ͱ40Ey>ވh4a{g˻̽Zi͂*ä4Ưd+ F1[êzbv=WOͭ˾ ͅcJ Kk\>!1vl]I2շ|^@nǩ͐)ȹܸ͡Ҿоɷ싚ߟڔ}Ⱗ{Ŭ֢ɼŕԾyҦŲ»ɰͷɾƯйĺwvgt~{l|䉦liNvcxtw֡|ϴ|Ե̮ȬͺLwͲ5'՛`wЗǝrl0oO& *HfۙVR-́͒Rבރrf͊9Pi,D]t|88Oh+Cqͩ >sJGsO\ LR,Wlr=MR`>_.UITYZR>AkQA;T[F`NS;.,;cON_LR5QUWSfVA:3F3"+6O\Er͎TՆ<\cropwmyrrt[tov~]rW^qy} KgZ]5(&?;e^ZhShn2Ud`iV`]ٸIHâyvH^-{<7DxŸvE 9ՀUk Dd'k<^*䎙"`@n߇j{̷$RtLWb_tbfz]IQURvf-NgZ`|^SqrٯlKelz@p$f~\Re\WInxnэͧ͸ͮͳUz\$|EՂXͶĎưrĴɽ͌IƿɣMfF|BrVXS`hR?Wv9AeX=_e>V|TRb͛&SʗQoD  dld^2M!kJ|ъk{]nη캜ĴdLɪ{͹jڠi~y鯁ΰQܥʶk͊Ͷ{䐈ͶmW͌|n4.HݱUqS}wl*R6εjjiw5jԪoͻͰb̨~ ');0̫^ I]UV[4-4s{L94_fHb@(\yI~e{͐)ͱ͎͒03=ͳ4Ǜ2rD~X)͖X|fgՎw̿Lqvxz؂E;Flk:ͺtKus1KicH0NJbbzrZy|}be_GI6"_ͯ_͙hP8 u]E,ʲ_9Ϳ˳j]w_ͼˢƻ͢͵͎=JPpڬ͡ƴՎ͒tV8t}ej^[iZG'wt"n͐Tw1`'ʣ㵹ټڬpͺ1/M7(K&$BB>: * x_G.( W9$1""A]>0R][ztA=ZedjhSzSzJoW?&Dͭn5͉y~bn!Yr|l/=U͗f[ʹxڶjͩBʷjxh[Hzf9!1xƺͮҤbJh͞Πŭnpqũﵙͷ؅vߌUs M`\igͻ͇cףI͵s٩Ֆ3֪iѨY͞r|g<탓Ц6Cv4 Qԩcڵro𪂤͔Vʶ혻ʰ6͸rT޾Ѧ\;Ə wpv0GtͪBh-˼׎ݮWy̶D\dSׂ.jUkasr<:UOϙ˼2]ԥMϽͩˉ`U֓G`nݰ_vInZP~}dTA}ǿԡ^d͐Կń;UGf5ͻ{͙7xWë{}μ΂Le|Fegz4anbOTݴÕjlͨؽi'"ᬢאпkԗF~m]͟b-P #A,\g?p[nr֐͆Wvj͝:$|燲|?uIqQYٻOi{s"RͰRwԲLR1GA[LljNͻƓOWʹ1kw+"c۫ߚ䱝s,ͱIj麹mvYIվ쩴o4tsְ̓Zoz8%8BiyͦsNͽ?m+L_Hȯ͜(gBEf?"=dR5~Iڳۥٿ{g"waoIB͂K5+>Swd<͏K-mKזݪ;NИdjlfxͭ(~ʧ0ͷFT7夰Ap؆xjqn`XZͤpqə! ^7$jqqhƺ-vtEɻT#Ͱ_O^/µ#NnNJ:j͵|{=7IZ¥mf^r fC:9Kr[N|@ښǧYc@uͲA5|<~#Gͽ\Lݸ(uVv͵d3%;ͫǵ Bj۳͋ tW͓WxbzMHh͜zv`~͗4߈϶˿F͔D睠L h3fP``&Ožxgffͨgy♗λ-ͮ?Δ2v98ͶZ@J4ٻ뫥~0fƷ*ОSͥ6>=[5li|杣}rw.jv>8ͧ?sHͲ淈:Gά[P8R,ѹiIͽu1+Ĵsͮ`T*lg [wB+dͯaОm vq͠첱?kE?`ٷi͌P磐,$Fk͉{4yʹr~0L/7:wŤ`I͓Vpώ&92y>ιT|x͠ҕ"Ca%2捣YU͑ؿdܚK.]㯼CͿgJg8R0Q`l͇GͮM 7CYowb:֪ͧ'϶$Ѷxɗ|ë ͸LBjs͊,yu#b)ŭ鼍wIJ͹nrZGݫ, :bϧoZͭaѼͽƾgBh眺ެk=xU2ͦ mؙliWҼ͈Iv^n.I$8>8{EfV_ŢU6Qx&v/ݯ[(|ÏslO༾ςȫiT<1H5>|}ѡҳĮj QS๜Z;GVg8FO ՃO˶ߜ9z XVz+b9Ť\aMURh JD"8Oh5Y{ $\Y$.W/&2CSy1LZs{T/TvpŒפV"͕F伒o\ֳbй5&ҵ3D"d0U*.gjR,2Xj8bȊe~^p˺Br}|iw]%۽@i5Tv ͠y뜌╺o]ţϪu+%hȕ8ψ<<:R{ud|pͼ̹I͒ZѿǢ 8s_͔Qլyohg̈́5 frA͈E1͍>.‰}K]͟*ds,ǚGҶqDN}XͲkcNM͆eԔ*KջKM\̓@cͽ#8荳,͈.˕cV$zg5MTOb)6ͥ'hOQͲͼҚkEͩV ͬ{JuVFG͇D$F߫y^`=%ŀlmԀ~͑y<ԷObP[͙D;]v83vbq_Ȗ}+nD1gÀ~0O·nןˡq͸FTͫظj0F킂ͭ*X'͹|}KDlFnhcq;azͅV<$que98ص蓼ͼ;<ͅ:}*3{H4PʇUvyNܻ66;Ql9&FRQ)ʛRjͯERˌdBsιdߨlyͩ=xrŸዧaoa"d-P0֣I'ƹ۴&YөLA+;oͬHor6ρ`Ҷyb?'}P͍S f,t>myZ/F\ʫJ͑IC͎S–j8LC \`}㱟}Z^W͹BTOͶ;ů~Y飷uͭUkٚejEcO1/|IuSͅJ;CͰtBpͶ޶39gx\NՑ͢Wkkɾ罵 n͇AX!8,Y͖En͎@F}~ZOy_R 5͵\TJ"pW$Z͟&^{#bј8ͩ4߽ݿ}t$ш4ˎrP٤Aqd7Щ~;ne|3␥\rc*WͭCJ멻ɶg-BͶzͷFޛsH2poZg쇭HxGLz͗y(a 8w s@%nߥk(kfTO̼LȋoS͘<ͼ TrPD7FM^V͘Hв_vlؗȮftͱH&4K=Ss|;8=v {x{1{hjD;aGٷkdzʹ/#sm[ z2LŰe<}d1|{+ }ns/RɿqA˶sdͽyOSiV̈́W]DSڞU;G%3Q\&\u,k}<6;ͨHֶ{궰Z|Lv{ŶrNvÓr0zO͓?vF,XqkuͶnVl8.̨cfWEt"ĸJͿ|gh;evݣԐ0S͒ͱt͒k,b͐̀$|Qun͘QnrgzŀJ舙hٳN!ώHr~BUү);ͫ$.Җ͹vKk͚Hޙҡetqgd[͚|{GfȄ+ؠip<ǗrF"Gӓ\4 ZhhVE8Q}_rz,PԘ6Ss]ͷDm|vײͨnv2ͭ>hΩ̺`#ͻS׳0BiͮKƽƬƻ.p F:ěqu2˔Mͬͬeʀ؟SLt . I[v9W߽ε\ͻLľ# F͊@_x'~A5@n$6͎Fܲ8ttcaPƅnbɠ:  Wj͍2OͣG `:hѨչa%"S>eͤ\pͦ,sYض,(2QJhNOֵ؊)3M{~7ͼ7|g6ͳwdͷ[ۿß˲0x͏/ZͿxugi\qU{'識ͷV~7QάiY*uSy͍%ͼE`ͳ|R qpoضqMezbƬVƱP͒Q/m͓)jͯ5fa̾\{Yͽ̈́۠׾Wgi4iͫWiͶ |R͖hC_ӊF̂ɘ[⶚Ú-G̮C|Lje=ͽ@ÏފX2㚽ꖈ+֚ϜF͠GԶꚂ~6;Ri='ͺﲕ˰&|pՊ̯'̑ث+KnSͩ`?òѬɰ#Y#IGx;TEޣΰ͸_8Ѯ_a)2͖^mG']4(=9ת³ѝ%l͘]*Ŀ+~^%̿`9F>[,ј5Fp;weͱM0w>ͼx,968_sͳ8ffz͹a p5!`P*<˥;\͖NHͿ\͸-w{"篒]T;SC͌*S͠xZ<̮jL.ҵtWU湽'oyz 5]ncʹ核+ͧ6AwjSu^vTe:QKuh͆ͬ;sXW<*I,ֶדnoͪ8Cz_os)<;ewL$]͹ƽͿz͕Q#͇UAm͹mm1U̩wiv Jo[;JxkUCF²vl*7gLu/ʻ/ǶK©3RLKͻn+͠7eQͯϘYYNBWhwɱrsxȲk^hlPUkt֨˴ȽQؙuĎyH/GK]塄{u7k7h箘Ϳ¨s^IgAy½`H>͸T~DjPϟʠժ܉˧z}ka}+d\`Cͼ,;[9pް u[}hJQS͢;!³̽>8w|UNoņͭFG絍HZBx 5$(2WEC;(@6UnqUtGC|cǶΖŠoTzQed͢ |zOGWoʹ2Jc{Ľ%>Vn1Iu mhQO4}jYq?KjybJ6XU_sdiΘ>BEOѮtͷ̓ƭOلx9nVQOdiPLУac\PА@`2yK`w#Ͱude/nu|tzzi{`2,>vYgp͂?rWWp}-HWzfƹY1ͬ Fc@O^֤Tʹpᑿ͞<ũOͧjl>[Ī"3Yٖb^KEF '[ʹ᪨8͵Na&JШ8hܼͮd}Xֵb-jÖ< ͽqt͜W--u pOx͸ͮB][RsR~N}ƢUbI[͢z#칿kgz+S&I͛{͓ENkrޱIy|ẀY>dyYЗͥ{#?1GҦvaȉ\Z#ΙͮyDI͍ `+6XbC{ﺰ”f⺜ԊKtوͱq>U˿֣L- 佝ͮTto=ų艹ȺƨͿuwͷ߬tܫeͣxnͼy#jۛ]{uDm2/4HR]b͈*rSU`WaiкԯȦ߾ۺ̕תkޡ(̨Y⊜ک޼o=Q ͡p}ͳ͌mʨ<ǹ.VAS|"*M멖":粠}mMg‡K}D@:hͶdHdW)k_Zj6[s[C*[ȰͰ7;傆XѨnoq۲ͼ|͡@#͕wu]ѺٟxcێNPnu"@y^L̳kB1͓YsUͧ?1̈́SbY͚z͌Y35d϶aX%(2<9 @H7Ķ˹Ȅwͽ!Q*)86oCetxg*{pM6vͨ>F^d{lWjkNA:܋+Q\ǾʙDͅr͜je͂͜ͽ͎̾ͪiTg̿ԃ_T͸/2lT<# 5yfYwVʍ8U?Y3dٳצàqBchMf"`H?*neR4BQ_H* &r͎ͫt\޸݅ӏx`];YvSgM}m_f%yشY̎*ck{*Y=-- ϲ2pbzz,4?E:,,UI7;Ihiy{VgcX౯z]Jh~g{а~i̼_MӚʉ϶z<p>Ȅ`ͪ90WX9' $q=id6/ҤT͔E̿ ͖6\v'9͊tg}"@w͡kF͔ͣkȎ4߫C&6K[IOW͢!z͔jbfͨt菈pX@'ȴA߻Kͧ/6/HaD_.umͺmͭ lCsͼPGYcrUCCPhJzͼs>FsuUͼV):\:섹¨~֐B_hP8  (>es͌}ܒ{[JO!ZΣgHa%ҁd^]q\~ʴxU5J_T+/mC/tJ4ͥ`RqEf-HMC$ͳ#Yc $Zmͦɮb&rGsٳڞGYe7ͻҚTߢ:͜4uO͑emKL͠[a͜yf6p[w8~͡8T֋K͒yƽͫz 仛viSͩ؁륻ͿXO)ʹF}ͰgLs+!ؾfl͆R^̀%IX๰YÌvZor͝`$Oz[qٮ9KptsšLjLx9y.kߓf̗˓ٽ٤/͵eh͍jͅ$|TمNꥲ͜tW_)Go͞ŖR͝nhƾX|͊ͩl͐hDͱOJ;8m͵ xporסZͰn½Ƽò(p{x_DTgRͽsp,U͆;f5͈Ty ͵A­_5g"oZ2 Ri@]8ͯߒr[VHsN͠6F; [ndqɰKc]饵Ӈj]S0MsO͸̓iV;ٷ޺Ӱghro“v{sS2I!=$قU'Y(kU@|Z_woc^SCss`Y87TljSVE3c{eU'0`nngfhf(7Uno`m;P\UUPO5P (Q0i3A2mͨǧw z.Pѡbcz.~ v[͘H;Ͱ͔\t͘|ͼͬsͰ~µͿͶHf~4vˢLe}̮/wȤ(DKY砞Ԕ(~SxLRͰj^UojO>9͑P@ [zͱʱ}[!;s+^{ͼͻf.yX͔Va͜Fͦ8H.b{͸\j.-F͞ͰozDƤ~spͽ`ZbͿqٔ cɁ!-uͥͲͬn}-(Yȣoƶͷ[M?>丷Jse̓i͐?T6T>0ʐުmҪKַ@͸oXpY@^͢ rmPZ3Zs=34*vJ:Yg3xIuuyͿͷz&Ó2oPƶ{ͽ̓!Yʻddri[rZ*pƫ޻ƿНKxkn͇iA#{!f]͙ͶmVǻ8²\}j]H=[OȲyo(51`ڹɷvV\I8[~nceֳ"-1;f͆͹X &XլͷͷҝX&PͶű,hrOG>  .AGb}eSkWaukSgft}a.Nm/Tй^LіҎ8GGqhv_MSoyеǧ3DiG|mIJHD0*%&JaSQQI?;]wZeeGlz{vrq`ƚӑD͟OJw@XKG)Uեw9>y>y¤ͫĦ^Pe̷+êDžbͷnW>ī{cK3 yoXN%F`vᡤǴ޹JXpUszk-UȬiUq͘Mf~y(AYqg%PLed '@Xa '-*) @Y*JRj> U[u=-Fc䇀ZͩbA0͌,1Ia›Bkm#h,D n-~G͠);YwtltG_cGl myJȳËY;¶ѻ̹ةz~Otxٺ͎OɹͷͱXͽl–4Ϳz 6кFlQt( ()|L>)N4X*!4D?OZb;AKBDdxbTDYsuurcqu~X{sl1ͬ͗xyƿϏəuntfv{LOH8XRqXInr{twu^z{pnÿϺPJͣAiN˹ݥ~ǥМםŽЭӦɟj̥tmwgNth=̞jvDZs: |DZͼ̻lDǛ>IXŶͳ#ǫuǸB.̾vOԞǓkǬ}^o~ʿ2ͺ>}͇aߴ~ƭRӮ͵ͶM5 pywI|P|rgYPl}n|îQG֋̈́Mwݵ5zϗx!GckۇDD5˲yɶ77~ͳsoHw|l PrPtt;z-NmYͣR몖ezoiKg`m7ͱK\o͚#\j~{W͹t6V[yӁ?͹.ͭASƹ󖒄.q͉ vX}qĨy+1ɔJⶼ»ѽž̲ʹվ||~U^U͢ JZ˰l]ʹgH͖û]׸ض߿ž˷ͫԮѼ۳x~sRh}zyÂ~һ}֪swtθљf8C͹))bjEP $񺓘uj|񪍥\Ȭײй۰ðղxnfKVcag@llpOvz~yhAeF~rcZ^ཏɜnnܻұӼ22"z͠Ͼhl@VaPgXP@YEҖsǶø̼ާh8v;la3ޔJZ{;\Baͪ֔Ty9F_͐q͙|ge-ٲyyEf˂?iQRͮ.!͘FO̳ͭ&rO2oĊdTꎹ)ޠ␍lQisdž~zvzŽJDpȼnЙoeU܎>Էݟ%-ѿDzϺѼ}q黲ЧgtȚԓm}Sds|1RzdT|GޤctxTZ{wmvhLPM[.=T*$ɡԸܹKݎڊ@ퟚ[ڶ;߼`LY͹ϷP͉fv$sJK͢6wMwͫͭԧZvRxвǸ|&EElV6W~mZ<#M9',L\h{iawbqWįcxvf含觎ۏ P3؁oTfUQ;zXN>0ejo`tYIFo|w\/JTgȸlmla~ֳ o͔輅(LvFT{L~͈j tb]ʙj2 ͉+`%}gd~{;^۩٧ȱμ!9Q[$* 7DXNo!ʝź<ӣ͉PߜEle~YᯝΚ9ok?׶٭ٳڙx(ەIIoiV^r͚HzO{eC͆5!`ά{Зk(lRYl ɿͽÀw7b˱ͤȥ⦵ݤxr\Kljmm:{LʹJ,@`͒G!iL ͓ ,Z͸Ymįw͏7xݶH^38^ͺKנڨlwffFա<5KJYK̪׻?A=̓̈́oi $tz3}u؟́ftm6P͉PoI͵@zX`hxpqGͷ6Rd͜[̧*+Q_d͞<}Ԙͦ,jͤ@aX% 9`͉S̲yy2͵W&ѱ_ְR͈ hJͧӮ^0-uY(HTJG͡5,w-̡ewgCdz͠s,͙f/$d7MNj,a9Z/͹9,l͎8pG2͸J-_fR5XZE.hNz}^ߞͪjEDͧл˚ܮͦB[ͺ' )hyͼ[4wN͜9̢|;]H޺͠-޾ڧ]]*n0hL3cNcZ?d YwH\Z/-V|wU^SU@͞:ZWxB`f)R͉=7BztVs͸\ӕzє|r@F^w# !:Qj.,ELRѷlVttBD͵|38ӹ۬Hѕ͡5%w͓'p;;ASͺͅ5)K]g纫JX|O-5nf(͕X|DzhNYد#2xڛ}H4z͔EcFW~Ϛϣ߯ʹV^#.ʤONO_ <"q"Jn͌֔Cۼ?ͥXԼi )džOg[TUaU]uy͏pzͮa׹TČtbjy˨CA}ՠ`X&Ƹ佌eMޕ^ͭ˾&>>ٍƃǠ=ͭFͧHV{v5*cߢJlr¾DuͶ͸Ֆ]㹰﹡ڤͱ[!͍lOjR⧞إ"c7u(9zޣ͇V͛uĒ˵߼IޔUɺ̰a} ͞Pw͟8>}a¥ϵœۯxc{E͡?֬{̓(Tq͵IUͷO'͕͝C{hbԩCK-ʾkzWͭi͡>ͲǤ[dtQΚﻪ͊ͼ륩Ͷγ멒 ͔ٴSKӨ ,L͆c[ ͒ͪ)3ǭ͏_K͗fP׬NͽK*ͫͿޫ_3̓͞«̚Hi#͕Cͨ cuԾ љfzͮkyڽͭͬE͠pͫ͛;bٹͼ|C)M鋤P$pq>4[BɺҪzsґחr9j6Ͳ^و>ƀdEw͉S ק)% GO5~Ol}Tˏ޻[L͡5Ξ”͈U͆XѿWfh_pFo4ho, XnwS+HÑ՘,`ا͠n[HqK*7qq^Aͷ7~X´ͬ̈́p#;Sk}y÷ځLў-͠[d>Jb{ͺͪEf̞ʹ#6ͷm?ͥZ=bFh9ͧ͵r2ͭͭpҤƔ:R'd͑ՖR`̻ͤض͇4+Xͮ%͊[tU'vQn͛u>͙ȋۤ;K%i۽cG)Jq;ʽۇͽߚi~͟ʊİ{v0ͤ"įGڲ͈&ΗdcL/3Kd|$QWoç\#3͔W֗́wȼȥȟ*fk˽߼ 7͡XʍzͲ΂ͺȾ0j~پ"NGoͻ͵5JU{zYW͸'F͖o͡˒kߥ͖خͳHuyߥԿv͐ȶҳ߁xIl?xa̬{͞ʹYN͠ڔͦs͐;S͍Hu(]͏Չɖ ^ͱ3_ܓߌ׹͕͈ͣuΥeLVuߥp5?O@͚OТ͸ͩ뽛}iڼʥ ͂HgiͰmQ͒aJx!.{v|`s͵arlDdGGmdZݿt F^o`1T˘,ڦɜ颡VI%,71I_<2ͶUmx/1[  "te,:; (>O++ !/I1-E^vŸ-[uܷ͙r\e͑+KQKͰߞy[xM/˕dn}v7 eO0RMJ.K>MopUQ929PU^&9/>ͦVmͻly̝Y^ͭVQiUE]ufͺl{oL͗#ܺѱqr͈Nͫ(CǧgXn#rPjFc|rͨ̈́gb\sw?WBJX\mmruPIfR%w͙I͎:_Ϳ֟2\+ ͑6āͭ]{ ͳʿt]EO~H^8ͼ`+Ȼ͑ʹͩ͢vDZƿbս͡ͰQ_w假L{ǧ,s&u_8&R;PrԨ͜Է͆N !gUEqϑ}lưͷ͖9ʹ8Qbr͈$o~TdҦ[uXaµꑰPY*3ͰͰ`*C[s;͖wO\@&h@*CP."K|ͣ͝Y'JL~3Y͖&/WHa>r? $<>/5I^9) &UHEQ=/_Q[xkMƲ͜Nx@Ͱ̇͟5nͺy͠y_͠qpLͳͷ}$NqbSFS͙Ͳ͈}:Qjv-E^uz YPEyeZyXaͺI¸sͧüͲ}ʬF[ĩͽNfNճ͙̈́ͥR͚Ku͛ƾć͍ ͍q%ו5Uwͷ?H9'9eޏ_sE鷤ɩ?͈͓mͶ_篆gu8:rͳȥpf{8鈀&/Goyͪͽ>͚͒ͪ͵Ͳ|Ř䇧(̟iͪL ================================================ FILE: src/navigation_tutorials/navigation_stage/stage_config/worlds/willow-pr2-2.5cm.world ================================================ define block model ( size [0.500 0.500 0.750] gui_nose 0 ) define topurg ranger ( sensor( range_max 30.0 fov 270.25 samples 1081 ) # generic model properties color "black" size [ 0.050 0.050 0.100 ] ) define pr2 position ( size [0.650 0.650 0.250] origin [-0.050 0 0 0] gui_nose 1 drive "omni" topurg(pose [ 0.275 0 0 0 ]) ) define floorplan model ( # sombre, sensible, artistic color "gray30" # most maps will need a bounding box boundary 1 gui_nose 0 gui_grid 0 gui_outline 0 gripper_return 0 fiducial_return 0 ranger_return 1 ) # set the resolution of the underlying raytrace model in meters resolution 0.01 interval_sim 100 # simulation timestep in milliseconds window ( size [ 745.000 448.000 ] rotate [ 0 -1.560 ] scale 30.287 ) # load an environment bitmap floorplan ( name "willow" bitmap "../maps/willow-full-0.025.pgm" size [58.300 45.625 1.000] pose [ -22.812 29.150 0 90.000 ] ) # throw in a robot pr2( pose [ -26.068 12.140 0 87.363 ] name "pr2" color "blue") block( pose [ -25.251 10.586 0 180.000 ] color "red") ================================================ FILE: src/navigation_tutorials/navigation_stage/stage_config/worlds/willow-pr2-5cm.world ================================================ define block model ( size [0.5 0.5 0.75] gui_nose 0 ) define topurg ranger ( sensor( range_max 30.0 fov 270.25 samples 1081 ) # generic model properties color "black" size [ 0.05 0.05 0.1 ] ) define pr2 position ( size [0.65 0.65 0.25] origin [-0.05 0 0 0] gui_nose 1 drive "omni" topurg(pose [ 0.275 0.000 0 0.000 ]) ) define floorplan model ( # sombre, sensible, artistic color "gray30" # most maps will need a bounding box boundary 1 gui_nose 0 gui_grid 0 gui_outline 0 gripper_return 0 fiducial_return 0 ranger_return 1 ) # set the resolution of the underlying raytrace model in meters resolution 0.02 interval_sim 100 # simulation timestep in milliseconds window ( size [ 745.000 448.000 ] rotate [ 0.000 -1.560 ] scale 18.806 ) # load an environment bitmap floorplan ( name "willow" bitmap "../maps/willow-full-0.05.pgm" size [58.25 47.25 1.0] pose [ -23.625 29.125 0 90.000 ] ) # throw in a robot pr2( pose [ -21.670 47.120 0 28.166 ] name "pr2" color "blue") block( pose [ -24.269 48.001 0 180.000 ] color "red") ================================================ FILE: src/navigation_tutorials/navigation_stage/stage_config/worlds/willow-pr2-multi.world ================================================ define block model ( size [0.5 0.5 0.5] gui_nose 0 ) define topurg ranger ( sensor( range_max 30.0 fov 270.25 samples 1081 ) # generic model properties color "black" size [ 0.05 0.05 0.1 ] ) define pr2 position ( size [0.65 0.65 0.25] origin [-0.05 0 0 0] gui_nose 1 drive "omni" topurg(pose [ 0.275 0.000 0 0.000 ]) ) define floorplan model ( # sombre, sensible, artistic color "gray30" # most maps will need a bounding box boundary 1 gui_nose 0 gui_grid 0 gui_outline 0 gripper_return 0 fiducial_return 0 ranger_return 1 ) # set the resolution of the underlying raytrace model in meters resolution 0.02 interval_sim 100 # simulation timestep in milliseconds window ( size [ 745.000 448.000 ] rotate [ 0.000 0.000 ] scale 28.806 ) # load an environment bitmap floorplan ( name "willow" bitmap "../maps/willow-full.pgm" size [58.4 52.6 0.5] pose [ -26.300 29.200 0 90.000 ] ) # throw in a robot pr2( pose [ -21.670 47.120 0 28.166 ] name "pr2_0" color "blue") pr2( pose [ -21.670 48.120 0 28.166 ] name "pr2_1" color "green") block( pose [ -24.269 48.001 0 180.000 ] color "red") ================================================ FILE: src/navigation_tutorials/navigation_stage/stage_config/worlds/willow-pr2.world ================================================ define block model ( size [0.5 0.5 0.5] gui_nose 0 ) define topurg ranger ( sensor( range_max 30.0 fov 270.25 samples 1081 ) # generic model properties color "black" size [ 0.05 0.05 0.1 ] ) define pr2 position ( size [0.65 0.65 0.25] origin [-0.05 0 0 0] gui_nose 1 drive "omni" topurg(pose [ 0.275 0.000 0 0.000 ]) ) define floorplan model ( # sombre, sensible, artistic color "gray30" # most maps will need a bounding box boundary 1 gui_nose 0 gui_grid 0 gui_outline 0 gripper_return 0 fiducial_return 0 ranger_return 1 ) # set the resolution of the underlying raytrace model in meters resolution 0.02 interval_sim 100 # simulation timestep in milliseconds window ( size [ 745.000 448.000 ] rotate [ 0.000 0.000 ] scale 28.806 ) # load an environment bitmap floorplan ( name "willow" bitmap "../maps/willow-full.pgm" size [58.4 52.6 0.5] pose [ -26.300 29.200 0 90.000 ] ) # throw in a robot pr2( pose [ -26.068 12.140 0 87.363 ] name "pr2" color "blue") block( pose [ -25.251 10.586 0 180.000 ] color "red") ================================================ FILE: src/navigation_tutorials/navigation_tutorials/CMakeLists.txt ================================================ cmake_minimum_required(VERSION 2.8.3) project(navigation_tutorials) find_package(catkin REQUIRED) catkin_metapackage() ================================================ FILE: src/navigation_tutorials/navigation_tutorials/package.xml ================================================ navigation_tutorials 0.2.3 Navigation related tutorials. William Woodall BSD http://www.ros.org/wiki/navigation_tutorials https://github.com/ros-planning/navigation_tutorials https://github.com/ros-planning/navigation_tutorials/issues catkin laser_scan_publisher_tutorial navigation_stage odometry_publisher_tutorial point_cloud_publisher_tutorial robot_setup_tf_tutorial roomba_stage simple_navigation_goals_tutorial ================================================ FILE: src/navigation_tutorials/odometry_publisher_tutorial/CMakeLists.txt ================================================ cmake_minimum_required(VERSION 2.8.3) project(odometry_publisher_tutorial) find_package(catkin REQUIRED COMPONENTS nav_msgs roscpp tf) catkin_package() include_directories(${catkin_INCLUDE_DIRS}) # Build the executable add_executable(odometry_publisher src/odometry_publisher.cpp) # Add a build order dependency on nav_msgs # This ensures that nav_msgs' msg headers are built before your executable if(nav_msgs_EXPORTED_TARGETS) add_dependencies(odometry_publisher ${nav_msgs_EXPORTED_TARGETS}) endif() # Link against the catkin libraries target_link_libraries(odometry_publisher ${catkin_LIBRARIES}) # Install the executable install(TARGETS odometry_publisher ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) ================================================ FILE: src/navigation_tutorials/odometry_publisher_tutorial/package.xml ================================================ odometry_publisher_tutorial 0.2.3 The odometry_publisher_tutorial package William Woodall BSD http://ros.org/wiki/odometry_publisher_tutorial https://github.com/ros-planning/navigation_tutorials https://github.com/ros-planning/navigation_tutorials/issues Eitan Marder-Eppstein catkin nav_msgs roscpp tf nav_msgs roscpp tf ================================================ FILE: src/navigation_tutorials/odometry_publisher_tutorial/src/odometry_publisher.cpp ================================================ /********************************************************************* * * Software License Agreement (BSD License) * * Copyright (c) 2009, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of Willow Garage, Inc. nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. * * Author: Eitan Marder-Eppstein *********************************************************************/ #include #include #include int main(int argc, char** argv){ ros::init(argc, argv, "odometry_publisher"); ros::NodeHandle n; ros::Publisher odom_pub = n.advertise("odom", 50); tf::TransformBroadcaster odom_broadcaster; double x = 0.0; double y = 0.0; double th = 0.0; double vx = 0.1; double vy = -0.1; double vth = 0.1; ros::Time current_time, last_time; current_time = ros::Time::now(); last_time = ros::Time::now(); ros::Rate r(1.0); while(n.ok()){ current_time = ros::Time::now(); //compute odometry in a typical way given the velocities of the robot double dt = (current_time - last_time).toSec(); double delta_x = (vx * cos(th) - vy * sin(th)) * dt; double delta_y = (vx * sin(th) + vy * cos(th)) * dt; double delta_th = vth * dt; x += delta_x; y += delta_y; th += delta_th; //since all odometry is 6DOF we'll need a quaternion created from yaw geometry_msgs::Quaternion odom_quat = tf::createQuaternionMsgFromYaw(th); //first, we'll publish the transform over tf geometry_msgs::TransformStamped odom_trans; odom_trans.header.stamp = current_time; odom_trans.header.frame_id = "odom"; odom_trans.child_frame_id = "base_link"; odom_trans.transform.translation.x = x; odom_trans.transform.translation.y = y; odom_trans.transform.translation.z = 0.0; odom_trans.transform.rotation = odom_quat; //send the transform odom_broadcaster.sendTransform(odom_trans); //next, we'll publish the odometry message over ROS nav_msgs::Odometry odom; odom.header.stamp = current_time; odom.header.frame_id = "odom"; odom.child_frame_id = "base_link"; //set the position odom.pose.pose.position.x = x; odom.pose.pose.position.y = y; odom.pose.pose.position.z = 0.0; odom.pose.pose.orientation = odom_quat; //set the velocity odom.twist.twist.linear.x = vx; odom.twist.twist.linear.y = vy; odom.twist.twist.angular.z = vth; //publish the message odom_pub.publish(odom); last_time = current_time; r.sleep(); } } ================================================ FILE: src/navigation_tutorials/point_cloud_publisher_tutorial/CMakeLists.txt ================================================ cmake_minimum_required(VERSION 2.8.3) project(point_cloud_publisher_tutorial) find_package(catkin REQUIRED COMPONENTS sensor_msgs roscpp) catkin_package() include_directories(${catkin_INCLUDE_DIRS}) # Build the executable add_executable(point_cloud_publisher src/point_cloud_publisher.cpp) # Add a build order dependency on sensor_msgs # This ensures that sensor_msgs' msg headers are built before your executable if(sensor_msgs_EXPORTED_TARGETS) add_dependencies(point_cloud_publisher ${sensor_msgs_EXPORTED_TARGETS}) endif() # Link against the catkin libraries target_link_libraries(point_cloud_publisher ${catkin_LIBRARIES}) # Install the executable install(TARGETS point_cloud_publisher ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) ================================================ FILE: src/navigation_tutorials/point_cloud_publisher_tutorial/package.xml ================================================ point_cloud_publisher_tutorial 0.2.3 The point_cloud_publisher_tutorial package William Woodall BSD http://ros.org/wiki/point_cloud_publisher_tutorial https://github.com/ros-planning/navigation_tutorials https://github.com/ros-planning/navigation_tutorials/issues Eitan Marder-Eppstein catkin sensor_msgs roscpp sensor_msgs roscpp ================================================ FILE: src/navigation_tutorials/point_cloud_publisher_tutorial/src/point_cloud_publisher.cpp ================================================ /********************************************************************* * * Software License Agreement (BSD License) * * Copyright (c) 2009, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of Willow Garage, Inc. nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. * * Author: Eitan Marder-Eppstein *********************************************************************/ #include #include int main(int argc, char** argv){ ros::init(argc, argv, "point_cloud_publisher"); ros::NodeHandle n; ros::Publisher cloud_pub = n.advertise("cloud", 50); unsigned int num_points = 100; int count = 0; ros::Rate r(1.0); while(n.ok()){ sensor_msgs::PointCloud cloud; cloud.header.stamp = ros::Time::now(); cloud.header.frame_id = "sensor_frame"; cloud.points.resize(num_points); //we'll also add an intensity channel to the cloud cloud.channels.resize(1); cloud.channels[0].name = "intensities"; cloud.channels[0].values.resize(num_points); //generate some fake data for our point cloud for(unsigned int i = 0; i < num_points; ++i){ cloud.points[i].x = 1 + count; cloud.points[i].y = 2 + count; cloud.points[i].z = 3 + count; cloud.channels[0].values[i] = 100 + count; } cloud_pub.publish(cloud); ++count; r.sleep(); } } ================================================ FILE: src/navigation_tutorials/robot_setup_tf_tutorial/CMakeLists.txt ================================================ cmake_minimum_required(VERSION 2.8.3) project(robot_setup_tf_tutorial) find_package(catkin REQUIRED COMPONENTS geometry_msgs roscpp tf) catkin_package() include_directories(${catkin_INCLUDE_DIRS}) # Build the tf_broadcaster executable add_executable(tf_broadcaster src/tf_broadcaster.cpp) # Add a build order dependency on geometry_msgs # This ensures that geometry_msgs' msg headers are built before your executable if(geometry_msgs_EXPORTED_TARGETS) add_dependencies(tf_broadcaster ${geometry_msgs_EXPORTED_TARGETS}) endif() # Link against the catkin libraries target_link_libraries(tf_broadcaster ${catkin_LIBRARIES}) # Build the tf_listener executable add_executable(tf_listener src/tf_listener.cpp) # Add a build order dependency on geometry_msgs # This ensures that geometry_msgs' msg headers are built before your executable if(geometry_msgs_EXPORTED_TARGETS) add_dependencies(tf_listener ${geometry_msgs_EXPORTED_TARGETS}) endif() # Link against the catkin libraries target_link_libraries(tf_listener ${catkin_LIBRARIES}) # Install the executable install(TARGETS tf_broadcaster tf_listener ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) ================================================ FILE: src/navigation_tutorials/robot_setup_tf_tutorial/manifest.xml ================================================ robot_setup_tf Eitan Marder-Eppstein BSD http://pr.willowgarage.com/wiki/robot_tf_publisher ================================================ FILE: src/navigation_tutorials/robot_setup_tf_tutorial/package.xml ================================================ robot_setup_tf_tutorial 0.2.3 The robot_setup_tf_tutorial package William Woodall BSD http://ros.org/wiki/robot_setup_tf_tutorial https://github.com/ros-planning/navigation_tutorials https://github.com/ros-planning/navigation_tutorials/issues Eitan Marder-Eppstein catkin geometry_msgs roscpp tf geometry_msgs roscpp tf ================================================ FILE: src/navigation_tutorials/robot_setup_tf_tutorial/src/tf_broadcaster.cpp ================================================ /********************************************************************* * * Software License Agreement (BSD License) * * Copyright (c) 2008, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of Willow Garage, Inc. nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. * * Author: Eitan Marder-Eppstein *********************************************************************/ #include #include int main(int argc, char** argv){ ros::init(argc, argv, "robot_tf_publisher"); ros::NodeHandle n; ros::Rate r(100); tf::TransformBroadcaster broadcaster; while(n.ok()){ broadcaster.sendTransform( tf::StampedTransform(tf::Transform(tf::Quaternion(0, 0, 0, 1), tf::Vector3(0.1, 0.0, 0.2)), ros::Time::now(), "base_link", "base_laser")); r.sleep(); } } ================================================ FILE: src/navigation_tutorials/robot_setup_tf_tutorial/src/tf_listener.cpp ================================================ /********************************************************************* * * Software License Agreement (BSD License) * * Copyright (c) 2008, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of Willow Garage, Inc. nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. * * Author: Eitan Marder-Eppstein *********************************************************************/ #include #include #include void transformPoint(const tf::TransformListener& listener){ //we'll create a point in the base_laser frame that we'd like to transform to the base_link frame geometry_msgs::PointStamped laser_point; laser_point.header.frame_id = "base_laser"; //we'll just use the most recent transform available for our simple example laser_point.header.stamp = ros::Time(); //just an arbitrary point in space laser_point.point.x = 1.0; laser_point.point.y = 0.2; laser_point.point.z = 0.0; try{ geometry_msgs::PointStamped base_point; listener.transformPoint("base_link", laser_point, base_point); ROS_INFO("base_laser: (%.2f, %.2f. %.2f) -----> base_link: (%.2f, %.2f, %.2f) at time %.2f", laser_point.point.x, laser_point.point.y, laser_point.point.z, base_point.point.x, base_point.point.y, base_point.point.z, base_point.header.stamp.toSec()); } catch(tf::TransformException& ex){ ROS_ERROR("Received an exception trying to transform a point from \"base_laser\" to \"base_link\": %s", ex.what()); } } int main(int argc, char** argv){ ros::init(argc, argv, "robot_tf_listener"); ros::NodeHandle n; tf::TransformListener listener(ros::Duration(10)); //we'll transform a point once every second ros::Timer timer = n.createTimer(ros::Duration(1.0), boost::bind(&transformPoint, boost::ref(listener))); ros::spin(); } ================================================ FILE: src/navigation_tutorials/roomba_stage/CMakeLists.txt ================================================ cmake_minimum_required(VERSION 2.8.3) project(roomba_stage) # Find catkin find_package(catkin REQUIRED) catkin_package() # Install maps files install(DIRECTORY maps DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) # Install params files install(DIRECTORY params DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) # Install other files install(FILES move_base_lse_arena.launch roomba_lse_arena.world roomba_stage.rviz DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) ================================================ FILE: src/navigation_tutorials/roomba_stage/manifest.xml ================================================ roomba_stage Gonçalo Cabrita BSD http://ros.org/wiki/roomba_stage ================================================ FILE: src/navigation_tutorials/roomba_stage/maps/lse_arena.yaml ================================================ image: lse_arena.pgm resolution: 0.050000 origin: [0.000000, 0.000000, 0.000000] negate: 0 occupied_thresh: 0.65 free_thresh: 0.196 ================================================ FILE: src/navigation_tutorials/roomba_stage/move_base_lse_arena.launch ================================================ ================================================ FILE: src/navigation_tutorials/roomba_stage/package.xml ================================================ roomba_stage 0.2.3 The roomba_stage package William Woodall BSD http://ros.org/wiki/roomba_stage https://github.com/ros-planning/navigation_tutorials https://github.com/ros-planning/navigation_tutorials/issues Gonçalo Cabrita catkin fake_localization map_server move_base stage_ros ================================================ FILE: src/navigation_tutorials/roomba_stage/params/amcl_roomba.launch ================================================ ================================================ FILE: src/navigation_tutorials/roomba_stage/params/base_local_planner_params.yaml ================================================ controller_frequency: 5.0 TrajectoryPlannerROS: max_vel_x: 0.20 min_vel_x: 0.10 max_rotational_vel: 1.5 min_in_place_rotational_vel: 0.1 acc_lim_th: 0.75 acc_lim_x: 0.50 acc_lim_y: 0.50 holonomic_robot: false yaw_goal_tolerance: 0.05 xy_goal_tolerance: 0.1 goal_distance_bias: 0.8 path_distance_bias: 0.6 sim_time: 1.5 heading_lookahead: 0.325 oscillation_reset_dist: 0.05 vx_samples: 6 vtheta_samples: 20 dwa: false ================================================ FILE: src/navigation_tutorials/roomba_stage/params/costmap_common_params.yaml ================================================ map_type: voxel z_voxels: 10 unknown_threshold: 8 obstacle_range: 2.5 raytrace_range: 3.0 robot_radius: 0.17 #footprint: [[0.17, 0.17], [-0.17, 0.17], [-0.17, -0.17], [0.17, -0.17]] inflation_radius: 0.18 observation_sources: laser_scan_sensor laser_scan_sensor: {sensor_frame: /base_laser_link, data_type: LaserScan, topic: /base_scan, marking: true, clearing: true} ================================================ FILE: src/navigation_tutorials/roomba_stage/params/global_costmap_params.yaml ================================================ global_costmap: global_frame: /odom robot_base_frame: /base_link update_frequency: 3.0 publish_frequency: 0.0 #static_map: true ================================================ FILE: src/navigation_tutorials/roomba_stage/params/local_costmap_params.yaml ================================================ local_costmap: global_frame: /odom robot_base_frame: /base_link update_frequency: 3.0 publish_frequency: 2.0 static_map: false rolling_window: true width: 4.0 height: 4.0 resolution: 0.05 ================================================ FILE: src/navigation_tutorials/roomba_stage/params/local_costmap_params_2.yaml ================================================ global_costmap: global_frame: /odom robot_base_frame: /base_link update_frequency: 3.0 publish_frequency: 2.0 static_map: false rolling_window: true width: 4.0 height: 4.0 resolution: 0.05 ================================================ FILE: src/navigation_tutorials/roomba_stage/roomba_lse_arena.world ================================================ # lse-roomba.world - basic world file for the roomba # Authors: Gonçalo Cabrita define hokuyo ranger ( sensor( range_min 0.0 range_max 2.0 fov 270.25 samples 1081 ) color "black" size [ 0.05 0.05 0.1 ] ) define roomba position ( size [0.33 0.33 0.1] # This block approximates the circular shape of a Roomba block ( points 16 point[0] [ 0.225 0.000 ] point[1] [ 0.208 0.086 ] point[2] [ 0.159 0.159 ] point[3] [ 0.086 0.208 ] point[4] [ 0.000 0.225 ] point[5] [ -0.086 0.208 ] point[6] [ -0.159 0.159 ] point[7] [ -0.208 0.086 ] point[8] [ -0.225 0.000 ] point[9] [ -0.208 -0.086 ] point[10] [ -0.159 -0.159 ] point[11] [ -0.086 -0.208 ] point[12] [ -0.000 -0.225 ] point[13] [ 0.086 -0.208 ] point[14] [ 0.159 -0.159 ] point[15] [ 0.208 -0.086 ] color "gray50" ) hokuyo( pose [0 0 0.1 0] ) color "gray50" ) define floorplan model ( # Sombre, sensible, artistic color "gray30" # Most maps will need a bounding box boundary 1 gui_nose 0 gui_grid 0 gui_move 0 gui_outline 0 gripper_return 0 fiducial_return 0 laser_return 1 ) # Set the resolution of the underlying raytrace model in meters resolution 0.02 interval_sim 100 # simulation timestep in milliseconds # Configure the GUI window window ( size [ 808.000 600.000 ] # in pixels scale 20 # pixels per meter center [ 2.0 1.5 ] rotate [ 0 0 ] show_data 1 # 1=on 0=off ) # load an environment bitmap floorplan ( name "lab_maze" size [4.0 3.0 1.00] pose [-1.5 2.0 0 90.000] bitmap "./maps/lse_arena.pgm" ) roomba ( # Can refer to the robot by this name name "roomba0" pose [ -1.0 1.0 0 0.0 ] drive "diff" # Report error-free position in world coordinates localization "gps" localization_origin [ 0 0 0 0 ] ) ================================================ FILE: src/navigation_tutorials/roomba_stage/roomba_stage.rviz ================================================ Panels: - Class: rviz/Displays Help Height: 78 Name: Displays Property Tree Widget: Expanded: - /Global Options1 Splitter Ratio: 0.5 Tree Height: 510 - Class: rviz/Selection Name: Selection - Class: rviz/Tool Properties Expanded: - /2D Pose Estimate1 - /2D Nav Goal1 - /Publish Point1 Name: Tool Properties Splitter Ratio: 0.588679 - Class: rviz/Views Expanded: - /Current View1 Name: Views Splitter Ratio: 0.5 - Class: rviz/Time Experimental: false Name: Time SyncMode: 0 SyncSource: LaserScan Visualization Manager: Class: "" Displays: - Alpha: 0.7 Class: rviz/Map Color Scheme: map Draw Behind: false Enabled: true Name: Map Topic: /map Value: true - Alpha: 1 Class: rviz/Polygon Color: 0; 0; 255 Enabled: true Name: Footprint Topic: /move_base/global_costmap/footprint_layer/footprint_stamped Value: true - Alpha: 1 Class: rviz/GridCells Color: 0; 0; 255 Enabled: true Name: Inflated Obstacles Topic: /move_base/local_costmap/inflated_obstacles Value: true - Alpha: 1 Class: rviz/GridCells Color: 0; 255; 0 Enabled: true Name: Obstacles Topic: /move_base/local_costmap/obstacles Value: true - Alpha: 1 Buffer Length: 1 Class: rviz/Path Color: 204; 0; 255 Enabled: true Name: Local Plan Topic: /move_base/TrajectoryPlannerROS/local_plan Value: true - Alpha: 1 Buffer Length: 1 Class: rviz/Path Color: 0; 255; 0 Enabled: true Name: Plan Topic: /move_base/NavfnROS/plan Value: true - Class: rviz/TF Enabled: false Frame Timeout: 15 Frames: All Enabled: true Marker Scale: 1 Name: TF Show Arrows: true Show Axes: true Show Names: true Tree: {} Update Interval: 0 Value: false - Alpha: 1 Autocompute Intensity Bounds: true Autocompute Value Bounds: Max Value: 10 Min Value: -10 Value: true Axis: Z Channel Name: intensity Class: rviz/LaserScan Color: 255; 255; 255 Color Transformer: Intensity Decay Time: 0 Enabled: true Max Color: 255; 255; 255 Max Intensity: 1 Min Color: 0; 0; 0 Min Intensity: 1 Name: LaserScan Position Transformer: XYZ Queue Size: 10 Selectable: true Size (Pixels): 3 Size (m): 0.01 Style: Flat Squares Topic: /base_scan Use Fixed Frame: true Use rainbow: true Value: true - Alpha: 1 Axes Length: 1 Axes Radius: 0.1 Class: rviz/Pose Color: 255; 25; 0 Enabled: true Head Length: 0.1 Head Radius: 0.05 Name: Pose Shaft Length: 0.25 Shaft Radius: 0.025 Shape: Arrow Topic: /move_base/current_goal Value: true Enabled: true Global Options: Background Color: 48; 48; 48 Fixed Frame: map Frame Rate: 30 Name: root Tools: - Class: rviz/Interact Hide Inactive Objects: true - Class: rviz/MoveCamera - Class: rviz/Select - Class: rviz/FocusCamera - Class: rviz/Measure - Class: rviz/SetInitialPose Topic: /initialpose - Class: rviz/SetGoal Topic: /move_base_simple/goal - Class: rviz/PublishPoint Single click: true Topic: /clicked_point Value: true Views: Current: Class: rviz/Orbit Distance: 4.91901 Focal Point: X: 0 Y: 0 Z: 0 Name: Current View Near Clip Distance: 0.01 Pitch: 0.645398 Target Frame: base_footprint Value: Orbit (rviz) Yaw: 0.275398 Saved: ~ Window Geometry: Displays: collapsed: false Height: 756 Hide Left Dock: false Hide Right Dock: false QMainWindow State: 000000ff00000000fd0000000400000000000001640000028cfc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005600fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000002540000011a00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000004c0000028c000000dc00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f0000028cfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000004c0000028c000000a500fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004fc0000003efc0100000002fb0000000800540069006d00650000000000000004fc0000020b00fffffffb0000000800540069006d00650100000000000004500000000000000000000002870000028c00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 Selection: collapsed: false Time: collapsed: false Tool Properties: collapsed: false Views: collapsed: false Width: 1276 X: 4 Y: 22 ================================================ FILE: src/navigation_tutorials/simple_navigation_goals_tutorial/CMakeLists.txt ================================================ cmake_minimum_required(VERSION 2.8.3) project(simple_navigation_goals_tutorial) find_package(catkin REQUIRED COMPONENTS actionlib move_base_msgs roscpp tf) catkin_package() include_directories(${catkin_INCLUDE_DIRS}) # Build the executable add_executable(simple_navigation_goals src/simple_navigation_goals.cpp) # Add a build order dependency on nav_msgs # This ensures that all msg headers are built before your executable if(catkin_EXPORTED_TARGETS) add_dependencies(simple_navigation_goals ${catkin_EXPORTED_TARGETS}) endif() # Link against the catkin libraries target_link_libraries(simple_navigation_goals ${catkin_LIBRARIES}) # Install the executable install(TARGETS simple_navigation_goals ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) ================================================ FILE: src/navigation_tutorials/simple_navigation_goals_tutorial/package.xml ================================================ simple_navigation_goals_tutorial 0.2.3 The simple_navigation_goals_tutorial package William Woodall BSD http://ros.org/wiki/simple_navigation_goals_tutorial https://github.com/ros-planning/navigation_tutorials https://github.com/ros-planning/navigation_tutorials/issues Eitan Marder-Eppstein catkin actionlib move_base_msgs roscpp tf actionlib move_base_msgs roscpp tf ================================================ FILE: src/navigation_tutorials/simple_navigation_goals_tutorial/src/simple_navigation_goals.cpp ================================================ /********************************************************************* * * Software License Agreement (BSD License) * * Copyright (c) 2008, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of Willow Garage, Inc. nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. * * Author: Eitan Marder-Eppstein * * For a discussion of this tutorial, please see: * http://pr.willowgarage.com/wiki/navigation/Tutorials/SendingSimpleGoals *********************************************************************/ #include #include #include #include #include typedef actionlib::SimpleActionClient MoveBaseClient; void spinThread(){ ros::spin(); } int main(int argc, char** argv){ ros::init(argc, argv, "simple_navigation_goals"); ros::NodeHandle n; boost::thread spin_thread = boost::thread(boost::bind(&spinThread)); MoveBaseClient ac("pose_base_controller"); //give some time for connections to register sleep(2.0); move_base_msgs::MoveBaseGoal goal; //we'll send a goal to the robot to move 2 meters forward goal.target_pose.header.frame_id = "base_link"; goal.target_pose.header.stamp = ros::Time::now(); goal.target_pose.pose.position.x = 2.0; goal.target_pose.pose.position.y = 0.2; goal.target_pose.pose.orientation = tf::createQuaternionMsgFromYaw(M_PI); ROS_INFO("Sending goal"); ac.sendGoal(goal); ac.waitForResult(); if(ac.getState() == actionlib::SimpleClientGoalState::SUCCEEDED) ROS_INFO("Hooray, the base moved 2 meters forward"); else ROS_INFO("The base failed to move forward 2 meters for some reason"); return 0; } ================================================ FILE: src/rf2o_laser_odometry/CMakeLists.txt ================================================ PROJECT(rf2o_laser_odometry) CMAKE_MINIMUM_REQUIRED(VERSION 3.3) # Require C++17 if(${CMAKE_VERSION} VERSION_LESS "3.8.0") set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++17") else() set(CMAKE_CXX_STANDARD 17) endif() ## Find catkin macros and libraries ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) ## is used, also find other catkin packages find_package(catkin REQUIRED COMPONENTS roscpp rospy nav_msgs sensor_msgs std_msgs tf ) ## System dependencies are found with CMake's conventions find_package(Boost REQUIRED COMPONENTS system) find_package(cmake_modules REQUIRED) find_package(Eigen3 REQUIRED) find_package(MRPT REQUIRED) MESSAGE(STATUS "Found MRPT: " ${MRPT_VERSION}) IF(MRPT_VERSION VERSION_LESS 1.9.9) # MRPT<2.0 find_package(MRPT REQUIRED base obs maps slam) ELSE() # MRPT>=2.0 find_package(MRPT REQUIRED obs maps slam poses core) ENDIF() #include_directories(${MRPT_INCLUDE_DIRS}) #MESSAGE( STATUS "MRPT_INCLUDE_DIRS: " ${MRPT_INCLUDE_DIRS}) #link_directories(${MRPT_LIBRARY_DIRS}) #MESSAGE( STATUS "MRPT_LIBRARY_DIRS: " ${MRPT_LIBS}) ################################### ## catkin specific configuration ## ################################### ## The catkin_package macro generates cmake config files for your package ## Declare things to be passed to dependent projects ## INCLUDE_DIRS: uncomment this if you package contains header files ## LIBRARIES: libraries you create in this project that dependent projects also need ## CATKIN_DEPENDS: catkin_packages dependent projects also need ## DEPENDS: system dependencies of this project that dependent projects also need catkin_package( INCLUDE_DIRS include LIBRARIES laser_odometry CATKIN_DEPENDS nav_msgs roscpp sensor_msgs std_msgs tf #DEPENDS system_lib ) ## Specify additional locations of header files ## Your package locations should be listed before other locations include_directories(include) include_directories( ${catkin_INCLUDE_DIRS} ${Boost_INCLUDE_DIRS} ${EIGEN_INCLUDE_DIRS} ${MRPT_INCLUDE_DIRS} ) ## Declare a cpp executable add_executable(rf2o_laser_odometry_node src/CLaserOdometry2D.cpp) ## Specify libraries to link a library or executable target against target_link_libraries(rf2o_laser_odometry_node ${catkin_LIBRARIES} ${Boost_LIBRARIES} ${EIGEN_LIBRARIES} ${MRPT_LIBS} ) ================================================ FILE: src/rf2o_laser_odometry/LICENSE ================================================ GNU GENERAL PUBLIC LICENSE Version 3, 29 June 2007 Copyright (C) 2007 Free Software Foundation, Inc. Everyone is permitted to copy and distribute verbatim copies of this license document, but changing it is not allowed. Preamble The GNU General Public License is a free, copyleft license for software and other kinds of works. The licenses for most software and other practical works are designed to take away your freedom to share and change the works. By contrast, the GNU General Public License is intended to guarantee your freedom to share and change all versions of a program--to make sure it remains free software for all its users. We, the Free Software Foundation, use the GNU General Public License for most of our software; it applies also to any other work released this way by its authors. You can apply it to your programs, too. When we speak of free software, we are referring to freedom, not price. Our General Public Licenses are designed to make sure that you have the freedom to distribute copies of free software (and charge for them if you wish), that you receive source code or can get it if you want it, that you can change the software or use pieces of it in new free programs, and that you know you can do these things. To protect your rights, we need to prevent others from denying you these rights or asking you to surrender the rights. Therefore, you have certain responsibilities if you distribute copies of the software, or if you modify it: responsibilities to respect the freedom of others. For example, if you distribute copies of such a program, whether gratis or for a fee, you must pass on to the recipients the same freedoms that you received. You must make sure that they, too, receive or can get the source code. And you must show them these terms so they know their rights. Developers that use the GNU GPL protect your rights with two steps: (1) assert copyright on the software, and (2) offer you this License giving you legal permission to copy, distribute and/or modify it. For the developers' and authors' protection, the GPL clearly explains that there is no warranty for this free software. For both users' and authors' sake, the GPL requires that modified versions be marked as changed, so that their problems will not be attributed erroneously to authors of previous versions. Some devices are designed to deny users access to install or run modified versions of the software inside them, although the manufacturer can do so. This is fundamentally incompatible with the aim of protecting users' freedom to change the software. The systematic pattern of such abuse occurs in the area of products for individuals to use, which is precisely where it is most unacceptable. Therefore, we have designed this version of the GPL to prohibit the practice for those products. If such problems arise substantially in other domains, we stand ready to extend this provision to those domains in future versions of the GPL, as needed to protect the freedom of users. Finally, every program is threatened constantly by software patents. States should not allow patents to restrict development and use of software on general-purpose computers, but in those that do, we wish to avoid the special danger that patents applied to a free program could make it effectively proprietary. To prevent this, the GPL assures that patents cannot be used to render the program non-free. The precise terms and conditions for copying, distribution and modification follow. TERMS AND CONDITIONS 0. Definitions. "This License" refers to version 3 of the GNU General Public License. "Copyright" also means copyright-like laws that apply to other kinds of works, such as semiconductor masks. "The Program" refers to any copyrightable work licensed under this License. Each licensee is addressed as "you". "Licensees" and "recipients" may be individuals or organizations. To "modify" a work means to copy from or adapt all or part of the work in a fashion requiring copyright permission, other than the making of an exact copy. The resulting work is called a "modified version" of the earlier work or a work "based on" the earlier work. A "covered work" means either the unmodified Program or a work based on the Program. To "propagate" a work means to do anything with it that, without permission, would make you directly or secondarily liable for infringement under applicable copyright law, except executing it on a computer or modifying a private copy. Propagation includes copying, distribution (with or without modification), making available to the public, and in some countries other activities as well. To "convey" a work means any kind of propagation that enables other parties to make or receive copies. Mere interaction with a user through a computer network, with no transfer of a copy, is not conveying. An interactive user interface displays "Appropriate Legal Notices" to the extent that it includes a convenient and prominently visible feature that (1) displays an appropriate copyright notice, and (2) tells the user that there is no warranty for the work (except to the extent that warranties are provided), that licensees may convey the work under this License, and how to view a copy of this License. If the interface presents a list of user commands or options, such as a menu, a prominent item in the list meets this criterion. 1. Source Code. The "source code" for a work means the preferred form of the work for making modifications to it. "Object code" means any non-source form of a work. A "Standard Interface" means an interface that either is an official standard defined by a recognized standards body, or, in the case of interfaces specified for a particular programming language, one that is widely used among developers working in that language. The "System Libraries" of an executable work include anything, other than the work as a whole, that (a) is included in the normal form of packaging a Major Component, but which is not part of that Major Component, and (b) serves only to enable use of the work with that Major Component, or to implement a Standard Interface for which an implementation is available to the public in source code form. A "Major Component", in this context, means a major essential component (kernel, window system, and so on) of the specific operating system (if any) on which the executable work runs, or a compiler used to produce the work, or an object code interpreter used to run it. The "Corresponding Source" for a work in object code form means all the source code needed to generate, install, and (for an executable work) run the object code and to modify the work, including scripts to control those activities. However, it does not include the work's System Libraries, or general-purpose tools or generally available free programs which are used unmodified in performing those activities but which are not part of the work. For example, Corresponding Source includes interface definition files associated with source files for the work, and the source code for shared libraries and dynamically linked subprograms that the work is specifically designed to require, such as by intimate data communication or control flow between those subprograms and other parts of the work. The Corresponding Source need not include anything that users can regenerate automatically from other parts of the Corresponding Source. The Corresponding Source for a work in source code form is that same work. 2. Basic Permissions. All rights granted under this License are granted for the term of copyright on the Program, and are irrevocable provided the stated conditions are met. This License explicitly affirms your unlimited permission to run the unmodified Program. The output from running a covered work is covered by this License only if the output, given its content, constitutes a covered work. This License acknowledges your rights of fair use or other equivalent, as provided by copyright law. You may make, run and propagate covered works that you do not convey, without conditions so long as your license otherwise remains in force. You may convey covered works to others for the sole purpose of having them make modifications exclusively for you, or provide you with facilities for running those works, provided that you comply with the terms of this License in conveying all material for which you do not control copyright. Those thus making or running the covered works for you must do so exclusively on your behalf, under your direction and control, on terms that prohibit them from making any copies of your copyrighted material outside their relationship with you. Conveying under any other circumstances is permitted solely under the conditions stated below. Sublicensing is not allowed; section 10 makes it unnecessary. 3. Protecting Users' Legal Rights From Anti-Circumvention Law. No covered work shall be deemed part of an effective technological measure under any applicable law fulfilling obligations under article 11 of the WIPO copyright treaty adopted on 20 December 1996, or similar laws prohibiting or restricting circumvention of such measures. When you convey a covered work, you waive any legal power to forbid circumvention of technological measures to the extent such circumvention is effected by exercising rights under this License with respect to the covered work, and you disclaim any intention to limit operation or modification of the work as a means of enforcing, against the work's users, your or third parties' legal rights to forbid circumvention of technological measures. 4. Conveying Verbatim Copies. You may convey verbatim copies of the Program's source code as you receive it, in any medium, provided that you conspicuously and appropriately publish on each copy an appropriate copyright notice; keep intact all notices stating that this License and any non-permissive terms added in accord with section 7 apply to the code; keep intact all notices of the absence of any warranty; and give all recipients a copy of this License along with the Program. You may charge any price or no price for each copy that you convey, and you may offer support or warranty protection for a fee. 5. Conveying Modified Source Versions. You may convey a work based on the Program, or the modifications to produce it from the Program, in the form of source code under the terms of section 4, provided that you also meet all of these conditions: a) The work must carry prominent notices stating that you modified it, and giving a relevant date. b) The work must carry prominent notices stating that it is released under this License and any conditions added under section 7. This requirement modifies the requirement in section 4 to "keep intact all notices". c) You must license the entire work, as a whole, under this License to anyone who comes into possession of a copy. This License will therefore apply, along with any applicable section 7 additional terms, to the whole of the work, and all its parts, regardless of how they are packaged. This License gives no permission to license the work in any other way, but it does not invalidate such permission if you have separately received it. d) If the work has interactive user interfaces, each must display Appropriate Legal Notices; however, if the Program has interactive interfaces that do not display Appropriate Legal Notices, your work need not make them do so. A compilation of a covered work with other separate and independent works, which are not by their nature extensions of the covered work, and which are not combined with it such as to form a larger program, in or on a volume of a storage or distribution medium, is called an "aggregate" if the compilation and its resulting copyright are not used to limit the access or legal rights of the compilation's users beyond what the individual works permit. Inclusion of a covered work in an aggregate does not cause this License to apply to the other parts of the aggregate. 6. Conveying Non-Source Forms. You may convey a covered work in object code form under the terms of sections 4 and 5, provided that you also convey the machine-readable Corresponding Source under the terms of this License, in one of these ways: a) Convey the object code in, or embodied in, a physical product (including a physical distribution medium), accompanied by the Corresponding Source fixed on a durable physical medium customarily used for software interchange. b) Convey the object code in, or embodied in, a physical product (including a physical distribution medium), accompanied by a written offer, valid for at least three years and valid for as long as you offer spare parts or customer support for that product model, to give anyone who possesses the object code either (1) a copy of the Corresponding Source for all the software in the product that is covered by this License, on a durable physical medium customarily used for software interchange, for a price no more than your reasonable cost of physically performing this conveying of source, or (2) access to copy the Corresponding Source from a network server at no charge. c) Convey individual copies of the object code with a copy of the written offer to provide the Corresponding Source. This alternative is allowed only occasionally and noncommercially, and only if you received the object code with such an offer, in accord with subsection 6b. d) Convey the object code by offering access from a designated place (gratis or for a charge), and offer equivalent access to the Corresponding Source in the same way through the same place at no further charge. You need not require recipients to copy the Corresponding Source along with the object code. If the place to copy the object code is a network server, the Corresponding Source may be on a different server (operated by you or a third party) that supports equivalent copying facilities, provided you maintain clear directions next to the object code saying where to find the Corresponding Source. Regardless of what server hosts the Corresponding Source, you remain obligated to ensure that it is available for as long as needed to satisfy these requirements. e) Convey the object code using peer-to-peer transmission, provided you inform other peers where the object code and Corresponding Source of the work are being offered to the general public at no charge under subsection 6d. A separable portion of the object code, whose source code is excluded from the Corresponding Source as a System Library, need not be included in conveying the object code work. A "User Product" is either (1) a "consumer product", which means any tangible personal property which is normally used for personal, family, or household purposes, or (2) anything designed or sold for incorporation into a dwelling. In determining whether a product is a consumer product, doubtful cases shall be resolved in favor of coverage. For a particular product received by a particular user, "normally used" refers to a typical or common use of that class of product, regardless of the status of the particular user or of the way in which the particular user actually uses, or expects or is expected to use, the product. A product is a consumer product regardless of whether the product has substantial commercial, industrial or non-consumer uses, unless such uses represent the only significant mode of use of the product. "Installation Information" for a User Product means any methods, procedures, authorization keys, or other information required to install and execute modified versions of a covered work in that User Product from a modified version of its Corresponding Source. The information must suffice to ensure that the continued functioning of the modified object code is in no case prevented or interfered with solely because modification has been made. If you convey an object code work under this section in, or with, or specifically for use in, a User Product, and the conveying occurs as part of a transaction in which the right of possession and use of the User Product is transferred to the recipient in perpetuity or for a fixed term (regardless of how the transaction is characterized), the Corresponding Source conveyed under this section must be accompanied by the Installation Information. But this requirement does not apply if neither you nor any third party retains the ability to install modified object code on the User Product (for example, the work has been installed in ROM). The requirement to provide Installation Information does not include a requirement to continue to provide support service, warranty, or updates for a work that has been modified or installed by the recipient, or for the User Product in which it has been modified or installed. Access to a network may be denied when the modification itself materially and adversely affects the operation of the network or violates the rules and protocols for communication across the network. Corresponding Source conveyed, and Installation Information provided, in accord with this section must be in a format that is publicly documented (and with an implementation available to the public in source code form), and must require no special password or key for unpacking, reading or copying. 7. Additional Terms. "Additional permissions" are terms that supplement the terms of this License by making exceptions from one or more of its conditions. Additional permissions that are applicable to the entire Program shall be treated as though they were included in this License, to the extent that they are valid under applicable law. If additional permissions apply only to part of the Program, that part may be used separately under those permissions, but the entire Program remains governed by this License without regard to the additional permissions. When you convey a copy of a covered work, you may at your option remove any additional permissions from that copy, or from any part of it. (Additional permissions may be written to require their own removal in certain cases when you modify the work.) You may place additional permissions on material, added by you to a covered work, for which you have or can give appropriate copyright permission. Notwithstanding any other provision of this License, for material you add to a covered work, you may (if authorized by the copyright holders of that material) supplement the terms of this License with terms: a) Disclaiming warranty or limiting liability differently from the terms of sections 15 and 16 of this License; or b) Requiring preservation of specified reasonable legal notices or author attributions in that material or in the Appropriate Legal Notices displayed by works containing it; or c) Prohibiting misrepresentation of the origin of that material, or requiring that modified versions of such material be marked in reasonable ways as different from the original version; or d) Limiting the use for publicity purposes of names of licensors or authors of the material; or e) Declining to grant rights under trademark law for use of some trade names, trademarks, or service marks; or f) Requiring indemnification of licensors and authors of that material by anyone who conveys the material (or modified versions of it) with contractual assumptions of liability to the recipient, for any liability that these contractual assumptions directly impose on those licensors and authors. All other non-permissive additional terms are considered "further restrictions" within the meaning of section 10. If the Program as you received it, or any part of it, contains a notice stating that it is governed by this License along with a term that is a further restriction, you may remove that term. If a license document contains a further restriction but permits relicensing or conveying under this License, you may add to a covered work material governed by the terms of that license document, provided that the further restriction does not survive such relicensing or conveying. If you add terms to a covered work in accord with this section, you must place, in the relevant source files, a statement of the additional terms that apply to those files, or a notice indicating where to find the applicable terms. Additional terms, permissive or non-permissive, may be stated in the form of a separately written license, or stated as exceptions; the above requirements apply either way. 8. Termination. You may not propagate or modify a covered work except as expressly provided under this License. Any attempt otherwise to propagate or modify it is void, and will automatically terminate your rights under this License (including any patent licenses granted under the third paragraph of section 11). However, if you cease all violation of this License, then your license from a particular copyright holder is reinstated (a) provisionally, unless and until the copyright holder explicitly and finally terminates your license, and (b) permanently, if the copyright holder fails to notify you of the violation by some reasonable means prior to 60 days after the cessation. Moreover, your license from a particular copyright holder is reinstated permanently if the copyright holder notifies you of the violation by some reasonable means, this is the first time you have received notice of violation of this License (for any work) from that copyright holder, and you cure the violation prior to 30 days after your receipt of the notice. Termination of your rights under this section does not terminate the licenses of parties who have received copies or rights from you under this License. If your rights have been terminated and not permanently reinstated, you do not qualify to receive new licenses for the same material under section 10. 9. Acceptance Not Required for Having Copies. You are not required to accept this License in order to receive or run a copy of the Program. Ancillary propagation of a covered work occurring solely as a consequence of using peer-to-peer transmission to receive a copy likewise does not require acceptance. However, nothing other than this License grants you permission to propagate or modify any covered work. These actions infringe copyright if you do not accept this License. Therefore, by modifying or propagating a covered work, you indicate your acceptance of this License to do so. 10. Automatic Licensing of Downstream Recipients. Each time you convey a covered work, the recipient automatically receives a license from the original licensors, to run, modify and propagate that work, subject to this License. You are not responsible for enforcing compliance by third parties with this License. An "entity transaction" is a transaction transferring control of an organization, or substantially all assets of one, or subdividing an organization, or merging organizations. If propagation of a covered work results from an entity transaction, each party to that transaction who receives a copy of the work also receives whatever licenses to the work the party's predecessor in interest had or could give under the previous paragraph, plus a right to possession of the Corresponding Source of the work from the predecessor in interest, if the predecessor has it or can get it with reasonable efforts. You may not impose any further restrictions on the exercise of the rights granted or affirmed under this License. For example, you may not impose a license fee, royalty, or other charge for exercise of rights granted under this License, and you may not initiate litigation (including a cross-claim or counterclaim in a lawsuit) alleging that any patent claim is infringed by making, using, selling, offering for sale, or importing the Program or any portion of it. 11. Patents. A "contributor" is a copyright holder who authorizes use under this License of the Program or a work on which the Program is based. The work thus licensed is called the contributor's "contributor version". A contributor's "essential patent claims" are all patent claims owned or controlled by the contributor, whether already acquired or hereafter acquired, that would be infringed by some manner, permitted by this License, of making, using, or selling its contributor version, but do not include claims that would be infringed only as a consequence of further modification of the contributor version. For purposes of this definition, "control" includes the right to grant patent sublicenses in a manner consistent with the requirements of this License. Each contributor grants you a non-exclusive, worldwide, royalty-free patent license under the contributor's essential patent claims, to make, use, sell, offer for sale, import and otherwise run, modify and propagate the contents of its contributor version. In the following three paragraphs, a "patent license" is any express agreement or commitment, however denominated, not to enforce a patent (such as an express permission to practice a patent or covenant not to sue for patent infringement). To "grant" such a patent license to a party means to make such an agreement or commitment not to enforce a patent against the party. If you convey a covered work, knowingly relying on a patent license, and the Corresponding Source of the work is not available for anyone to copy, free of charge and under the terms of this License, through a publicly available network server or other readily accessible means, then you must either (1) cause the Corresponding Source to be so available, or (2) arrange to deprive yourself of the benefit of the patent license for this particular work, or (3) arrange, in a manner consistent with the requirements of this License, to extend the patent license to downstream recipients. "Knowingly relying" means you have actual knowledge that, but for the patent license, your conveying the covered work in a country, or your recipient's use of the covered work in a country, would infringe one or more identifiable patents in that country that you have reason to believe are valid. If, pursuant to or in connection with a single transaction or arrangement, you convey, or propagate by procuring conveyance of, a covered work, and grant a patent license to some of the parties receiving the covered work authorizing them to use, propagate, modify or convey a specific copy of the covered work, then the patent license you grant is automatically extended to all recipients of the covered work and works based on it. A patent license is "discriminatory" if it does not include within the scope of its coverage, prohibits the exercise of, or is conditioned on the non-exercise of one or more of the rights that are specifically granted under this License. You may not convey a covered work if you are a party to an arrangement with a third party that is in the business of distributing software, under which you make payment to the third party based on the extent of your activity of conveying the work, and under which the third party grants, to any of the parties who would receive the covered work from you, a discriminatory patent license (a) in connection with copies of the covered work conveyed by you (or copies made from those copies), or (b) primarily for and in connection with specific products or compilations that contain the covered work, unless you entered into that arrangement, or that patent license was granted, prior to 28 March 2007. Nothing in this License shall be construed as excluding or limiting any implied license or other defenses to infringement that may otherwise be available to you under applicable patent law. 12. No Surrender of Others' Freedom. If conditions are imposed on you (whether by court order, agreement or otherwise) that contradict the conditions of this License, they do not excuse you from the conditions of this License. If you cannot convey a covered work so as to satisfy simultaneously your obligations under this License and any other pertinent obligations, then as a consequence you may not convey it at all. For example, if you agree to terms that obligate you to collect a royalty for further conveying from those to whom you convey the Program, the only way you could satisfy both those terms and this License would be to refrain entirely from conveying the Program. 13. Use with the GNU Affero General Public License. Notwithstanding any other provision of this License, you have permission to link or combine any covered work with a work licensed under version 3 of the GNU Affero General Public License into a single combined work, and to convey the resulting work. The terms of this License will continue to apply to the part which is the covered work, but the special requirements of the GNU Affero General Public License, section 13, concerning interaction through a network will apply to the combination as such. 14. Revised Versions of this License. The Free Software Foundation may publish revised and/or new versions of the GNU General Public License from time to time. Such new versions will be similar in spirit to the present version, but may differ in detail to address new problems or concerns. Each version is given a distinguishing version number. If the Program specifies that a certain numbered version of the GNU General Public License "or any later version" applies to it, you have the option of following the terms and conditions either of that numbered version or of any later version published by the Free Software Foundation. If the Program does not specify a version number of the GNU General Public License, you may choose any version ever published by the Free Software Foundation. If the Program specifies that a proxy can decide which future versions of the GNU General Public License can be used, that proxy's public statement of acceptance of a version permanently authorizes you to choose that version for the Program. Later license versions may give you additional or different permissions. However, no additional obligations are imposed on any author or copyright holder as a result of your choosing to follow a later version. 15. Disclaimer of Warranty. THERE IS NO WARRANTY FOR THE PROGRAM, TO THE EXTENT PERMITTED BY APPLICABLE LAW. EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT HOLDERS AND/OR OTHER PARTIES PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE PROGRAM IS WITH YOU. SHOULD THE PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF ALL NECESSARY SERVICING, REPAIR OR CORRECTION. 16. Limitation of Liability. IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MODIFIES AND/OR CONVEYS THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING OUT OF THE USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED TO LOSS OF DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER PROGRAMS), EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGES. 17. Interpretation of Sections 15 and 16. If the disclaimer of warranty and limitation of liability provided above cannot be given local legal effect according to their terms, reviewing courts shall apply local law that most closely approximates an absolute waiver of all civil liability in connection with the Program, unless a warranty or assumption of liability accompanies a copy of the Program in return for a fee. END OF TERMS AND CONDITIONS How to Apply These Terms to Your New Programs If you develop a new program, and you want it to be of the greatest possible use to the public, the best way to achieve this is to make it free software which everyone can redistribute and change under these terms. To do so, attach the following notices to the program. It is safest to attach them to the start of each source file to most effectively state the exclusion of warranty; and each file should have at least the "copyright" line and a pointer to where the full notice is found. {one line to give the program's name and a brief idea of what it does.} Copyright (C) {year} {name of author} This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation, either version 3 of the License, or (at your option) any later version. This program is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details. You should have received a copy of the GNU General Public License along with this program. If not, see . Also add information on how to contact you by electronic and paper mail. If the program does terminal interaction, make it output a short notice like this when it starts in an interactive mode: {project} Copyright (C) {year} {fullname} This program comes with ABSOLUTELY NO WARRANTY; for details type `show w'. This is free software, and you are welcome to redistribute it under certain conditions; type `show c' for details. The hypothetical commands `show w' and `show c' should show the appropriate parts of the General Public License. Of course, your program's commands might be different; for a GUI interface, you would use an "about box". You should also get your employer (if you work as a programmer) or school, if any, to sign a "copyright disclaimer" for the program, if necessary. For more information on this, and how to apply and follow the GNU GPL, see . The GNU General Public License does not permit incorporating your program into proprietary programs. If your program is a subroutine library, you may consider it more useful to permit linking proprietary applications with the library. If this is what you want to do, use the GNU Lesser General Public License instead of this License. But first, please read . ================================================ FILE: src/rf2o_laser_odometry/README.md ================================================ # rf2o_laser_odometry Estimation of 2D odometry based on planar laser scans. Useful for mobile robots with innacurate base odometry. RF2O is a fast and precise method to estimate the planar motion of a lidar from consecutive range scans. For every scanned point we formulate the range flow constraint equation in terms of the sensor velocity, and minimize a robust function of the resulting geometric constraints to obtain the motion estimate. Conversely to traditional approaches, this method does not search for correspondences but performs dense scan alignment based on the scan gradients, in the fashion of dense 3D visual odometry. Its very low computational cost (0.9 milliseconds on a single CPU core) together whit its high precission, makes RF2O a suitable method for those robotic applications that require planar odometry. For full description of the algorithm, please refer to: **Planar Odometry from a Radial Laser Scanner. A Range Flow-based Approach. ICRA 2016** Available at: http://mapir.isa.uma.es/work/rf2o # Requirements RF2O core is implemented within the **Mobile Robot Programming Toolkit** [MRPT](http://www.mrpt.org/), so it is necessary to install this powerful library (see instructions [here](http://www.mrpt.org/download-mrpt/)) So far RF2O has been tested with the Ubuntu official repository version (MRPT v1.3), and we are working to update it to MRPT v.1.9 ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CATKIN_IGNORE ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeCache.txt ================================================ # This is the CMakeCache file. # For build in directory: /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # It was generated by CMake: /home/zn/.ide/clion/bin/cmake/bin/cmake # You can edit this file to change values found and used by cmake. # If you do not want to change any of the values, simply exit the editor. # If you do want to change a value, simply edit, save, and exit the editor. # The syntax for the file is as follows: # KEY:TYPE=VALUE # KEY is the name of a variable in the cache. # TYPE is a hint to GUIs for the type of VALUE, DO NOT EDIT TYPE!. # VALUE is the current value for the KEY. ######################## # EXTERNAL cache entries ######################## //Build dynamically-linked binaries BUILD_SHARED_LIBS:BOOL=ON //The directory containing a CMake configuration file for Boost. Boost_DIR:PATH=Boost_DIR-NOTFOUND //Path to a file. Boost_INCLUDE_DIR:PATH=/usr/include //Boost library directory DEBUG Boost_LIBRARY_DIR_DEBUG:PATH=/usr/lib/x86_64-linux-gnu //Boost library directory RELEASE Boost_LIBRARY_DIR_RELEASE:PATH=/usr/lib/x86_64-linux-gnu //Boost system library (debug) Boost_SYSTEM_LIBRARY_DEBUG:FILEPATH=/usr/lib/x86_64-linux-gnu/libboost_system.so //Boost system library (release) Boost_SYSTEM_LIBRARY_RELEASE:FILEPATH=/usr/lib/x86_64-linux-gnu/libboost_system.so //Catkin enable testing CATKIN_ENABLE_TESTING:BOOL=ON //Prefix to apply to package generated via gendebian CATKIN_PACKAGE_PREFIX:STRING= //Catkin skip testing CATKIN_SKIP_TESTING:BOOL=OFF //Path to a program. CMAKE_AR:FILEPATH=/usr/bin/ar //Choose the type of build, options are: None(CMAKE_CXX_FLAGS or // CMAKE_C_FLAGS used) Debug Release RelWithDebInfo MinSizeRel. CMAKE_BUILD_TYPE:STRING=Debug //The CodeBlocks executable CMAKE_CODEBLOCKS_EXECUTABLE:FILEPATH=CMAKE_CODEBLOCKS_EXECUTABLE-NOTFOUND //Additional command line arguments when CodeBlocks invokes make. // Enter e.g. -j to get parallel builds CMAKE_CODEBLOCKS_MAKE_ARGUMENTS:STRING=-j8 //Enable/Disable color output during build. CMAKE_COLOR_MAKEFILE:BOOL=ON //CXX compiler CMAKE_CXX_COMPILER:FILEPATH=/usr/bin/c++ //A wrapper around 'ar' adding the appropriate '--plugin' option // for the GCC compiler CMAKE_CXX_COMPILER_AR:FILEPATH=/usr/bin/gcc-ar-5 //A wrapper around 'ranlib' adding the appropriate '--plugin' option // for the GCC compiler CMAKE_CXX_COMPILER_RANLIB:FILEPATH=/usr/bin/gcc-ranlib-5 //Flags used by the compiler during all build types. CMAKE_CXX_FLAGS:STRING= //Flags used by the compiler during debug builds. CMAKE_CXX_FLAGS_DEBUG:STRING=-g //Flags used by the compiler during release builds for minimum // size. CMAKE_CXX_FLAGS_MINSIZEREL:STRING=-Os -DNDEBUG //Flags used by the compiler during release builds. CMAKE_CXX_FLAGS_RELEASE:STRING=-O3 -DNDEBUG //Flags used by the compiler during release builds with debug info. CMAKE_CXX_FLAGS_RELWITHDEBINFO:STRING=-O2 -g -DNDEBUG //C compiler CMAKE_C_COMPILER:FILEPATH=/usr/bin/cc //A wrapper around 'ar' adding the appropriate '--plugin' option // for the GCC compiler CMAKE_C_COMPILER_AR:FILEPATH=/usr/bin/gcc-ar-5 //A wrapper around 'ranlib' adding the appropriate '--plugin' option // for the GCC compiler CMAKE_C_COMPILER_RANLIB:FILEPATH=/usr/bin/gcc-ranlib-5 //Flags used by the compiler during all build types. CMAKE_C_FLAGS:STRING= //Flags used by the compiler during debug builds. CMAKE_C_FLAGS_DEBUG:STRING=-g //Flags used by the compiler during release builds for minimum // size. CMAKE_C_FLAGS_MINSIZEREL:STRING=-Os -DNDEBUG //Flags used by the compiler during release builds. CMAKE_C_FLAGS_RELEASE:STRING=-O3 -DNDEBUG //Flags used by the compiler during release builds with debug info. CMAKE_C_FLAGS_RELWITHDEBINFO:STRING=-O2 -g -DNDEBUG //Flags used by the linker. CMAKE_EXE_LINKER_FLAGS:STRING= //Flags used by the linker during debug builds. CMAKE_EXE_LINKER_FLAGS_DEBUG:STRING= //Flags used by the linker during release minsize builds. CMAKE_EXE_LINKER_FLAGS_MINSIZEREL:STRING= //Flags used by the linker during release builds. CMAKE_EXE_LINKER_FLAGS_RELEASE:STRING= //Flags used by the linker during Release with Debug Info builds. CMAKE_EXE_LINKER_FLAGS_RELWITHDEBINFO:STRING= //Enable/Disable output of compile commands during generation. CMAKE_EXPORT_COMPILE_COMMANDS:BOOL=OFF //Install path prefix, prepended onto install directories. CMAKE_INSTALL_PREFIX:PATH=/usr/local //Path to a program. CMAKE_LINKER:FILEPATH=/usr/bin/ld //Path to a program. CMAKE_MAKE_PROGRAM:FILEPATH=/usr/bin/make //Flags used by the linker during the creation of modules. CMAKE_MODULE_LINKER_FLAGS:STRING= //Flags used by the linker during debug builds. CMAKE_MODULE_LINKER_FLAGS_DEBUG:STRING= //Flags used by the linker during release minsize builds. CMAKE_MODULE_LINKER_FLAGS_MINSIZEREL:STRING= //Flags used by the linker during release builds. CMAKE_MODULE_LINKER_FLAGS_RELEASE:STRING= //Flags used by the linker during Release with Debug Info builds. CMAKE_MODULE_LINKER_FLAGS_RELWITHDEBINFO:STRING= //Path to a program. CMAKE_NM:FILEPATH=/usr/bin/nm //Path to a program. CMAKE_OBJCOPY:FILEPATH=/usr/bin/objcopy //Path to a program. CMAKE_OBJDUMP:FILEPATH=/usr/bin/objdump //Value Computed by CMake CMAKE_PROJECT_NAME:STATIC=rf2o_laser_odometry //Path to a program. CMAKE_RANLIB:FILEPATH=/usr/bin/ranlib //Flags used by the linker during the creation of dll's. CMAKE_SHARED_LINKER_FLAGS:STRING= //Flags used by the linker during debug builds. CMAKE_SHARED_LINKER_FLAGS_DEBUG:STRING= //Flags used by the linker during release minsize builds. CMAKE_SHARED_LINKER_FLAGS_MINSIZEREL:STRING= //Flags used by the linker during release builds. CMAKE_SHARED_LINKER_FLAGS_RELEASE:STRING= //Flags used by the linker during Release with Debug Info builds. CMAKE_SHARED_LINKER_FLAGS_RELWITHDEBINFO:STRING= //If set, runtime paths are not added when installing shared libraries, // but are added when building. CMAKE_SKIP_INSTALL_RPATH:BOOL=NO //If set, runtime paths are not added when using shared libraries. CMAKE_SKIP_RPATH:BOOL=NO //Flags used by the linker during the creation of static libraries. CMAKE_STATIC_LINKER_FLAGS:STRING= //Flags used by the linker during debug builds. CMAKE_STATIC_LINKER_FLAGS_DEBUG:STRING= //Flags used by the linker during release minsize builds. CMAKE_STATIC_LINKER_FLAGS_MINSIZEREL:STRING= //Flags used by the linker during release builds. CMAKE_STATIC_LINKER_FLAGS_RELEASE:STRING= //Flags used by the linker during Release with Debug Info builds. CMAKE_STATIC_LINKER_FLAGS_RELWITHDEBINFO:STRING= //Path to a program. CMAKE_STRIP:FILEPATH=/usr/bin/strip //If this value is on, makefiles will be generated without the // .SILENT directive, and all commands will be echoed to the console // during the make. This is useful for debugging only. With Visual // Studio IDE projects all commands are done without /nologo. CMAKE_VERBOSE_MAKEFILE:BOOL=FALSE //Path to a program. DOXYGEN_EXECUTABLE:FILEPATH=DOXYGEN_EXECUTABLE-NOTFOUND //Path to a program. EMPY_EXECUTABLE:FILEPATH=/usr/bin/empy //Empy script EMPY_SCRIPT:STRING=/usr/bin/empy //The directory containing a CMake configuration file for Eigen3. Eigen3_DIR:PATH=/usr/lib/cmake/eigen3 //The directory containing a CMake configuration file for GMock. GMock_DIR:PATH=GMock_DIR-NOTFOUND //Path to a file. GTEST_INCLUDE_DIR:PATH=/usr/local/include //Path to a library. GTEST_LIBRARY:FILEPATH=/usr/local/lib/libgtest.a //Path to a library. GTEST_LIBRARY_DEBUG:FILEPATH=GTEST_LIBRARY_DEBUG-NOTFOUND //Path to a library. GTEST_MAIN_LIBRARY:FILEPATH=/usr/local/lib/libgtest_main.a //Path to a library. GTEST_MAIN_LIBRARY_DEBUG:FILEPATH=GTEST_MAIN_LIBRARY_DEBUG-NOTFOUND //lsb_release executable was found LSB_FOUND:BOOL=TRUE //Path to a program. LSB_RELEASE_EXECUTABLE:FILEPATH=/usr/bin/lsb_release //The directory containing a CMake configuration file for MRPT. MRPT_DIR:PATH=/usr/share/mrpt //Path to a program. NOSETESTS:FILEPATH=/usr/bin/nosetests-2.7 //Path to a program. PYTHON_EXECUTABLE:FILEPATH=/usr/bin/python //Specify specific Python version to use ('major.minor' or 'major') PYTHON_VERSION:STRING= //Path to a program. ProcessorCount_cmd_getconf:FILEPATH=/usr/bin/getconf //Path to a program. ProcessorCount_cmd_sysctl:FILEPATH=/sbin/sysctl //Path to a library. RT_LIBRARY:FILEPATH=/usr/lib/x86_64-linux-gnu/librt.so //Enable debian style python package layout SETUPTOOLS_DEB_LAYOUT:BOOL=ON //LSB Distrib tag UBUNTU:BOOL=TRUE //LSB Distrib - codename tag UBUNTU_XENIAL:BOOL=TRUE //The directory containing a CMake configuration file for actionlib. actionlib_DIR:PATH=/opt/ros/kinetic/share/actionlib/cmake //The directory containing a CMake configuration file for actionlib_msgs. actionlib_msgs_DIR:PATH=/opt/ros/kinetic/share/actionlib_msgs/cmake //The directory containing a CMake configuration file for catkin. catkin_DIR:PATH=/opt/ros/kinetic/share/catkin/cmake //The directory containing a CMake configuration file for cmake_modules. cmake_modules_DIR:PATH=/opt/ros/kinetic/share/cmake_modules/cmake //The directory containing a CMake configuration file for cpp_common. cpp_common_DIR:PATH=/opt/ros/kinetic/share/cpp_common/cmake //The directory containing a CMake configuration file for gencpp. gencpp_DIR:PATH=/opt/ros/kinetic/share/gencpp/cmake //The directory containing a CMake configuration file for geneus. geneus_DIR:PATH=/opt/ros/kinetic/share/geneus/cmake //The directory containing a CMake configuration file for genlisp. genlisp_DIR:PATH=/opt/ros/kinetic/share/genlisp/cmake //The directory containing a CMake configuration file for genmsg. genmsg_DIR:PATH=/opt/ros/kinetic/share/genmsg/cmake //The directory containing a CMake configuration file for gennodejs. gennodejs_DIR:PATH=/opt/ros/kinetic/share/gennodejs/cmake //The directory containing a CMake configuration file for genpy. genpy_DIR:PATH=/opt/ros/kinetic/share/genpy/cmake //The directory containing a CMake configuration file for geometry_msgs. geometry_msgs_DIR:PATH=/opt/ros/kinetic/share/geometry_msgs/cmake //Path to a library. lib:FILEPATH=/opt/ros/kinetic/lib/libtf2.so //The directory containing a CMake configuration file for message_filters. message_filters_DIR:PATH=/opt/ros/kinetic/share/message_filters/cmake //The directory containing a CMake configuration file for message_generation. message_generation_DIR:PATH=/opt/ros/kinetic/share/message_generation/cmake //The directory containing a CMake configuration file for message_runtime. message_runtime_DIR:PATH=/opt/ros/kinetic/share/message_runtime/cmake //The directory containing a CMake configuration file for nav_msgs. nav_msgs_DIR:PATH=/opt/ros/kinetic/share/nav_msgs/cmake //Value Computed by CMake rf2o_laser_odometry_BINARY_DIR:STATIC=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug //Value Computed by CMake rf2o_laser_odometry_SOURCE_DIR:STATIC=/home/zn/racecar/src/rf2o_laser_odometry //The directory containing a CMake configuration file for rosconsole. rosconsole_DIR:PATH=/opt/ros/kinetic/share/rosconsole/cmake //The directory containing a CMake configuration file for roscpp. roscpp_DIR:PATH=/opt/ros/kinetic/share/roscpp/cmake //The directory containing a CMake configuration file for roscpp_serialization. roscpp_serialization_DIR:PATH=/opt/ros/kinetic/share/roscpp_serialization/cmake //The directory containing a CMake configuration file for roscpp_traits. roscpp_traits_DIR:PATH=/opt/ros/kinetic/share/roscpp_traits/cmake //The directory containing a CMake configuration file for rosgraph. rosgraph_DIR:PATH=/opt/ros/kinetic/share/rosgraph/cmake //The directory containing a CMake configuration file for rosgraph_msgs. rosgraph_msgs_DIR:PATH=/opt/ros/kinetic/share/rosgraph_msgs/cmake //The directory containing a CMake configuration file for rospy. rospy_DIR:PATH=/opt/ros/kinetic/share/rospy/cmake //The directory containing a CMake configuration file for rostime. rostime_DIR:PATH=/opt/ros/kinetic/share/rostime/cmake //The directory containing a CMake configuration file for sensor_msgs. sensor_msgs_DIR:PATH=/opt/ros/kinetic/share/sensor_msgs/cmake //The directory containing a CMake configuration file for std_msgs. std_msgs_DIR:PATH=/opt/ros/kinetic/share/std_msgs/cmake //The directory containing a CMake configuration file for tf2. tf2_DIR:PATH=/opt/ros/kinetic/share/tf2/cmake //The directory containing a CMake configuration file for tf2_msgs. tf2_msgs_DIR:PATH=/opt/ros/kinetic/share/tf2_msgs/cmake //The directory containing a CMake configuration file for tf2_py. tf2_py_DIR:PATH=/opt/ros/kinetic/share/tf2_py/cmake //The directory containing a CMake configuration file for tf2_ros. tf2_ros_DIR:PATH=/opt/ros/kinetic/share/tf2_ros/cmake //The directory containing a CMake configuration file for tf. tf_DIR:PATH=/opt/ros/kinetic/share/tf/cmake //The directory containing a CMake configuration file for xmlrpcpp. xmlrpcpp_DIR:PATH=/opt/ros/kinetic/share/xmlrpcpp/cmake ######################## # INTERNAL cache entries ######################## //ADVANCED property for variable: Boost_DIR Boost_DIR-ADVANCED:INTERNAL=1 //ADVANCED property for variable: Boost_INCLUDE_DIR Boost_INCLUDE_DIR-ADVANCED:INTERNAL=1 //ADVANCED property for variable: Boost_LIBRARY_DIR_DEBUG Boost_LIBRARY_DIR_DEBUG-ADVANCED:INTERNAL=1 //ADVANCED property for variable: Boost_LIBRARY_DIR_RELEASE Boost_LIBRARY_DIR_RELEASE-ADVANCED:INTERNAL=1 //ADVANCED property for variable: Boost_SYSTEM_LIBRARY_DEBUG Boost_SYSTEM_LIBRARY_DEBUG-ADVANCED:INTERNAL=1 //ADVANCED property for variable: Boost_SYSTEM_LIBRARY_RELEASE Boost_SYSTEM_LIBRARY_RELEASE-ADVANCED:INTERNAL=1 //catkin environment CATKIN_ENV:INTERNAL=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/env_cached.sh CATKIN_TEST_RESULTS_DIR:INTERNAL=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/test_results //ADVANCED property for variable: CMAKE_AR CMAKE_AR-ADVANCED:INTERNAL=1 //This is the directory where this CMakeCache.txt was created CMAKE_CACHEFILE_DIR:INTERNAL=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug //Major version of cmake used to create the current loaded cache CMAKE_CACHE_MAJOR_VERSION:INTERNAL=3 //Minor version of cmake used to create the current loaded cache CMAKE_CACHE_MINOR_VERSION:INTERNAL=9 //Patch version of cmake used to create the current loaded cache CMAKE_CACHE_PATCH_VERSION:INTERNAL=6 //ADVANCED property for variable: CMAKE_COLOR_MAKEFILE CMAKE_COLOR_MAKEFILE-ADVANCED:INTERNAL=1 //Path to CMake executable. CMAKE_COMMAND:INTERNAL=/home/zn/.ide/clion/bin/cmake/bin/cmake //Path to cpack program executable. CMAKE_CPACK_COMMAND:INTERNAL=/home/zn/.ide/clion/bin/cmake/bin/cpack //Path to ctest program executable. CMAKE_CTEST_COMMAND:INTERNAL=/home/zn/.ide/clion/bin/cmake/bin/ctest //ADVANCED property for variable: CMAKE_CXX_COMPILER CMAKE_CXX_COMPILER-ADVANCED:INTERNAL=1 //ADVANCED property for variable: CMAKE_CXX_COMPILER_AR CMAKE_CXX_COMPILER_AR-ADVANCED:INTERNAL=1 //ADVANCED property for variable: CMAKE_CXX_COMPILER_RANLIB CMAKE_CXX_COMPILER_RANLIB-ADVANCED:INTERNAL=1 //ADVANCED property for variable: CMAKE_CXX_FLAGS CMAKE_CXX_FLAGS-ADVANCED:INTERNAL=1 //ADVANCED property for variable: CMAKE_CXX_FLAGS_DEBUG CMAKE_CXX_FLAGS_DEBUG-ADVANCED:INTERNAL=1 //ADVANCED property for variable: CMAKE_CXX_FLAGS_MINSIZEREL CMAKE_CXX_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 //ADVANCED property for variable: CMAKE_CXX_FLAGS_RELEASE CMAKE_CXX_FLAGS_RELEASE-ADVANCED:INTERNAL=1 //ADVANCED property for variable: CMAKE_CXX_FLAGS_RELWITHDEBINFO CMAKE_CXX_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 //ADVANCED property for variable: CMAKE_C_COMPILER CMAKE_C_COMPILER-ADVANCED:INTERNAL=1 //ADVANCED property for variable: CMAKE_C_COMPILER_AR CMAKE_C_COMPILER_AR-ADVANCED:INTERNAL=1 //ADVANCED property for variable: CMAKE_C_COMPILER_RANLIB CMAKE_C_COMPILER_RANLIB-ADVANCED:INTERNAL=1 //ADVANCED property for variable: CMAKE_C_FLAGS CMAKE_C_FLAGS-ADVANCED:INTERNAL=1 //ADVANCED property for variable: CMAKE_C_FLAGS_DEBUG CMAKE_C_FLAGS_DEBUG-ADVANCED:INTERNAL=1 //ADVANCED property for variable: CMAKE_C_FLAGS_MINSIZEREL CMAKE_C_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 //ADVANCED property for variable: CMAKE_C_FLAGS_RELEASE CMAKE_C_FLAGS_RELEASE-ADVANCED:INTERNAL=1 //ADVANCED property for variable: CMAKE_C_FLAGS_RELWITHDEBINFO CMAKE_C_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 //Executable file format CMAKE_EXECUTABLE_FORMAT:INTERNAL=ELF //ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS CMAKE_EXE_LINKER_FLAGS-ADVANCED:INTERNAL=1 //ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_DEBUG CMAKE_EXE_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1 //ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_MINSIZEREL CMAKE_EXE_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 //ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_RELEASE CMAKE_EXE_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1 //ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_RELWITHDEBINFO CMAKE_EXE_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 //ADVANCED property for variable: CMAKE_EXPORT_COMPILE_COMMANDS CMAKE_EXPORT_COMPILE_COMMANDS-ADVANCED:INTERNAL=1 //Name of external makefile project generator. CMAKE_EXTRA_GENERATOR:INTERNAL=CodeBlocks //CXX compiler system defined macros CMAKE_EXTRA_GENERATOR_CXX_SYSTEM_DEFINED_MACROS:INTERNAL=__STDC__;1;__STDC_VERSION__;201112L;__STDC_UTF_16__;1;__STDC_UTF_32__;1;__STDC_HOSTED__;1;__GNUC__;5;__GNUC_MINOR__;4;__GNUC_PATCHLEVEL__; ;__VERSION__;"5.4.0 20160609";__ATOMIC_RELAXED; ;__ATOMIC_SEQ_CST;5;__ATOMIC_ACQUIRE;2;__ATOMIC_RELEASE;3;__ATOMIC_ACQ_REL;4;__ATOMIC_CONSUME;1;__FINITE_MATH_ONLY__; ;_LP64;1;__LP64__;1;__SIZEOF_INT__;4;__SIZEOF_LONG__;8;__SIZEOF_LONG_LONG__;8;__SIZEOF_SHORT__;2;__SIZEOF_FLOAT__;4;__SIZEOF_DOUBLE__;8;__SIZEOF_LONG_DOUBLE__;16;__SIZEOF_SIZE_T__;8;__CHAR_BIT__;8;__BIGGEST_ALIGNMENT__;16;__ORDER_LITTLE_ENDIAN__;1234;__ORDER_BIG_ENDIAN__;4321;__ORDER_PDP_ENDIAN__;3412;__BYTE_ORDER__;__ORDER_LITTLE_ENDIAN__;__FLOAT_WORD_ORDER__;__ORDER_LITTLE_ENDIAN__;__SIZEOF_POINTER__;8;__SIZE_TYPE__;long unsigned int;__PTRDIFF_TYPE__;long int;__WCHAR_TYPE__;int;__WINT_TYPE__;unsigned int;__INTMAX_TYPE__;long int;__UINTMAX_TYPE__;long unsigned int;__CHAR16_TYPE__;short unsigned int;__CHAR32_TYPE__;unsigned int;__SIG_ATOMIC_TYPE__;int;__INT8_TYPE__;signed char;__INT16_TYPE__;short int;__INT32_TYPE__;int;__INT64_TYPE__;long int;__UINT8_TYPE__;unsigned char;__UINT16_TYPE__;short unsigned int;__UINT32_TYPE__;unsigned int;__UINT64_TYPE__;long unsigned int;__INT_LEAST8_TYPE__;signed char;__INT_LEAST16_TYPE__;short int;__INT_LEAST32_TYPE__;int;__INT_LEAST64_TYPE__;long int;__UINT_LEAST8_TYPE__;unsigned char;__UINT_LEAST16_TYPE__;short unsigned int;__UINT_LEAST32_TYPE__;unsigned int;__UINT_LEAST64_TYPE__;long unsigned int;__INT_FAST8_TYPE__;signed char;__INT_FAST16_TYPE__;long int;__INT_FAST32_TYPE__;long int;__INT_FAST64_TYPE__;long int;__UINT_FAST8_TYPE__;unsigned char;__UINT_FAST16_TYPE__;long unsigned int;__UINT_FAST32_TYPE__;long unsigned int;__UINT_FAST64_TYPE__;long unsigned int;__INTPTR_TYPE__;long int;__UINTPTR_TYPE__;long unsigned int;__has_include(STR);__has_include__(STR);__has_include_next(STR);__has_include_next__(STR);__GXX_ABI_VERSION;1009;__SCHAR_MAX__;0x7f;__SHRT_MAX__;0x7fff;__INT_MAX__;0x7fffffff;__LONG_MAX__;0x7fffffffffffffffL;__LONG_LONG_MAX__;0x7fffffffffffffffLL;__WCHAR_MAX__;0x7fffffff;__WCHAR_MIN__;(-__WCHAR_MAX__ - 1);__WINT_MAX__;0xffffffffU;__WINT_MIN__;0U;__PTRDIFF_MAX__;0x7fffffffffffffffL;__SIZE_MAX__;0xffffffffffffffffUL;__INTMAX_MAX__;0x7fffffffffffffffL;__INTMAX_C(c);c ## L;__UINTMAX_MAX__;0xffffffffffffffffUL;__UINTMAX_C(c);c ## UL;__SIG_ATOMIC_MAX__;0x7fffffff;__SIG_ATOMIC_MIN__;(-__SIG_ATOMIC_MAX__ - 1);__INT8_MAX__;0x7f;__INT16_MAX__;0x7fff;__INT32_MAX__;0x7fffffff;__INT64_MAX__;0x7fffffffffffffffL;__UINT8_MAX__;0xff;__UINT16_MAX__;0xffff;__UINT32_MAX__;0xffffffffU;__UINT64_MAX__;0xffffffffffffffffUL;__INT_LEAST8_MAX__;0x7f;__INT8_C(c);c;__INT_LEAST16_MAX__;0x7fff;__INT16_C(c);c;__INT_LEAST32_MAX__;0x7fffffff;__INT32_C(c);c;__INT_LEAST64_MAX__;0x7fffffffffffffffL;__INT64_C(c);c ## L;__UINT_LEAST8_MAX__;0xff;__UINT8_C(c);c;__UINT_LEAST16_MAX__;0xffff;__UINT16_C(c);c;__UINT_LEAST32_MAX__;0xffffffffU;__UINT32_C(c);c ## U;__UINT_LEAST64_MAX__;0xffffffffffffffffUL;__UINT64_C(c);c ## UL;__INT_FAST8_MAX__;0x7f;__INT_FAST16_MAX__;0x7fffffffffffffffL;__INT_FAST32_MAX__;0x7fffffffffffffffL;__INT_FAST64_MAX__;0x7fffffffffffffffL;__UINT_FAST8_MAX__;0xff;__UINT_FAST16_MAX__;0xffffffffffffffffUL;__UINT_FAST32_MAX__;0xffffffffffffffffUL;__UINT_FAST64_MAX__;0xffffffffffffffffUL;__INTPTR_MAX__;0x7fffffffffffffffL;__UINTPTR_MAX__;0xffffffffffffffffUL;__GCC_IEC_559;2;__GCC_IEC_559_COMPLEX;2;__FLT_EVAL_METHOD__; ;__DEC_EVAL_METHOD__;2;__FLT_RADIX__;2;__FLT_MANT_DIG__;24;__FLT_DIG__;6;__FLT_MIN_EXP__;(-125);__FLT_MIN_10_EXP__;(-37);__FLT_MAX_EXP__;128;__FLT_MAX_10_EXP__;38;__FLT_DECIMAL_DIG__;9;__FLT_MAX__;3.40282346638528859812e+38F;__FLT_MIN__;1.17549435082228750797e-38F;__FLT_EPSILON__;1.19209289550781250000e-7F;__FLT_DENORM_MIN__;1.40129846432481707092e-45F;__FLT_HAS_DENORM__;1;__FLT_HAS_INFINITY__;1;__FLT_HAS_QUIET_NAN__;1;__DBL_MANT_DIG__;53;__DBL_DIG__;15;__DBL_MIN_EXP__;(-1021);__DBL_MIN_10_EXP__;(-307);__DBL_MAX_EXP__;1024;__DBL_MAX_10_EXP__;308;__DBL_DECIMAL_DIG__;17;__DBL_MAX__;((double)1.79769313486231570815e+308L);__DBL_MIN__;((double)2.22507385850720138309e-308L);__DBL_EPSILON__;((double)2.22044604925031308085e-16L);__DBL_DENORM_MIN__;((double)4.94065645841246544177e-324L);__DBL_HAS_DENORM__;1;__DBL_HAS_INFINITY__;1;__DBL_HAS_QUIET_NAN__;1;__LDBL_MANT_DIG__;64;__LDBL_DIG__;18;__LDBL_MIN_EXP__;(-16381);__LDBL_MIN_10_EXP__;(-4931);__LDBL_MAX_EXP__;16384;__LDBL_MAX_10_EXP__;4932;__DECIMAL_DIG__;21;__LDBL_MAX__;1.18973149535723176502e+4932L;__LDBL_MIN__;3.36210314311209350626e-4932L;__LDBL_EPSILON__;1.08420217248550443401e-19L;__LDBL_DENORM_MIN__;3.64519953188247460253e-4951L;__LDBL_HAS_DENORM__;1;__LDBL_HAS_INFINITY__;1;__LDBL_HAS_QUIET_NAN__;1;__DEC32_MANT_DIG__;7;__DEC32_MIN_EXP__;(-94);__DEC32_MAX_EXP__;97;__DEC32_MIN__;1E-95DF;__DEC32_MAX__;9.999999E96DF;__DEC32_EPSILON__;1E-6DF;__DEC32_SUBNORMAL_MIN__;0.000001E-95DF;__DEC64_MANT_DIG__;16;__DEC64_MIN_EXP__;(-382);__DEC64_MAX_EXP__;385;__DEC64_MIN__;1E-383DD;__DEC64_MAX__;9.999999999999999E384DD;__DEC64_EPSILON__;1E-15DD;__DEC64_SUBNORMAL_MIN__;0.000000000000001E-383DD;__DEC128_MANT_DIG__;34;__DEC128_MIN_EXP__;(-6142);__DEC128_MAX_EXP__;6145;__DEC128_MIN__;1E-6143DL;__DEC128_MAX__;9.999999999999999999999999999999999E6144DL;__DEC128_EPSILON__;1E-33DL;__DEC128_SUBNORMAL_MIN__;0.000000000000000000000000000000001E-6143DL;__REGISTER_PREFIX__; ;__USER_LABEL_PREFIX__; ;__GNUC_STDC_INLINE__;1;__NO_INLINE__;1;__GCC_HAVE_SYNC_COMPARE_AND_SWAP_1;1;__GCC_HAVE_SYNC_COMPARE_AND_SWAP_2;1;__GCC_HAVE_SYNC_COMPARE_AND_SWAP_4;1;__GCC_HAVE_SYNC_COMPARE_AND_SWAP_8;1;__GCC_ATOMIC_BOOL_LOCK_FREE;2;__GCC_ATOMIC_CHAR_LOCK_FREE;2;__GCC_ATOMIC_CHAR16_T_LOCK_FREE;2;__GCC_ATOMIC_CHAR32_T_LOCK_FREE;2;__GCC_ATOMIC_WCHAR_T_LOCK_FREE;2;__GCC_ATOMIC_SHORT_LOCK_FREE;2;__GCC_ATOMIC_INT_LOCK_FREE;2;__GCC_ATOMIC_LONG_LOCK_FREE;2;__GCC_ATOMIC_LLONG_LOCK_FREE;2;__GCC_ATOMIC_TEST_AND_SET_TRUEVAL;1;__GCC_ATOMIC_POINTER_LOCK_FREE;2;__GCC_HAVE_DWARF2_CFI_ASM;1;__PRAGMA_REDEFINE_EXTNAME;1;__SSP_STRONG__;3;__SIZEOF_INT128__;16;__SIZEOF_WCHAR_T__;4;__SIZEOF_WINT_T__;4;__SIZEOF_PTRDIFF_T__;8;__amd64;1;__amd64__;1;__x86_64;1;__x86_64__;1;__SIZEOF_FLOAT80__;16;__SIZEOF_FLOAT128__;16;__ATOMIC_HLE_ACQUIRE;65536;__ATOMIC_HLE_RELEASE;131072;__k8;1;__k8__;1;__code_model_small__;1;__MMX__;1;__SSE__;1;__SSE2__;1;__FXSR__;1;__SSE_MATH__;1;__SSE2_MATH__;1;__gnu_linux__;1;__linux;1;__linux__;1;linux;1;__unix;1;__unix__;1;unix;1;__ELF__;1;__DECIMAL_BID_FORMAT__;1;_STDC_PREDEF_H;1;__STDC_IEC_559__;1;__STDC_IEC_559_COMPLEX__;1;__STDC_ISO_10646__;201505L;__STDC_NO_THREADS__;1;__STDC__;1;__cplusplus;199711L;__STDC_HOSTED__;1;__GNUC__;5;__GNUC_MINOR__;4;__GNUC_PATCHLEVEL__; ;__VERSION__;"5.4.0 20160609";__ATOMIC_RELAXED; ;__ATOMIC_SEQ_CST;5;__ATOMIC_ACQUIRE;2;__ATOMIC_RELEASE;3;__ATOMIC_ACQ_REL;4;__ATOMIC_CONSUME;1;__FINITE_MATH_ONLY__; ;_LP64;1;__LP64__;1;__SIZEOF_INT__;4;__SIZEOF_LONG__;8;__SIZEOF_LONG_LONG__;8;__SIZEOF_SHORT__;2;__SIZEOF_FLOAT__;4;__SIZEOF_DOUBLE__;8;__SIZEOF_LONG_DOUBLE__;16;__SIZEOF_SIZE_T__;8;__CHAR_BIT__;8;__BIGGEST_ALIGNMENT__;16;__ORDER_LITTLE_ENDIAN__;1234;__ORDER_BIG_ENDIAN__;4321;__ORDER_PDP_ENDIAN__;3412;__BYTE_ORDER__;__ORDER_LITTLE_ENDIAN__;__FLOAT_WORD_ORDER__;__ORDER_LITTLE_ENDIAN__;__SIZEOF_POINTER__;8;__GNUG__;5;__SIZE_TYPE__;long unsigned int;__PTRDIFF_TYPE__;long int;__WCHAR_TYPE__;int;__WINT_TYPE__;unsigned int;__INTMAX_TYPE__;long int;__UINTMAX_TYPE__;long unsigned int;__CHAR16_TYPE__;short unsigned int;__CHAR32_TYPE__;unsigned int;__SIG_ATOMIC_TYPE__;int;__INT8_TYPE__;signed char;__INT16_TYPE__;short int;__INT32_TYPE__;int;__INT64_TYPE__;long int;__UINT8_TYPE__;unsigned char;__UINT16_TYPE__;short unsigned int;__UINT32_TYPE__;unsigned int;__UINT64_TYPE__;long unsigned int;__INT_LEAST8_TYPE__;signed char;__INT_LEAST16_TYPE__;short int;__INT_LEAST32_TYPE__;int;__INT_LEAST64_TYPE__;long int;__UINT_LEAST8_TYPE__;unsigned char;__UINT_LEAST16_TYPE__;short unsigned int;__UINT_LEAST32_TYPE__;unsigned int;__UINT_LEAST64_TYPE__;long unsigned int;__INT_FAST8_TYPE__;signed char;__INT_FAST16_TYPE__;long int;__INT_FAST32_TYPE__;long int;__INT_FAST64_TYPE__;long int;__UINT_FAST8_TYPE__;unsigned char;__UINT_FAST16_TYPE__;long unsigned int;__UINT_FAST32_TYPE__;long unsigned int;__UINT_FAST64_TYPE__;long unsigned int;__INTPTR_TYPE__;long int;__UINTPTR_TYPE__;long unsigned int;__has_include(STR);__has_include__(STR);__has_include_next(STR);__has_include_next__(STR);__GXX_WEAK__;1;__DEPRECATED;1;__GXX_RTTI;1;__cpp_rtti;199711;__cpp_binary_literals;201304;__cpp_runtime_arrays;198712;__EXCEPTIONS;1;__cpp_exceptions;199711;__GXX_ABI_VERSION;1009;__SCHAR_MAX__;0x7f;__SHRT_MAX__;0x7fff;__INT_MAX__;0x7fffffff;__LONG_MAX__;0x7fffffffffffffffL;__LONG_LONG_MAX__;0x7fffffffffffffffLL;__WCHAR_MAX__;0x7fffffff;__WCHAR_MIN__;(-__WCHAR_MAX__ - 1);__WINT_MAX__;0xffffffffU;__WINT_MIN__;0U;__PTRDIFF_MAX__;0x7fffffffffffffffL;__SIZE_MAX__;0xffffffffffffffffUL;__GLIBCXX_TYPE_INT_N_0;__int128;__GLIBCXX_BITSIZE_INT_N_0;128;__INTMAX_MAX__;0x7fffffffffffffffL;__INTMAX_C(c);c ## L;__UINTMAX_MAX__;0xffffffffffffffffUL;__UINTMAX_C(c);c ## UL;__SIG_ATOMIC_MAX__;0x7fffffff;__SIG_ATOMIC_MIN__;(-__SIG_ATOMIC_MAX__ - 1);__INT8_MAX__;0x7f;__INT16_MAX__;0x7fff;__INT32_MAX__;0x7fffffff;__INT64_MAX__;0x7fffffffffffffffL;__UINT8_MAX__;0xff;__UINT16_MAX__;0xffff;__UINT32_MAX__;0xffffffffU;__UINT64_MAX__;0xffffffffffffffffUL;__INT_LEAST8_MAX__;0x7f;__INT8_C(c);c;__INT_LEAST16_MAX__;0x7fff;__INT16_C(c);c;__INT_LEAST32_MAX__;0x7fffffff;__INT32_C(c);c;__INT_LEAST64_MAX__;0x7fffffffffffffffL;__INT64_C(c);c ## L;__UINT_LEAST8_MAX__;0xff;__UINT8_C(c);c;__UINT_LEAST16_MAX__;0xffff;__UINT16_C(c);c;__UINT_LEAST32_MAX__;0xffffffffU;__UINT32_C(c);c ## U;__UINT_LEAST64_MAX__;0xffffffffffffffffUL;__UINT64_C(c);c ## UL;__INT_FAST8_MAX__;0x7f;__INT_FAST16_MAX__;0x7fffffffffffffffL;__INT_FAST32_MAX__;0x7fffffffffffffffL;__INT_FAST64_MAX__;0x7fffffffffffffffL;__UINT_FAST8_MAX__;0xff;__UINT_FAST16_MAX__;0xffffffffffffffffUL;__UINT_FAST32_MAX__;0xffffffffffffffffUL;__UINT_FAST64_MAX__;0xffffffffffffffffUL;__INTPTR_MAX__;0x7fffffffffffffffL;__UINTPTR_MAX__;0xffffffffffffffffUL;__GCC_IEC_559;2;__GCC_IEC_559_COMPLEX;2;__FLT_EVAL_METHOD__; ;__DEC_EVAL_METHOD__;2;__FLT_RADIX__;2;__FLT_MANT_DIG__;24;__FLT_DIG__;6;__FLT_MIN_EXP__;(-125);__FLT_MIN_10_EXP__;(-37);__FLT_MAX_EXP__;128;__FLT_MAX_10_EXP__;38;__FLT_DECIMAL_DIG__;9;__FLT_MAX__;3.40282346638528859812e+38F;__FLT_MIN__;1.17549435082228750797e-38F;__FLT_EPSILON__;1.19209289550781250000e-7F;__FLT_DENORM_MIN__;1.40129846432481707092e-45F;__FLT_HAS_DENORM__;1;__FLT_HAS_INFINITY__;1;__FLT_HAS_QUIET_NAN__;1;__DBL_MANT_DIG__;53;__DBL_DIG__;15;__DBL_MIN_EXP__;(-1021);__DBL_MIN_10_EXP__;(-307);__DBL_MAX_EXP__;1024;__DBL_MAX_10_EXP__;308;__DBL_DECIMAL_DIG__;17;__DBL_MAX__;double(1.79769313486231570815e+308L);__DBL_MIN__;double(2.22507385850720138309e-308L);__DBL_EPSILON__;double(2.22044604925031308085e-16L);__DBL_DENORM_MIN__;double(4.94065645841246544177e-324L);__DBL_HAS_DENORM__;1;__DBL_HAS_INFINITY__;1;__DBL_HAS_QUIET_NAN__;1;__LDBL_MANT_DIG__;64;__LDBL_DIG__;18;__LDBL_MIN_EXP__;(-16381);__LDBL_MIN_10_EXP__;(-4931);__LDBL_MAX_EXP__;16384;__LDBL_MAX_10_EXP__;4932;__DECIMAL_DIG__;21;__LDBL_MAX__;1.18973149535723176502e+4932L;__LDBL_MIN__;3.36210314311209350626e-4932L;__LDBL_EPSILON__;1.08420217248550443401e-19L;__LDBL_DENORM_MIN__;3.64519953188247460253e-4951L;__LDBL_HAS_DENORM__;1;__LDBL_HAS_INFINITY__;1;__LDBL_HAS_QUIET_NAN__;1;__DEC32_MANT_DIG__;7;__DEC32_MIN_EXP__;(-94);__DEC32_MAX_EXP__;97;__DEC32_MIN__;1E-95DF;__DEC32_MAX__;9.999999E96DF;__DEC32_EPSILON__;1E-6DF;__DEC32_SUBNORMAL_MIN__;0.000001E-95DF;__DEC64_MANT_DIG__;16;__DEC64_MIN_EXP__;(-382);__DEC64_MAX_EXP__;385;__DEC64_MIN__;1E-383DD;__DEC64_MAX__;9.999999999999999E384DD;__DEC64_EPSILON__;1E-15DD;__DEC64_SUBNORMAL_MIN__;0.000000000000001E-383DD;__DEC128_MANT_DIG__;34;__DEC128_MIN_EXP__;(-6142);__DEC128_MAX_EXP__;6145;__DEC128_MIN__;1E-6143DL;__DEC128_MAX__;9.999999999999999999999999999999999E6144DL;__DEC128_EPSILON__;1E-33DL;__DEC128_SUBNORMAL_MIN__;0.000000000000000000000000000000001E-6143DL;__REGISTER_PREFIX__; ;__USER_LABEL_PREFIX__; ;__GNUC_GNU_INLINE__;1;__NO_INLINE__;1;__GCC_HAVE_SYNC_COMPARE_AND_SWAP_1;1;__GCC_HAVE_SYNC_COMPARE_AND_SWAP_2;1;__GCC_HAVE_SYNC_COMPARE_AND_SWAP_4;1;__GCC_HAVE_SYNC_COMPARE_AND_SWAP_8;1;__GCC_ATOMIC_BOOL_LOCK_FREE;2;__GCC_ATOMIC_CHAR_LOCK_FREE;2;__GCC_ATOMIC_CHAR16_T_LOCK_FREE;2;__GCC_ATOMIC_CHAR32_T_LOCK_FREE;2;__GCC_ATOMIC_WCHAR_T_LOCK_FREE;2;__GCC_ATOMIC_SHORT_LOCK_FREE;2;__GCC_ATOMIC_INT_LOCK_FREE;2;__GCC_ATOMIC_LONG_LOCK_FREE;2;__GCC_ATOMIC_LLONG_LOCK_FREE;2;__GCC_ATOMIC_TEST_AND_SET_TRUEVAL;1;__GCC_ATOMIC_POINTER_LOCK_FREE;2;__GCC_HAVE_DWARF2_CFI_ASM;1;__PRAGMA_REDEFINE_EXTNAME;1;__SSP_STRONG__;3;__SIZEOF_INT128__;16;__SIZEOF_WCHAR_T__;4;__SIZEOF_WINT_T__;4;__SIZEOF_PTRDIFF_T__;8;__amd64;1;__amd64__;1;__x86_64;1;__x86_64__;1;__SIZEOF_FLOAT80__;16;__SIZEOF_FLOAT128__;16;__ATOMIC_HLE_ACQUIRE;65536;__ATOMIC_HLE_RELEASE;131072;__k8;1;__k8__;1;__code_model_small__;1;__MMX__;1;__SSE__;1;__SSE2__;1;__FXSR__;1;__SSE_MATH__;1;__SSE2_MATH__;1;__gnu_linux__;1;__linux;1;__linux__;1;linux;1;__unix;1;__unix__;1;unix;1;__ELF__;1;__DECIMAL_BID_FORMAT__;1;_GNU_SOURCE;1;_STDC_PREDEF_H;1;__STDC_IEC_559__;1;__STDC_IEC_559_COMPLEX__;1;__STDC_ISO_10646__;201505L;__STDC_NO_THREADS__;1 //CXX compiler system include directories CMAKE_EXTRA_GENERATOR_CXX_SYSTEM_INCLUDE_DIRS:INTERNAL=/usr/include/c++/5;/usr/include/x86_64-linux-gnu/c++/5;/usr/include/c++/5/backward;/usr/lib/gcc/x86_64-linux-gnu/5/include;/usr/local/include;/usr/lib/gcc/x86_64-linux-gnu/5/include-fixed;/usr/include/x86_64-linux-gnu;/usr/include //C compiler system defined macros CMAKE_EXTRA_GENERATOR_C_SYSTEM_DEFINED_MACROS:INTERNAL=__STDC__;1;__STDC_VERSION__;201112L;__STDC_UTF_16__;1;__STDC_UTF_32__;1;__STDC_HOSTED__;1;__GNUC__;5;__GNUC_MINOR__;4;__GNUC_PATCHLEVEL__; ;__VERSION__;"5.4.0 20160609";__ATOMIC_RELAXED; ;__ATOMIC_SEQ_CST;5;__ATOMIC_ACQUIRE;2;__ATOMIC_RELEASE;3;__ATOMIC_ACQ_REL;4;__ATOMIC_CONSUME;1;__FINITE_MATH_ONLY__; ;_LP64;1;__LP64__;1;__SIZEOF_INT__;4;__SIZEOF_LONG__;8;__SIZEOF_LONG_LONG__;8;__SIZEOF_SHORT__;2;__SIZEOF_FLOAT__;4;__SIZEOF_DOUBLE__;8;__SIZEOF_LONG_DOUBLE__;16;__SIZEOF_SIZE_T__;8;__CHAR_BIT__;8;__BIGGEST_ALIGNMENT__;16;__ORDER_LITTLE_ENDIAN__;1234;__ORDER_BIG_ENDIAN__;4321;__ORDER_PDP_ENDIAN__;3412;__BYTE_ORDER__;__ORDER_LITTLE_ENDIAN__;__FLOAT_WORD_ORDER__;__ORDER_LITTLE_ENDIAN__;__SIZEOF_POINTER__;8;__SIZE_TYPE__;long unsigned int;__PTRDIFF_TYPE__;long int;__WCHAR_TYPE__;int;__WINT_TYPE__;unsigned int;__INTMAX_TYPE__;long int;__UINTMAX_TYPE__;long unsigned int;__CHAR16_TYPE__;short unsigned int;__CHAR32_TYPE__;unsigned int;__SIG_ATOMIC_TYPE__;int;__INT8_TYPE__;signed char;__INT16_TYPE__;short int;__INT32_TYPE__;int;__INT64_TYPE__;long int;__UINT8_TYPE__;unsigned char;__UINT16_TYPE__;short unsigned int;__UINT32_TYPE__;unsigned int;__UINT64_TYPE__;long unsigned int;__INT_LEAST8_TYPE__;signed char;__INT_LEAST16_TYPE__;short int;__INT_LEAST32_TYPE__;int;__INT_LEAST64_TYPE__;long int;__UINT_LEAST8_TYPE__;unsigned char;__UINT_LEAST16_TYPE__;short unsigned int;__UINT_LEAST32_TYPE__;unsigned int;__UINT_LEAST64_TYPE__;long unsigned int;__INT_FAST8_TYPE__;signed char;__INT_FAST16_TYPE__;long int;__INT_FAST32_TYPE__;long int;__INT_FAST64_TYPE__;long int;__UINT_FAST8_TYPE__;unsigned char;__UINT_FAST16_TYPE__;long unsigned int;__UINT_FAST32_TYPE__;long unsigned int;__UINT_FAST64_TYPE__;long unsigned int;__INTPTR_TYPE__;long int;__UINTPTR_TYPE__;long unsigned int;__has_include(STR);__has_include__(STR);__has_include_next(STR);__has_include_next__(STR);__GXX_ABI_VERSION;1009;__SCHAR_MAX__;0x7f;__SHRT_MAX__;0x7fff;__INT_MAX__;0x7fffffff;__LONG_MAX__;0x7fffffffffffffffL;__LONG_LONG_MAX__;0x7fffffffffffffffLL;__WCHAR_MAX__;0x7fffffff;__WCHAR_MIN__;(-__WCHAR_MAX__ - 1);__WINT_MAX__;0xffffffffU;__WINT_MIN__;0U;__PTRDIFF_MAX__;0x7fffffffffffffffL;__SIZE_MAX__;0xffffffffffffffffUL;__INTMAX_MAX__;0x7fffffffffffffffL;__INTMAX_C(c);c ## L;__UINTMAX_MAX__;0xffffffffffffffffUL;__UINTMAX_C(c);c ## UL;__SIG_ATOMIC_MAX__;0x7fffffff;__SIG_ATOMIC_MIN__;(-__SIG_ATOMIC_MAX__ - 1);__INT8_MAX__;0x7f;__INT16_MAX__;0x7fff;__INT32_MAX__;0x7fffffff;__INT64_MAX__;0x7fffffffffffffffL;__UINT8_MAX__;0xff;__UINT16_MAX__;0xffff;__UINT32_MAX__;0xffffffffU;__UINT64_MAX__;0xffffffffffffffffUL;__INT_LEAST8_MAX__;0x7f;__INT8_C(c);c;__INT_LEAST16_MAX__;0x7fff;__INT16_C(c);c;__INT_LEAST32_MAX__;0x7fffffff;__INT32_C(c);c;__INT_LEAST64_MAX__;0x7fffffffffffffffL;__INT64_C(c);c ## L;__UINT_LEAST8_MAX__;0xff;__UINT8_C(c);c;__UINT_LEAST16_MAX__;0xffff;__UINT16_C(c);c;__UINT_LEAST32_MAX__;0xffffffffU;__UINT32_C(c);c ## U;__UINT_LEAST64_MAX__;0xffffffffffffffffUL;__UINT64_C(c);c ## UL;__INT_FAST8_MAX__;0x7f;__INT_FAST16_MAX__;0x7fffffffffffffffL;__INT_FAST32_MAX__;0x7fffffffffffffffL;__INT_FAST64_MAX__;0x7fffffffffffffffL;__UINT_FAST8_MAX__;0xff;__UINT_FAST16_MAX__;0xffffffffffffffffUL;__UINT_FAST32_MAX__;0xffffffffffffffffUL;__UINT_FAST64_MAX__;0xffffffffffffffffUL;__INTPTR_MAX__;0x7fffffffffffffffL;__UINTPTR_MAX__;0xffffffffffffffffUL;__GCC_IEC_559;2;__GCC_IEC_559_COMPLEX;2;__FLT_EVAL_METHOD__; ;__DEC_EVAL_METHOD__;2;__FLT_RADIX__;2;__FLT_MANT_DIG__;24;__FLT_DIG__;6;__FLT_MIN_EXP__;(-125);__FLT_MIN_10_EXP__;(-37);__FLT_MAX_EXP__;128;__FLT_MAX_10_EXP__;38;__FLT_DECIMAL_DIG__;9;__FLT_MAX__;3.40282346638528859812e+38F;__FLT_MIN__;1.17549435082228750797e-38F;__FLT_EPSILON__;1.19209289550781250000e-7F;__FLT_DENORM_MIN__;1.40129846432481707092e-45F;__FLT_HAS_DENORM__;1;__FLT_HAS_INFINITY__;1;__FLT_HAS_QUIET_NAN__;1;__DBL_MANT_DIG__;53;__DBL_DIG__;15;__DBL_MIN_EXP__;(-1021);__DBL_MIN_10_EXP__;(-307);__DBL_MAX_EXP__;1024;__DBL_MAX_10_EXP__;308;__DBL_DECIMAL_DIG__;17;__DBL_MAX__;((double)1.79769313486231570815e+308L);__DBL_MIN__;((double)2.22507385850720138309e-308L);__DBL_EPSILON__;((double)2.22044604925031308085e-16L);__DBL_DENORM_MIN__;((double)4.94065645841246544177e-324L);__DBL_HAS_DENORM__;1;__DBL_HAS_INFINITY__;1;__DBL_HAS_QUIET_NAN__;1;__LDBL_MANT_DIG__;64;__LDBL_DIG__;18;__LDBL_MIN_EXP__;(-16381);__LDBL_MIN_10_EXP__;(-4931);__LDBL_MAX_EXP__;16384;__LDBL_MAX_10_EXP__;4932;__DECIMAL_DIG__;21;__LDBL_MAX__;1.18973149535723176502e+4932L;__LDBL_MIN__;3.36210314311209350626e-4932L;__LDBL_EPSILON__;1.08420217248550443401e-19L;__LDBL_DENORM_MIN__;3.64519953188247460253e-4951L;__LDBL_HAS_DENORM__;1;__LDBL_HAS_INFINITY__;1;__LDBL_HAS_QUIET_NAN__;1;__DEC32_MANT_DIG__;7;__DEC32_MIN_EXP__;(-94);__DEC32_MAX_EXP__;97;__DEC32_MIN__;1E-95DF;__DEC32_MAX__;9.999999E96DF;__DEC32_EPSILON__;1E-6DF;__DEC32_SUBNORMAL_MIN__;0.000001E-95DF;__DEC64_MANT_DIG__;16;__DEC64_MIN_EXP__;(-382);__DEC64_MAX_EXP__;385;__DEC64_MIN__;1E-383DD;__DEC64_MAX__;9.999999999999999E384DD;__DEC64_EPSILON__;1E-15DD;__DEC64_SUBNORMAL_MIN__;0.000000000000001E-383DD;__DEC128_MANT_DIG__;34;__DEC128_MIN_EXP__;(-6142);__DEC128_MAX_EXP__;6145;__DEC128_MIN__;1E-6143DL;__DEC128_MAX__;9.999999999999999999999999999999999E6144DL;__DEC128_EPSILON__;1E-33DL;__DEC128_SUBNORMAL_MIN__;0.000000000000000000000000000000001E-6143DL;__REGISTER_PREFIX__; ;__USER_LABEL_PREFIX__; ;__GNUC_STDC_INLINE__;1;__NO_INLINE__;1;__GCC_HAVE_SYNC_COMPARE_AND_SWAP_1;1;__GCC_HAVE_SYNC_COMPARE_AND_SWAP_2;1;__GCC_HAVE_SYNC_COMPARE_AND_SWAP_4;1;__GCC_HAVE_SYNC_COMPARE_AND_SWAP_8;1;__GCC_ATOMIC_BOOL_LOCK_FREE;2;__GCC_ATOMIC_CHAR_LOCK_FREE;2;__GCC_ATOMIC_CHAR16_T_LOCK_FREE;2;__GCC_ATOMIC_CHAR32_T_LOCK_FREE;2;__GCC_ATOMIC_WCHAR_T_LOCK_FREE;2;__GCC_ATOMIC_SHORT_LOCK_FREE;2;__GCC_ATOMIC_INT_LOCK_FREE;2;__GCC_ATOMIC_LONG_LOCK_FREE;2;__GCC_ATOMIC_LLONG_LOCK_FREE;2;__GCC_ATOMIC_TEST_AND_SET_TRUEVAL;1;__GCC_ATOMIC_POINTER_LOCK_FREE;2;__GCC_HAVE_DWARF2_CFI_ASM;1;__PRAGMA_REDEFINE_EXTNAME;1;__SSP_STRONG__;3;__SIZEOF_INT128__;16;__SIZEOF_WCHAR_T__;4;__SIZEOF_WINT_T__;4;__SIZEOF_PTRDIFF_T__;8;__amd64;1;__amd64__;1;__x86_64;1;__x86_64__;1;__SIZEOF_FLOAT80__;16;__SIZEOF_FLOAT128__;16;__ATOMIC_HLE_ACQUIRE;65536;__ATOMIC_HLE_RELEASE;131072;__k8;1;__k8__;1;__code_model_small__;1;__MMX__;1;__SSE__;1;__SSE2__;1;__FXSR__;1;__SSE_MATH__;1;__SSE2_MATH__;1;__gnu_linux__;1;__linux;1;__linux__;1;linux;1;__unix;1;__unix__;1;unix;1;__ELF__;1;__DECIMAL_BID_FORMAT__;1;_STDC_PREDEF_H;1;__STDC_IEC_559__;1;__STDC_IEC_559_COMPLEX__;1;__STDC_ISO_10646__;201505L;__STDC_NO_THREADS__;1 //C compiler system include directories CMAKE_EXTRA_GENERATOR_C_SYSTEM_INCLUDE_DIRS:INTERNAL=/usr/lib/gcc/x86_64-linux-gnu/5/include;/usr/local/include;/usr/lib/gcc/x86_64-linux-gnu/5/include-fixed;/usr/include/x86_64-linux-gnu;/usr/include //Name of generator. CMAKE_GENERATOR:INTERNAL=Unix Makefiles //Name of generator platform. CMAKE_GENERATOR_PLATFORM:INTERNAL= //Name of generator toolset. CMAKE_GENERATOR_TOOLSET:INTERNAL= //Have symbol pthread_create CMAKE_HAVE_LIBC_CREATE:INTERNAL= //Have library pthreads CMAKE_HAVE_PTHREADS_CREATE:INTERNAL= //Have library pthread CMAKE_HAVE_PTHREAD_CREATE:INTERNAL=1 //Have include pthread.h CMAKE_HAVE_PTHREAD_H:INTERNAL=1 //Source directory with the top level CMakeLists.txt file for this // project CMAKE_HOME_DIRECTORY:INTERNAL=/home/zn/racecar/src/rf2o_laser_odometry //Install .so files without execute permission. CMAKE_INSTALL_SO_NO_EXE:INTERNAL=1 //ADVANCED property for variable: CMAKE_LINKER CMAKE_LINKER-ADVANCED:INTERNAL=1 //ADVANCED property for variable: CMAKE_MAKE_PROGRAM CMAKE_MAKE_PROGRAM-ADVANCED:INTERNAL=1 //ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS CMAKE_MODULE_LINKER_FLAGS-ADVANCED:INTERNAL=1 //ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_DEBUG CMAKE_MODULE_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1 //ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_MINSIZEREL CMAKE_MODULE_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 //ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_RELEASE CMAKE_MODULE_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1 //ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_RELWITHDEBINFO CMAKE_MODULE_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 //ADVANCED property for variable: CMAKE_NM CMAKE_NM-ADVANCED:INTERNAL=1 //number of local generators CMAKE_NUMBER_OF_MAKEFILES:INTERNAL=1 //ADVANCED property for variable: CMAKE_OBJCOPY CMAKE_OBJCOPY-ADVANCED:INTERNAL=1 //ADVANCED property for variable: CMAKE_OBJDUMP CMAKE_OBJDUMP-ADVANCED:INTERNAL=1 //Platform information initialized CMAKE_PLATFORM_INFO_INITIALIZED:INTERNAL=1 //ADVANCED property for variable: CMAKE_RANLIB CMAKE_RANLIB-ADVANCED:INTERNAL=1 //Path to CMake installation. CMAKE_ROOT:INTERNAL=/home/zn/.ide/clion/bin/cmake/share/cmake-3.9 //ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS CMAKE_SHARED_LINKER_FLAGS-ADVANCED:INTERNAL=1 //ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_DEBUG CMAKE_SHARED_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1 //ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_MINSIZEREL CMAKE_SHARED_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 //ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_RELEASE CMAKE_SHARED_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1 //ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_RELWITHDEBINFO CMAKE_SHARED_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 //ADVANCED property for variable: CMAKE_SKIP_INSTALL_RPATH CMAKE_SKIP_INSTALL_RPATH-ADVANCED:INTERNAL=1 //ADVANCED property for variable: CMAKE_SKIP_RPATH CMAKE_SKIP_RPATH-ADVANCED:INTERNAL=1 //ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS CMAKE_STATIC_LINKER_FLAGS-ADVANCED:INTERNAL=1 //ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_DEBUG CMAKE_STATIC_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1 //ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_MINSIZEREL CMAKE_STATIC_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 //ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_RELEASE CMAKE_STATIC_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1 //ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_RELWITHDEBINFO CMAKE_STATIC_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 //ADVANCED property for variable: CMAKE_STRIP CMAKE_STRIP-ADVANCED:INTERNAL=1 //uname command CMAKE_UNAME:INTERNAL=/bin/uname //ADVANCED property for variable: CMAKE_VERBOSE_MAKEFILE CMAKE_VERBOSE_MAKEFILE-ADVANCED:INTERNAL=1 //Details about finding PythonInterp FIND_PACKAGE_MESSAGE_DETAILS_PythonInterp:INTERNAL=[/usr/bin/python][v2.7.12()] GTEST_BOTH_LIBRARIES:INTERNAL=/usr/local/lib/libgtest.a;/usr/local/lib/libgtest_main.a GTEST_FOUND:INTERNAL=TRUE //ADVANCED property for variable: GTEST_INCLUDE_DIR GTEST_INCLUDE_DIR-ADVANCED:INTERNAL=1 GTEST_INCLUDE_DIRS:INTERNAL=/usr/local/include GTEST_LIBRARIES:INTERNAL=/usr/local/lib/libgtest.a //ADVANCED property for variable: GTEST_LIBRARY GTEST_LIBRARY-ADVANCED:INTERNAL=1 //ADVANCED property for variable: GTEST_LIBRARY_DEBUG GTEST_LIBRARY_DEBUG-ADVANCED:INTERNAL=1 GTEST_MAIN_LIBRARIES:INTERNAL=/usr/local/lib/libgtest_main.a //ADVANCED property for variable: GTEST_MAIN_LIBRARY GTEST_MAIN_LIBRARY-ADVANCED:INTERNAL=1 //ADVANCED property for variable: GTEST_MAIN_LIBRARY_DEBUG GTEST_MAIN_LIBRARY_DEBUG-ADVANCED:INTERNAL=1 //ADVANCED property for variable: PYTHON_EXECUTABLE PYTHON_EXECUTABLE-ADVANCED:INTERNAL=1 //This needs to be in PYTHONPATH when 'setup.py install' is called. // And it needs to match. But setuptools won't tell us where // it will install things. PYTHON_INSTALL_DIR:INTERNAL=lib/python2.7/dist-packages //ADVANCED property for variable: ProcessorCount_cmd_getconf ProcessorCount_cmd_getconf-ADVANCED:INTERNAL=1 //ADVANCED property for variable: ProcessorCount_cmd_sysctl ProcessorCount_cmd_sysctl-ADVANCED:INTERNAL=1 //Components requested for this build tree. _Boost_COMPONENTS_SEARCHED:INTERNAL=system //Last used Boost_INCLUDE_DIR value. _Boost_INCLUDE_DIR_LAST:INTERNAL=/usr/include //Last used Boost_LIBRARY_DIR_DEBUG value. _Boost_LIBRARY_DIR_DEBUG_LAST:INTERNAL=/usr/lib/x86_64-linux-gnu //Last used Boost_LIBRARY_DIR_RELEASE value. _Boost_LIBRARY_DIR_RELEASE_LAST:INTERNAL=/usr/lib/x86_64-linux-gnu //Last used Boost_NAMESPACE value. _Boost_NAMESPACE_LAST:INTERNAL=boost //Last used Boost_USE_MULTITHREADED value. _Boost_USE_MULTITHREADED_LAST:INTERNAL=TRUE ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/3.9.6/CMakeCCompiler.cmake ================================================ set(CMAKE_C_COMPILER "/usr/bin/cc") set(CMAKE_C_COMPILER_ARG1 "") set(CMAKE_C_COMPILER_ID "GNU") set(CMAKE_C_COMPILER_VERSION "5.4.0") set(CMAKE_C_COMPILER_WRAPPER "") set(CMAKE_C_STANDARD_COMPUTED_DEFAULT "11") set(CMAKE_C_COMPILE_FEATURES "c_std_90;c_function_prototypes;c_std_99;c_restrict;c_variadic_macros;c_std_11;c_static_assert") set(CMAKE_C90_COMPILE_FEATURES "c_std_90;c_function_prototypes") set(CMAKE_C99_COMPILE_FEATURES "c_std_99;c_restrict;c_variadic_macros") set(CMAKE_C11_COMPILE_FEATURES "c_std_11;c_static_assert") set(CMAKE_C_PLATFORM_ID "Linux") set(CMAKE_C_SIMULATE_ID "") set(CMAKE_C_SIMULATE_VERSION "") set(CMAKE_AR "/usr/bin/ar") set(CMAKE_C_COMPILER_AR "/usr/bin/gcc-ar-5") set(CMAKE_RANLIB "/usr/bin/ranlib") set(CMAKE_C_COMPILER_RANLIB "/usr/bin/gcc-ranlib-5") set(CMAKE_LINKER "/usr/bin/ld") set(CMAKE_COMPILER_IS_GNUCC 1) set(CMAKE_C_COMPILER_LOADED 1) set(CMAKE_C_COMPILER_WORKS TRUE) set(CMAKE_C_ABI_COMPILED TRUE) set(CMAKE_COMPILER_IS_MINGW ) set(CMAKE_COMPILER_IS_CYGWIN ) if(CMAKE_COMPILER_IS_CYGWIN) set(CYGWIN 1) set(UNIX 1) endif() set(CMAKE_C_COMPILER_ENV_VAR "CC") if(CMAKE_COMPILER_IS_MINGW) set(MINGW 1) endif() set(CMAKE_C_COMPILER_ID_RUN 1) set(CMAKE_C_SOURCE_FILE_EXTENSIONS c;m) set(CMAKE_C_IGNORE_EXTENSIONS h;H;o;O;obj;OBJ;def;DEF;rc;RC) set(CMAKE_C_LINKER_PREFERENCE 10) # Save compiler ABI information. set(CMAKE_C_SIZEOF_DATA_PTR "8") set(CMAKE_C_COMPILER_ABI "ELF") set(CMAKE_C_LIBRARY_ARCHITECTURE "x86_64-linux-gnu") if(CMAKE_C_SIZEOF_DATA_PTR) set(CMAKE_SIZEOF_VOID_P "${CMAKE_C_SIZEOF_DATA_PTR}") endif() if(CMAKE_C_COMPILER_ABI) set(CMAKE_INTERNAL_PLATFORM_ABI "${CMAKE_C_COMPILER_ABI}") endif() if(CMAKE_C_LIBRARY_ARCHITECTURE) set(CMAKE_LIBRARY_ARCHITECTURE "x86_64-linux-gnu") endif() set(CMAKE_C_CL_SHOWINCLUDES_PREFIX "") if(CMAKE_C_CL_SHOWINCLUDES_PREFIX) set(CMAKE_CL_SHOWINCLUDES_PREFIX "${CMAKE_C_CL_SHOWINCLUDES_PREFIX}") endif() set(CMAKE_C_IMPLICIT_LINK_LIBRARIES "gcc;gcc_s;c;gcc;gcc_s") set(CMAKE_C_IMPLICIT_LINK_DIRECTORIES "/usr/lib/gcc/x86_64-linux-gnu/5;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib") set(CMAKE_C_IMPLICIT_LINK_FRAMEWORK_DIRECTORIES "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/3.9.6/CMakeCXXCompiler.cmake ================================================ set(CMAKE_CXX_COMPILER "/usr/bin/c++") set(CMAKE_CXX_COMPILER_ARG1 "") set(CMAKE_CXX_COMPILER_ID "GNU") set(CMAKE_CXX_COMPILER_VERSION "5.4.0") set(CMAKE_CXX_COMPILER_WRAPPER "") set(CMAKE_CXX_STANDARD_COMPUTED_DEFAULT "98") set(CMAKE_CXX_COMPILE_FEATURES "cxx_std_98;cxx_template_template_parameters;cxx_std_11;cxx_alias_templates;cxx_alignas;cxx_alignof;cxx_attributes;cxx_auto_type;cxx_constexpr;cxx_decltype;cxx_decltype_incomplete_return_types;cxx_default_function_template_args;cxx_defaulted_functions;cxx_defaulted_move_initializers;cxx_delegating_constructors;cxx_deleted_functions;cxx_enum_forward_declarations;cxx_explicit_conversions;cxx_extended_friend_declarations;cxx_extern_templates;cxx_final;cxx_func_identifier;cxx_generalized_initializers;cxx_inheriting_constructors;cxx_inline_namespaces;cxx_lambdas;cxx_local_type_template_args;cxx_long_long_type;cxx_noexcept;cxx_nonstatic_member_init;cxx_nullptr;cxx_override;cxx_range_for;cxx_raw_string_literals;cxx_reference_qualified_functions;cxx_right_angle_brackets;cxx_rvalue_references;cxx_sizeof_member;cxx_static_assert;cxx_strong_enums;cxx_thread_local;cxx_trailing_return_types;cxx_unicode_literals;cxx_uniform_initialization;cxx_unrestricted_unions;cxx_user_literals;cxx_variadic_macros;cxx_variadic_templates;cxx_std_14;cxx_aggregate_default_initializers;cxx_attribute_deprecated;cxx_binary_literals;cxx_contextual_conversions;cxx_decltype_auto;cxx_digit_separators;cxx_generic_lambdas;cxx_lambda_init_captures;cxx_relaxed_constexpr;cxx_return_type_deduction;cxx_variable_templates;cxx_std_17") set(CMAKE_CXX98_COMPILE_FEATURES "cxx_std_98;cxx_template_template_parameters") set(CMAKE_CXX11_COMPILE_FEATURES "cxx_std_11;cxx_alias_templates;cxx_alignas;cxx_alignof;cxx_attributes;cxx_auto_type;cxx_constexpr;cxx_decltype;cxx_decltype_incomplete_return_types;cxx_default_function_template_args;cxx_defaulted_functions;cxx_defaulted_move_initializers;cxx_delegating_constructors;cxx_deleted_functions;cxx_enum_forward_declarations;cxx_explicit_conversions;cxx_extended_friend_declarations;cxx_extern_templates;cxx_final;cxx_func_identifier;cxx_generalized_initializers;cxx_inheriting_constructors;cxx_inline_namespaces;cxx_lambdas;cxx_local_type_template_args;cxx_long_long_type;cxx_noexcept;cxx_nonstatic_member_init;cxx_nullptr;cxx_override;cxx_range_for;cxx_raw_string_literals;cxx_reference_qualified_functions;cxx_right_angle_brackets;cxx_rvalue_references;cxx_sizeof_member;cxx_static_assert;cxx_strong_enums;cxx_thread_local;cxx_trailing_return_types;cxx_unicode_literals;cxx_uniform_initialization;cxx_unrestricted_unions;cxx_user_literals;cxx_variadic_macros;cxx_variadic_templates") set(CMAKE_CXX14_COMPILE_FEATURES "cxx_std_14;cxx_aggregate_default_initializers;cxx_attribute_deprecated;cxx_binary_literals;cxx_contextual_conversions;cxx_decltype_auto;cxx_digit_separators;cxx_generic_lambdas;cxx_lambda_init_captures;cxx_relaxed_constexpr;cxx_return_type_deduction;cxx_variable_templates") set(CMAKE_CXX17_COMPILE_FEATURES "cxx_std_17") set(CMAKE_CXX_PLATFORM_ID "Linux") set(CMAKE_CXX_SIMULATE_ID "") set(CMAKE_CXX_SIMULATE_VERSION "") set(CMAKE_AR "/usr/bin/ar") set(CMAKE_CXX_COMPILER_AR "/usr/bin/gcc-ar-5") set(CMAKE_RANLIB "/usr/bin/ranlib") set(CMAKE_CXX_COMPILER_RANLIB "/usr/bin/gcc-ranlib-5") set(CMAKE_LINKER "/usr/bin/ld") set(CMAKE_COMPILER_IS_GNUCXX 1) set(CMAKE_CXX_COMPILER_LOADED 1) set(CMAKE_CXX_COMPILER_WORKS TRUE) set(CMAKE_CXX_ABI_COMPILED TRUE) set(CMAKE_COMPILER_IS_MINGW ) set(CMAKE_COMPILER_IS_CYGWIN ) if(CMAKE_COMPILER_IS_CYGWIN) set(CYGWIN 1) set(UNIX 1) endif() set(CMAKE_CXX_COMPILER_ENV_VAR "CXX") if(CMAKE_COMPILER_IS_MINGW) set(MINGW 1) endif() set(CMAKE_CXX_COMPILER_ID_RUN 1) set(CMAKE_CXX_IGNORE_EXTENSIONS inl;h;hpp;HPP;H;o;O;obj;OBJ;def;DEF;rc;RC) set(CMAKE_CXX_SOURCE_FILE_EXTENSIONS C;M;c++;cc;cpp;cxx;mm;CPP) set(CMAKE_CXX_LINKER_PREFERENCE 30) set(CMAKE_CXX_LINKER_PREFERENCE_PROPAGATES 1) # Save compiler ABI information. set(CMAKE_CXX_SIZEOF_DATA_PTR "8") set(CMAKE_CXX_COMPILER_ABI "ELF") set(CMAKE_CXX_LIBRARY_ARCHITECTURE "x86_64-linux-gnu") if(CMAKE_CXX_SIZEOF_DATA_PTR) set(CMAKE_SIZEOF_VOID_P "${CMAKE_CXX_SIZEOF_DATA_PTR}") endif() if(CMAKE_CXX_COMPILER_ABI) set(CMAKE_INTERNAL_PLATFORM_ABI "${CMAKE_CXX_COMPILER_ABI}") endif() if(CMAKE_CXX_LIBRARY_ARCHITECTURE) set(CMAKE_LIBRARY_ARCHITECTURE "x86_64-linux-gnu") endif() set(CMAKE_CXX_CL_SHOWINCLUDES_PREFIX "") if(CMAKE_CXX_CL_SHOWINCLUDES_PREFIX) set(CMAKE_CL_SHOWINCLUDES_PREFIX "${CMAKE_CXX_CL_SHOWINCLUDES_PREFIX}") endif() set(CMAKE_CXX_IMPLICIT_LINK_LIBRARIES "stdc++;m;gcc_s;gcc;c;gcc_s;gcc") set(CMAKE_CXX_IMPLICIT_LINK_DIRECTORIES "/usr/lib/gcc/x86_64-linux-gnu/5;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib") set(CMAKE_CXX_IMPLICIT_LINK_FRAMEWORK_DIRECTORIES "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/3.9.6/CMakeSystem.cmake ================================================ set(CMAKE_HOST_SYSTEM "Linux-4.13.0-38-generic") set(CMAKE_HOST_SYSTEM_NAME "Linux") set(CMAKE_HOST_SYSTEM_VERSION "4.13.0-38-generic") set(CMAKE_HOST_SYSTEM_PROCESSOR "x86_64") set(CMAKE_SYSTEM "Linux-4.13.0-38-generic") set(CMAKE_SYSTEM_NAME "Linux") set(CMAKE_SYSTEM_VERSION "4.13.0-38-generic") set(CMAKE_SYSTEM_PROCESSOR "x86_64") set(CMAKE_CROSSCOMPILING "FALSE") set(CMAKE_SYSTEM_LOADED 1) ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/3.9.6/CompilerIdC/CMakeCCompilerId.c ================================================ #ifdef __cplusplus # error "A C++ compiler has been selected for C." #endif #if defined(__18CXX) # define ID_VOID_MAIN #endif #if defined(__CLASSIC_C__) /* cv-qualifiers did not exist in K&R C */ # define const # define volatile #endif /* Version number components: V=Version, R=Revision, P=Patch Version date components: YYYY=Year, MM=Month, DD=Day */ #if defined(__INTEL_COMPILER) || defined(__ICC) # define COMPILER_ID "Intel" # if defined(_MSC_VER) # define SIMULATE_ID "MSVC" # endif /* __INTEL_COMPILER = VRP */ # define COMPILER_VERSION_MAJOR DEC(__INTEL_COMPILER/100) # define COMPILER_VERSION_MINOR DEC(__INTEL_COMPILER/10 % 10) # if defined(__INTEL_COMPILER_UPDATE) # define COMPILER_VERSION_PATCH DEC(__INTEL_COMPILER_UPDATE) # else # define COMPILER_VERSION_PATCH DEC(__INTEL_COMPILER % 10) # endif # if defined(__INTEL_COMPILER_BUILD_DATE) /* __INTEL_COMPILER_BUILD_DATE = YYYYMMDD */ # define COMPILER_VERSION_TWEAK DEC(__INTEL_COMPILER_BUILD_DATE) # endif # if defined(_MSC_VER) /* _MSC_VER = VVRR */ # define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100) # define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100) # endif #elif defined(__PATHCC__) # define COMPILER_ID "PathScale" # define COMPILER_VERSION_MAJOR DEC(__PATHCC__) # define COMPILER_VERSION_MINOR DEC(__PATHCC_MINOR__) # if defined(__PATHCC_PATCHLEVEL__) # define COMPILER_VERSION_PATCH DEC(__PATHCC_PATCHLEVEL__) # endif #elif defined(__BORLANDC__) && defined(__CODEGEARC_VERSION__) # define COMPILER_ID "Embarcadero" # define COMPILER_VERSION_MAJOR HEX(__CODEGEARC_VERSION__>>24 & 0x00FF) # define COMPILER_VERSION_MINOR HEX(__CODEGEARC_VERSION__>>16 & 0x00FF) # define COMPILER_VERSION_PATCH DEC(__CODEGEARC_VERSION__ & 0xFFFF) #elif defined(__BORLANDC__) # define COMPILER_ID "Borland" /* __BORLANDC__ = 0xVRR */ # define COMPILER_VERSION_MAJOR HEX(__BORLANDC__>>8) # define COMPILER_VERSION_MINOR HEX(__BORLANDC__ & 0xFF) #elif defined(__WATCOMC__) && __WATCOMC__ < 1200 # define COMPILER_ID "Watcom" /* __WATCOMC__ = VVRR */ # define COMPILER_VERSION_MAJOR DEC(__WATCOMC__ / 100) # define COMPILER_VERSION_MINOR DEC((__WATCOMC__ / 10) % 10) # if (__WATCOMC__ % 10) > 0 # define COMPILER_VERSION_PATCH DEC(__WATCOMC__ % 10) # endif #elif defined(__WATCOMC__) # define COMPILER_ID "OpenWatcom" /* __WATCOMC__ = VVRP + 1100 */ # define COMPILER_VERSION_MAJOR DEC((__WATCOMC__ - 1100) / 100) # define COMPILER_VERSION_MINOR DEC((__WATCOMC__ / 10) % 10) # if (__WATCOMC__ % 10) > 0 # define COMPILER_VERSION_PATCH DEC(__WATCOMC__ % 10) # endif #elif defined(__SUNPRO_C) # define COMPILER_ID "SunPro" # if __SUNPRO_C >= 0x5100 /* __SUNPRO_C = 0xVRRP */ # define COMPILER_VERSION_MAJOR HEX(__SUNPRO_C>>12) # define COMPILER_VERSION_MINOR HEX(__SUNPRO_C>>4 & 0xFF) # define COMPILER_VERSION_PATCH HEX(__SUNPRO_C & 0xF) # else /* __SUNPRO_CC = 0xVRP */ # define COMPILER_VERSION_MAJOR HEX(__SUNPRO_C>>8) # define COMPILER_VERSION_MINOR HEX(__SUNPRO_C>>4 & 0xF) # define COMPILER_VERSION_PATCH HEX(__SUNPRO_C & 0xF) # endif #elif defined(__HP_cc) # define COMPILER_ID "HP" /* __HP_cc = VVRRPP */ # define COMPILER_VERSION_MAJOR DEC(__HP_cc/10000) # define COMPILER_VERSION_MINOR DEC(__HP_cc/100 % 100) # define COMPILER_VERSION_PATCH DEC(__HP_cc % 100) #elif defined(__DECC) # define COMPILER_ID "Compaq" /* __DECC_VER = VVRRTPPPP */ # define COMPILER_VERSION_MAJOR DEC(__DECC_VER/10000000) # define COMPILER_VERSION_MINOR DEC(__DECC_VER/100000 % 100) # define COMPILER_VERSION_PATCH DEC(__DECC_VER % 10000) #elif defined(__IBMC__) && defined(__COMPILER_VER__) # define COMPILER_ID "zOS" /* __IBMC__ = VRP */ # define COMPILER_VERSION_MAJOR DEC(__IBMC__/100) # define COMPILER_VERSION_MINOR DEC(__IBMC__/10 % 10) # define COMPILER_VERSION_PATCH DEC(__IBMC__ % 10) #elif defined(__IBMC__) && !defined(__COMPILER_VER__) && __IBMC__ >= 800 # define COMPILER_ID "XL" /* __IBMC__ = VRP */ # define COMPILER_VERSION_MAJOR DEC(__IBMC__/100) # define COMPILER_VERSION_MINOR DEC(__IBMC__/10 % 10) # define COMPILER_VERSION_PATCH DEC(__IBMC__ % 10) #elif defined(__IBMC__) && !defined(__COMPILER_VER__) && __IBMC__ < 800 # define COMPILER_ID "VisualAge" /* __IBMC__ = VRP */ # define COMPILER_VERSION_MAJOR DEC(__IBMC__/100) # define COMPILER_VERSION_MINOR DEC(__IBMC__/10 % 10) # define COMPILER_VERSION_PATCH DEC(__IBMC__ % 10) #elif defined(__PGI) # define COMPILER_ID "PGI" # define COMPILER_VERSION_MAJOR DEC(__PGIC__) # define COMPILER_VERSION_MINOR DEC(__PGIC_MINOR__) # if defined(__PGIC_PATCHLEVEL__) # define COMPILER_VERSION_PATCH DEC(__PGIC_PATCHLEVEL__) # endif #elif defined(_CRAYC) # define COMPILER_ID "Cray" # define COMPILER_VERSION_MAJOR DEC(_RELEASE_MAJOR) # define COMPILER_VERSION_MINOR DEC(_RELEASE_MINOR) #elif defined(__TI_COMPILER_VERSION__) # define COMPILER_ID "TI" /* __TI_COMPILER_VERSION__ = VVVRRRPPP */ # define COMPILER_VERSION_MAJOR DEC(__TI_COMPILER_VERSION__/1000000) # define COMPILER_VERSION_MINOR DEC(__TI_COMPILER_VERSION__/1000 % 1000) # define COMPILER_VERSION_PATCH DEC(__TI_COMPILER_VERSION__ % 1000) #elif defined(__FUJITSU) || defined(__FCC_VERSION) || defined(__fcc_version) # define COMPILER_ID "Fujitsu" #elif defined(__TINYC__) # define COMPILER_ID "TinyCC" #elif defined(__BCC__) # define COMPILER_ID "Bruce" #elif defined(__SCO_VERSION__) # define COMPILER_ID "SCO" #elif defined(__clang__) && defined(__apple_build_version__) # define COMPILER_ID "AppleClang" # if defined(_MSC_VER) # define SIMULATE_ID "MSVC" # endif # define COMPILER_VERSION_MAJOR DEC(__clang_major__) # define COMPILER_VERSION_MINOR DEC(__clang_minor__) # define COMPILER_VERSION_PATCH DEC(__clang_patchlevel__) # if defined(_MSC_VER) /* _MSC_VER = VVRR */ # define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100) # define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100) # endif # define COMPILER_VERSION_TWEAK DEC(__apple_build_version__) #elif defined(__clang__) # define COMPILER_ID "Clang" # if defined(_MSC_VER) # define SIMULATE_ID "MSVC" # endif # define COMPILER_VERSION_MAJOR DEC(__clang_major__) # define COMPILER_VERSION_MINOR DEC(__clang_minor__) # define COMPILER_VERSION_PATCH DEC(__clang_patchlevel__) # if defined(_MSC_VER) /* _MSC_VER = VVRR */ # define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100) # define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100) # endif #elif defined(__GNUC__) # define COMPILER_ID "GNU" # define COMPILER_VERSION_MAJOR DEC(__GNUC__) # if defined(__GNUC_MINOR__) # define COMPILER_VERSION_MINOR DEC(__GNUC_MINOR__) # endif # if defined(__GNUC_PATCHLEVEL__) # define COMPILER_VERSION_PATCH DEC(__GNUC_PATCHLEVEL__) # endif #elif defined(_MSC_VER) # define COMPILER_ID "MSVC" /* _MSC_VER = VVRR */ # define COMPILER_VERSION_MAJOR DEC(_MSC_VER / 100) # define COMPILER_VERSION_MINOR DEC(_MSC_VER % 100) # if defined(_MSC_FULL_VER) # if _MSC_VER >= 1400 /* _MSC_FULL_VER = VVRRPPPPP */ # define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 100000) # else /* _MSC_FULL_VER = VVRRPPPP */ # define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 10000) # endif # endif # if defined(_MSC_BUILD) # define COMPILER_VERSION_TWEAK DEC(_MSC_BUILD) # endif #elif defined(__VISUALDSPVERSION__) || defined(__ADSPBLACKFIN__) || defined(__ADSPTS__) || defined(__ADSP21000__) # define COMPILER_ID "ADSP" #if defined(__VISUALDSPVERSION__) /* __VISUALDSPVERSION__ = 0xVVRRPP00 */ # define COMPILER_VERSION_MAJOR HEX(__VISUALDSPVERSION__>>24) # define COMPILER_VERSION_MINOR HEX(__VISUALDSPVERSION__>>16 & 0xFF) # define COMPILER_VERSION_PATCH HEX(__VISUALDSPVERSION__>>8 & 0xFF) #endif #elif defined(__IAR_SYSTEMS_ICC__ ) || defined(__IAR_SYSTEMS_ICC) # define COMPILER_ID "IAR" #elif defined(__ARMCC_VERSION) # define COMPILER_ID "ARMCC" #if __ARMCC_VERSION >= 1000000 /* __ARMCC_VERSION = VRRPPPP */ # define COMPILER_VERSION_MAJOR DEC(__ARMCC_VERSION/1000000) # define COMPILER_VERSION_MINOR DEC(__ARMCC_VERSION/10000 % 100) # define COMPILER_VERSION_PATCH DEC(__ARMCC_VERSION % 10000) #else /* __ARMCC_VERSION = VRPPPP */ # define COMPILER_VERSION_MAJOR DEC(__ARMCC_VERSION/100000) # define COMPILER_VERSION_MINOR DEC(__ARMCC_VERSION/10000 % 10) # define COMPILER_VERSION_PATCH DEC(__ARMCC_VERSION % 10000) #endif #elif defined(__SDCC_VERSION_MAJOR) || defined(SDCC) # define COMPILER_ID "SDCC" # if defined(__SDCC_VERSION_MAJOR) # define COMPILER_VERSION_MAJOR DEC(__SDCC_VERSION_MAJOR) # define COMPILER_VERSION_MINOR DEC(__SDCC_VERSION_MINOR) # define COMPILER_VERSION_PATCH DEC(__SDCC_VERSION_PATCH) # else /* SDCC = VRP */ # define COMPILER_VERSION_MAJOR DEC(SDCC/100) # define COMPILER_VERSION_MINOR DEC(SDCC/10 % 10) # define COMPILER_VERSION_PATCH DEC(SDCC % 10) # endif #elif defined(_SGI_COMPILER_VERSION) || defined(_COMPILER_VERSION) # define COMPILER_ID "MIPSpro" # if defined(_SGI_COMPILER_VERSION) /* _SGI_COMPILER_VERSION = VRP */ # define COMPILER_VERSION_MAJOR DEC(_SGI_COMPILER_VERSION/100) # define COMPILER_VERSION_MINOR DEC(_SGI_COMPILER_VERSION/10 % 10) # define COMPILER_VERSION_PATCH DEC(_SGI_COMPILER_VERSION % 10) # else /* _COMPILER_VERSION = VRP */ # define COMPILER_VERSION_MAJOR DEC(_COMPILER_VERSION/100) # define COMPILER_VERSION_MINOR DEC(_COMPILER_VERSION/10 % 10) # define COMPILER_VERSION_PATCH DEC(_COMPILER_VERSION % 10) # endif /* These compilers are either not known or too old to define an identification macro. Try to identify the platform and guess that it is the native compiler. */ #elif defined(__sgi) # define COMPILER_ID "MIPSpro" #elif defined(__hpux) || defined(__hpua) # define COMPILER_ID "HP" #else /* unknown compiler */ # define COMPILER_ID "" #endif /* Construct the string literal in pieces to prevent the source from getting matched. Store it in a pointer rather than an array because some compilers will just produce instructions to fill the array rather than assigning a pointer to a static array. */ char const* info_compiler = "INFO" ":" "compiler[" COMPILER_ID "]"; #ifdef SIMULATE_ID char const* info_simulate = "INFO" ":" "simulate[" SIMULATE_ID "]"; #endif #ifdef __QNXNTO__ char const* qnxnto = "INFO" ":" "qnxnto[]"; #endif #if defined(__CRAYXE) || defined(__CRAYXC) char const *info_cray = "INFO" ":" "compiler_wrapper[CrayPrgEnv]"; #endif #define STRINGIFY_HELPER(X) #X #define STRINGIFY(X) STRINGIFY_HELPER(X) /* Identify known platforms by name. */ #if defined(__linux) || defined(__linux__) || defined(linux) # define PLATFORM_ID "Linux" #elif defined(__CYGWIN__) # define PLATFORM_ID "Cygwin" #elif defined(__MINGW32__) # define PLATFORM_ID "MinGW" #elif defined(__APPLE__) # define PLATFORM_ID "Darwin" #elif defined(_WIN32) || defined(__WIN32__) || defined(WIN32) # define PLATFORM_ID "Windows" #elif defined(__FreeBSD__) || defined(__FreeBSD) # define PLATFORM_ID "FreeBSD" #elif defined(__NetBSD__) || defined(__NetBSD) # define PLATFORM_ID "NetBSD" #elif defined(__OpenBSD__) || defined(__OPENBSD) # define PLATFORM_ID "OpenBSD" #elif defined(__sun) || defined(sun) # define PLATFORM_ID "SunOS" #elif defined(_AIX) || defined(__AIX) || defined(__AIX__) || defined(__aix) || defined(__aix__) # define PLATFORM_ID "AIX" #elif defined(__sgi) || defined(__sgi__) || defined(_SGI) # define PLATFORM_ID "IRIX" #elif defined(__hpux) || defined(__hpux__) # define PLATFORM_ID "HP-UX" #elif defined(__HAIKU__) # define PLATFORM_ID "Haiku" #elif defined(__BeOS) || defined(__BEOS__) || defined(_BEOS) # define PLATFORM_ID "BeOS" #elif defined(__QNX__) || defined(__QNXNTO__) # define PLATFORM_ID "QNX" #elif defined(__tru64) || defined(_tru64) || defined(__TRU64__) # define PLATFORM_ID "Tru64" #elif defined(__riscos) || defined(__riscos__) # define PLATFORM_ID "RISCos" #elif defined(__sinix) || defined(__sinix__) || defined(__SINIX__) # define PLATFORM_ID "SINIX" #elif defined(__UNIX_SV__) # define PLATFORM_ID "UNIX_SV" #elif defined(__bsdos__) # define PLATFORM_ID "BSDOS" #elif defined(_MPRAS) || defined(MPRAS) # define PLATFORM_ID "MP-RAS" #elif defined(__osf) || defined(__osf__) # define PLATFORM_ID "OSF1" #elif defined(_SCO_SV) || defined(SCO_SV) || defined(sco_sv) # define PLATFORM_ID "SCO_SV" #elif defined(__ultrix) || defined(__ultrix__) || defined(_ULTRIX) # define PLATFORM_ID "ULTRIX" #elif defined(__XENIX__) || defined(_XENIX) || defined(XENIX) # define PLATFORM_ID "Xenix" #elif defined(__WATCOMC__) # if defined(__LINUX__) # define PLATFORM_ID "Linux" # elif defined(__DOS__) # define PLATFORM_ID "DOS" # elif defined(__OS2__) # define PLATFORM_ID "OS2" # elif defined(__WINDOWS__) # define PLATFORM_ID "Windows3x" # else /* unknown platform */ # define PLATFORM_ID # endif #else /* unknown platform */ # define PLATFORM_ID #endif /* For windows compilers MSVC and Intel we can determine the architecture of the compiler being used. This is because the compilers do not have flags that can change the architecture, but rather depend on which compiler is being used */ #if defined(_WIN32) && defined(_MSC_VER) # if defined(_M_IA64) # define ARCHITECTURE_ID "IA64" # elif defined(_M_X64) || defined(_M_AMD64) # define ARCHITECTURE_ID "x64" # elif defined(_M_IX86) # define ARCHITECTURE_ID "X86" # elif defined(_M_ARM) # if _M_ARM == 4 # define ARCHITECTURE_ID "ARMV4I" # elif _M_ARM == 5 # define ARCHITECTURE_ID "ARMV5I" # else # define ARCHITECTURE_ID "ARMV" STRINGIFY(_M_ARM) # endif # elif defined(_M_MIPS) # define ARCHITECTURE_ID "MIPS" # elif defined(_M_SH) # define ARCHITECTURE_ID "SHx" # else /* unknown architecture */ # define ARCHITECTURE_ID "" # endif #elif defined(__WATCOMC__) # if defined(_M_I86) # define ARCHITECTURE_ID "I86" # elif defined(_M_IX86) # define ARCHITECTURE_ID "X86" # else /* unknown architecture */ # define ARCHITECTURE_ID "" # endif #else # define ARCHITECTURE_ID #endif /* Convert integer to decimal digit literals. */ #define DEC(n) \ ('0' + (((n) / 10000000)%10)), \ ('0' + (((n) / 1000000)%10)), \ ('0' + (((n) / 100000)%10)), \ ('0' + (((n) / 10000)%10)), \ ('0' + (((n) / 1000)%10)), \ ('0' + (((n) / 100)%10)), \ ('0' + (((n) / 10)%10)), \ ('0' + ((n) % 10)) /* Convert integer to hex digit literals. */ #define HEX(n) \ ('0' + ((n)>>28 & 0xF)), \ ('0' + ((n)>>24 & 0xF)), \ ('0' + ((n)>>20 & 0xF)), \ ('0' + ((n)>>16 & 0xF)), \ ('0' + ((n)>>12 & 0xF)), \ ('0' + ((n)>>8 & 0xF)), \ ('0' + ((n)>>4 & 0xF)), \ ('0' + ((n) & 0xF)) /* Construct a string literal encoding the version number components. */ #ifdef COMPILER_VERSION_MAJOR char const info_version[] = { 'I', 'N', 'F', 'O', ':', 'c','o','m','p','i','l','e','r','_','v','e','r','s','i','o','n','[', COMPILER_VERSION_MAJOR, # ifdef COMPILER_VERSION_MINOR '.', COMPILER_VERSION_MINOR, # ifdef COMPILER_VERSION_PATCH '.', COMPILER_VERSION_PATCH, # ifdef COMPILER_VERSION_TWEAK '.', COMPILER_VERSION_TWEAK, # endif # endif # endif ']','\0'}; #endif /* Construct a string literal encoding the version number components. */ #ifdef SIMULATE_VERSION_MAJOR char const info_simulate_version[] = { 'I', 'N', 'F', 'O', ':', 's','i','m','u','l','a','t','e','_','v','e','r','s','i','o','n','[', SIMULATE_VERSION_MAJOR, # ifdef SIMULATE_VERSION_MINOR '.', SIMULATE_VERSION_MINOR, # ifdef SIMULATE_VERSION_PATCH '.', SIMULATE_VERSION_PATCH, # ifdef SIMULATE_VERSION_TWEAK '.', SIMULATE_VERSION_TWEAK, # endif # endif # endif ']','\0'}; #endif /* Construct the string literal in pieces to prevent the source from getting matched. Store it in a pointer rather than an array because some compilers will just produce instructions to fill the array rather than assigning a pointer to a static array. */ char const* info_platform = "INFO" ":" "platform[" PLATFORM_ID "]"; char const* info_arch = "INFO" ":" "arch[" ARCHITECTURE_ID "]"; #if !defined(__STDC__) # if defined(_MSC_VER) && !defined(__clang__) # define C_DIALECT "90" # else # define C_DIALECT # endif #elif __STDC_VERSION__ >= 201000L # define C_DIALECT "11" #elif __STDC_VERSION__ >= 199901L # define C_DIALECT "99" #else # define C_DIALECT "90" #endif const char* info_language_dialect_default = "INFO" ":" "dialect_default[" C_DIALECT "]"; /*--------------------------------------------------------------------------*/ #ifdef ID_VOID_MAIN void main() {} #else # if defined(__CLASSIC_C__) int main(argc, argv) int argc; char *argv[]; # else int main(int argc, char* argv[]) # endif { int require = 0; require += info_compiler[argc]; require += info_platform[argc]; require += info_arch[argc]; #ifdef COMPILER_VERSION_MAJOR require += info_version[argc]; #endif #ifdef SIMULATE_ID require += info_simulate[argc]; #endif #ifdef SIMULATE_VERSION_MAJOR require += info_simulate_version[argc]; #endif #if defined(__CRAYXE) || defined(__CRAYXC) require += info_cray[argc]; #endif require += info_language_dialect_default[argc]; (void)argv; return require; } #endif ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/3.9.6/CompilerIdCXX/CMakeCXXCompilerId.cpp ================================================ /* This source file must have a .cpp extension so that all C++ compilers recognize the extension without flags. Borland does not know .cxx for example. */ #ifndef __cplusplus # error "A C compiler has been selected for C++." #endif /* Version number components: V=Version, R=Revision, P=Patch Version date components: YYYY=Year, MM=Month, DD=Day */ #if defined(__COMO__) # define COMPILER_ID "Comeau" /* __COMO_VERSION__ = VRR */ # define COMPILER_VERSION_MAJOR DEC(__COMO_VERSION__ / 100) # define COMPILER_VERSION_MINOR DEC(__COMO_VERSION__ % 100) #elif defined(__INTEL_COMPILER) || defined(__ICC) # define COMPILER_ID "Intel" # if defined(_MSC_VER) # define SIMULATE_ID "MSVC" # endif /* __INTEL_COMPILER = VRP */ # define COMPILER_VERSION_MAJOR DEC(__INTEL_COMPILER/100) # define COMPILER_VERSION_MINOR DEC(__INTEL_COMPILER/10 % 10) # if defined(__INTEL_COMPILER_UPDATE) # define COMPILER_VERSION_PATCH DEC(__INTEL_COMPILER_UPDATE) # else # define COMPILER_VERSION_PATCH DEC(__INTEL_COMPILER % 10) # endif # if defined(__INTEL_COMPILER_BUILD_DATE) /* __INTEL_COMPILER_BUILD_DATE = YYYYMMDD */ # define COMPILER_VERSION_TWEAK DEC(__INTEL_COMPILER_BUILD_DATE) # endif # if defined(_MSC_VER) /* _MSC_VER = VVRR */ # define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100) # define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100) # endif #elif defined(__PATHCC__) # define COMPILER_ID "PathScale" # define COMPILER_VERSION_MAJOR DEC(__PATHCC__) # define COMPILER_VERSION_MINOR DEC(__PATHCC_MINOR__) # if defined(__PATHCC_PATCHLEVEL__) # define COMPILER_VERSION_PATCH DEC(__PATHCC_PATCHLEVEL__) # endif #elif defined(__BORLANDC__) && defined(__CODEGEARC_VERSION__) # define COMPILER_ID "Embarcadero" # define COMPILER_VERSION_MAJOR HEX(__CODEGEARC_VERSION__>>24 & 0x00FF) # define COMPILER_VERSION_MINOR HEX(__CODEGEARC_VERSION__>>16 & 0x00FF) # define COMPILER_VERSION_PATCH DEC(__CODEGEARC_VERSION__ & 0xFFFF) #elif defined(__BORLANDC__) # define COMPILER_ID "Borland" /* __BORLANDC__ = 0xVRR */ # define COMPILER_VERSION_MAJOR HEX(__BORLANDC__>>8) # define COMPILER_VERSION_MINOR HEX(__BORLANDC__ & 0xFF) #elif defined(__WATCOMC__) && __WATCOMC__ < 1200 # define COMPILER_ID "Watcom" /* __WATCOMC__ = VVRR */ # define COMPILER_VERSION_MAJOR DEC(__WATCOMC__ / 100) # define COMPILER_VERSION_MINOR DEC((__WATCOMC__ / 10) % 10) # if (__WATCOMC__ % 10) > 0 # define COMPILER_VERSION_PATCH DEC(__WATCOMC__ % 10) # endif #elif defined(__WATCOMC__) # define COMPILER_ID "OpenWatcom" /* __WATCOMC__ = VVRP + 1100 */ # define COMPILER_VERSION_MAJOR DEC((__WATCOMC__ - 1100) / 100) # define COMPILER_VERSION_MINOR DEC((__WATCOMC__ / 10) % 10) # if (__WATCOMC__ % 10) > 0 # define COMPILER_VERSION_PATCH DEC(__WATCOMC__ % 10) # endif #elif defined(__SUNPRO_CC) # define COMPILER_ID "SunPro" # if __SUNPRO_CC >= 0x5100 /* __SUNPRO_CC = 0xVRRP */ # define COMPILER_VERSION_MAJOR HEX(__SUNPRO_CC>>12) # define COMPILER_VERSION_MINOR HEX(__SUNPRO_CC>>4 & 0xFF) # define COMPILER_VERSION_PATCH HEX(__SUNPRO_CC & 0xF) # else /* __SUNPRO_CC = 0xVRP */ # define COMPILER_VERSION_MAJOR HEX(__SUNPRO_CC>>8) # define COMPILER_VERSION_MINOR HEX(__SUNPRO_CC>>4 & 0xF) # define COMPILER_VERSION_PATCH HEX(__SUNPRO_CC & 0xF) # endif #elif defined(__HP_aCC) # define COMPILER_ID "HP" /* __HP_aCC = VVRRPP */ # define COMPILER_VERSION_MAJOR DEC(__HP_aCC/10000) # define COMPILER_VERSION_MINOR DEC(__HP_aCC/100 % 100) # define COMPILER_VERSION_PATCH DEC(__HP_aCC % 100) #elif defined(__DECCXX) # define COMPILER_ID "Compaq" /* __DECCXX_VER = VVRRTPPPP */ # define COMPILER_VERSION_MAJOR DEC(__DECCXX_VER/10000000) # define COMPILER_VERSION_MINOR DEC(__DECCXX_VER/100000 % 100) # define COMPILER_VERSION_PATCH DEC(__DECCXX_VER % 10000) #elif defined(__IBMCPP__) && defined(__COMPILER_VER__) # define COMPILER_ID "zOS" /* __IBMCPP__ = VRP */ # define COMPILER_VERSION_MAJOR DEC(__IBMCPP__/100) # define COMPILER_VERSION_MINOR DEC(__IBMCPP__/10 % 10) # define COMPILER_VERSION_PATCH DEC(__IBMCPP__ % 10) #elif defined(__IBMCPP__) && !defined(__COMPILER_VER__) && __IBMCPP__ >= 800 # define COMPILER_ID "XL" /* __IBMCPP__ = VRP */ # define COMPILER_VERSION_MAJOR DEC(__IBMCPP__/100) # define COMPILER_VERSION_MINOR DEC(__IBMCPP__/10 % 10) # define COMPILER_VERSION_PATCH DEC(__IBMCPP__ % 10) #elif defined(__IBMCPP__) && !defined(__COMPILER_VER__) && __IBMCPP__ < 800 # define COMPILER_ID "VisualAge" /* __IBMCPP__ = VRP */ # define COMPILER_VERSION_MAJOR DEC(__IBMCPP__/100) # define COMPILER_VERSION_MINOR DEC(__IBMCPP__/10 % 10) # define COMPILER_VERSION_PATCH DEC(__IBMCPP__ % 10) #elif defined(__PGI) # define COMPILER_ID "PGI" # define COMPILER_VERSION_MAJOR DEC(__PGIC__) # define COMPILER_VERSION_MINOR DEC(__PGIC_MINOR__) # if defined(__PGIC_PATCHLEVEL__) # define COMPILER_VERSION_PATCH DEC(__PGIC_PATCHLEVEL__) # endif #elif defined(_CRAYC) # define COMPILER_ID "Cray" # define COMPILER_VERSION_MAJOR DEC(_RELEASE_MAJOR) # define COMPILER_VERSION_MINOR DEC(_RELEASE_MINOR) #elif defined(__TI_COMPILER_VERSION__) # define COMPILER_ID "TI" /* __TI_COMPILER_VERSION__ = VVVRRRPPP */ # define COMPILER_VERSION_MAJOR DEC(__TI_COMPILER_VERSION__/1000000) # define COMPILER_VERSION_MINOR DEC(__TI_COMPILER_VERSION__/1000 % 1000) # define COMPILER_VERSION_PATCH DEC(__TI_COMPILER_VERSION__ % 1000) #elif defined(__FUJITSU) || defined(__FCC_VERSION) || defined(__fcc_version) # define COMPILER_ID "Fujitsu" #elif defined(__SCO_VERSION__) # define COMPILER_ID "SCO" #elif defined(__clang__) && defined(__apple_build_version__) # define COMPILER_ID "AppleClang" # if defined(_MSC_VER) # define SIMULATE_ID "MSVC" # endif # define COMPILER_VERSION_MAJOR DEC(__clang_major__) # define COMPILER_VERSION_MINOR DEC(__clang_minor__) # define COMPILER_VERSION_PATCH DEC(__clang_patchlevel__) # if defined(_MSC_VER) /* _MSC_VER = VVRR */ # define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100) # define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100) # endif # define COMPILER_VERSION_TWEAK DEC(__apple_build_version__) #elif defined(__clang__) # define COMPILER_ID "Clang" # if defined(_MSC_VER) # define SIMULATE_ID "MSVC" # endif # define COMPILER_VERSION_MAJOR DEC(__clang_major__) # define COMPILER_VERSION_MINOR DEC(__clang_minor__) # define COMPILER_VERSION_PATCH DEC(__clang_patchlevel__) # if defined(_MSC_VER) /* _MSC_VER = VVRR */ # define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100) # define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100) # endif #elif defined(__GNUC__) || defined(__GNUG__) # define COMPILER_ID "GNU" # if defined(__GNUC__) # define COMPILER_VERSION_MAJOR DEC(__GNUC__) # else # define COMPILER_VERSION_MAJOR DEC(__GNUG__) # endif # if defined(__GNUC_MINOR__) # define COMPILER_VERSION_MINOR DEC(__GNUC_MINOR__) # endif # if defined(__GNUC_PATCHLEVEL__) # define COMPILER_VERSION_PATCH DEC(__GNUC_PATCHLEVEL__) # endif #elif defined(_MSC_VER) # define COMPILER_ID "MSVC" /* _MSC_VER = VVRR */ # define COMPILER_VERSION_MAJOR DEC(_MSC_VER / 100) # define COMPILER_VERSION_MINOR DEC(_MSC_VER % 100) # if defined(_MSC_FULL_VER) # if _MSC_VER >= 1400 /* _MSC_FULL_VER = VVRRPPPPP */ # define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 100000) # else /* _MSC_FULL_VER = VVRRPPPP */ # define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 10000) # endif # endif # if defined(_MSC_BUILD) # define COMPILER_VERSION_TWEAK DEC(_MSC_BUILD) # endif #elif defined(__VISUALDSPVERSION__) || defined(__ADSPBLACKFIN__) || defined(__ADSPTS__) || defined(__ADSP21000__) # define COMPILER_ID "ADSP" #if defined(__VISUALDSPVERSION__) /* __VISUALDSPVERSION__ = 0xVVRRPP00 */ # define COMPILER_VERSION_MAJOR HEX(__VISUALDSPVERSION__>>24) # define COMPILER_VERSION_MINOR HEX(__VISUALDSPVERSION__>>16 & 0xFF) # define COMPILER_VERSION_PATCH HEX(__VISUALDSPVERSION__>>8 & 0xFF) #endif #elif defined(__IAR_SYSTEMS_ICC__ ) || defined(__IAR_SYSTEMS_ICC) # define COMPILER_ID "IAR" #elif defined(__ARMCC_VERSION) # define COMPILER_ID "ARMCC" #if __ARMCC_VERSION >= 1000000 /* __ARMCC_VERSION = VRRPPPP */ # define COMPILER_VERSION_MAJOR DEC(__ARMCC_VERSION/1000000) # define COMPILER_VERSION_MINOR DEC(__ARMCC_VERSION/10000 % 100) # define COMPILER_VERSION_PATCH DEC(__ARMCC_VERSION % 10000) #else /* __ARMCC_VERSION = VRPPPP */ # define COMPILER_VERSION_MAJOR DEC(__ARMCC_VERSION/100000) # define COMPILER_VERSION_MINOR DEC(__ARMCC_VERSION/10000 % 10) # define COMPILER_VERSION_PATCH DEC(__ARMCC_VERSION % 10000) #endif #elif defined(_SGI_COMPILER_VERSION) || defined(_COMPILER_VERSION) # define COMPILER_ID "MIPSpro" # if defined(_SGI_COMPILER_VERSION) /* _SGI_COMPILER_VERSION = VRP */ # define COMPILER_VERSION_MAJOR DEC(_SGI_COMPILER_VERSION/100) # define COMPILER_VERSION_MINOR DEC(_SGI_COMPILER_VERSION/10 % 10) # define COMPILER_VERSION_PATCH DEC(_SGI_COMPILER_VERSION % 10) # else /* _COMPILER_VERSION = VRP */ # define COMPILER_VERSION_MAJOR DEC(_COMPILER_VERSION/100) # define COMPILER_VERSION_MINOR DEC(_COMPILER_VERSION/10 % 10) # define COMPILER_VERSION_PATCH DEC(_COMPILER_VERSION % 10) # endif /* These compilers are either not known or too old to define an identification macro. Try to identify the platform and guess that it is the native compiler. */ #elif defined(__sgi) # define COMPILER_ID "MIPSpro" #elif defined(__hpux) || defined(__hpua) # define COMPILER_ID "HP" #else /* unknown compiler */ # define COMPILER_ID "" #endif /* Construct the string literal in pieces to prevent the source from getting matched. Store it in a pointer rather than an array because some compilers will just produce instructions to fill the array rather than assigning a pointer to a static array. */ char const* info_compiler = "INFO" ":" "compiler[" COMPILER_ID "]"; #ifdef SIMULATE_ID char const* info_simulate = "INFO" ":" "simulate[" SIMULATE_ID "]"; #endif #ifdef __QNXNTO__ char const* qnxnto = "INFO" ":" "qnxnto[]"; #endif #if defined(__CRAYXE) || defined(__CRAYXC) char const *info_cray = "INFO" ":" "compiler_wrapper[CrayPrgEnv]"; #endif #define STRINGIFY_HELPER(X) #X #define STRINGIFY(X) STRINGIFY_HELPER(X) /* Identify known platforms by name. */ #if defined(__linux) || defined(__linux__) || defined(linux) # define PLATFORM_ID "Linux" #elif defined(__CYGWIN__) # define PLATFORM_ID "Cygwin" #elif defined(__MINGW32__) # define PLATFORM_ID "MinGW" #elif defined(__APPLE__) # define PLATFORM_ID "Darwin" #elif defined(_WIN32) || defined(__WIN32__) || defined(WIN32) # define PLATFORM_ID "Windows" #elif defined(__FreeBSD__) || defined(__FreeBSD) # define PLATFORM_ID "FreeBSD" #elif defined(__NetBSD__) || defined(__NetBSD) # define PLATFORM_ID "NetBSD" #elif defined(__OpenBSD__) || defined(__OPENBSD) # define PLATFORM_ID "OpenBSD" #elif defined(__sun) || defined(sun) # define PLATFORM_ID "SunOS" #elif defined(_AIX) || defined(__AIX) || defined(__AIX__) || defined(__aix) || defined(__aix__) # define PLATFORM_ID "AIX" #elif defined(__sgi) || defined(__sgi__) || defined(_SGI) # define PLATFORM_ID "IRIX" #elif defined(__hpux) || defined(__hpux__) # define PLATFORM_ID "HP-UX" #elif defined(__HAIKU__) # define PLATFORM_ID "Haiku" #elif defined(__BeOS) || defined(__BEOS__) || defined(_BEOS) # define PLATFORM_ID "BeOS" #elif defined(__QNX__) || defined(__QNXNTO__) # define PLATFORM_ID "QNX" #elif defined(__tru64) || defined(_tru64) || defined(__TRU64__) # define PLATFORM_ID "Tru64" #elif defined(__riscos) || defined(__riscos__) # define PLATFORM_ID "RISCos" #elif defined(__sinix) || defined(__sinix__) || defined(__SINIX__) # define PLATFORM_ID "SINIX" #elif defined(__UNIX_SV__) # define PLATFORM_ID "UNIX_SV" #elif defined(__bsdos__) # define PLATFORM_ID "BSDOS" #elif defined(_MPRAS) || defined(MPRAS) # define PLATFORM_ID "MP-RAS" #elif defined(__osf) || defined(__osf__) # define PLATFORM_ID "OSF1" #elif defined(_SCO_SV) || defined(SCO_SV) || defined(sco_sv) # define PLATFORM_ID "SCO_SV" #elif defined(__ultrix) || defined(__ultrix__) || defined(_ULTRIX) # define PLATFORM_ID "ULTRIX" #elif defined(__XENIX__) || defined(_XENIX) || defined(XENIX) # define PLATFORM_ID "Xenix" #elif defined(__WATCOMC__) # if defined(__LINUX__) # define PLATFORM_ID "Linux" # elif defined(__DOS__) # define PLATFORM_ID "DOS" # elif defined(__OS2__) # define PLATFORM_ID "OS2" # elif defined(__WINDOWS__) # define PLATFORM_ID "Windows3x" # else /* unknown platform */ # define PLATFORM_ID # endif #else /* unknown platform */ # define PLATFORM_ID #endif /* For windows compilers MSVC and Intel we can determine the architecture of the compiler being used. This is because the compilers do not have flags that can change the architecture, but rather depend on which compiler is being used */ #if defined(_WIN32) && defined(_MSC_VER) # if defined(_M_IA64) # define ARCHITECTURE_ID "IA64" # elif defined(_M_X64) || defined(_M_AMD64) # define ARCHITECTURE_ID "x64" # elif defined(_M_IX86) # define ARCHITECTURE_ID "X86" # elif defined(_M_ARM) # if _M_ARM == 4 # define ARCHITECTURE_ID "ARMV4I" # elif _M_ARM == 5 # define ARCHITECTURE_ID "ARMV5I" # else # define ARCHITECTURE_ID "ARMV" STRINGIFY(_M_ARM) # endif # elif defined(_M_MIPS) # define ARCHITECTURE_ID "MIPS" # elif defined(_M_SH) # define ARCHITECTURE_ID "SHx" # else /* unknown architecture */ # define ARCHITECTURE_ID "" # endif #elif defined(__WATCOMC__) # if defined(_M_I86) # define ARCHITECTURE_ID "I86" # elif defined(_M_IX86) # define ARCHITECTURE_ID "X86" # else /* unknown architecture */ # define ARCHITECTURE_ID "" # endif #else # define ARCHITECTURE_ID #endif /* Convert integer to decimal digit literals. */ #define DEC(n) \ ('0' + (((n) / 10000000)%10)), \ ('0' + (((n) / 1000000)%10)), \ ('0' + (((n) / 100000)%10)), \ ('0' + (((n) / 10000)%10)), \ ('0' + (((n) / 1000)%10)), \ ('0' + (((n) / 100)%10)), \ ('0' + (((n) / 10)%10)), \ ('0' + ((n) % 10)) /* Convert integer to hex digit literals. */ #define HEX(n) \ ('0' + ((n)>>28 & 0xF)), \ ('0' + ((n)>>24 & 0xF)), \ ('0' + ((n)>>20 & 0xF)), \ ('0' + ((n)>>16 & 0xF)), \ ('0' + ((n)>>12 & 0xF)), \ ('0' + ((n)>>8 & 0xF)), \ ('0' + ((n)>>4 & 0xF)), \ ('0' + ((n) & 0xF)) /* Construct a string literal encoding the version number components. */ #ifdef COMPILER_VERSION_MAJOR char const info_version[] = { 'I', 'N', 'F', 'O', ':', 'c','o','m','p','i','l','e','r','_','v','e','r','s','i','o','n','[', COMPILER_VERSION_MAJOR, # ifdef COMPILER_VERSION_MINOR '.', COMPILER_VERSION_MINOR, # ifdef COMPILER_VERSION_PATCH '.', COMPILER_VERSION_PATCH, # ifdef COMPILER_VERSION_TWEAK '.', COMPILER_VERSION_TWEAK, # endif # endif # endif ']','\0'}; #endif /* Construct a string literal encoding the version number components. */ #ifdef SIMULATE_VERSION_MAJOR char const info_simulate_version[] = { 'I', 'N', 'F', 'O', ':', 's','i','m','u','l','a','t','e','_','v','e','r','s','i','o','n','[', SIMULATE_VERSION_MAJOR, # ifdef SIMULATE_VERSION_MINOR '.', SIMULATE_VERSION_MINOR, # ifdef SIMULATE_VERSION_PATCH '.', SIMULATE_VERSION_PATCH, # ifdef SIMULATE_VERSION_TWEAK '.', SIMULATE_VERSION_TWEAK, # endif # endif # endif ']','\0'}; #endif /* Construct the string literal in pieces to prevent the source from getting matched. Store it in a pointer rather than an array because some compilers will just produce instructions to fill the array rather than assigning a pointer to a static array. */ char const* info_platform = "INFO" ":" "platform[" PLATFORM_ID "]"; char const* info_arch = "INFO" ":" "arch[" ARCHITECTURE_ID "]"; const char* info_language_dialect_default = "INFO" ":" "dialect_default[" #if __cplusplus > 201402L "17" #elif __cplusplus >= 201402L "14" #elif __cplusplus >= 201103L "11" #else "98" #endif "]"; /*--------------------------------------------------------------------------*/ int main(int argc, char* argv[]) { int require = 0; require += info_compiler[argc]; require += info_platform[argc]; #ifdef COMPILER_VERSION_MAJOR require += info_version[argc]; #endif #ifdef SIMULATE_ID require += info_simulate[argc]; #endif #ifdef SIMULATE_VERSION_MAJOR require += info_simulate_version[argc]; #endif #if defined(__CRAYXE) || defined(__CRAYXC) require += info_cray[argc]; #endif require += info_language_dialect_default[argc]; (void)argv; return require; } ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeDirectoryInformation.cmake ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Relative path conversion top directories. set(CMAKE_RELATIVE_PATH_TOP_SOURCE "/home/zn/racecar/src/rf2o_laser_odometry") set(CMAKE_RELATIVE_PATH_TOP_BINARY "/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug") # Force unix paths in dependencies. set(CMAKE_FORCE_UNIX_PATHS 1) # The C and CXX include file regular expressions for this directory. set(CMAKE_C_INCLUDE_REGEX_SCAN "^.*$") set(CMAKE_C_INCLUDE_REGEX_COMPLAIN "^$") set(CMAKE_CXX_INCLUDE_REGEX_SCAN ${CMAKE_C_INCLUDE_REGEX_SCAN}) set(CMAKE_CXX_INCLUDE_REGEX_COMPLAIN ${CMAKE_C_INCLUDE_REGEX_COMPLAIN}) ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeError.log ================================================ Determining if the pthread_create exist failed with the following output: Change Dir: /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp Run Build Command:"/usr/bin/make" "cmTC_a87d6/fast" /usr/bin/make -f CMakeFiles/cmTC_a87d6.dir/build.make CMakeFiles/cmTC_a87d6.dir/build make[1]: Entering directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp' Building C object CMakeFiles/cmTC_a87d6.dir/CheckSymbolExists.c.o /usr/bin/cc -o CMakeFiles/cmTC_a87d6.dir/CheckSymbolExists.c.o -c /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp/CheckSymbolExists.c Linking C executable cmTC_a87d6 /home/zn/.ide/clion/bin/cmake/bin/cmake -E cmake_link_script CMakeFiles/cmTC_a87d6.dir/link.txt --verbose=1 /usr/bin/cc -rdynamic CMakeFiles/cmTC_a87d6.dir/CheckSymbolExists.c.o -o cmTC_a87d6 CMakeFiles/cmTC_a87d6.dir/CheckSymbolExists.c.o: In function `main': CheckSymbolExists.c:(.text+0x16): undefined reference to `pthread_create' collect2: error: ld returned 1 exit status CMakeFiles/cmTC_a87d6.dir/build.make:97: recipe for target 'cmTC_a87d6' failed make[1]: *** [cmTC_a87d6] Error 1 make[1]: Leaving directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp' Makefile:126: recipe for target 'cmTC_a87d6/fast' failed make: *** [cmTC_a87d6/fast] Error 2 File /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp/CheckSymbolExists.c: /* */ #include int main(int argc, char** argv) { (void)argv; #ifndef pthread_create return ((int*)(&pthread_create))[argc]; #else (void)argc; return 0; #endif } Determining if the function pthread_create exists in the pthreads failed with the following output: Change Dir: /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp Run Build Command:"/usr/bin/make" "cmTC_20b42/fast" /usr/bin/make -f CMakeFiles/cmTC_20b42.dir/build.make CMakeFiles/cmTC_20b42.dir/build make[1]: Entering directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp' Building C object CMakeFiles/cmTC_20b42.dir/CheckFunctionExists.c.o /usr/bin/cc -DCHECK_FUNCTION_EXISTS=pthread_create -o CMakeFiles/cmTC_20b42.dir/CheckFunctionExists.c.o -c /home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CheckFunctionExists.c Linking C executable cmTC_20b42 /home/zn/.ide/clion/bin/cmake/bin/cmake -E cmake_link_script CMakeFiles/cmTC_20b42.dir/link.txt --verbose=1 /usr/bin/cc -DCHECK_FUNCTION_EXISTS=pthread_create -rdynamic CMakeFiles/cmTC_20b42.dir/CheckFunctionExists.c.o -o cmTC_20b42 -lpthreads /usr/bin/ld: cannot find -lpthreads collect2: error: ld returned 1 exit status CMakeFiles/cmTC_20b42.dir/build.make:97: recipe for target 'cmTC_20b42' failed make[1]: *** [cmTC_20b42] Error 1 make[1]: Leaving directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp' Makefile:126: recipe for target 'cmTC_20b42/fast' failed make: *** [cmTC_20b42/fast] Error 2 ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeOutput.log ================================================ The system is: Linux - 4.13.0-38-generic - x86_64 Compiling the C compiler identification source file "CMakeCCompilerId.c" succeeded. Compiler: /usr/bin/cc Build flags: Id flags: The output was: 0 Compilation of the C compiler identification source "CMakeCCompilerId.c" produced "a.out" The C compiler identification is GNU, found in "/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/3.9.6/CompilerIdC/a.out" Compiling the CXX compiler identification source file "CMakeCXXCompilerId.cpp" succeeded. Compiler: /usr/bin/c++ Build flags: Id flags: The output was: 0 Compilation of the CXX compiler identification source "CMakeCXXCompilerId.cpp" produced "a.out" The CXX compiler identification is GNU, found in "/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/3.9.6/CompilerIdCXX/a.out" Determining if the C compiler works passed with the following output: Change Dir: /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp Run Build Command:"/usr/bin/make" "cmTC_e13f3/fast" /usr/bin/make -f CMakeFiles/cmTC_e13f3.dir/build.make CMakeFiles/cmTC_e13f3.dir/build make[1]: Entering directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp' Building C object CMakeFiles/cmTC_e13f3.dir/testCCompiler.c.o /usr/bin/cc -o CMakeFiles/cmTC_e13f3.dir/testCCompiler.c.o -c /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp/testCCompiler.c Linking C executable cmTC_e13f3 /home/zn/.ide/clion/bin/cmake/bin/cmake -E cmake_link_script CMakeFiles/cmTC_e13f3.dir/link.txt --verbose=1 /usr/bin/cc -rdynamic CMakeFiles/cmTC_e13f3.dir/testCCompiler.c.o -o cmTC_e13f3 make[1]: Leaving directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp' Detecting C compiler ABI info compiled with the following output: Change Dir: /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp Run Build Command:"/usr/bin/make" "cmTC_1b6e6/fast" /usr/bin/make -f CMakeFiles/cmTC_1b6e6.dir/build.make CMakeFiles/cmTC_1b6e6.dir/build make[1]: Entering directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp' Building C object CMakeFiles/cmTC_1b6e6.dir/CMakeCCompilerABI.c.o /usr/bin/cc -o CMakeFiles/cmTC_1b6e6.dir/CMakeCCompilerABI.c.o -c /home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeCCompilerABI.c Linking C executable cmTC_1b6e6 /home/zn/.ide/clion/bin/cmake/bin/cmake -E cmake_link_script CMakeFiles/cmTC_1b6e6.dir/link.txt --verbose=1 /usr/bin/cc -v -rdynamic CMakeFiles/cmTC_1b6e6.dir/CMakeCCompilerABI.c.o -o cmTC_1b6e6 Using built-in specs. COLLECT_GCC=/usr/bin/cc COLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/5/lto-wrapper Target: x86_64-linux-gnu Configured with: ../src/configure -v --with-pkgversion='Ubuntu 5.4.0-6ubuntu1~16.04.9' --with-bugurl=file:///usr/share/doc/gcc-5/README.Bugs --enable-languages=c,ada,c++,java,go,d,fortran,objc,obj-c++ --prefix=/usr --program-suffix=-5 --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --libdir=/usr/lib --enable-nls --with-sysroot=/ --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --with-default-libstdcxx-abi=new --enable-gnu-unique-object --disable-vtable-verify --enable-libmpx --enable-plugin --with-system-zlib --disable-browser-plugin --enable-java-awt=gtk --enable-gtk-cairo --with-java-home=/usr/lib/jvm/java-1.5.0-gcj-5-amd64/jre --enable-java-home --with-jvm-root-dir=/usr/lib/jvm/java-1.5.0-gcj-5-amd64 --with-jvm-jar-dir=/usr/lib/jvm-exports/java-1.5.0-gcj-5-amd64 --with-arch-directory=amd64 --with-ecj-jar=/usr/share/java/eclipse-ecj.jar --enable-objc-gc --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32,m64,mx32 --enable-multilib --with-tune=generic --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu Thread model: posix gcc version 5.4.0 20160609 (Ubuntu 5.4.0-6ubuntu1~16.04.9) COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/5/:/usr/lib/gcc/x86_64-linux-gnu/5/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/5/:/usr/lib/gcc/x86_64-linux-gnu/ LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/5/:/usr/lib/gcc/x86_64-linux-gnu/5/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/5/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/5/../../../:/lib/:/usr/lib/ COLLECT_GCC_OPTIONS='-v' '-rdynamic' '-o' 'cmTC_1b6e6' '-mtune=generic' '-march=x86-64' /usr/lib/gcc/x86_64-linux-gnu/5/collect2 -plugin /usr/lib/gcc/x86_64-linux-gnu/5/liblto_plugin.so -plugin-opt=/usr/lib/gcc/x86_64-linux-gnu/5/lto-wrapper -plugin-opt=-fresolution=/tmp/ccGW6Hat.res -plugin-opt=-pass-through=-lgcc -plugin-opt=-pass-through=-lgcc_s -plugin-opt=-pass-through=-lc -plugin-opt=-pass-through=-lgcc -plugin-opt=-pass-through=-lgcc_s --sysroot=/ --build-id --eh-frame-hdr -m elf_x86_64 --hash-style=gnu --as-needed -export-dynamic -dynamic-linker /lib64/ld-linux-x86-64.so.2 -z relro -o cmTC_1b6e6 /usr/lib/gcc/x86_64-linux-gnu/5/../../../x86_64-linux-gnu/crt1.o /usr/lib/gcc/x86_64-linux-gnu/5/../../../x86_64-linux-gnu/crti.o /usr/lib/gcc/x86_64-linux-gnu/5/crtbegin.o -L/usr/lib/gcc/x86_64-linux-gnu/5 -L/usr/lib/gcc/x86_64-linux-gnu/5/../../../x86_64-linux-gnu -L/usr/lib/gcc/x86_64-linux-gnu/5/../../../../lib -L/lib/x86_64-linux-gnu -L/lib/../lib -L/usr/lib/x86_64-linux-gnu -L/usr/lib/../lib -L/usr/lib/gcc/x86_64-linux-gnu/5/../../.. CMakeFiles/cmTC_1b6e6.dir/CMakeCCompilerABI.c.o -lgcc --as-needed -lgcc_s --no-as-needed -lc -lgcc --as-needed -lgcc_s --no-as-needed /usr/lib/gcc/x86_64-linux-gnu/5/crtend.o /usr/lib/gcc/x86_64-linux-gnu/5/../../../x86_64-linux-gnu/crtn.o make[1]: Leaving directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp' Parsed C implicit link information from above output: link line regex: [^( *|.*[/\])(ld|CMAKE_LINK_STARTFILE-NOTFOUND|([^/\]+-)?ld|collect2)[^/\]*( |$)] ignore line: [Change Dir: /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp] ignore line: [] ignore line: [Run Build Command:"/usr/bin/make" "cmTC_1b6e6/fast"] ignore line: [/usr/bin/make -f CMakeFiles/cmTC_1b6e6.dir/build.make CMakeFiles/cmTC_1b6e6.dir/build] ignore line: [make[1]: Entering directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp'] ignore line: [Building C object CMakeFiles/cmTC_1b6e6.dir/CMakeCCompilerABI.c.o] ignore line: [/usr/bin/cc -o CMakeFiles/cmTC_1b6e6.dir/CMakeCCompilerABI.c.o -c /home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeCCompilerABI.c] ignore line: [Linking C executable cmTC_1b6e6] ignore line: [/home/zn/.ide/clion/bin/cmake/bin/cmake -E cmake_link_script CMakeFiles/cmTC_1b6e6.dir/link.txt --verbose=1] ignore line: [/usr/bin/cc -v -rdynamic CMakeFiles/cmTC_1b6e6.dir/CMakeCCompilerABI.c.o -o cmTC_1b6e6 ] ignore line: [Using built-in specs.] ignore line: [COLLECT_GCC=/usr/bin/cc] ignore line: [COLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/5/lto-wrapper] ignore line: [Target: x86_64-linux-gnu] ignore line: [Configured with: ../src/configure -v --with-pkgversion='Ubuntu 5.4.0-6ubuntu1~16.04.9' --with-bugurl=file:///usr/share/doc/gcc-5/README.Bugs --enable-languages=c,ada,c++,java,go,d,fortran,objc,obj-c++ --prefix=/usr --program-suffix=-5 --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --libdir=/usr/lib --enable-nls --with-sysroot=/ --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --with-default-libstdcxx-abi=new --enable-gnu-unique-object --disable-vtable-verify --enable-libmpx --enable-plugin --with-system-zlib --disable-browser-plugin --enable-java-awt=gtk --enable-gtk-cairo --with-java-home=/usr/lib/jvm/java-1.5.0-gcj-5-amd64/jre --enable-java-home --with-jvm-root-dir=/usr/lib/jvm/java-1.5.0-gcj-5-amd64 --with-jvm-jar-dir=/usr/lib/jvm-exports/java-1.5.0-gcj-5-amd64 --with-arch-directory=amd64 --with-ecj-jar=/usr/share/java/eclipse-ecj.jar --enable-objc-gc --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32,m64,mx32 --enable-multilib --with-tune=generic --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu] ignore line: [Thread model: posix] ignore line: [gcc version 5.4.0 20160609 (Ubuntu 5.4.0-6ubuntu1~16.04.9) ] ignore line: [COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/5/:/usr/lib/gcc/x86_64-linux-gnu/5/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/5/:/usr/lib/gcc/x86_64-linux-gnu/] ignore line: [LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/5/:/usr/lib/gcc/x86_64-linux-gnu/5/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/5/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/5/../../../:/lib/:/usr/lib/] ignore line: [COLLECT_GCC_OPTIONS='-v' '-rdynamic' '-o' 'cmTC_1b6e6' '-mtune=generic' '-march=x86-64'] link line: [ /usr/lib/gcc/x86_64-linux-gnu/5/collect2 -plugin /usr/lib/gcc/x86_64-linux-gnu/5/liblto_plugin.so -plugin-opt=/usr/lib/gcc/x86_64-linux-gnu/5/lto-wrapper -plugin-opt=-fresolution=/tmp/ccGW6Hat.res -plugin-opt=-pass-through=-lgcc -plugin-opt=-pass-through=-lgcc_s -plugin-opt=-pass-through=-lc -plugin-opt=-pass-through=-lgcc -plugin-opt=-pass-through=-lgcc_s --sysroot=/ --build-id --eh-frame-hdr -m elf_x86_64 --hash-style=gnu --as-needed -export-dynamic -dynamic-linker /lib64/ld-linux-x86-64.so.2 -z relro -o cmTC_1b6e6 /usr/lib/gcc/x86_64-linux-gnu/5/../../../x86_64-linux-gnu/crt1.o /usr/lib/gcc/x86_64-linux-gnu/5/../../../x86_64-linux-gnu/crti.o /usr/lib/gcc/x86_64-linux-gnu/5/crtbegin.o -L/usr/lib/gcc/x86_64-linux-gnu/5 -L/usr/lib/gcc/x86_64-linux-gnu/5/../../../x86_64-linux-gnu -L/usr/lib/gcc/x86_64-linux-gnu/5/../../../../lib -L/lib/x86_64-linux-gnu -L/lib/../lib -L/usr/lib/x86_64-linux-gnu -L/usr/lib/../lib -L/usr/lib/gcc/x86_64-linux-gnu/5/../../.. CMakeFiles/cmTC_1b6e6.dir/CMakeCCompilerABI.c.o -lgcc --as-needed -lgcc_s --no-as-needed -lc -lgcc --as-needed -lgcc_s --no-as-needed /usr/lib/gcc/x86_64-linux-gnu/5/crtend.o /usr/lib/gcc/x86_64-linux-gnu/5/../../../x86_64-linux-gnu/crtn.o] arg [/usr/lib/gcc/x86_64-linux-gnu/5/collect2] ==> ignore arg [-plugin] ==> ignore arg [/usr/lib/gcc/x86_64-linux-gnu/5/liblto_plugin.so] ==> ignore arg [-plugin-opt=/usr/lib/gcc/x86_64-linux-gnu/5/lto-wrapper] ==> ignore arg [-plugin-opt=-fresolution=/tmp/ccGW6Hat.res] ==> ignore arg [-plugin-opt=-pass-through=-lgcc] ==> ignore arg [-plugin-opt=-pass-through=-lgcc_s] ==> ignore arg [-plugin-opt=-pass-through=-lc] ==> ignore arg [-plugin-opt=-pass-through=-lgcc] ==> ignore arg [-plugin-opt=-pass-through=-lgcc_s] ==> ignore arg [--sysroot=/] ==> ignore arg [--build-id] ==> ignore arg [--eh-frame-hdr] ==> ignore arg [-m] ==> ignore arg [elf_x86_64] ==> ignore arg [--hash-style=gnu] ==> ignore arg [--as-needed] ==> ignore arg [-export-dynamic] ==> ignore arg [-dynamic-linker] ==> ignore arg [/lib64/ld-linux-x86-64.so.2] ==> ignore arg [-zrelro] ==> ignore arg [-o] ==> ignore arg [cmTC_1b6e6] ==> ignore arg [/usr/lib/gcc/x86_64-linux-gnu/5/../../../x86_64-linux-gnu/crt1.o] ==> ignore arg [/usr/lib/gcc/x86_64-linux-gnu/5/../../../x86_64-linux-gnu/crti.o] ==> ignore arg [/usr/lib/gcc/x86_64-linux-gnu/5/crtbegin.o] ==> ignore arg [-L/usr/lib/gcc/x86_64-linux-gnu/5] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/5] arg [-L/usr/lib/gcc/x86_64-linux-gnu/5/../../../x86_64-linux-gnu] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/5/../../../x86_64-linux-gnu] arg [-L/usr/lib/gcc/x86_64-linux-gnu/5/../../../../lib] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/5/../../../../lib] arg [-L/lib/x86_64-linux-gnu] ==> dir [/lib/x86_64-linux-gnu] arg [-L/lib/../lib] ==> dir [/lib/../lib] arg [-L/usr/lib/x86_64-linux-gnu] ==> dir [/usr/lib/x86_64-linux-gnu] arg [-L/usr/lib/../lib] ==> dir [/usr/lib/../lib] arg [-L/usr/lib/gcc/x86_64-linux-gnu/5/../../..] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/5/../../..] arg [CMakeFiles/cmTC_1b6e6.dir/CMakeCCompilerABI.c.o] ==> ignore arg [-lgcc] ==> lib [gcc] arg [--as-needed] ==> ignore arg [-lgcc_s] ==> lib [gcc_s] arg [--no-as-needed] ==> ignore arg [-lc] ==> lib [c] arg [-lgcc] ==> lib [gcc] arg [--as-needed] ==> ignore arg [-lgcc_s] ==> lib [gcc_s] arg [--no-as-needed] ==> ignore arg [/usr/lib/gcc/x86_64-linux-gnu/5/crtend.o] ==> ignore arg [/usr/lib/gcc/x86_64-linux-gnu/5/../../../x86_64-linux-gnu/crtn.o] ==> ignore collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/5] ==> [/usr/lib/gcc/x86_64-linux-gnu/5] collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/5/../../../x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu] collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/5/../../../../lib] ==> [/usr/lib] collapse library dir [/lib/x86_64-linux-gnu] ==> [/lib/x86_64-linux-gnu] collapse library dir [/lib/../lib] ==> [/lib] collapse library dir [/usr/lib/x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu] collapse library dir [/usr/lib/../lib] ==> [/usr/lib] collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/5/../../..] ==> [/usr/lib] implicit libs: [gcc;gcc_s;c;gcc;gcc_s] implicit dirs: [/usr/lib/gcc/x86_64-linux-gnu/5;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib] implicit fwks: [] Detecting C [-std=c11] compiler features compiled with the following output: Change Dir: /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp Run Build Command:"/usr/bin/make" "cmTC_d3b2f/fast" /usr/bin/make -f CMakeFiles/cmTC_d3b2f.dir/build.make CMakeFiles/cmTC_d3b2f.dir/build make[1]: Entering directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp' Building C object CMakeFiles/cmTC_d3b2f.dir/feature_tests.c.o /usr/bin/cc -std=c11 -o CMakeFiles/cmTC_d3b2f.dir/feature_tests.c.o -c /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/feature_tests.c Linking C executable cmTC_d3b2f /home/zn/.ide/clion/bin/cmake/bin/cmake -E cmake_link_script CMakeFiles/cmTC_d3b2f.dir/link.txt --verbose=1 /usr/bin/cc -rdynamic CMakeFiles/cmTC_d3b2f.dir/feature_tests.c.o -o cmTC_d3b2f make[1]: Leaving directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp' Feature record: C_FEATURE:1c_function_prototypes Feature record: C_FEATURE:1c_restrict Feature record: C_FEATURE:1c_static_assert Feature record: C_FEATURE:1c_variadic_macros Detecting C [-std=c99] compiler features compiled with the following output: Change Dir: /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp Run Build Command:"/usr/bin/make" "cmTC_71a21/fast" /usr/bin/make -f CMakeFiles/cmTC_71a21.dir/build.make CMakeFiles/cmTC_71a21.dir/build make[1]: Entering directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp' Building C object CMakeFiles/cmTC_71a21.dir/feature_tests.c.o /usr/bin/cc -std=c99 -o CMakeFiles/cmTC_71a21.dir/feature_tests.c.o -c /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/feature_tests.c Linking C executable cmTC_71a21 /home/zn/.ide/clion/bin/cmake/bin/cmake -E cmake_link_script CMakeFiles/cmTC_71a21.dir/link.txt --verbose=1 /usr/bin/cc -rdynamic CMakeFiles/cmTC_71a21.dir/feature_tests.c.o -o cmTC_71a21 make[1]: Leaving directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp' Feature record: C_FEATURE:1c_function_prototypes Feature record: C_FEATURE:1c_restrict Feature record: C_FEATURE:0c_static_assert Feature record: C_FEATURE:1c_variadic_macros Detecting C [-std=c90] compiler features compiled with the following output: Change Dir: /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp Run Build Command:"/usr/bin/make" "cmTC_2eb43/fast" /usr/bin/make -f CMakeFiles/cmTC_2eb43.dir/build.make CMakeFiles/cmTC_2eb43.dir/build make[1]: Entering directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp' Building C object CMakeFiles/cmTC_2eb43.dir/feature_tests.c.o /usr/bin/cc -std=c90 -o CMakeFiles/cmTC_2eb43.dir/feature_tests.c.o -c /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/feature_tests.c Linking C executable cmTC_2eb43 /home/zn/.ide/clion/bin/cmake/bin/cmake -E cmake_link_script CMakeFiles/cmTC_2eb43.dir/link.txt --verbose=1 /usr/bin/cc -rdynamic CMakeFiles/cmTC_2eb43.dir/feature_tests.c.o -o cmTC_2eb43 make[1]: Leaving directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp' Feature record: C_FEATURE:1c_function_prototypes Feature record: C_FEATURE:0c_restrict Feature record: C_FEATURE:0c_static_assert Feature record: C_FEATURE:0c_variadic_macros Determining if the CXX compiler works passed with the following output: Change Dir: /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp Run Build Command:"/usr/bin/make" "cmTC_c6cd7/fast" /usr/bin/make -f CMakeFiles/cmTC_c6cd7.dir/build.make CMakeFiles/cmTC_c6cd7.dir/build make[1]: Entering directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp' Building CXX object CMakeFiles/cmTC_c6cd7.dir/testCXXCompiler.cxx.o /usr/bin/c++ -o CMakeFiles/cmTC_c6cd7.dir/testCXXCompiler.cxx.o -c /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp/testCXXCompiler.cxx Linking CXX executable cmTC_c6cd7 /home/zn/.ide/clion/bin/cmake/bin/cmake -E cmake_link_script CMakeFiles/cmTC_c6cd7.dir/link.txt --verbose=1 /usr/bin/c++ -rdynamic CMakeFiles/cmTC_c6cd7.dir/testCXXCompiler.cxx.o -o cmTC_c6cd7 make[1]: Leaving directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp' Detecting CXX compiler ABI info compiled with the following output: Change Dir: /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp Run Build Command:"/usr/bin/make" "cmTC_d3f63/fast" /usr/bin/make -f CMakeFiles/cmTC_d3f63.dir/build.make CMakeFiles/cmTC_d3f63.dir/build make[1]: Entering directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp' Building CXX object CMakeFiles/cmTC_d3f63.dir/CMakeCXXCompilerABI.cpp.o /usr/bin/c++ -o CMakeFiles/cmTC_d3f63.dir/CMakeCXXCompilerABI.cpp.o -c /home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeCXXCompilerABI.cpp Linking CXX executable cmTC_d3f63 /home/zn/.ide/clion/bin/cmake/bin/cmake -E cmake_link_script CMakeFiles/cmTC_d3f63.dir/link.txt --verbose=1 /usr/bin/c++ -v -rdynamic CMakeFiles/cmTC_d3f63.dir/CMakeCXXCompilerABI.cpp.o -o cmTC_d3f63 Using built-in specs. COLLECT_GCC=/usr/bin/c++ COLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/5/lto-wrapper Target: x86_64-linux-gnu Configured with: ../src/configure -v --with-pkgversion='Ubuntu 5.4.0-6ubuntu1~16.04.9' --with-bugurl=file:///usr/share/doc/gcc-5/README.Bugs --enable-languages=c,ada,c++,java,go,d,fortran,objc,obj-c++ --prefix=/usr --program-suffix=-5 --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --libdir=/usr/lib --enable-nls --with-sysroot=/ --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --with-default-libstdcxx-abi=new --enable-gnu-unique-object --disable-vtable-verify --enable-libmpx --enable-plugin --with-system-zlib --disable-browser-plugin --enable-java-awt=gtk --enable-gtk-cairo --with-java-home=/usr/lib/jvm/java-1.5.0-gcj-5-amd64/jre --enable-java-home --with-jvm-root-dir=/usr/lib/jvm/java-1.5.0-gcj-5-amd64 --with-jvm-jar-dir=/usr/lib/jvm-exports/java-1.5.0-gcj-5-amd64 --with-arch-directory=amd64 --with-ecj-jar=/usr/share/java/eclipse-ecj.jar --enable-objc-gc --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32,m64,mx32 --enable-multilib --with-tune=generic --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu Thread model: posix gcc version 5.4.0 20160609 (Ubuntu 5.4.0-6ubuntu1~16.04.9) COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/5/:/usr/lib/gcc/x86_64-linux-gnu/5/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/5/:/usr/lib/gcc/x86_64-linux-gnu/ LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/5/:/usr/lib/gcc/x86_64-linux-gnu/5/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/5/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/5/../../../:/lib/:/usr/lib/ COLLECT_GCC_OPTIONS='-v' '-rdynamic' '-o' 'cmTC_d3f63' '-shared-libgcc' '-mtune=generic' '-march=x86-64' /usr/lib/gcc/x86_64-linux-gnu/5/collect2 -plugin /usr/lib/gcc/x86_64-linux-gnu/5/liblto_plugin.so -plugin-opt=/usr/lib/gcc/x86_64-linux-gnu/5/lto-wrapper -plugin-opt=-fresolution=/tmp/ccHH93NP.res -plugin-opt=-pass-through=-lgcc_s -plugin-opt=-pass-through=-lgcc -plugin-opt=-pass-through=-lc -plugin-opt=-pass-through=-lgcc_s -plugin-opt=-pass-through=-lgcc --sysroot=/ --build-id --eh-frame-hdr -m elf_x86_64 --hash-style=gnu --as-needed -export-dynamic -dynamic-linker /lib64/ld-linux-x86-64.so.2 -z relro -o cmTC_d3f63 /usr/lib/gcc/x86_64-linux-gnu/5/../../../x86_64-linux-gnu/crt1.o /usr/lib/gcc/x86_64-linux-gnu/5/../../../x86_64-linux-gnu/crti.o /usr/lib/gcc/x86_64-linux-gnu/5/crtbegin.o -L/usr/lib/gcc/x86_64-linux-gnu/5 -L/usr/lib/gcc/x86_64-linux-gnu/5/../../../x86_64-linux-gnu -L/usr/lib/gcc/x86_64-linux-gnu/5/../../../../lib -L/lib/x86_64-linux-gnu -L/lib/../lib -L/usr/lib/x86_64-linux-gnu -L/usr/lib/../lib -L/usr/lib/gcc/x86_64-linux-gnu/5/../../.. CMakeFiles/cmTC_d3f63.dir/CMakeCXXCompilerABI.cpp.o -lstdc++ -lm -lgcc_s -lgcc -lc -lgcc_s -lgcc /usr/lib/gcc/x86_64-linux-gnu/5/crtend.o /usr/lib/gcc/x86_64-linux-gnu/5/../../../x86_64-linux-gnu/crtn.o make[1]: Leaving directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp' Parsed CXX implicit link information from above output: link line regex: [^( *|.*[/\])(ld|CMAKE_LINK_STARTFILE-NOTFOUND|([^/\]+-)?ld|collect2)[^/\]*( |$)] ignore line: [Change Dir: /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp] ignore line: [] ignore line: [Run Build Command:"/usr/bin/make" "cmTC_d3f63/fast"] ignore line: [/usr/bin/make -f CMakeFiles/cmTC_d3f63.dir/build.make CMakeFiles/cmTC_d3f63.dir/build] ignore line: [make[1]: Entering directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp'] ignore line: [Building CXX object CMakeFiles/cmTC_d3f63.dir/CMakeCXXCompilerABI.cpp.o] ignore line: [/usr/bin/c++ -o CMakeFiles/cmTC_d3f63.dir/CMakeCXXCompilerABI.cpp.o -c /home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeCXXCompilerABI.cpp] ignore line: [Linking CXX executable cmTC_d3f63] ignore line: [/home/zn/.ide/clion/bin/cmake/bin/cmake -E cmake_link_script CMakeFiles/cmTC_d3f63.dir/link.txt --verbose=1] ignore line: [/usr/bin/c++ -v -rdynamic CMakeFiles/cmTC_d3f63.dir/CMakeCXXCompilerABI.cpp.o -o cmTC_d3f63 ] ignore line: [Using built-in specs.] ignore line: [COLLECT_GCC=/usr/bin/c++] ignore line: [COLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/5/lto-wrapper] ignore line: [Target: x86_64-linux-gnu] ignore line: [Configured with: ../src/configure -v --with-pkgversion='Ubuntu 5.4.0-6ubuntu1~16.04.9' --with-bugurl=file:///usr/share/doc/gcc-5/README.Bugs --enable-languages=c,ada,c++,java,go,d,fortran,objc,obj-c++ --prefix=/usr --program-suffix=-5 --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --libdir=/usr/lib --enable-nls --with-sysroot=/ --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --with-default-libstdcxx-abi=new --enable-gnu-unique-object --disable-vtable-verify --enable-libmpx --enable-plugin --with-system-zlib --disable-browser-plugin --enable-java-awt=gtk --enable-gtk-cairo --with-java-home=/usr/lib/jvm/java-1.5.0-gcj-5-amd64/jre --enable-java-home --with-jvm-root-dir=/usr/lib/jvm/java-1.5.0-gcj-5-amd64 --with-jvm-jar-dir=/usr/lib/jvm-exports/java-1.5.0-gcj-5-amd64 --with-arch-directory=amd64 --with-ecj-jar=/usr/share/java/eclipse-ecj.jar --enable-objc-gc --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32,m64,mx32 --enable-multilib --with-tune=generic --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu] ignore line: [Thread model: posix] ignore line: [gcc version 5.4.0 20160609 (Ubuntu 5.4.0-6ubuntu1~16.04.9) ] ignore line: [COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/5/:/usr/lib/gcc/x86_64-linux-gnu/5/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/5/:/usr/lib/gcc/x86_64-linux-gnu/] ignore line: [LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/5/:/usr/lib/gcc/x86_64-linux-gnu/5/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/5/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/5/../../../:/lib/:/usr/lib/] ignore line: [COLLECT_GCC_OPTIONS='-v' '-rdynamic' '-o' 'cmTC_d3f63' '-shared-libgcc' '-mtune=generic' '-march=x86-64'] link line: [ /usr/lib/gcc/x86_64-linux-gnu/5/collect2 -plugin /usr/lib/gcc/x86_64-linux-gnu/5/liblto_plugin.so -plugin-opt=/usr/lib/gcc/x86_64-linux-gnu/5/lto-wrapper -plugin-opt=-fresolution=/tmp/ccHH93NP.res -plugin-opt=-pass-through=-lgcc_s -plugin-opt=-pass-through=-lgcc -plugin-opt=-pass-through=-lc -plugin-opt=-pass-through=-lgcc_s -plugin-opt=-pass-through=-lgcc --sysroot=/ --build-id --eh-frame-hdr -m elf_x86_64 --hash-style=gnu --as-needed -export-dynamic -dynamic-linker /lib64/ld-linux-x86-64.so.2 -z relro -o cmTC_d3f63 /usr/lib/gcc/x86_64-linux-gnu/5/../../../x86_64-linux-gnu/crt1.o /usr/lib/gcc/x86_64-linux-gnu/5/../../../x86_64-linux-gnu/crti.o /usr/lib/gcc/x86_64-linux-gnu/5/crtbegin.o -L/usr/lib/gcc/x86_64-linux-gnu/5 -L/usr/lib/gcc/x86_64-linux-gnu/5/../../../x86_64-linux-gnu -L/usr/lib/gcc/x86_64-linux-gnu/5/../../../../lib -L/lib/x86_64-linux-gnu -L/lib/../lib -L/usr/lib/x86_64-linux-gnu -L/usr/lib/../lib -L/usr/lib/gcc/x86_64-linux-gnu/5/../../.. CMakeFiles/cmTC_d3f63.dir/CMakeCXXCompilerABI.cpp.o -lstdc++ -lm -lgcc_s -lgcc -lc -lgcc_s -lgcc /usr/lib/gcc/x86_64-linux-gnu/5/crtend.o /usr/lib/gcc/x86_64-linux-gnu/5/../../../x86_64-linux-gnu/crtn.o] arg [/usr/lib/gcc/x86_64-linux-gnu/5/collect2] ==> ignore arg [-plugin] ==> ignore arg [/usr/lib/gcc/x86_64-linux-gnu/5/liblto_plugin.so] ==> ignore arg [-plugin-opt=/usr/lib/gcc/x86_64-linux-gnu/5/lto-wrapper] ==> ignore arg [-plugin-opt=-fresolution=/tmp/ccHH93NP.res] ==> ignore arg [-plugin-opt=-pass-through=-lgcc_s] ==> ignore arg [-plugin-opt=-pass-through=-lgcc] ==> ignore arg [-plugin-opt=-pass-through=-lc] ==> ignore arg [-plugin-opt=-pass-through=-lgcc_s] ==> ignore arg [-plugin-opt=-pass-through=-lgcc] ==> ignore arg [--sysroot=/] ==> ignore arg [--build-id] ==> ignore arg [--eh-frame-hdr] ==> ignore arg [-m] ==> ignore arg [elf_x86_64] ==> ignore arg [--hash-style=gnu] ==> ignore arg [--as-needed] ==> ignore arg [-export-dynamic] ==> ignore arg [-dynamic-linker] ==> ignore arg [/lib64/ld-linux-x86-64.so.2] ==> ignore arg [-zrelro] ==> ignore arg [-o] ==> ignore arg [cmTC_d3f63] ==> ignore arg [/usr/lib/gcc/x86_64-linux-gnu/5/../../../x86_64-linux-gnu/crt1.o] ==> ignore arg [/usr/lib/gcc/x86_64-linux-gnu/5/../../../x86_64-linux-gnu/crti.o] ==> ignore arg [/usr/lib/gcc/x86_64-linux-gnu/5/crtbegin.o] ==> ignore arg [-L/usr/lib/gcc/x86_64-linux-gnu/5] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/5] arg [-L/usr/lib/gcc/x86_64-linux-gnu/5/../../../x86_64-linux-gnu] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/5/../../../x86_64-linux-gnu] arg [-L/usr/lib/gcc/x86_64-linux-gnu/5/../../../../lib] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/5/../../../../lib] arg [-L/lib/x86_64-linux-gnu] ==> dir [/lib/x86_64-linux-gnu] arg [-L/lib/../lib] ==> dir [/lib/../lib] arg [-L/usr/lib/x86_64-linux-gnu] ==> dir [/usr/lib/x86_64-linux-gnu] arg [-L/usr/lib/../lib] ==> dir [/usr/lib/../lib] arg [-L/usr/lib/gcc/x86_64-linux-gnu/5/../../..] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/5/../../..] arg [CMakeFiles/cmTC_d3f63.dir/CMakeCXXCompilerABI.cpp.o] ==> ignore arg [-lstdc++] ==> lib [stdc++] arg [-lm] ==> lib [m] arg [-lgcc_s] ==> lib [gcc_s] arg [-lgcc] ==> lib [gcc] arg [-lc] ==> lib [c] arg [-lgcc_s] ==> lib [gcc_s] arg [-lgcc] ==> lib [gcc] arg [/usr/lib/gcc/x86_64-linux-gnu/5/crtend.o] ==> ignore arg [/usr/lib/gcc/x86_64-linux-gnu/5/../../../x86_64-linux-gnu/crtn.o] ==> ignore collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/5] ==> [/usr/lib/gcc/x86_64-linux-gnu/5] collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/5/../../../x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu] collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/5/../../../../lib] ==> [/usr/lib] collapse library dir [/lib/x86_64-linux-gnu] ==> [/lib/x86_64-linux-gnu] collapse library dir [/lib/../lib] ==> [/lib] collapse library dir [/usr/lib/x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu] collapse library dir [/usr/lib/../lib] ==> [/usr/lib] collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/5/../../..] ==> [/usr/lib] implicit libs: [stdc++;m;gcc_s;gcc;c;gcc_s;gcc] implicit dirs: [/usr/lib/gcc/x86_64-linux-gnu/5;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib] implicit fwks: [] Detecting CXX [-std=c++1z] compiler features compiled with the following output: Change Dir: /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp Run Build Command:"/usr/bin/make" "cmTC_07712/fast" /usr/bin/make -f CMakeFiles/cmTC_07712.dir/build.make CMakeFiles/cmTC_07712.dir/build make[1]: Entering directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp' Building CXX object CMakeFiles/cmTC_07712.dir/feature_tests.cxx.o /usr/bin/c++ -std=c++1z -o CMakeFiles/cmTC_07712.dir/feature_tests.cxx.o -c /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/feature_tests.cxx Linking CXX executable cmTC_07712 /home/zn/.ide/clion/bin/cmake/bin/cmake -E cmake_link_script CMakeFiles/cmTC_07712.dir/link.txt --verbose=1 /usr/bin/c++ -rdynamic CMakeFiles/cmTC_07712.dir/feature_tests.cxx.o -o cmTC_07712 make[1]: Leaving directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp' Feature record: CXX_FEATURE:1cxx_aggregate_default_initializers Feature record: CXX_FEATURE:1cxx_alias_templates Feature record: CXX_FEATURE:1cxx_alignas Feature record: CXX_FEATURE:1cxx_alignof Feature record: CXX_FEATURE:1cxx_attributes Feature record: CXX_FEATURE:1cxx_attribute_deprecated Feature record: CXX_FEATURE:1cxx_auto_type Feature record: CXX_FEATURE:1cxx_binary_literals Feature record: CXX_FEATURE:1cxx_constexpr Feature record: CXX_FEATURE:1cxx_contextual_conversions Feature record: CXX_FEATURE:1cxx_decltype Feature record: CXX_FEATURE:1cxx_decltype_auto Feature record: CXX_FEATURE:1cxx_decltype_incomplete_return_types Feature record: CXX_FEATURE:1cxx_default_function_template_args Feature record: CXX_FEATURE:1cxx_defaulted_functions Feature record: CXX_FEATURE:1cxx_defaulted_move_initializers Feature record: CXX_FEATURE:1cxx_delegating_constructors Feature record: CXX_FEATURE:1cxx_deleted_functions Feature record: CXX_FEATURE:1cxx_digit_separators Feature record: CXX_FEATURE:1cxx_enum_forward_declarations Feature record: CXX_FEATURE:1cxx_explicit_conversions Feature record: CXX_FEATURE:1cxx_extended_friend_declarations Feature record: CXX_FEATURE:1cxx_extern_templates Feature record: CXX_FEATURE:1cxx_final Feature record: CXX_FEATURE:1cxx_func_identifier Feature record: CXX_FEATURE:1cxx_generalized_initializers Feature record: CXX_FEATURE:1cxx_generic_lambdas Feature record: CXX_FEATURE:1cxx_inheriting_constructors Feature record: CXX_FEATURE:1cxx_inline_namespaces Feature record: CXX_FEATURE:1cxx_lambdas Feature record: CXX_FEATURE:1cxx_lambda_init_captures Feature record: CXX_FEATURE:1cxx_local_type_template_args Feature record: CXX_FEATURE:1cxx_long_long_type Feature record: CXX_FEATURE:1cxx_noexcept Feature record: CXX_FEATURE:1cxx_nonstatic_member_init Feature record: CXX_FEATURE:1cxx_nullptr Feature record: CXX_FEATURE:1cxx_override Feature record: CXX_FEATURE:1cxx_range_for Feature record: CXX_FEATURE:1cxx_raw_string_literals Feature record: CXX_FEATURE:1cxx_reference_qualified_functions Feature record: CXX_FEATURE:1cxx_relaxed_constexpr Feature record: CXX_FEATURE:1cxx_return_type_deduction Feature record: CXX_FEATURE:1cxx_right_angle_brackets Feature record: CXX_FEATURE:1cxx_rvalue_references Feature record: CXX_FEATURE:1cxx_sizeof_member Feature record: CXX_FEATURE:1cxx_static_assert Feature record: CXX_FEATURE:1cxx_strong_enums Feature record: CXX_FEATURE:1cxx_template_template_parameters Feature record: CXX_FEATURE:1cxx_thread_local Feature record: CXX_FEATURE:1cxx_trailing_return_types Feature record: CXX_FEATURE:1cxx_unicode_literals Feature record: CXX_FEATURE:1cxx_uniform_initialization Feature record: CXX_FEATURE:1cxx_unrestricted_unions Feature record: CXX_FEATURE:1cxx_user_literals Feature record: CXX_FEATURE:1cxx_variable_templates Feature record: CXX_FEATURE:1cxx_variadic_macros Feature record: CXX_FEATURE:1cxx_variadic_templates Detecting CXX [-std=c++14] compiler features compiled with the following output: Change Dir: /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp Run Build Command:"/usr/bin/make" "cmTC_d0df9/fast" /usr/bin/make -f CMakeFiles/cmTC_d0df9.dir/build.make CMakeFiles/cmTC_d0df9.dir/build make[1]: Entering directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp' Building CXX object CMakeFiles/cmTC_d0df9.dir/feature_tests.cxx.o /usr/bin/c++ -std=c++14 -o CMakeFiles/cmTC_d0df9.dir/feature_tests.cxx.o -c /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/feature_tests.cxx Linking CXX executable cmTC_d0df9 /home/zn/.ide/clion/bin/cmake/bin/cmake -E cmake_link_script CMakeFiles/cmTC_d0df9.dir/link.txt --verbose=1 /usr/bin/c++ -rdynamic CMakeFiles/cmTC_d0df9.dir/feature_tests.cxx.o -o cmTC_d0df9 make[1]: Leaving directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp' Feature record: CXX_FEATURE:1cxx_aggregate_default_initializers Feature record: CXX_FEATURE:1cxx_alias_templates Feature record: CXX_FEATURE:1cxx_alignas Feature record: CXX_FEATURE:1cxx_alignof Feature record: CXX_FEATURE:1cxx_attributes Feature record: CXX_FEATURE:1cxx_attribute_deprecated Feature record: CXX_FEATURE:1cxx_auto_type Feature record: CXX_FEATURE:1cxx_binary_literals Feature record: CXX_FEATURE:1cxx_constexpr Feature record: CXX_FEATURE:1cxx_contextual_conversions Feature record: CXX_FEATURE:1cxx_decltype Feature record: CXX_FEATURE:1cxx_decltype_auto Feature record: CXX_FEATURE:1cxx_decltype_incomplete_return_types Feature record: CXX_FEATURE:1cxx_default_function_template_args Feature record: CXX_FEATURE:1cxx_defaulted_functions Feature record: CXX_FEATURE:1cxx_defaulted_move_initializers Feature record: CXX_FEATURE:1cxx_delegating_constructors Feature record: CXX_FEATURE:1cxx_deleted_functions Feature record: CXX_FEATURE:1cxx_digit_separators Feature record: CXX_FEATURE:1cxx_enum_forward_declarations Feature record: CXX_FEATURE:1cxx_explicit_conversions Feature record: CXX_FEATURE:1cxx_extended_friend_declarations Feature record: CXX_FEATURE:1cxx_extern_templates Feature record: CXX_FEATURE:1cxx_final Feature record: CXX_FEATURE:1cxx_func_identifier Feature record: CXX_FEATURE:1cxx_generalized_initializers Feature record: CXX_FEATURE:1cxx_generic_lambdas Feature record: CXX_FEATURE:1cxx_inheriting_constructors Feature record: CXX_FEATURE:1cxx_inline_namespaces Feature record: CXX_FEATURE:1cxx_lambdas Feature record: CXX_FEATURE:1cxx_lambda_init_captures Feature record: CXX_FEATURE:1cxx_local_type_template_args Feature record: CXX_FEATURE:1cxx_long_long_type Feature record: CXX_FEATURE:1cxx_noexcept Feature record: CXX_FEATURE:1cxx_nonstatic_member_init Feature record: CXX_FEATURE:1cxx_nullptr Feature record: CXX_FEATURE:1cxx_override Feature record: CXX_FEATURE:1cxx_range_for Feature record: CXX_FEATURE:1cxx_raw_string_literals Feature record: CXX_FEATURE:1cxx_reference_qualified_functions Feature record: CXX_FEATURE:1cxx_relaxed_constexpr Feature record: CXX_FEATURE:1cxx_return_type_deduction Feature record: CXX_FEATURE:1cxx_right_angle_brackets Feature record: CXX_FEATURE:1cxx_rvalue_references Feature record: CXX_FEATURE:1cxx_sizeof_member Feature record: CXX_FEATURE:1cxx_static_assert Feature record: CXX_FEATURE:1cxx_strong_enums Feature record: CXX_FEATURE:1cxx_template_template_parameters Feature record: CXX_FEATURE:1cxx_thread_local Feature record: CXX_FEATURE:1cxx_trailing_return_types Feature record: CXX_FEATURE:1cxx_unicode_literals Feature record: CXX_FEATURE:1cxx_uniform_initialization Feature record: CXX_FEATURE:1cxx_unrestricted_unions Feature record: CXX_FEATURE:1cxx_user_literals Feature record: CXX_FEATURE:1cxx_variable_templates Feature record: CXX_FEATURE:1cxx_variadic_macros Feature record: CXX_FEATURE:1cxx_variadic_templates Detecting CXX [-std=c++11] compiler features compiled with the following output: Change Dir: /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp Run Build Command:"/usr/bin/make" "cmTC_a7bdf/fast" /usr/bin/make -f CMakeFiles/cmTC_a7bdf.dir/build.make CMakeFiles/cmTC_a7bdf.dir/build make[1]: Entering directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp' Building CXX object CMakeFiles/cmTC_a7bdf.dir/feature_tests.cxx.o /usr/bin/c++ -std=c++11 -o CMakeFiles/cmTC_a7bdf.dir/feature_tests.cxx.o -c /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/feature_tests.cxx Linking CXX executable cmTC_a7bdf /home/zn/.ide/clion/bin/cmake/bin/cmake -E cmake_link_script CMakeFiles/cmTC_a7bdf.dir/link.txt --verbose=1 /usr/bin/c++ -rdynamic CMakeFiles/cmTC_a7bdf.dir/feature_tests.cxx.o -o cmTC_a7bdf make[1]: Leaving directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp' Feature record: CXX_FEATURE:0cxx_aggregate_default_initializers Feature record: CXX_FEATURE:1cxx_alias_templates Feature record: CXX_FEATURE:1cxx_alignas Feature record: CXX_FEATURE:1cxx_alignof Feature record: CXX_FEATURE:1cxx_attributes Feature record: CXX_FEATURE:0cxx_attribute_deprecated Feature record: CXX_FEATURE:1cxx_auto_type Feature record: CXX_FEATURE:0cxx_binary_literals Feature record: CXX_FEATURE:1cxx_constexpr Feature record: CXX_FEATURE:0cxx_contextual_conversions Feature record: CXX_FEATURE:1cxx_decltype Feature record: CXX_FEATURE:0cxx_decltype_auto Feature record: CXX_FEATURE:1cxx_decltype_incomplete_return_types Feature record: CXX_FEATURE:1cxx_default_function_template_args Feature record: CXX_FEATURE:1cxx_defaulted_functions Feature record: CXX_FEATURE:1cxx_defaulted_move_initializers Feature record: CXX_FEATURE:1cxx_delegating_constructors Feature record: CXX_FEATURE:1cxx_deleted_functions Feature record: CXX_FEATURE:0cxx_digit_separators Feature record: CXX_FEATURE:1cxx_enum_forward_declarations Feature record: CXX_FEATURE:1cxx_explicit_conversions Feature record: CXX_FEATURE:1cxx_extended_friend_declarations Feature record: CXX_FEATURE:1cxx_extern_templates Feature record: CXX_FEATURE:1cxx_final Feature record: CXX_FEATURE:1cxx_func_identifier Feature record: CXX_FEATURE:1cxx_generalized_initializers Feature record: CXX_FEATURE:0cxx_generic_lambdas Feature record: CXX_FEATURE:1cxx_inheriting_constructors Feature record: CXX_FEATURE:1cxx_inline_namespaces Feature record: CXX_FEATURE:1cxx_lambdas Feature record: CXX_FEATURE:0cxx_lambda_init_captures Feature record: CXX_FEATURE:1cxx_local_type_template_args Feature record: CXX_FEATURE:1cxx_long_long_type Feature record: CXX_FEATURE:1cxx_noexcept Feature record: CXX_FEATURE:1cxx_nonstatic_member_init Feature record: CXX_FEATURE:1cxx_nullptr Feature record: CXX_FEATURE:1cxx_override Feature record: CXX_FEATURE:1cxx_range_for Feature record: CXX_FEATURE:1cxx_raw_string_literals Feature record: CXX_FEATURE:1cxx_reference_qualified_functions Feature record: CXX_FEATURE:0cxx_relaxed_constexpr Feature record: CXX_FEATURE:0cxx_return_type_deduction Feature record: CXX_FEATURE:1cxx_right_angle_brackets Feature record: CXX_FEATURE:1cxx_rvalue_references Feature record: CXX_FEATURE:1cxx_sizeof_member Feature record: CXX_FEATURE:1cxx_static_assert Feature record: CXX_FEATURE:1cxx_strong_enums Feature record: CXX_FEATURE:1cxx_template_template_parameters Feature record: CXX_FEATURE:1cxx_thread_local Feature record: CXX_FEATURE:1cxx_trailing_return_types Feature record: CXX_FEATURE:1cxx_unicode_literals Feature record: CXX_FEATURE:1cxx_uniform_initialization Feature record: CXX_FEATURE:1cxx_unrestricted_unions Feature record: CXX_FEATURE:1cxx_user_literals Feature record: CXX_FEATURE:0cxx_variable_templates Feature record: CXX_FEATURE:1cxx_variadic_macros Feature record: CXX_FEATURE:1cxx_variadic_templates Detecting CXX [-std=c++98] compiler features compiled with the following output: Change Dir: /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp Run Build Command:"/usr/bin/make" "cmTC_73896/fast" /usr/bin/make -f CMakeFiles/cmTC_73896.dir/build.make CMakeFiles/cmTC_73896.dir/build make[1]: Entering directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp' Building CXX object CMakeFiles/cmTC_73896.dir/feature_tests.cxx.o /usr/bin/c++ -std=c++98 -o CMakeFiles/cmTC_73896.dir/feature_tests.cxx.o -c /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/feature_tests.cxx Linking CXX executable cmTC_73896 /home/zn/.ide/clion/bin/cmake/bin/cmake -E cmake_link_script CMakeFiles/cmTC_73896.dir/link.txt --verbose=1 /usr/bin/c++ -rdynamic CMakeFiles/cmTC_73896.dir/feature_tests.cxx.o -o cmTC_73896 make[1]: Leaving directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp' Feature record: CXX_FEATURE:0cxx_aggregate_default_initializers Feature record: CXX_FEATURE:0cxx_alias_templates Feature record: CXX_FEATURE:0cxx_alignas Feature record: CXX_FEATURE:0cxx_alignof Feature record: CXX_FEATURE:0cxx_attributes Feature record: CXX_FEATURE:0cxx_attribute_deprecated Feature record: CXX_FEATURE:0cxx_auto_type Feature record: CXX_FEATURE:0cxx_binary_literals Feature record: CXX_FEATURE:0cxx_constexpr Feature record: CXX_FEATURE:0cxx_contextual_conversions Feature record: CXX_FEATURE:0cxx_decltype Feature record: CXX_FEATURE:0cxx_decltype_auto Feature record: CXX_FEATURE:0cxx_decltype_incomplete_return_types Feature record: CXX_FEATURE:0cxx_default_function_template_args Feature record: CXX_FEATURE:0cxx_defaulted_functions Feature record: CXX_FEATURE:0cxx_defaulted_move_initializers Feature record: CXX_FEATURE:0cxx_delegating_constructors Feature record: CXX_FEATURE:0cxx_deleted_functions Feature record: CXX_FEATURE:0cxx_digit_separators Feature record: CXX_FEATURE:0cxx_enum_forward_declarations Feature record: CXX_FEATURE:0cxx_explicit_conversions Feature record: CXX_FEATURE:0cxx_extended_friend_declarations Feature record: CXX_FEATURE:0cxx_extern_templates Feature record: CXX_FEATURE:0cxx_final Feature record: CXX_FEATURE:0cxx_func_identifier Feature record: CXX_FEATURE:0cxx_generalized_initializers Feature record: CXX_FEATURE:0cxx_generic_lambdas Feature record: CXX_FEATURE:0cxx_inheriting_constructors Feature record: CXX_FEATURE:0cxx_inline_namespaces Feature record: CXX_FEATURE:0cxx_lambdas Feature record: CXX_FEATURE:0cxx_lambda_init_captures Feature record: CXX_FEATURE:0cxx_local_type_template_args Feature record: CXX_FEATURE:0cxx_long_long_type Feature record: CXX_FEATURE:0cxx_noexcept Feature record: CXX_FEATURE:0cxx_nonstatic_member_init Feature record: CXX_FEATURE:0cxx_nullptr Feature record: CXX_FEATURE:0cxx_override Feature record: CXX_FEATURE:0cxx_range_for Feature record: CXX_FEATURE:0cxx_raw_string_literals Feature record: CXX_FEATURE:0cxx_reference_qualified_functions Feature record: CXX_FEATURE:0cxx_relaxed_constexpr Feature record: CXX_FEATURE:0cxx_return_type_deduction Feature record: CXX_FEATURE:0cxx_right_angle_brackets Feature record: CXX_FEATURE:0cxx_rvalue_references Feature record: CXX_FEATURE:0cxx_sizeof_member Feature record: CXX_FEATURE:0cxx_static_assert Feature record: CXX_FEATURE:0cxx_strong_enums Feature record: CXX_FEATURE:1cxx_template_template_parameters Feature record: CXX_FEATURE:0cxx_thread_local Feature record: CXX_FEATURE:0cxx_trailing_return_types Feature record: CXX_FEATURE:0cxx_unicode_literals Feature record: CXX_FEATURE:0cxx_uniform_initialization Feature record: CXX_FEATURE:0cxx_unrestricted_unions Feature record: CXX_FEATURE:0cxx_user_literals Feature record: CXX_FEATURE:0cxx_variable_templates Feature record: CXX_FEATURE:0cxx_variadic_macros Feature record: CXX_FEATURE:0cxx_variadic_templates Determining if the include file pthread.h exists passed with the following output: Change Dir: /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp Run Build Command:"/usr/bin/make" "cmTC_d2f5c/fast" /usr/bin/make -f CMakeFiles/cmTC_d2f5c.dir/build.make CMakeFiles/cmTC_d2f5c.dir/build make[1]: Entering directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp' Building C object CMakeFiles/cmTC_d2f5c.dir/CheckIncludeFile.c.o /usr/bin/cc -o CMakeFiles/cmTC_d2f5c.dir/CheckIncludeFile.c.o -c /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp/CheckIncludeFile.c Linking C executable cmTC_d2f5c /home/zn/.ide/clion/bin/cmake/bin/cmake -E cmake_link_script CMakeFiles/cmTC_d2f5c.dir/link.txt --verbose=1 /usr/bin/cc -rdynamic CMakeFiles/cmTC_d2f5c.dir/CheckIncludeFile.c.o -o cmTC_d2f5c make[1]: Leaving directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp' Determining if the function pthread_create exists in the pthread passed with the following output: Change Dir: /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp Run Build Command:"/usr/bin/make" "cmTC_c1478/fast" /usr/bin/make -f CMakeFiles/cmTC_c1478.dir/build.make CMakeFiles/cmTC_c1478.dir/build make[1]: Entering directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp' Building C object CMakeFiles/cmTC_c1478.dir/CheckFunctionExists.c.o /usr/bin/cc -DCHECK_FUNCTION_EXISTS=pthread_create -o CMakeFiles/cmTC_c1478.dir/CheckFunctionExists.c.o -c /home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CheckFunctionExists.c Linking C executable cmTC_c1478 /home/zn/.ide/clion/bin/cmake/bin/cmake -E cmake_link_script CMakeFiles/cmTC_c1478.dir/link.txt --verbose=1 /usr/bin/cc -DCHECK_FUNCTION_EXISTS=pthread_create -rdynamic CMakeFiles/cmTC_c1478.dir/CheckFunctionExists.c.o -o cmTC_c1478 -lpthread make[1]: Leaving directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp' ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeRuleHashes.txt ================================================ # Hashes of file build rules. 2c614c39f77a5e21e00ecd0f46df5d82 CMakeFiles/clean_test_results ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/Makefile.cmake ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # The generator used is: set(CMAKE_DEPENDS_GENERATOR "Unix Makefiles") # The top level Makefile was generated from the following files: set(CMAKE_MAKEFILE_DEPENDS "CMakeCache.txt" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeCCompiler.cmake.in" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeCCompilerABI.c" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeCInformation.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeCXXCompiler.cmake.in" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeCXXCompilerABI.cpp" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeCXXInformation.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeCommonLanguageInclude.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeCompilerIdDetection.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeConfigurableFile.in" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeDetermineCCompiler.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeDetermineCXXCompiler.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeDetermineCompileFeatures.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeDetermineCompiler.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeDetermineCompilerABI.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeDetermineCompilerId.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeDetermineSystem.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeExtraGeneratorDetermineCompilerMacrosAndIncludeDirs.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeFindBinUtils.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeFindCodeBlocks.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeFindDependencyMacro.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeGenericSystem.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeLanguageInformation.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeParseArguments.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeParseImplicitLinkInfo.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeSystem.cmake.in" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeSystemSpecificInformation.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeSystemSpecificInitialize.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeTestCCompiler.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeTestCXXCompiler.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeTestCompilerCommon.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeUnixFindMake.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CheckFunctionExists.c" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CheckIncludeFile.c.in" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CheckIncludeFile.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CheckLibraryExists.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CheckSymbolExists.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/ADSP-DetermineCompiler.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/ARMCC-DetermineCompiler.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/AppleClang-DetermineCompiler.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/Borland-DetermineCompiler.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/Bruce-C-DetermineCompiler.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/CMakeCommonCompilerMacros.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/Clang-DetermineCompiler.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/Clang-DetermineCompilerInternal.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/Comeau-CXX-DetermineCompiler.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/Compaq-C-DetermineCompiler.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/Compaq-CXX-DetermineCompiler.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/Cray-DetermineCompiler.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/Embarcadero-DetermineCompiler.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/Fujitsu-DetermineCompiler.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/GHS-DetermineCompiler.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/GNU-C-DetermineCompiler.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/GNU-C-FeatureTests.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/GNU-C.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/GNU-CXX-DetermineCompiler.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/GNU-CXX-FeatureTests.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/GNU-CXX.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/GNU-FindBinUtils.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/GNU.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/HP-C-DetermineCompiler.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/HP-CXX-DetermineCompiler.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/IAR-DetermineCompiler.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/IBMCPP-C-DetermineVersionInternal.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/IBMCPP-CXX-DetermineVersionInternal.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/Intel-DetermineCompiler.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/MIPSpro-DetermineCompiler.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/MSVC-DetermineCompiler.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/NVIDIA-DetermineCompiler.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/OpenWatcom-DetermineCompiler.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/PGI-DetermineCompiler.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/PathScale-DetermineCompiler.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/SCO-DetermineCompiler.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/SDCC-C-DetermineCompiler.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/SunPro-C-DetermineCompiler.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/SunPro-CXX-DetermineCompiler.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/TI-DetermineCompiler.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/TinyCC-C-DetermineCompiler.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/VisualAge-C-DetermineCompiler.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/VisualAge-CXX-DetermineCompiler.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/Watcom-DetermineCompiler.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/XL-C-DetermineCompiler.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/XL-CXX-DetermineCompiler.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/zOS-C-DetermineCompiler.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/zOS-CXX-DetermineCompiler.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/FindBoost.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/FindGTest.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/FindPackageHandleStandardArgs.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/FindPackageMessage.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/FindPythonInterp.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/FindThreads.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/GoogleTest.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Internal/FeatureTesting.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Platform/Linux-Determine-CXX.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Platform/Linux-GNU-C.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Platform/Linux-GNU-CXX.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Platform/Linux-GNU.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Platform/Linux.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Platform/UnixPaths.cmake" "/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/ProcessorCount.cmake" "../CMakeLists.txt" "CMakeFiles/3.9.6/CMakeCCompiler.cmake" "CMakeFiles/3.9.6/CMakeCXXCompiler.cmake" "CMakeFiles/3.9.6/CMakeSystem.cmake" "CMakeFiles/feature_tests.c" "CMakeFiles/feature_tests.cxx" "catkin/catkin_generated/version/package.cmake" "catkin_generated/installspace/_setup_util.py" "catkin_generated/ordered_paths.cmake" "catkin_generated/package.cmake" "../package.xml" "/opt/ros/kinetic/share/actionlib/cmake/actionlib-msg-extras.cmake" "/opt/ros/kinetic/share/actionlib/cmake/actionlibConfig-version.cmake" "/opt/ros/kinetic/share/actionlib/cmake/actionlibConfig.cmake" "/opt/ros/kinetic/share/actionlib_msgs/cmake/actionlib_msgs-extras.cmake" "/opt/ros/kinetic/share/actionlib_msgs/cmake/actionlib_msgs-msg-extras.cmake" "/opt/ros/kinetic/share/actionlib_msgs/cmake/actionlib_msgsConfig-version.cmake" "/opt/ros/kinetic/share/actionlib_msgs/cmake/actionlib_msgsConfig.cmake" "/opt/ros/kinetic/share/catkin/cmake/../package.xml" "/opt/ros/kinetic/share/catkin/cmake/all.cmake" "/opt/ros/kinetic/share/catkin/cmake/assert.cmake" "/opt/ros/kinetic/share/catkin/cmake/atomic_configure_file.cmake" "/opt/ros/kinetic/share/catkin/cmake/catkinConfig-version.cmake" "/opt/ros/kinetic/share/catkin/cmake/catkinConfig.cmake" "/opt/ros/kinetic/share/catkin/cmake/catkin_add_env_hooks.cmake" "/opt/ros/kinetic/share/catkin/cmake/catkin_destinations.cmake" "/opt/ros/kinetic/share/catkin/cmake/catkin_download.cmake" "/opt/ros/kinetic/share/catkin/cmake/catkin_generate_environment.cmake" "/opt/ros/kinetic/share/catkin/cmake/catkin_install_python.cmake" "/opt/ros/kinetic/share/catkin/cmake/catkin_libraries.cmake" "/opt/ros/kinetic/share/catkin/cmake/catkin_metapackage.cmake" "/opt/ros/kinetic/share/catkin/cmake/catkin_package.cmake" "/opt/ros/kinetic/share/catkin/cmake/catkin_package_xml.cmake" "/opt/ros/kinetic/share/catkin/cmake/catkin_python_setup.cmake" "/opt/ros/kinetic/share/catkin/cmake/catkin_workspace.cmake" "/opt/ros/kinetic/share/catkin/cmake/debug_message.cmake" "/opt/ros/kinetic/share/catkin/cmake/em/pkg.pc.em" "/opt/ros/kinetic/share/catkin/cmake/em_expand.cmake" "/opt/ros/kinetic/share/catkin/cmake/empy.cmake" "/opt/ros/kinetic/share/catkin/cmake/find_program_required.cmake" "/opt/ros/kinetic/share/catkin/cmake/interrogate_setup_dot_py.py" "/opt/ros/kinetic/share/catkin/cmake/legacy.cmake" "/opt/ros/kinetic/share/catkin/cmake/list_append_deduplicate.cmake" "/opt/ros/kinetic/share/catkin/cmake/list_append_unique.cmake" "/opt/ros/kinetic/share/catkin/cmake/list_insert_in_workspace_order.cmake" "/opt/ros/kinetic/share/catkin/cmake/platform/lsb.cmake" "/opt/ros/kinetic/share/catkin/cmake/platform/ubuntu.cmake" "/opt/ros/kinetic/share/catkin/cmake/platform/windows.cmake" "/opt/ros/kinetic/share/catkin/cmake/python.cmake" "/opt/ros/kinetic/share/catkin/cmake/safe_execute_process.cmake" "/opt/ros/kinetic/share/catkin/cmake/stamp.cmake" "/opt/ros/kinetic/share/catkin/cmake/string_starts_with.cmake" "/opt/ros/kinetic/share/catkin/cmake/templates/_setup_util.py.in" "/opt/ros/kinetic/share/catkin/cmake/templates/env.sh.in" "/opt/ros/kinetic/share/catkin/cmake/templates/generate_cached_setup.py.in" "/opt/ros/kinetic/share/catkin/cmake/templates/pkg.context.pc.in" "/opt/ros/kinetic/share/catkin/cmake/templates/pkgConfig-version.cmake.in" "/opt/ros/kinetic/share/catkin/cmake/templates/pkgConfig.cmake.in" "/opt/ros/kinetic/share/catkin/cmake/templates/rosinstall.in" "/opt/ros/kinetic/share/catkin/cmake/templates/setup.bash.in" "/opt/ros/kinetic/share/catkin/cmake/templates/setup.sh.in" "/opt/ros/kinetic/share/catkin/cmake/templates/setup.zsh.in" "/opt/ros/kinetic/share/catkin/cmake/test/catkin_download_test_data.cmake" "/opt/ros/kinetic/share/catkin/cmake/test/gtest.cmake" "/opt/ros/kinetic/share/catkin/cmake/test/nosetests.cmake" "/opt/ros/kinetic/share/catkin/cmake/test/tests.cmake" "/opt/ros/kinetic/share/catkin/cmake/tools/doxygen.cmake" "/opt/ros/kinetic/share/catkin/cmake/tools/libraries.cmake" "/opt/ros/kinetic/share/catkin/cmake/tools/rt.cmake" "/opt/ros/kinetic/share/cmake_modules/cmake/cmake_modules-extras.cmake" "/opt/ros/kinetic/share/cmake_modules/cmake/cmake_modulesConfig-version.cmake" "/opt/ros/kinetic/share/cmake_modules/cmake/cmake_modulesConfig.cmake" "/opt/ros/kinetic/share/cpp_common/cmake/cpp_commonConfig-version.cmake" "/opt/ros/kinetic/share/cpp_common/cmake/cpp_commonConfig.cmake" "/opt/ros/kinetic/share/gencpp/cmake/gencpp-extras.cmake" "/opt/ros/kinetic/share/gencpp/cmake/gencppConfig-version.cmake" "/opt/ros/kinetic/share/gencpp/cmake/gencppConfig.cmake" "/opt/ros/kinetic/share/geneus/cmake/geneus-extras.cmake" "/opt/ros/kinetic/share/geneus/cmake/geneusConfig-version.cmake" "/opt/ros/kinetic/share/geneus/cmake/geneusConfig.cmake" "/opt/ros/kinetic/share/genlisp/cmake/genlisp-extras.cmake" "/opt/ros/kinetic/share/genlisp/cmake/genlispConfig-version.cmake" "/opt/ros/kinetic/share/genlisp/cmake/genlispConfig.cmake" "/opt/ros/kinetic/share/genmsg/cmake/genmsg-extras.cmake" "/opt/ros/kinetic/share/genmsg/cmake/genmsgConfig-version.cmake" "/opt/ros/kinetic/share/genmsg/cmake/genmsgConfig.cmake" "/opt/ros/kinetic/share/gennodejs/cmake/gennodejs-extras.cmake" "/opt/ros/kinetic/share/gennodejs/cmake/gennodejsConfig-version.cmake" "/opt/ros/kinetic/share/gennodejs/cmake/gennodejsConfig.cmake" "/opt/ros/kinetic/share/genpy/cmake/genpy-extras.cmake" "/opt/ros/kinetic/share/genpy/cmake/genpyConfig-version.cmake" "/opt/ros/kinetic/share/genpy/cmake/genpyConfig.cmake" "/opt/ros/kinetic/share/geometry_msgs/cmake/geometry_msgs-msg-extras.cmake" "/opt/ros/kinetic/share/geometry_msgs/cmake/geometry_msgsConfig-version.cmake" "/opt/ros/kinetic/share/geometry_msgs/cmake/geometry_msgsConfig.cmake" "/opt/ros/kinetic/share/message_filters/cmake/message_filtersConfig-version.cmake" "/opt/ros/kinetic/share/message_filters/cmake/message_filtersConfig.cmake" "/opt/ros/kinetic/share/message_generation/cmake/message_generationConfig-version.cmake" "/opt/ros/kinetic/share/message_generation/cmake/message_generationConfig.cmake" "/opt/ros/kinetic/share/message_runtime/cmake/message_runtimeConfig-version.cmake" "/opt/ros/kinetic/share/message_runtime/cmake/message_runtimeConfig.cmake" "/opt/ros/kinetic/share/nav_msgs/cmake/nav_msgs-msg-extras.cmake" "/opt/ros/kinetic/share/nav_msgs/cmake/nav_msgsConfig-version.cmake" "/opt/ros/kinetic/share/nav_msgs/cmake/nav_msgsConfig.cmake" "/opt/ros/kinetic/share/rosconsole/cmake/rosconsole-extras.cmake" "/opt/ros/kinetic/share/rosconsole/cmake/rosconsoleConfig-version.cmake" "/opt/ros/kinetic/share/rosconsole/cmake/rosconsoleConfig.cmake" "/opt/ros/kinetic/share/roscpp/cmake/roscpp-msg-extras.cmake" "/opt/ros/kinetic/share/roscpp/cmake/roscppConfig-version.cmake" "/opt/ros/kinetic/share/roscpp/cmake/roscppConfig.cmake" "/opt/ros/kinetic/share/roscpp_serialization/cmake/roscpp_serializationConfig-version.cmake" "/opt/ros/kinetic/share/roscpp_serialization/cmake/roscpp_serializationConfig.cmake" "/opt/ros/kinetic/share/roscpp_traits/cmake/roscpp_traitsConfig-version.cmake" "/opt/ros/kinetic/share/roscpp_traits/cmake/roscpp_traitsConfig.cmake" "/opt/ros/kinetic/share/rosgraph/cmake/rosgraphConfig-version.cmake" "/opt/ros/kinetic/share/rosgraph/cmake/rosgraphConfig.cmake" "/opt/ros/kinetic/share/rosgraph_msgs/cmake/rosgraph_msgs-msg-extras.cmake" "/opt/ros/kinetic/share/rosgraph_msgs/cmake/rosgraph_msgsConfig-version.cmake" "/opt/ros/kinetic/share/rosgraph_msgs/cmake/rosgraph_msgsConfig.cmake" "/opt/ros/kinetic/share/rospy/cmake/rospyConfig-version.cmake" "/opt/ros/kinetic/share/rospy/cmake/rospyConfig.cmake" "/opt/ros/kinetic/share/rostime/cmake/rostimeConfig-version.cmake" "/opt/ros/kinetic/share/rostime/cmake/rostimeConfig.cmake" "/opt/ros/kinetic/share/sensor_msgs/cmake/sensor_msgs-msg-extras.cmake" "/opt/ros/kinetic/share/sensor_msgs/cmake/sensor_msgsConfig-version.cmake" "/opt/ros/kinetic/share/sensor_msgs/cmake/sensor_msgsConfig.cmake" "/opt/ros/kinetic/share/std_msgs/cmake/std_msgs-msg-extras.cmake" "/opt/ros/kinetic/share/std_msgs/cmake/std_msgsConfig-version.cmake" "/opt/ros/kinetic/share/std_msgs/cmake/std_msgsConfig.cmake" "/opt/ros/kinetic/share/tf/cmake/tf-msg-extras.cmake" "/opt/ros/kinetic/share/tf/cmake/tfConfig-version.cmake" "/opt/ros/kinetic/share/tf/cmake/tfConfig.cmake" "/opt/ros/kinetic/share/tf2/cmake/tf2Config-version.cmake" "/opt/ros/kinetic/share/tf2/cmake/tf2Config.cmake" "/opt/ros/kinetic/share/tf2_msgs/cmake/tf2_msgs-msg-extras.cmake" "/opt/ros/kinetic/share/tf2_msgs/cmake/tf2_msgsConfig-version.cmake" "/opt/ros/kinetic/share/tf2_msgs/cmake/tf2_msgsConfig.cmake" "/opt/ros/kinetic/share/tf2_py/cmake/tf2_pyConfig-version.cmake" "/opt/ros/kinetic/share/tf2_py/cmake/tf2_pyConfig.cmake" "/opt/ros/kinetic/share/tf2_ros/cmake/tf2_rosConfig-version.cmake" "/opt/ros/kinetic/share/tf2_ros/cmake/tf2_rosConfig.cmake" "/opt/ros/kinetic/share/xmlrpcpp/cmake/xmlrpcpp-extras.cmake" "/opt/ros/kinetic/share/xmlrpcpp/cmake/xmlrpcppConfig-version.cmake" "/opt/ros/kinetic/share/xmlrpcpp/cmake/xmlrpcppConfig.cmake" "/usr/lib/cmake/eigen3/Eigen3Config.cmake" "/usr/share/mrpt/MRPTConfig-version.cmake" "/usr/share/mrpt/MRPTConfig.cmake" ) # The corresponding makefile is: set(CMAKE_MAKEFILE_OUTPUTS "Makefile" "CMakeFiles/cmake.check_cache" ) # Byproducts of CMake generate step: set(CMAKE_MAKEFILE_PRODUCTS "CMakeFiles/3.9.6/CMakeSystem.cmake" "CMakeFiles/3.9.6/CMakeCCompiler.cmake" "CMakeFiles/3.9.6/CMakeCXXCompiler.cmake" "CMakeFiles/3.9.6/CMakeCCompiler.cmake" "CMakeFiles/3.9.6/CMakeCXXCompiler.cmake" "catkin_generated/stamps/rf2o_laser_odometry/package.xml.stamp" "catkin_generated/installspace/_setup_util.py" "catkin_generated/stamps/rf2o_laser_odometry/_setup_util.py.stamp" "catkin_generated/installspace/env.sh" "catkin_generated/installspace/setup.bash" "catkin_generated/installspace/setup.sh" "catkin_generated/installspace/setup.zsh" "catkin_generated/installspace/.rosinstall" "catkin_generated/generate_cached_setup.py" "catkin_generated/env_cached.sh" "catkin_generated/stamps/rf2o_laser_odometry/interrogate_setup_dot_py.py.stamp" "catkin_generated/stamps/rf2o_laser_odometry/package.xml.stamp" "catkin_generated/pkg.develspace.context.pc.py" "catkin_generated/stamps/rf2o_laser_odometry/pkg.pc.em.stamp" "devel/share/rf2o_laser_odometry/cmake/rf2o_laser_odometryConfig.cmake" "devel/share/rf2o_laser_odometry/cmake/rf2o_laser_odometryConfig-version.cmake" "catkin_generated/pkg.installspace.context.pc.py" "catkin_generated/stamps/rf2o_laser_odometry/pkg.pc.em.stamp" "catkin_generated/installspace/rf2o_laser_odometryConfig.cmake" "catkin_generated/installspace/rf2o_laser_odometryConfig-version.cmake" "CMakeFiles/CMakeDirectoryInformation.cmake" ) # Dependency information for all targets: set(CMAKE_DEPEND_INFO_FILES "CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/DependInfo.cmake" "CMakeFiles/tf2_msgs_generate_messages_lisp.dir/DependInfo.cmake" "CMakeFiles/tf2_msgs_generate_messages_eus.dir/DependInfo.cmake" "CMakeFiles/tf2_msgs_generate_messages_cpp.dir/DependInfo.cmake" "CMakeFiles/actionlib_generate_messages_py.dir/DependInfo.cmake" "CMakeFiles/actionlib_generate_messages_eus.dir/DependInfo.cmake" "CMakeFiles/nav_msgs_generate_messages_eus.dir/DependInfo.cmake" "CMakeFiles/std_msgs_generate_messages_eus.dir/DependInfo.cmake" "CMakeFiles/roscpp_generate_messages_lisp.dir/DependInfo.cmake" "CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/DependInfo.cmake" "CMakeFiles/tests.dir/DependInfo.cmake" "CMakeFiles/rf2o_laser_odometry_node.dir/DependInfo.cmake" "CMakeFiles/roscpp_generate_messages_nodejs.dir/DependInfo.cmake" "CMakeFiles/tf_generate_messages_eus.dir/DependInfo.cmake" "CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/DependInfo.cmake" "CMakeFiles/nav_msgs_generate_messages_cpp.dir/DependInfo.cmake" "CMakeFiles/std_msgs_generate_messages_lisp.dir/DependInfo.cmake" "CMakeFiles/geometry_msgs_generate_messages_lisp.dir/DependInfo.cmake" "CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/DependInfo.cmake" "CMakeFiles/run_tests.dir/DependInfo.cmake" "CMakeFiles/actionlib_generate_messages_lisp.dir/DependInfo.cmake" "CMakeFiles/actionlib_msgs_generate_messages_eus.dir/DependInfo.cmake" "CMakeFiles/roscpp_generate_messages_eus.dir/DependInfo.cmake" "CMakeFiles/roscpp_generate_messages_cpp.dir/DependInfo.cmake" "CMakeFiles/geometry_msgs_generate_messages_eus.dir/DependInfo.cmake" "CMakeFiles/actionlib_msgs_generate_messages_py.dir/DependInfo.cmake" "CMakeFiles/clean_test_results.dir/DependInfo.cmake" "CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/DependInfo.cmake" "CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/DependInfo.cmake" "CMakeFiles/doxygen.dir/DependInfo.cmake" "CMakeFiles/tf_generate_messages_cpp.dir/DependInfo.cmake" "CMakeFiles/nav_msgs_generate_messages_lisp.dir/DependInfo.cmake" "CMakeFiles/nav_msgs_generate_messages_nodejs.dir/DependInfo.cmake" "CMakeFiles/std_msgs_generate_messages_py.dir/DependInfo.cmake" "CMakeFiles/nav_msgs_generate_messages_py.dir/DependInfo.cmake" "CMakeFiles/geometry_msgs_generate_messages_cpp.dir/DependInfo.cmake" "CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/DependInfo.cmake" "CMakeFiles/std_msgs_generate_messages_nodejs.dir/DependInfo.cmake" "CMakeFiles/geometry_msgs_generate_messages_py.dir/DependInfo.cmake" "CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/DependInfo.cmake" "CMakeFiles/tf2_msgs_generate_messages_py.dir/DependInfo.cmake" "CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/DependInfo.cmake" "CMakeFiles/sensor_msgs_generate_messages_cpp.dir/DependInfo.cmake" "CMakeFiles/actionlib_generate_messages_nodejs.dir/DependInfo.cmake" "CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/DependInfo.cmake" "CMakeFiles/std_msgs_generate_messages_cpp.dir/DependInfo.cmake" "CMakeFiles/sensor_msgs_generate_messages_eus.dir/DependInfo.cmake" "CMakeFiles/download_extra_data.dir/DependInfo.cmake" "CMakeFiles/sensor_msgs_generate_messages_lisp.dir/DependInfo.cmake" "CMakeFiles/actionlib_generate_messages_cpp.dir/DependInfo.cmake" "CMakeFiles/sensor_msgs_generate_messages_py.dir/DependInfo.cmake" "CMakeFiles/rosgraph_msgs_generate_messages_py.dir/DependInfo.cmake" "CMakeFiles/tf_generate_messages_lisp.dir/DependInfo.cmake" "CMakeFiles/roscpp_generate_messages_py.dir/DependInfo.cmake" "CMakeFiles/tf_generate_messages_nodejs.dir/DependInfo.cmake" "CMakeFiles/tf_generate_messages_py.dir/DependInfo.cmake" ) ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/Makefile2 ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Default target executed when no arguments are given to make. default_target: all .PHONY : default_target # The main recursive all target all: .PHONY : all # The main recursive preinstall target preinstall: .PHONY : preinstall #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug #============================================================================= # Target rules for target CMakeFiles/tf2_msgs_generate_messages_nodejs.dir # All Build rule for target. CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/all: $(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/depend $(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target tf2_msgs_generate_messages_nodejs" .PHONY : CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/all # Build rule for subdir invocation for target. CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/rule # Convenience name for target. tf2_msgs_generate_messages_nodejs: CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/rule .PHONY : tf2_msgs_generate_messages_nodejs # clean rule for target. CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/clean: $(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/clean .PHONY : CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/clean # clean rule for target. clean: CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/tf2_msgs_generate_messages_lisp.dir # All Build rule for target. CMakeFiles/tf2_msgs_generate_messages_lisp.dir/all: $(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_lisp.dir/build.make CMakeFiles/tf2_msgs_generate_messages_lisp.dir/depend $(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_lisp.dir/build.make CMakeFiles/tf2_msgs_generate_messages_lisp.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target tf2_msgs_generate_messages_lisp" .PHONY : CMakeFiles/tf2_msgs_generate_messages_lisp.dir/all # Build rule for subdir invocation for target. CMakeFiles/tf2_msgs_generate_messages_lisp.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/tf2_msgs_generate_messages_lisp.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/tf2_msgs_generate_messages_lisp.dir/rule # Convenience name for target. tf2_msgs_generate_messages_lisp: CMakeFiles/tf2_msgs_generate_messages_lisp.dir/rule .PHONY : tf2_msgs_generate_messages_lisp # clean rule for target. CMakeFiles/tf2_msgs_generate_messages_lisp.dir/clean: $(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_lisp.dir/build.make CMakeFiles/tf2_msgs_generate_messages_lisp.dir/clean .PHONY : CMakeFiles/tf2_msgs_generate_messages_lisp.dir/clean # clean rule for target. clean: CMakeFiles/tf2_msgs_generate_messages_lisp.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/tf2_msgs_generate_messages_eus.dir # All Build rule for target. CMakeFiles/tf2_msgs_generate_messages_eus.dir/all: $(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_eus.dir/build.make CMakeFiles/tf2_msgs_generate_messages_eus.dir/depend $(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_eus.dir/build.make CMakeFiles/tf2_msgs_generate_messages_eus.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target tf2_msgs_generate_messages_eus" .PHONY : CMakeFiles/tf2_msgs_generate_messages_eus.dir/all # Build rule for subdir invocation for target. CMakeFiles/tf2_msgs_generate_messages_eus.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/tf2_msgs_generate_messages_eus.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/tf2_msgs_generate_messages_eus.dir/rule # Convenience name for target. tf2_msgs_generate_messages_eus: CMakeFiles/tf2_msgs_generate_messages_eus.dir/rule .PHONY : tf2_msgs_generate_messages_eus # clean rule for target. CMakeFiles/tf2_msgs_generate_messages_eus.dir/clean: $(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_eus.dir/build.make CMakeFiles/tf2_msgs_generate_messages_eus.dir/clean .PHONY : CMakeFiles/tf2_msgs_generate_messages_eus.dir/clean # clean rule for target. clean: CMakeFiles/tf2_msgs_generate_messages_eus.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/tf2_msgs_generate_messages_cpp.dir # All Build rule for target. CMakeFiles/tf2_msgs_generate_messages_cpp.dir/all: $(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_cpp.dir/build.make CMakeFiles/tf2_msgs_generate_messages_cpp.dir/depend $(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_cpp.dir/build.make CMakeFiles/tf2_msgs_generate_messages_cpp.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target tf2_msgs_generate_messages_cpp" .PHONY : CMakeFiles/tf2_msgs_generate_messages_cpp.dir/all # Build rule for subdir invocation for target. CMakeFiles/tf2_msgs_generate_messages_cpp.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/tf2_msgs_generate_messages_cpp.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/tf2_msgs_generate_messages_cpp.dir/rule # Convenience name for target. tf2_msgs_generate_messages_cpp: CMakeFiles/tf2_msgs_generate_messages_cpp.dir/rule .PHONY : tf2_msgs_generate_messages_cpp # clean rule for target. CMakeFiles/tf2_msgs_generate_messages_cpp.dir/clean: $(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_cpp.dir/build.make CMakeFiles/tf2_msgs_generate_messages_cpp.dir/clean .PHONY : CMakeFiles/tf2_msgs_generate_messages_cpp.dir/clean # clean rule for target. clean: CMakeFiles/tf2_msgs_generate_messages_cpp.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/actionlib_generate_messages_py.dir # All Build rule for target. CMakeFiles/actionlib_generate_messages_py.dir/all: $(MAKE) -f CMakeFiles/actionlib_generate_messages_py.dir/build.make CMakeFiles/actionlib_generate_messages_py.dir/depend $(MAKE) -f CMakeFiles/actionlib_generate_messages_py.dir/build.make CMakeFiles/actionlib_generate_messages_py.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target actionlib_generate_messages_py" .PHONY : CMakeFiles/actionlib_generate_messages_py.dir/all # Build rule for subdir invocation for target. CMakeFiles/actionlib_generate_messages_py.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/actionlib_generate_messages_py.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/actionlib_generate_messages_py.dir/rule # Convenience name for target. actionlib_generate_messages_py: CMakeFiles/actionlib_generate_messages_py.dir/rule .PHONY : actionlib_generate_messages_py # clean rule for target. CMakeFiles/actionlib_generate_messages_py.dir/clean: $(MAKE) -f CMakeFiles/actionlib_generate_messages_py.dir/build.make CMakeFiles/actionlib_generate_messages_py.dir/clean .PHONY : CMakeFiles/actionlib_generate_messages_py.dir/clean # clean rule for target. clean: CMakeFiles/actionlib_generate_messages_py.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/actionlib_generate_messages_eus.dir # All Build rule for target. CMakeFiles/actionlib_generate_messages_eus.dir/all: $(MAKE) -f CMakeFiles/actionlib_generate_messages_eus.dir/build.make CMakeFiles/actionlib_generate_messages_eus.dir/depend $(MAKE) -f CMakeFiles/actionlib_generate_messages_eus.dir/build.make CMakeFiles/actionlib_generate_messages_eus.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target actionlib_generate_messages_eus" .PHONY : CMakeFiles/actionlib_generate_messages_eus.dir/all # Build rule for subdir invocation for target. CMakeFiles/actionlib_generate_messages_eus.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/actionlib_generate_messages_eus.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/actionlib_generate_messages_eus.dir/rule # Convenience name for target. actionlib_generate_messages_eus: CMakeFiles/actionlib_generate_messages_eus.dir/rule .PHONY : actionlib_generate_messages_eus # clean rule for target. CMakeFiles/actionlib_generate_messages_eus.dir/clean: $(MAKE) -f CMakeFiles/actionlib_generate_messages_eus.dir/build.make CMakeFiles/actionlib_generate_messages_eus.dir/clean .PHONY : CMakeFiles/actionlib_generate_messages_eus.dir/clean # clean rule for target. clean: CMakeFiles/actionlib_generate_messages_eus.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/nav_msgs_generate_messages_eus.dir # All Build rule for target. CMakeFiles/nav_msgs_generate_messages_eus.dir/all: $(MAKE) -f CMakeFiles/nav_msgs_generate_messages_eus.dir/build.make CMakeFiles/nav_msgs_generate_messages_eus.dir/depend $(MAKE) -f CMakeFiles/nav_msgs_generate_messages_eus.dir/build.make CMakeFiles/nav_msgs_generate_messages_eus.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target nav_msgs_generate_messages_eus" .PHONY : CMakeFiles/nav_msgs_generate_messages_eus.dir/all # Build rule for subdir invocation for target. CMakeFiles/nav_msgs_generate_messages_eus.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/nav_msgs_generate_messages_eus.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/nav_msgs_generate_messages_eus.dir/rule # Convenience name for target. nav_msgs_generate_messages_eus: CMakeFiles/nav_msgs_generate_messages_eus.dir/rule .PHONY : nav_msgs_generate_messages_eus # clean rule for target. CMakeFiles/nav_msgs_generate_messages_eus.dir/clean: $(MAKE) -f CMakeFiles/nav_msgs_generate_messages_eus.dir/build.make CMakeFiles/nav_msgs_generate_messages_eus.dir/clean .PHONY : CMakeFiles/nav_msgs_generate_messages_eus.dir/clean # clean rule for target. clean: CMakeFiles/nav_msgs_generate_messages_eus.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/std_msgs_generate_messages_eus.dir # All Build rule for target. CMakeFiles/std_msgs_generate_messages_eus.dir/all: $(MAKE) -f CMakeFiles/std_msgs_generate_messages_eus.dir/build.make CMakeFiles/std_msgs_generate_messages_eus.dir/depend $(MAKE) -f CMakeFiles/std_msgs_generate_messages_eus.dir/build.make CMakeFiles/std_msgs_generate_messages_eus.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target std_msgs_generate_messages_eus" .PHONY : CMakeFiles/std_msgs_generate_messages_eus.dir/all # Build rule for subdir invocation for target. CMakeFiles/std_msgs_generate_messages_eus.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/std_msgs_generate_messages_eus.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/std_msgs_generate_messages_eus.dir/rule # Convenience name for target. std_msgs_generate_messages_eus: CMakeFiles/std_msgs_generate_messages_eus.dir/rule .PHONY : std_msgs_generate_messages_eus # clean rule for target. CMakeFiles/std_msgs_generate_messages_eus.dir/clean: $(MAKE) -f CMakeFiles/std_msgs_generate_messages_eus.dir/build.make CMakeFiles/std_msgs_generate_messages_eus.dir/clean .PHONY : CMakeFiles/std_msgs_generate_messages_eus.dir/clean # clean rule for target. clean: CMakeFiles/std_msgs_generate_messages_eus.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/roscpp_generate_messages_lisp.dir # All Build rule for target. CMakeFiles/roscpp_generate_messages_lisp.dir/all: $(MAKE) -f CMakeFiles/roscpp_generate_messages_lisp.dir/build.make CMakeFiles/roscpp_generate_messages_lisp.dir/depend $(MAKE) -f CMakeFiles/roscpp_generate_messages_lisp.dir/build.make CMakeFiles/roscpp_generate_messages_lisp.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target roscpp_generate_messages_lisp" .PHONY : CMakeFiles/roscpp_generate_messages_lisp.dir/all # Build rule for subdir invocation for target. CMakeFiles/roscpp_generate_messages_lisp.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/roscpp_generate_messages_lisp.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/roscpp_generate_messages_lisp.dir/rule # Convenience name for target. roscpp_generate_messages_lisp: CMakeFiles/roscpp_generate_messages_lisp.dir/rule .PHONY : roscpp_generate_messages_lisp # clean rule for target. CMakeFiles/roscpp_generate_messages_lisp.dir/clean: $(MAKE) -f CMakeFiles/roscpp_generate_messages_lisp.dir/build.make CMakeFiles/roscpp_generate_messages_lisp.dir/clean .PHONY : CMakeFiles/roscpp_generate_messages_lisp.dir/clean # clean rule for target. clean: CMakeFiles/roscpp_generate_messages_lisp.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir # All Build rule for target. CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/all: $(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/depend $(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target rosgraph_msgs_generate_messages_lisp" .PHONY : CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/all # Build rule for subdir invocation for target. CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/rule # Convenience name for target. rosgraph_msgs_generate_messages_lisp: CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/rule .PHONY : rosgraph_msgs_generate_messages_lisp # clean rule for target. CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/clean: $(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/clean .PHONY : CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/clean # clean rule for target. clean: CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/tests.dir # All Build rule for target. CMakeFiles/tests.dir/all: $(MAKE) -f CMakeFiles/tests.dir/build.make CMakeFiles/tests.dir/depend $(MAKE) -f CMakeFiles/tests.dir/build.make CMakeFiles/tests.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target tests" .PHONY : CMakeFiles/tests.dir/all # Build rule for subdir invocation for target. CMakeFiles/tests.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/tests.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/tests.dir/rule # Convenience name for target. tests: CMakeFiles/tests.dir/rule .PHONY : tests # clean rule for target. CMakeFiles/tests.dir/clean: $(MAKE) -f CMakeFiles/tests.dir/build.make CMakeFiles/tests.dir/clean .PHONY : CMakeFiles/tests.dir/clean # clean rule for target. clean: CMakeFiles/tests.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/rf2o_laser_odometry_node.dir # All Build rule for target. CMakeFiles/rf2o_laser_odometry_node.dir/all: $(MAKE) -f CMakeFiles/rf2o_laser_odometry_node.dir/build.make CMakeFiles/rf2o_laser_odometry_node.dir/depend $(MAKE) -f CMakeFiles/rf2o_laser_odometry_node.dir/build.make CMakeFiles/rf2o_laser_odometry_node.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num=1,2 "Built target rf2o_laser_odometry_node" .PHONY : CMakeFiles/rf2o_laser_odometry_node.dir/all # Include target in all. all: CMakeFiles/rf2o_laser_odometry_node.dir/all .PHONY : all # Build rule for subdir invocation for target. CMakeFiles/rf2o_laser_odometry_node.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 2 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/rf2o_laser_odometry_node.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/rf2o_laser_odometry_node.dir/rule # Convenience name for target. rf2o_laser_odometry_node: CMakeFiles/rf2o_laser_odometry_node.dir/rule .PHONY : rf2o_laser_odometry_node # clean rule for target. CMakeFiles/rf2o_laser_odometry_node.dir/clean: $(MAKE) -f CMakeFiles/rf2o_laser_odometry_node.dir/build.make CMakeFiles/rf2o_laser_odometry_node.dir/clean .PHONY : CMakeFiles/rf2o_laser_odometry_node.dir/clean # clean rule for target. clean: CMakeFiles/rf2o_laser_odometry_node.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/roscpp_generate_messages_nodejs.dir # All Build rule for target. CMakeFiles/roscpp_generate_messages_nodejs.dir/all: $(MAKE) -f CMakeFiles/roscpp_generate_messages_nodejs.dir/build.make CMakeFiles/roscpp_generate_messages_nodejs.dir/depend $(MAKE) -f CMakeFiles/roscpp_generate_messages_nodejs.dir/build.make CMakeFiles/roscpp_generate_messages_nodejs.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target roscpp_generate_messages_nodejs" .PHONY : CMakeFiles/roscpp_generate_messages_nodejs.dir/all # Build rule for subdir invocation for target. CMakeFiles/roscpp_generate_messages_nodejs.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/roscpp_generate_messages_nodejs.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/roscpp_generate_messages_nodejs.dir/rule # Convenience name for target. roscpp_generate_messages_nodejs: CMakeFiles/roscpp_generate_messages_nodejs.dir/rule .PHONY : roscpp_generate_messages_nodejs # clean rule for target. CMakeFiles/roscpp_generate_messages_nodejs.dir/clean: $(MAKE) -f CMakeFiles/roscpp_generate_messages_nodejs.dir/build.make CMakeFiles/roscpp_generate_messages_nodejs.dir/clean .PHONY : CMakeFiles/roscpp_generate_messages_nodejs.dir/clean # clean rule for target. clean: CMakeFiles/roscpp_generate_messages_nodejs.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/tf_generate_messages_eus.dir # All Build rule for target. CMakeFiles/tf_generate_messages_eus.dir/all: $(MAKE) -f CMakeFiles/tf_generate_messages_eus.dir/build.make CMakeFiles/tf_generate_messages_eus.dir/depend $(MAKE) -f CMakeFiles/tf_generate_messages_eus.dir/build.make CMakeFiles/tf_generate_messages_eus.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target tf_generate_messages_eus" .PHONY : CMakeFiles/tf_generate_messages_eus.dir/all # Build rule for subdir invocation for target. CMakeFiles/tf_generate_messages_eus.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/tf_generate_messages_eus.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/tf_generate_messages_eus.dir/rule # Convenience name for target. tf_generate_messages_eus: CMakeFiles/tf_generate_messages_eus.dir/rule .PHONY : tf_generate_messages_eus # clean rule for target. CMakeFiles/tf_generate_messages_eus.dir/clean: $(MAKE) -f CMakeFiles/tf_generate_messages_eus.dir/build.make CMakeFiles/tf_generate_messages_eus.dir/clean .PHONY : CMakeFiles/tf_generate_messages_eus.dir/clean # clean rule for target. clean: CMakeFiles/tf_generate_messages_eus.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir # All Build rule for target. CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/all: $(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/depend $(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target rosgraph_msgs_generate_messages_nodejs" .PHONY : CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/all # Build rule for subdir invocation for target. CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/rule # Convenience name for target. rosgraph_msgs_generate_messages_nodejs: CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/rule .PHONY : rosgraph_msgs_generate_messages_nodejs # clean rule for target. CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/clean: $(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/clean .PHONY : CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/clean # clean rule for target. clean: CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/nav_msgs_generate_messages_cpp.dir # All Build rule for target. CMakeFiles/nav_msgs_generate_messages_cpp.dir/all: $(MAKE) -f CMakeFiles/nav_msgs_generate_messages_cpp.dir/build.make CMakeFiles/nav_msgs_generate_messages_cpp.dir/depend $(MAKE) -f CMakeFiles/nav_msgs_generate_messages_cpp.dir/build.make CMakeFiles/nav_msgs_generate_messages_cpp.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target nav_msgs_generate_messages_cpp" .PHONY : CMakeFiles/nav_msgs_generate_messages_cpp.dir/all # Build rule for subdir invocation for target. CMakeFiles/nav_msgs_generate_messages_cpp.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/nav_msgs_generate_messages_cpp.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/nav_msgs_generate_messages_cpp.dir/rule # Convenience name for target. nav_msgs_generate_messages_cpp: CMakeFiles/nav_msgs_generate_messages_cpp.dir/rule .PHONY : nav_msgs_generate_messages_cpp # clean rule for target. CMakeFiles/nav_msgs_generate_messages_cpp.dir/clean: $(MAKE) -f CMakeFiles/nav_msgs_generate_messages_cpp.dir/build.make CMakeFiles/nav_msgs_generate_messages_cpp.dir/clean .PHONY : CMakeFiles/nav_msgs_generate_messages_cpp.dir/clean # clean rule for target. clean: CMakeFiles/nav_msgs_generate_messages_cpp.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/std_msgs_generate_messages_lisp.dir # All Build rule for target. CMakeFiles/std_msgs_generate_messages_lisp.dir/all: $(MAKE) -f CMakeFiles/std_msgs_generate_messages_lisp.dir/build.make CMakeFiles/std_msgs_generate_messages_lisp.dir/depend $(MAKE) -f CMakeFiles/std_msgs_generate_messages_lisp.dir/build.make CMakeFiles/std_msgs_generate_messages_lisp.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target std_msgs_generate_messages_lisp" .PHONY : CMakeFiles/std_msgs_generate_messages_lisp.dir/all # Build rule for subdir invocation for target. CMakeFiles/std_msgs_generate_messages_lisp.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/std_msgs_generate_messages_lisp.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/std_msgs_generate_messages_lisp.dir/rule # Convenience name for target. std_msgs_generate_messages_lisp: CMakeFiles/std_msgs_generate_messages_lisp.dir/rule .PHONY : std_msgs_generate_messages_lisp # clean rule for target. CMakeFiles/std_msgs_generate_messages_lisp.dir/clean: $(MAKE) -f CMakeFiles/std_msgs_generate_messages_lisp.dir/build.make CMakeFiles/std_msgs_generate_messages_lisp.dir/clean .PHONY : CMakeFiles/std_msgs_generate_messages_lisp.dir/clean # clean rule for target. clean: CMakeFiles/std_msgs_generate_messages_lisp.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/geometry_msgs_generate_messages_lisp.dir # All Build rule for target. CMakeFiles/geometry_msgs_generate_messages_lisp.dir/all: $(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_lisp.dir/build.make CMakeFiles/geometry_msgs_generate_messages_lisp.dir/depend $(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_lisp.dir/build.make CMakeFiles/geometry_msgs_generate_messages_lisp.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target geometry_msgs_generate_messages_lisp" .PHONY : CMakeFiles/geometry_msgs_generate_messages_lisp.dir/all # Build rule for subdir invocation for target. CMakeFiles/geometry_msgs_generate_messages_lisp.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/geometry_msgs_generate_messages_lisp.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/geometry_msgs_generate_messages_lisp.dir/rule # Convenience name for target. geometry_msgs_generate_messages_lisp: CMakeFiles/geometry_msgs_generate_messages_lisp.dir/rule .PHONY : geometry_msgs_generate_messages_lisp # clean rule for target. CMakeFiles/geometry_msgs_generate_messages_lisp.dir/clean: $(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_lisp.dir/build.make CMakeFiles/geometry_msgs_generate_messages_lisp.dir/clean .PHONY : CMakeFiles/geometry_msgs_generate_messages_lisp.dir/clean # clean rule for target. clean: CMakeFiles/geometry_msgs_generate_messages_lisp.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir # All Build rule for target. CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/all: $(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/depend $(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target rosgraph_msgs_generate_messages_cpp" .PHONY : CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/all # Build rule for subdir invocation for target. CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/rule # Convenience name for target. rosgraph_msgs_generate_messages_cpp: CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/rule .PHONY : rosgraph_msgs_generate_messages_cpp # clean rule for target. CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/clean: $(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/clean .PHONY : CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/clean # clean rule for target. clean: CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/run_tests.dir # All Build rule for target. CMakeFiles/run_tests.dir/all: $(MAKE) -f CMakeFiles/run_tests.dir/build.make CMakeFiles/run_tests.dir/depend $(MAKE) -f CMakeFiles/run_tests.dir/build.make CMakeFiles/run_tests.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target run_tests" .PHONY : CMakeFiles/run_tests.dir/all # Build rule for subdir invocation for target. CMakeFiles/run_tests.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/run_tests.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/run_tests.dir/rule # Convenience name for target. run_tests: CMakeFiles/run_tests.dir/rule .PHONY : run_tests # clean rule for target. CMakeFiles/run_tests.dir/clean: $(MAKE) -f CMakeFiles/run_tests.dir/build.make CMakeFiles/run_tests.dir/clean .PHONY : CMakeFiles/run_tests.dir/clean # clean rule for target. clean: CMakeFiles/run_tests.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/actionlib_generate_messages_lisp.dir # All Build rule for target. CMakeFiles/actionlib_generate_messages_lisp.dir/all: $(MAKE) -f CMakeFiles/actionlib_generate_messages_lisp.dir/build.make CMakeFiles/actionlib_generate_messages_lisp.dir/depend $(MAKE) -f CMakeFiles/actionlib_generate_messages_lisp.dir/build.make CMakeFiles/actionlib_generate_messages_lisp.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target actionlib_generate_messages_lisp" .PHONY : CMakeFiles/actionlib_generate_messages_lisp.dir/all # Build rule for subdir invocation for target. CMakeFiles/actionlib_generate_messages_lisp.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/actionlib_generate_messages_lisp.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/actionlib_generate_messages_lisp.dir/rule # Convenience name for target. actionlib_generate_messages_lisp: CMakeFiles/actionlib_generate_messages_lisp.dir/rule .PHONY : actionlib_generate_messages_lisp # clean rule for target. CMakeFiles/actionlib_generate_messages_lisp.dir/clean: $(MAKE) -f CMakeFiles/actionlib_generate_messages_lisp.dir/build.make CMakeFiles/actionlib_generate_messages_lisp.dir/clean .PHONY : CMakeFiles/actionlib_generate_messages_lisp.dir/clean # clean rule for target. clean: CMakeFiles/actionlib_generate_messages_lisp.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/actionlib_msgs_generate_messages_eus.dir # All Build rule for target. CMakeFiles/actionlib_msgs_generate_messages_eus.dir/all: $(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_eus.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_eus.dir/depend $(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_eus.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_eus.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target actionlib_msgs_generate_messages_eus" .PHONY : CMakeFiles/actionlib_msgs_generate_messages_eus.dir/all # Build rule for subdir invocation for target. CMakeFiles/actionlib_msgs_generate_messages_eus.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/actionlib_msgs_generate_messages_eus.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/actionlib_msgs_generate_messages_eus.dir/rule # Convenience name for target. actionlib_msgs_generate_messages_eus: CMakeFiles/actionlib_msgs_generate_messages_eus.dir/rule .PHONY : actionlib_msgs_generate_messages_eus # clean rule for target. CMakeFiles/actionlib_msgs_generate_messages_eus.dir/clean: $(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_eus.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_eus.dir/clean .PHONY : CMakeFiles/actionlib_msgs_generate_messages_eus.dir/clean # clean rule for target. clean: CMakeFiles/actionlib_msgs_generate_messages_eus.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/roscpp_generate_messages_eus.dir # All Build rule for target. CMakeFiles/roscpp_generate_messages_eus.dir/all: $(MAKE) -f CMakeFiles/roscpp_generate_messages_eus.dir/build.make CMakeFiles/roscpp_generate_messages_eus.dir/depend $(MAKE) -f CMakeFiles/roscpp_generate_messages_eus.dir/build.make CMakeFiles/roscpp_generate_messages_eus.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target roscpp_generate_messages_eus" .PHONY : CMakeFiles/roscpp_generate_messages_eus.dir/all # Build rule for subdir invocation for target. CMakeFiles/roscpp_generate_messages_eus.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/roscpp_generate_messages_eus.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/roscpp_generate_messages_eus.dir/rule # Convenience name for target. roscpp_generate_messages_eus: CMakeFiles/roscpp_generate_messages_eus.dir/rule .PHONY : roscpp_generate_messages_eus # clean rule for target. CMakeFiles/roscpp_generate_messages_eus.dir/clean: $(MAKE) -f CMakeFiles/roscpp_generate_messages_eus.dir/build.make CMakeFiles/roscpp_generate_messages_eus.dir/clean .PHONY : CMakeFiles/roscpp_generate_messages_eus.dir/clean # clean rule for target. clean: CMakeFiles/roscpp_generate_messages_eus.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/roscpp_generate_messages_cpp.dir # All Build rule for target. CMakeFiles/roscpp_generate_messages_cpp.dir/all: $(MAKE) -f CMakeFiles/roscpp_generate_messages_cpp.dir/build.make CMakeFiles/roscpp_generate_messages_cpp.dir/depend $(MAKE) -f CMakeFiles/roscpp_generate_messages_cpp.dir/build.make CMakeFiles/roscpp_generate_messages_cpp.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target roscpp_generate_messages_cpp" .PHONY : CMakeFiles/roscpp_generate_messages_cpp.dir/all # Build rule for subdir invocation for target. CMakeFiles/roscpp_generate_messages_cpp.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/roscpp_generate_messages_cpp.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/roscpp_generate_messages_cpp.dir/rule # Convenience name for target. roscpp_generate_messages_cpp: CMakeFiles/roscpp_generate_messages_cpp.dir/rule .PHONY : roscpp_generate_messages_cpp # clean rule for target. CMakeFiles/roscpp_generate_messages_cpp.dir/clean: $(MAKE) -f CMakeFiles/roscpp_generate_messages_cpp.dir/build.make CMakeFiles/roscpp_generate_messages_cpp.dir/clean .PHONY : CMakeFiles/roscpp_generate_messages_cpp.dir/clean # clean rule for target. clean: CMakeFiles/roscpp_generate_messages_cpp.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/geometry_msgs_generate_messages_eus.dir # All Build rule for target. CMakeFiles/geometry_msgs_generate_messages_eus.dir/all: $(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_eus.dir/build.make CMakeFiles/geometry_msgs_generate_messages_eus.dir/depend $(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_eus.dir/build.make CMakeFiles/geometry_msgs_generate_messages_eus.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target geometry_msgs_generate_messages_eus" .PHONY : CMakeFiles/geometry_msgs_generate_messages_eus.dir/all # Build rule for subdir invocation for target. CMakeFiles/geometry_msgs_generate_messages_eus.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/geometry_msgs_generate_messages_eus.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/geometry_msgs_generate_messages_eus.dir/rule # Convenience name for target. geometry_msgs_generate_messages_eus: CMakeFiles/geometry_msgs_generate_messages_eus.dir/rule .PHONY : geometry_msgs_generate_messages_eus # clean rule for target. CMakeFiles/geometry_msgs_generate_messages_eus.dir/clean: $(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_eus.dir/build.make CMakeFiles/geometry_msgs_generate_messages_eus.dir/clean .PHONY : CMakeFiles/geometry_msgs_generate_messages_eus.dir/clean # clean rule for target. clean: CMakeFiles/geometry_msgs_generate_messages_eus.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/actionlib_msgs_generate_messages_py.dir # All Build rule for target. CMakeFiles/actionlib_msgs_generate_messages_py.dir/all: $(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_py.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_py.dir/depend $(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_py.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_py.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target actionlib_msgs_generate_messages_py" .PHONY : CMakeFiles/actionlib_msgs_generate_messages_py.dir/all # Build rule for subdir invocation for target. CMakeFiles/actionlib_msgs_generate_messages_py.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/actionlib_msgs_generate_messages_py.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/actionlib_msgs_generate_messages_py.dir/rule # Convenience name for target. actionlib_msgs_generate_messages_py: CMakeFiles/actionlib_msgs_generate_messages_py.dir/rule .PHONY : actionlib_msgs_generate_messages_py # clean rule for target. CMakeFiles/actionlib_msgs_generate_messages_py.dir/clean: $(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_py.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_py.dir/clean .PHONY : CMakeFiles/actionlib_msgs_generate_messages_py.dir/clean # clean rule for target. clean: CMakeFiles/actionlib_msgs_generate_messages_py.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/clean_test_results.dir # All Build rule for target. CMakeFiles/clean_test_results.dir/all: $(MAKE) -f CMakeFiles/clean_test_results.dir/build.make CMakeFiles/clean_test_results.dir/depend $(MAKE) -f CMakeFiles/clean_test_results.dir/build.make CMakeFiles/clean_test_results.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target clean_test_results" .PHONY : CMakeFiles/clean_test_results.dir/all # Build rule for subdir invocation for target. CMakeFiles/clean_test_results.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/clean_test_results.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/clean_test_results.dir/rule # Convenience name for target. clean_test_results: CMakeFiles/clean_test_results.dir/rule .PHONY : clean_test_results # clean rule for target. CMakeFiles/clean_test_results.dir/clean: $(MAKE) -f CMakeFiles/clean_test_results.dir/build.make CMakeFiles/clean_test_results.dir/clean .PHONY : CMakeFiles/clean_test_results.dir/clean # clean rule for target. clean: CMakeFiles/clean_test_results.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/geometry_msgs_generate_messages_nodejs.dir # All Build rule for target. CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/all: $(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/depend $(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target geometry_msgs_generate_messages_nodejs" .PHONY : CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/all # Build rule for subdir invocation for target. CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/rule # Convenience name for target. geometry_msgs_generate_messages_nodejs: CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/rule .PHONY : geometry_msgs_generate_messages_nodejs # clean rule for target. CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/clean: $(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/clean .PHONY : CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/clean # clean rule for target. clean: CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/rosgraph_msgs_generate_messages_eus.dir # All Build rule for target. CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/all: $(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/depend $(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target rosgraph_msgs_generate_messages_eus" .PHONY : CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/all # Build rule for subdir invocation for target. CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/rule # Convenience name for target. rosgraph_msgs_generate_messages_eus: CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/rule .PHONY : rosgraph_msgs_generate_messages_eus # clean rule for target. CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/clean: $(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/clean .PHONY : CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/clean # clean rule for target. clean: CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/doxygen.dir # All Build rule for target. CMakeFiles/doxygen.dir/all: $(MAKE) -f CMakeFiles/doxygen.dir/build.make CMakeFiles/doxygen.dir/depend $(MAKE) -f CMakeFiles/doxygen.dir/build.make CMakeFiles/doxygen.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target doxygen" .PHONY : CMakeFiles/doxygen.dir/all # Build rule for subdir invocation for target. CMakeFiles/doxygen.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/doxygen.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/doxygen.dir/rule # Convenience name for target. doxygen: CMakeFiles/doxygen.dir/rule .PHONY : doxygen # clean rule for target. CMakeFiles/doxygen.dir/clean: $(MAKE) -f CMakeFiles/doxygen.dir/build.make CMakeFiles/doxygen.dir/clean .PHONY : CMakeFiles/doxygen.dir/clean # clean rule for target. clean: CMakeFiles/doxygen.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/tf_generate_messages_cpp.dir # All Build rule for target. CMakeFiles/tf_generate_messages_cpp.dir/all: $(MAKE) -f CMakeFiles/tf_generate_messages_cpp.dir/build.make CMakeFiles/tf_generate_messages_cpp.dir/depend $(MAKE) -f CMakeFiles/tf_generate_messages_cpp.dir/build.make CMakeFiles/tf_generate_messages_cpp.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target tf_generate_messages_cpp" .PHONY : CMakeFiles/tf_generate_messages_cpp.dir/all # Build rule for subdir invocation for target. CMakeFiles/tf_generate_messages_cpp.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/tf_generate_messages_cpp.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/tf_generate_messages_cpp.dir/rule # Convenience name for target. tf_generate_messages_cpp: CMakeFiles/tf_generate_messages_cpp.dir/rule .PHONY : tf_generate_messages_cpp # clean rule for target. CMakeFiles/tf_generate_messages_cpp.dir/clean: $(MAKE) -f CMakeFiles/tf_generate_messages_cpp.dir/build.make CMakeFiles/tf_generate_messages_cpp.dir/clean .PHONY : CMakeFiles/tf_generate_messages_cpp.dir/clean # clean rule for target. clean: CMakeFiles/tf_generate_messages_cpp.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/nav_msgs_generate_messages_lisp.dir # All Build rule for target. CMakeFiles/nav_msgs_generate_messages_lisp.dir/all: $(MAKE) -f CMakeFiles/nav_msgs_generate_messages_lisp.dir/build.make CMakeFiles/nav_msgs_generate_messages_lisp.dir/depend $(MAKE) -f CMakeFiles/nav_msgs_generate_messages_lisp.dir/build.make CMakeFiles/nav_msgs_generate_messages_lisp.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target nav_msgs_generate_messages_lisp" .PHONY : CMakeFiles/nav_msgs_generate_messages_lisp.dir/all # Build rule for subdir invocation for target. CMakeFiles/nav_msgs_generate_messages_lisp.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/nav_msgs_generate_messages_lisp.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/nav_msgs_generate_messages_lisp.dir/rule # Convenience name for target. nav_msgs_generate_messages_lisp: CMakeFiles/nav_msgs_generate_messages_lisp.dir/rule .PHONY : nav_msgs_generate_messages_lisp # clean rule for target. CMakeFiles/nav_msgs_generate_messages_lisp.dir/clean: $(MAKE) -f CMakeFiles/nav_msgs_generate_messages_lisp.dir/build.make CMakeFiles/nav_msgs_generate_messages_lisp.dir/clean .PHONY : CMakeFiles/nav_msgs_generate_messages_lisp.dir/clean # clean rule for target. clean: CMakeFiles/nav_msgs_generate_messages_lisp.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/nav_msgs_generate_messages_nodejs.dir # All Build rule for target. CMakeFiles/nav_msgs_generate_messages_nodejs.dir/all: $(MAKE) -f CMakeFiles/nav_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/nav_msgs_generate_messages_nodejs.dir/depend $(MAKE) -f CMakeFiles/nav_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/nav_msgs_generate_messages_nodejs.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target nav_msgs_generate_messages_nodejs" .PHONY : CMakeFiles/nav_msgs_generate_messages_nodejs.dir/all # Build rule for subdir invocation for target. CMakeFiles/nav_msgs_generate_messages_nodejs.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/nav_msgs_generate_messages_nodejs.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/nav_msgs_generate_messages_nodejs.dir/rule # Convenience name for target. nav_msgs_generate_messages_nodejs: CMakeFiles/nav_msgs_generate_messages_nodejs.dir/rule .PHONY : nav_msgs_generate_messages_nodejs # clean rule for target. CMakeFiles/nav_msgs_generate_messages_nodejs.dir/clean: $(MAKE) -f CMakeFiles/nav_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/nav_msgs_generate_messages_nodejs.dir/clean .PHONY : CMakeFiles/nav_msgs_generate_messages_nodejs.dir/clean # clean rule for target. clean: CMakeFiles/nav_msgs_generate_messages_nodejs.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/std_msgs_generate_messages_py.dir # All Build rule for target. CMakeFiles/std_msgs_generate_messages_py.dir/all: $(MAKE) -f CMakeFiles/std_msgs_generate_messages_py.dir/build.make CMakeFiles/std_msgs_generate_messages_py.dir/depend $(MAKE) -f CMakeFiles/std_msgs_generate_messages_py.dir/build.make CMakeFiles/std_msgs_generate_messages_py.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target std_msgs_generate_messages_py" .PHONY : CMakeFiles/std_msgs_generate_messages_py.dir/all # Build rule for subdir invocation for target. CMakeFiles/std_msgs_generate_messages_py.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/std_msgs_generate_messages_py.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/std_msgs_generate_messages_py.dir/rule # Convenience name for target. std_msgs_generate_messages_py: CMakeFiles/std_msgs_generate_messages_py.dir/rule .PHONY : std_msgs_generate_messages_py # clean rule for target. CMakeFiles/std_msgs_generate_messages_py.dir/clean: $(MAKE) -f CMakeFiles/std_msgs_generate_messages_py.dir/build.make CMakeFiles/std_msgs_generate_messages_py.dir/clean .PHONY : CMakeFiles/std_msgs_generate_messages_py.dir/clean # clean rule for target. clean: CMakeFiles/std_msgs_generate_messages_py.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/nav_msgs_generate_messages_py.dir # All Build rule for target. CMakeFiles/nav_msgs_generate_messages_py.dir/all: $(MAKE) -f CMakeFiles/nav_msgs_generate_messages_py.dir/build.make CMakeFiles/nav_msgs_generate_messages_py.dir/depend $(MAKE) -f CMakeFiles/nav_msgs_generate_messages_py.dir/build.make CMakeFiles/nav_msgs_generate_messages_py.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target nav_msgs_generate_messages_py" .PHONY : CMakeFiles/nav_msgs_generate_messages_py.dir/all # Build rule for subdir invocation for target. CMakeFiles/nav_msgs_generate_messages_py.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/nav_msgs_generate_messages_py.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/nav_msgs_generate_messages_py.dir/rule # Convenience name for target. nav_msgs_generate_messages_py: CMakeFiles/nav_msgs_generate_messages_py.dir/rule .PHONY : nav_msgs_generate_messages_py # clean rule for target. CMakeFiles/nav_msgs_generate_messages_py.dir/clean: $(MAKE) -f CMakeFiles/nav_msgs_generate_messages_py.dir/build.make CMakeFiles/nav_msgs_generate_messages_py.dir/clean .PHONY : CMakeFiles/nav_msgs_generate_messages_py.dir/clean # clean rule for target. clean: CMakeFiles/nav_msgs_generate_messages_py.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/geometry_msgs_generate_messages_cpp.dir # All Build rule for target. CMakeFiles/geometry_msgs_generate_messages_cpp.dir/all: $(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_cpp.dir/build.make CMakeFiles/geometry_msgs_generate_messages_cpp.dir/depend $(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_cpp.dir/build.make CMakeFiles/geometry_msgs_generate_messages_cpp.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target geometry_msgs_generate_messages_cpp" .PHONY : CMakeFiles/geometry_msgs_generate_messages_cpp.dir/all # Build rule for subdir invocation for target. CMakeFiles/geometry_msgs_generate_messages_cpp.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/geometry_msgs_generate_messages_cpp.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/geometry_msgs_generate_messages_cpp.dir/rule # Convenience name for target. geometry_msgs_generate_messages_cpp: CMakeFiles/geometry_msgs_generate_messages_cpp.dir/rule .PHONY : geometry_msgs_generate_messages_cpp # clean rule for target. CMakeFiles/geometry_msgs_generate_messages_cpp.dir/clean: $(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_cpp.dir/build.make CMakeFiles/geometry_msgs_generate_messages_cpp.dir/clean .PHONY : CMakeFiles/geometry_msgs_generate_messages_cpp.dir/clean # clean rule for target. clean: CMakeFiles/geometry_msgs_generate_messages_cpp.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/sensor_msgs_generate_messages_nodejs.dir # All Build rule for target. CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/all: $(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/depend $(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target sensor_msgs_generate_messages_nodejs" .PHONY : CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/all # Build rule for subdir invocation for target. CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/rule # Convenience name for target. sensor_msgs_generate_messages_nodejs: CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/rule .PHONY : sensor_msgs_generate_messages_nodejs # clean rule for target. CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/clean: $(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/clean .PHONY : CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/clean # clean rule for target. clean: CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/std_msgs_generate_messages_nodejs.dir # All Build rule for target. CMakeFiles/std_msgs_generate_messages_nodejs.dir/all: $(MAKE) -f CMakeFiles/std_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/std_msgs_generate_messages_nodejs.dir/depend $(MAKE) -f CMakeFiles/std_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/std_msgs_generate_messages_nodejs.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target std_msgs_generate_messages_nodejs" .PHONY : CMakeFiles/std_msgs_generate_messages_nodejs.dir/all # Build rule for subdir invocation for target. CMakeFiles/std_msgs_generate_messages_nodejs.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/std_msgs_generate_messages_nodejs.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/std_msgs_generate_messages_nodejs.dir/rule # Convenience name for target. std_msgs_generate_messages_nodejs: CMakeFiles/std_msgs_generate_messages_nodejs.dir/rule .PHONY : std_msgs_generate_messages_nodejs # clean rule for target. CMakeFiles/std_msgs_generate_messages_nodejs.dir/clean: $(MAKE) -f CMakeFiles/std_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/std_msgs_generate_messages_nodejs.dir/clean .PHONY : CMakeFiles/std_msgs_generate_messages_nodejs.dir/clean # clean rule for target. clean: CMakeFiles/std_msgs_generate_messages_nodejs.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/geometry_msgs_generate_messages_py.dir # All Build rule for target. CMakeFiles/geometry_msgs_generate_messages_py.dir/all: $(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_py.dir/build.make CMakeFiles/geometry_msgs_generate_messages_py.dir/depend $(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_py.dir/build.make CMakeFiles/geometry_msgs_generate_messages_py.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target geometry_msgs_generate_messages_py" .PHONY : CMakeFiles/geometry_msgs_generate_messages_py.dir/all # Build rule for subdir invocation for target. CMakeFiles/geometry_msgs_generate_messages_py.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/geometry_msgs_generate_messages_py.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/geometry_msgs_generate_messages_py.dir/rule # Convenience name for target. geometry_msgs_generate_messages_py: CMakeFiles/geometry_msgs_generate_messages_py.dir/rule .PHONY : geometry_msgs_generate_messages_py # clean rule for target. CMakeFiles/geometry_msgs_generate_messages_py.dir/clean: $(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_py.dir/build.make CMakeFiles/geometry_msgs_generate_messages_py.dir/clean .PHONY : CMakeFiles/geometry_msgs_generate_messages_py.dir/clean # clean rule for target. clean: CMakeFiles/geometry_msgs_generate_messages_py.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/actionlib_msgs_generate_messages_lisp.dir # All Build rule for target. CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/all: $(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/depend $(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target actionlib_msgs_generate_messages_lisp" .PHONY : CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/all # Build rule for subdir invocation for target. CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/rule # Convenience name for target. actionlib_msgs_generate_messages_lisp: CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/rule .PHONY : actionlib_msgs_generate_messages_lisp # clean rule for target. CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/clean: $(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/clean .PHONY : CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/clean # clean rule for target. clean: CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/tf2_msgs_generate_messages_py.dir # All Build rule for target. CMakeFiles/tf2_msgs_generate_messages_py.dir/all: $(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_py.dir/build.make CMakeFiles/tf2_msgs_generate_messages_py.dir/depend $(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_py.dir/build.make CMakeFiles/tf2_msgs_generate_messages_py.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target tf2_msgs_generate_messages_py" .PHONY : CMakeFiles/tf2_msgs_generate_messages_py.dir/all # Build rule for subdir invocation for target. CMakeFiles/tf2_msgs_generate_messages_py.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/tf2_msgs_generate_messages_py.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/tf2_msgs_generate_messages_py.dir/rule # Convenience name for target. tf2_msgs_generate_messages_py: CMakeFiles/tf2_msgs_generate_messages_py.dir/rule .PHONY : tf2_msgs_generate_messages_py # clean rule for target. CMakeFiles/tf2_msgs_generate_messages_py.dir/clean: $(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_py.dir/build.make CMakeFiles/tf2_msgs_generate_messages_py.dir/clean .PHONY : CMakeFiles/tf2_msgs_generate_messages_py.dir/clean # clean rule for target. clean: CMakeFiles/tf2_msgs_generate_messages_py.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir # All Build rule for target. CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/all: $(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/depend $(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target actionlib_msgs_generate_messages_nodejs" .PHONY : CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/all # Build rule for subdir invocation for target. CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/rule # Convenience name for target. actionlib_msgs_generate_messages_nodejs: CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/rule .PHONY : actionlib_msgs_generate_messages_nodejs # clean rule for target. CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/clean: $(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/clean .PHONY : CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/clean # clean rule for target. clean: CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/sensor_msgs_generate_messages_cpp.dir # All Build rule for target. CMakeFiles/sensor_msgs_generate_messages_cpp.dir/all: $(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_cpp.dir/build.make CMakeFiles/sensor_msgs_generate_messages_cpp.dir/depend $(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_cpp.dir/build.make CMakeFiles/sensor_msgs_generate_messages_cpp.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target sensor_msgs_generate_messages_cpp" .PHONY : CMakeFiles/sensor_msgs_generate_messages_cpp.dir/all # Build rule for subdir invocation for target. CMakeFiles/sensor_msgs_generate_messages_cpp.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/sensor_msgs_generate_messages_cpp.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/sensor_msgs_generate_messages_cpp.dir/rule # Convenience name for target. sensor_msgs_generate_messages_cpp: CMakeFiles/sensor_msgs_generate_messages_cpp.dir/rule .PHONY : sensor_msgs_generate_messages_cpp # clean rule for target. CMakeFiles/sensor_msgs_generate_messages_cpp.dir/clean: $(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_cpp.dir/build.make CMakeFiles/sensor_msgs_generate_messages_cpp.dir/clean .PHONY : CMakeFiles/sensor_msgs_generate_messages_cpp.dir/clean # clean rule for target. clean: CMakeFiles/sensor_msgs_generate_messages_cpp.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/actionlib_generate_messages_nodejs.dir # All Build rule for target. CMakeFiles/actionlib_generate_messages_nodejs.dir/all: $(MAKE) -f CMakeFiles/actionlib_generate_messages_nodejs.dir/build.make CMakeFiles/actionlib_generate_messages_nodejs.dir/depend $(MAKE) -f CMakeFiles/actionlib_generate_messages_nodejs.dir/build.make CMakeFiles/actionlib_generate_messages_nodejs.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target actionlib_generate_messages_nodejs" .PHONY : CMakeFiles/actionlib_generate_messages_nodejs.dir/all # Build rule for subdir invocation for target. CMakeFiles/actionlib_generate_messages_nodejs.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/actionlib_generate_messages_nodejs.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/actionlib_generate_messages_nodejs.dir/rule # Convenience name for target. actionlib_generate_messages_nodejs: CMakeFiles/actionlib_generate_messages_nodejs.dir/rule .PHONY : actionlib_generate_messages_nodejs # clean rule for target. CMakeFiles/actionlib_generate_messages_nodejs.dir/clean: $(MAKE) -f CMakeFiles/actionlib_generate_messages_nodejs.dir/build.make CMakeFiles/actionlib_generate_messages_nodejs.dir/clean .PHONY : CMakeFiles/actionlib_generate_messages_nodejs.dir/clean # clean rule for target. clean: CMakeFiles/actionlib_generate_messages_nodejs.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/actionlib_msgs_generate_messages_cpp.dir # All Build rule for target. CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/all: $(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/depend $(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target actionlib_msgs_generate_messages_cpp" .PHONY : CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/all # Build rule for subdir invocation for target. CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/rule # Convenience name for target. actionlib_msgs_generate_messages_cpp: CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/rule .PHONY : actionlib_msgs_generate_messages_cpp # clean rule for target. CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/clean: $(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/clean .PHONY : CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/clean # clean rule for target. clean: CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/std_msgs_generate_messages_cpp.dir # All Build rule for target. CMakeFiles/std_msgs_generate_messages_cpp.dir/all: $(MAKE) -f CMakeFiles/std_msgs_generate_messages_cpp.dir/build.make CMakeFiles/std_msgs_generate_messages_cpp.dir/depend $(MAKE) -f CMakeFiles/std_msgs_generate_messages_cpp.dir/build.make CMakeFiles/std_msgs_generate_messages_cpp.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target std_msgs_generate_messages_cpp" .PHONY : CMakeFiles/std_msgs_generate_messages_cpp.dir/all # Build rule for subdir invocation for target. CMakeFiles/std_msgs_generate_messages_cpp.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/std_msgs_generate_messages_cpp.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/std_msgs_generate_messages_cpp.dir/rule # Convenience name for target. std_msgs_generate_messages_cpp: CMakeFiles/std_msgs_generate_messages_cpp.dir/rule .PHONY : std_msgs_generate_messages_cpp # clean rule for target. CMakeFiles/std_msgs_generate_messages_cpp.dir/clean: $(MAKE) -f CMakeFiles/std_msgs_generate_messages_cpp.dir/build.make CMakeFiles/std_msgs_generate_messages_cpp.dir/clean .PHONY : CMakeFiles/std_msgs_generate_messages_cpp.dir/clean # clean rule for target. clean: CMakeFiles/std_msgs_generate_messages_cpp.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/sensor_msgs_generate_messages_eus.dir # All Build rule for target. CMakeFiles/sensor_msgs_generate_messages_eus.dir/all: $(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_eus.dir/build.make CMakeFiles/sensor_msgs_generate_messages_eus.dir/depend $(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_eus.dir/build.make CMakeFiles/sensor_msgs_generate_messages_eus.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target sensor_msgs_generate_messages_eus" .PHONY : CMakeFiles/sensor_msgs_generate_messages_eus.dir/all # Build rule for subdir invocation for target. CMakeFiles/sensor_msgs_generate_messages_eus.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/sensor_msgs_generate_messages_eus.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/sensor_msgs_generate_messages_eus.dir/rule # Convenience name for target. sensor_msgs_generate_messages_eus: CMakeFiles/sensor_msgs_generate_messages_eus.dir/rule .PHONY : sensor_msgs_generate_messages_eus # clean rule for target. CMakeFiles/sensor_msgs_generate_messages_eus.dir/clean: $(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_eus.dir/build.make CMakeFiles/sensor_msgs_generate_messages_eus.dir/clean .PHONY : CMakeFiles/sensor_msgs_generate_messages_eus.dir/clean # clean rule for target. clean: CMakeFiles/sensor_msgs_generate_messages_eus.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/download_extra_data.dir # All Build rule for target. CMakeFiles/download_extra_data.dir/all: $(MAKE) -f CMakeFiles/download_extra_data.dir/build.make CMakeFiles/download_extra_data.dir/depend $(MAKE) -f CMakeFiles/download_extra_data.dir/build.make CMakeFiles/download_extra_data.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target download_extra_data" .PHONY : CMakeFiles/download_extra_data.dir/all # Build rule for subdir invocation for target. CMakeFiles/download_extra_data.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/download_extra_data.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/download_extra_data.dir/rule # Convenience name for target. download_extra_data: CMakeFiles/download_extra_data.dir/rule .PHONY : download_extra_data # clean rule for target. CMakeFiles/download_extra_data.dir/clean: $(MAKE) -f CMakeFiles/download_extra_data.dir/build.make CMakeFiles/download_extra_data.dir/clean .PHONY : CMakeFiles/download_extra_data.dir/clean # clean rule for target. clean: CMakeFiles/download_extra_data.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/sensor_msgs_generate_messages_lisp.dir # All Build rule for target. CMakeFiles/sensor_msgs_generate_messages_lisp.dir/all: $(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_lisp.dir/build.make CMakeFiles/sensor_msgs_generate_messages_lisp.dir/depend $(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_lisp.dir/build.make CMakeFiles/sensor_msgs_generate_messages_lisp.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target sensor_msgs_generate_messages_lisp" .PHONY : CMakeFiles/sensor_msgs_generate_messages_lisp.dir/all # Build rule for subdir invocation for target. CMakeFiles/sensor_msgs_generate_messages_lisp.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/sensor_msgs_generate_messages_lisp.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/sensor_msgs_generate_messages_lisp.dir/rule # Convenience name for target. sensor_msgs_generate_messages_lisp: CMakeFiles/sensor_msgs_generate_messages_lisp.dir/rule .PHONY : sensor_msgs_generate_messages_lisp # clean rule for target. CMakeFiles/sensor_msgs_generate_messages_lisp.dir/clean: $(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_lisp.dir/build.make CMakeFiles/sensor_msgs_generate_messages_lisp.dir/clean .PHONY : CMakeFiles/sensor_msgs_generate_messages_lisp.dir/clean # clean rule for target. clean: CMakeFiles/sensor_msgs_generate_messages_lisp.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/actionlib_generate_messages_cpp.dir # All Build rule for target. CMakeFiles/actionlib_generate_messages_cpp.dir/all: $(MAKE) -f CMakeFiles/actionlib_generate_messages_cpp.dir/build.make CMakeFiles/actionlib_generate_messages_cpp.dir/depend $(MAKE) -f CMakeFiles/actionlib_generate_messages_cpp.dir/build.make CMakeFiles/actionlib_generate_messages_cpp.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target actionlib_generate_messages_cpp" .PHONY : CMakeFiles/actionlib_generate_messages_cpp.dir/all # Build rule for subdir invocation for target. CMakeFiles/actionlib_generate_messages_cpp.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/actionlib_generate_messages_cpp.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/actionlib_generate_messages_cpp.dir/rule # Convenience name for target. actionlib_generate_messages_cpp: CMakeFiles/actionlib_generate_messages_cpp.dir/rule .PHONY : actionlib_generate_messages_cpp # clean rule for target. CMakeFiles/actionlib_generate_messages_cpp.dir/clean: $(MAKE) -f CMakeFiles/actionlib_generate_messages_cpp.dir/build.make CMakeFiles/actionlib_generate_messages_cpp.dir/clean .PHONY : CMakeFiles/actionlib_generate_messages_cpp.dir/clean # clean rule for target. clean: CMakeFiles/actionlib_generate_messages_cpp.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/sensor_msgs_generate_messages_py.dir # All Build rule for target. CMakeFiles/sensor_msgs_generate_messages_py.dir/all: $(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_py.dir/build.make CMakeFiles/sensor_msgs_generate_messages_py.dir/depend $(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_py.dir/build.make CMakeFiles/sensor_msgs_generate_messages_py.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target sensor_msgs_generate_messages_py" .PHONY : CMakeFiles/sensor_msgs_generate_messages_py.dir/all # Build rule for subdir invocation for target. CMakeFiles/sensor_msgs_generate_messages_py.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/sensor_msgs_generate_messages_py.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/sensor_msgs_generate_messages_py.dir/rule # Convenience name for target. sensor_msgs_generate_messages_py: CMakeFiles/sensor_msgs_generate_messages_py.dir/rule .PHONY : sensor_msgs_generate_messages_py # clean rule for target. CMakeFiles/sensor_msgs_generate_messages_py.dir/clean: $(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_py.dir/build.make CMakeFiles/sensor_msgs_generate_messages_py.dir/clean .PHONY : CMakeFiles/sensor_msgs_generate_messages_py.dir/clean # clean rule for target. clean: CMakeFiles/sensor_msgs_generate_messages_py.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/rosgraph_msgs_generate_messages_py.dir # All Build rule for target. CMakeFiles/rosgraph_msgs_generate_messages_py.dir/all: $(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_py.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_py.dir/depend $(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_py.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_py.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target rosgraph_msgs_generate_messages_py" .PHONY : CMakeFiles/rosgraph_msgs_generate_messages_py.dir/all # Build rule for subdir invocation for target. CMakeFiles/rosgraph_msgs_generate_messages_py.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/rosgraph_msgs_generate_messages_py.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/rosgraph_msgs_generate_messages_py.dir/rule # Convenience name for target. rosgraph_msgs_generate_messages_py: CMakeFiles/rosgraph_msgs_generate_messages_py.dir/rule .PHONY : rosgraph_msgs_generate_messages_py # clean rule for target. CMakeFiles/rosgraph_msgs_generate_messages_py.dir/clean: $(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_py.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_py.dir/clean .PHONY : CMakeFiles/rosgraph_msgs_generate_messages_py.dir/clean # clean rule for target. clean: CMakeFiles/rosgraph_msgs_generate_messages_py.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/tf_generate_messages_lisp.dir # All Build rule for target. CMakeFiles/tf_generate_messages_lisp.dir/all: $(MAKE) -f CMakeFiles/tf_generate_messages_lisp.dir/build.make CMakeFiles/tf_generate_messages_lisp.dir/depend $(MAKE) -f CMakeFiles/tf_generate_messages_lisp.dir/build.make CMakeFiles/tf_generate_messages_lisp.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target tf_generate_messages_lisp" .PHONY : CMakeFiles/tf_generate_messages_lisp.dir/all # Build rule for subdir invocation for target. CMakeFiles/tf_generate_messages_lisp.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/tf_generate_messages_lisp.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/tf_generate_messages_lisp.dir/rule # Convenience name for target. tf_generate_messages_lisp: CMakeFiles/tf_generate_messages_lisp.dir/rule .PHONY : tf_generate_messages_lisp # clean rule for target. CMakeFiles/tf_generate_messages_lisp.dir/clean: $(MAKE) -f CMakeFiles/tf_generate_messages_lisp.dir/build.make CMakeFiles/tf_generate_messages_lisp.dir/clean .PHONY : CMakeFiles/tf_generate_messages_lisp.dir/clean # clean rule for target. clean: CMakeFiles/tf_generate_messages_lisp.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/roscpp_generate_messages_py.dir # All Build rule for target. CMakeFiles/roscpp_generate_messages_py.dir/all: $(MAKE) -f CMakeFiles/roscpp_generate_messages_py.dir/build.make CMakeFiles/roscpp_generate_messages_py.dir/depend $(MAKE) -f CMakeFiles/roscpp_generate_messages_py.dir/build.make CMakeFiles/roscpp_generate_messages_py.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target roscpp_generate_messages_py" .PHONY : CMakeFiles/roscpp_generate_messages_py.dir/all # Build rule for subdir invocation for target. CMakeFiles/roscpp_generate_messages_py.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/roscpp_generate_messages_py.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/roscpp_generate_messages_py.dir/rule # Convenience name for target. roscpp_generate_messages_py: CMakeFiles/roscpp_generate_messages_py.dir/rule .PHONY : roscpp_generate_messages_py # clean rule for target. CMakeFiles/roscpp_generate_messages_py.dir/clean: $(MAKE) -f CMakeFiles/roscpp_generate_messages_py.dir/build.make CMakeFiles/roscpp_generate_messages_py.dir/clean .PHONY : CMakeFiles/roscpp_generate_messages_py.dir/clean # clean rule for target. clean: CMakeFiles/roscpp_generate_messages_py.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/tf_generate_messages_nodejs.dir # All Build rule for target. CMakeFiles/tf_generate_messages_nodejs.dir/all: $(MAKE) -f CMakeFiles/tf_generate_messages_nodejs.dir/build.make CMakeFiles/tf_generate_messages_nodejs.dir/depend $(MAKE) -f CMakeFiles/tf_generate_messages_nodejs.dir/build.make CMakeFiles/tf_generate_messages_nodejs.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target tf_generate_messages_nodejs" .PHONY : CMakeFiles/tf_generate_messages_nodejs.dir/all # Build rule for subdir invocation for target. CMakeFiles/tf_generate_messages_nodejs.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/tf_generate_messages_nodejs.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/tf_generate_messages_nodejs.dir/rule # Convenience name for target. tf_generate_messages_nodejs: CMakeFiles/tf_generate_messages_nodejs.dir/rule .PHONY : tf_generate_messages_nodejs # clean rule for target. CMakeFiles/tf_generate_messages_nodejs.dir/clean: $(MAKE) -f CMakeFiles/tf_generate_messages_nodejs.dir/build.make CMakeFiles/tf_generate_messages_nodejs.dir/clean .PHONY : CMakeFiles/tf_generate_messages_nodejs.dir/clean # clean rule for target. clean: CMakeFiles/tf_generate_messages_nodejs.dir/clean .PHONY : clean #============================================================================= # Target rules for target CMakeFiles/tf_generate_messages_py.dir # All Build rule for target. CMakeFiles/tf_generate_messages_py.dir/all: $(MAKE) -f CMakeFiles/tf_generate_messages_py.dir/build.make CMakeFiles/tf_generate_messages_py.dir/depend $(MAKE) -f CMakeFiles/tf_generate_messages_py.dir/build.make CMakeFiles/tf_generate_messages_py.dir/build @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num= "Built target tf_generate_messages_py" .PHONY : CMakeFiles/tf_generate_messages_py.dir/all # Build rule for subdir invocation for target. CMakeFiles/tf_generate_messages_py.dir/rule: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/tf_generate_messages_py.dir/all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : CMakeFiles/tf_generate_messages_py.dir/rule # Convenience name for target. tf_generate_messages_py: CMakeFiles/tf_generate_messages_py.dir/rule .PHONY : tf_generate_messages_py # clean rule for target. CMakeFiles/tf_generate_messages_py.dir/clean: $(MAKE) -f CMakeFiles/tf_generate_messages_py.dir/build.make CMakeFiles/tf_generate_messages_py.dir/clean .PHONY : CMakeFiles/tf_generate_messages_py.dir/clean # clean rule for target. clean: CMakeFiles/tf_generate_messages_py.dir/clean .PHONY : clean #============================================================================= # Special targets to cleanup operation of make. # Special rule to run CMake to check the build system integrity. # No rule that depends on this can have commands that come from listfiles # because they might be regenerated. cmake_check_build_system: $(CMAKE_COMMAND) -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 0 .PHONY : cmake_check_build_system ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/Progress/2 ================================================ empty ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/Progress/count.txt ================================================ 2 ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/TargetDirectories.txt ================================================ /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/install/local.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/edit_cache.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_nodejs.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_lisp.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_eus.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_cpp.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_py.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_eus.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/install/strip.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_eus.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_eus.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_lisp.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tests.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rf2o_laser_odometry_node.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_nodejs.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rebuild_cache.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_eus.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_cpp.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/install.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_lisp.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_lisp.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/run_tests.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_lisp.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_eus.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/list_install_components.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_eus.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_cpp.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_eus.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_py.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/clean_test_results.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_nodejs.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_eus.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/doxygen.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_cpp.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_lisp.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_nodejs.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_py.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_py.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/test.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_cpp.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_nodejs.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_nodejs.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_py.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_lisp.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_py.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_cpp.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_nodejs.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_cpp.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_cpp.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_eus.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/download_extra_data.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_lisp.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_cpp.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_py.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_py.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_lisp.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_py.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_nodejs.dir /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_py.dir ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_cpp.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_cpp.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for actionlib_generate_messages_cpp. # Include the progress variables for this target. include CMakeFiles/actionlib_generate_messages_cpp.dir/progress.make actionlib_generate_messages_cpp: CMakeFiles/actionlib_generate_messages_cpp.dir/build.make .PHONY : actionlib_generate_messages_cpp # Rule to build all files generated by this target. CMakeFiles/actionlib_generate_messages_cpp.dir/build: actionlib_generate_messages_cpp .PHONY : CMakeFiles/actionlib_generate_messages_cpp.dir/build CMakeFiles/actionlib_generate_messages_cpp.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/actionlib_generate_messages_cpp.dir/cmake_clean.cmake .PHONY : CMakeFiles/actionlib_generate_messages_cpp.dir/clean CMakeFiles/actionlib_generate_messages_cpp.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_cpp.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/actionlib_generate_messages_cpp.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_cpp.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/actionlib_generate_messages_cpp.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_cpp.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_eus.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_eus.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for actionlib_generate_messages_eus. # Include the progress variables for this target. include CMakeFiles/actionlib_generate_messages_eus.dir/progress.make actionlib_generate_messages_eus: CMakeFiles/actionlib_generate_messages_eus.dir/build.make .PHONY : actionlib_generate_messages_eus # Rule to build all files generated by this target. CMakeFiles/actionlib_generate_messages_eus.dir/build: actionlib_generate_messages_eus .PHONY : CMakeFiles/actionlib_generate_messages_eus.dir/build CMakeFiles/actionlib_generate_messages_eus.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/actionlib_generate_messages_eus.dir/cmake_clean.cmake .PHONY : CMakeFiles/actionlib_generate_messages_eus.dir/clean CMakeFiles/actionlib_generate_messages_eus.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_eus.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/actionlib_generate_messages_eus.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_eus.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/actionlib_generate_messages_eus.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_eus.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_lisp.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_lisp.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for actionlib_generate_messages_lisp. # Include the progress variables for this target. include CMakeFiles/actionlib_generate_messages_lisp.dir/progress.make actionlib_generate_messages_lisp: CMakeFiles/actionlib_generate_messages_lisp.dir/build.make .PHONY : actionlib_generate_messages_lisp # Rule to build all files generated by this target. CMakeFiles/actionlib_generate_messages_lisp.dir/build: actionlib_generate_messages_lisp .PHONY : CMakeFiles/actionlib_generate_messages_lisp.dir/build CMakeFiles/actionlib_generate_messages_lisp.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/actionlib_generate_messages_lisp.dir/cmake_clean.cmake .PHONY : CMakeFiles/actionlib_generate_messages_lisp.dir/clean CMakeFiles/actionlib_generate_messages_lisp.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_lisp.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/actionlib_generate_messages_lisp.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_lisp.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/actionlib_generate_messages_lisp.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_lisp.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_nodejs.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_nodejs.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for actionlib_generate_messages_nodejs. # Include the progress variables for this target. include CMakeFiles/actionlib_generate_messages_nodejs.dir/progress.make actionlib_generate_messages_nodejs: CMakeFiles/actionlib_generate_messages_nodejs.dir/build.make .PHONY : actionlib_generate_messages_nodejs # Rule to build all files generated by this target. CMakeFiles/actionlib_generate_messages_nodejs.dir/build: actionlib_generate_messages_nodejs .PHONY : CMakeFiles/actionlib_generate_messages_nodejs.dir/build CMakeFiles/actionlib_generate_messages_nodejs.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/actionlib_generate_messages_nodejs.dir/cmake_clean.cmake .PHONY : CMakeFiles/actionlib_generate_messages_nodejs.dir/clean CMakeFiles/actionlib_generate_messages_nodejs.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_nodejs.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/actionlib_generate_messages_nodejs.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_nodejs.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/actionlib_generate_messages_nodejs.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_nodejs.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_py.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_py.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for actionlib_generate_messages_py. # Include the progress variables for this target. include CMakeFiles/actionlib_generate_messages_py.dir/progress.make actionlib_generate_messages_py: CMakeFiles/actionlib_generate_messages_py.dir/build.make .PHONY : actionlib_generate_messages_py # Rule to build all files generated by this target. CMakeFiles/actionlib_generate_messages_py.dir/build: actionlib_generate_messages_py .PHONY : CMakeFiles/actionlib_generate_messages_py.dir/build CMakeFiles/actionlib_generate_messages_py.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/actionlib_generate_messages_py.dir/cmake_clean.cmake .PHONY : CMakeFiles/actionlib_generate_messages_py.dir/clean CMakeFiles/actionlib_generate_messages_py.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_py.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/actionlib_generate_messages_py.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_py.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/actionlib_generate_messages_py.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_py.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for actionlib_msgs_generate_messages_cpp. # Include the progress variables for this target. include CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/progress.make actionlib_msgs_generate_messages_cpp: CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/build.make .PHONY : actionlib_msgs_generate_messages_cpp # Rule to build all files generated by this target. CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/build: actionlib_msgs_generate_messages_cpp .PHONY : CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/build CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/cmake_clean.cmake .PHONY : CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/clean CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_eus.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_eus.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for actionlib_msgs_generate_messages_eus. # Include the progress variables for this target. include CMakeFiles/actionlib_msgs_generate_messages_eus.dir/progress.make actionlib_msgs_generate_messages_eus: CMakeFiles/actionlib_msgs_generate_messages_eus.dir/build.make .PHONY : actionlib_msgs_generate_messages_eus # Rule to build all files generated by this target. CMakeFiles/actionlib_msgs_generate_messages_eus.dir/build: actionlib_msgs_generate_messages_eus .PHONY : CMakeFiles/actionlib_msgs_generate_messages_eus.dir/build CMakeFiles/actionlib_msgs_generate_messages_eus.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/actionlib_msgs_generate_messages_eus.dir/cmake_clean.cmake .PHONY : CMakeFiles/actionlib_msgs_generate_messages_eus.dir/clean CMakeFiles/actionlib_msgs_generate_messages_eus.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_eus.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/actionlib_msgs_generate_messages_eus.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_eus.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/actionlib_msgs_generate_messages_eus.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_eus.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for actionlib_msgs_generate_messages_lisp. # Include the progress variables for this target. include CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/progress.make actionlib_msgs_generate_messages_lisp: CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/build.make .PHONY : actionlib_msgs_generate_messages_lisp # Rule to build all files generated by this target. CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/build: actionlib_msgs_generate_messages_lisp .PHONY : CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/build CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/cmake_clean.cmake .PHONY : CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/clean CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for actionlib_msgs_generate_messages_nodejs. # Include the progress variables for this target. include CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/progress.make actionlib_msgs_generate_messages_nodejs: CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/build.make .PHONY : actionlib_msgs_generate_messages_nodejs # Rule to build all files generated by this target. CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/build: actionlib_msgs_generate_messages_nodejs .PHONY : CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/build CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/cmake_clean.cmake .PHONY : CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/clean CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_py.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_py.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for actionlib_msgs_generate_messages_py. # Include the progress variables for this target. include CMakeFiles/actionlib_msgs_generate_messages_py.dir/progress.make actionlib_msgs_generate_messages_py: CMakeFiles/actionlib_msgs_generate_messages_py.dir/build.make .PHONY : actionlib_msgs_generate_messages_py # Rule to build all files generated by this target. CMakeFiles/actionlib_msgs_generate_messages_py.dir/build: actionlib_msgs_generate_messages_py .PHONY : CMakeFiles/actionlib_msgs_generate_messages_py.dir/build CMakeFiles/actionlib_msgs_generate_messages_py.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/actionlib_msgs_generate_messages_py.dir/cmake_clean.cmake .PHONY : CMakeFiles/actionlib_msgs_generate_messages_py.dir/clean CMakeFiles/actionlib_msgs_generate_messages_py.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_py.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/actionlib_msgs_generate_messages_py.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_py.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/actionlib_msgs_generate_messages_py.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_py.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/clean_test_results.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/clean_test_results.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for clean_test_results. # Include the progress variables for this target. include CMakeFiles/clean_test_results.dir/progress.make CMakeFiles/clean_test_results: /usr/bin/python /opt/ros/kinetic/share/catkin/cmake/test/remove_test_results.py /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/test_results clean_test_results: CMakeFiles/clean_test_results clean_test_results: CMakeFiles/clean_test_results.dir/build.make .PHONY : clean_test_results # Rule to build all files generated by this target. CMakeFiles/clean_test_results.dir/build: clean_test_results .PHONY : CMakeFiles/clean_test_results.dir/build CMakeFiles/clean_test_results.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/clean_test_results.dir/cmake_clean.cmake .PHONY : CMakeFiles/clean_test_results.dir/clean CMakeFiles/clean_test_results.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/clean_test_results.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/clean_test_results.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/clean_test_results.dir/cmake_clean.cmake ================================================ file(REMOVE_RECURSE "CMakeFiles/clean_test_results" ) # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/clean_test_results.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/clean_test_results.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/clion-environment.txt ================================================ Options: Options: ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/clion-log.txt ================================================ /home/zn/.ide/clion/bin/cmake/bin/cmake -DCMAKE_BUILD_TYPE=Debug -G "CodeBlocks - Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry -- The C compiler identification is GNU 5.4.0 -- The CXX compiler identification is GNU 5.4.0 -- Check for working C compiler: /usr/bin/cc -- Check for working C compiler: /usr/bin/cc -- works -- Detecting C compiler ABI info -- Detecting C compiler ABI info - done -- Detecting C compile features -- Detecting C compile features - done -- Check for working CXX compiler: /usr/bin/c++ -- Check for working CXX compiler: /usr/bin/c++ -- works -- Detecting CXX compiler ABI info -- Detecting CXX compiler ABI info - done -- Detecting CXX compile features -- Detecting CXX compile features - done -- Using CATKIN_DEVEL_PREFIX: /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/devel -- Using CMAKE_PREFIX_PATH: /home/zn/artrobot/devel;/opt/ros/kinetic -- This workspace overlays: /home/zn/artrobot/devel;/opt/ros/kinetic -- Found PythonInterp: /usr/bin/python (found version "2.7.12") -- Using PYTHON_EXECUTABLE: /usr/bin/python -- Using Debian Python package layout -- Using empy: /usr/bin/empy -- Using CATKIN_ENABLE_TESTING: ON -- Call enable_testing() -- Using CATKIN_TEST_RESULTS_DIR: /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/test_results -- Found gtest: gtests will be built -- Using Python nosetests: /usr/bin/nosetests-2.7 -- catkin 0.7.11 -- Using these message generators: gencpp;geneus;genlisp;gennodejs;genpy -- Boost version: 1.58.0 -- Found the following Boost libraries: -- system -- Found MRPT: 1.3.2 -- Configuring done -- Generating done -- Build files have been written to: /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/cmake.check_cache ================================================ # This file is generated by cmake for dependency checking of the CMakeCache.txt file ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/download_extra_data.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/download_extra_data.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for download_extra_data. # Include the progress variables for this target. include CMakeFiles/download_extra_data.dir/progress.make download_extra_data: CMakeFiles/download_extra_data.dir/build.make .PHONY : download_extra_data # Rule to build all files generated by this target. CMakeFiles/download_extra_data.dir/build: download_extra_data .PHONY : CMakeFiles/download_extra_data.dir/build CMakeFiles/download_extra_data.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/download_extra_data.dir/cmake_clean.cmake .PHONY : CMakeFiles/download_extra_data.dir/clean CMakeFiles/download_extra_data.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/download_extra_data.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/download_extra_data.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/download_extra_data.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/download_extra_data.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/download_extra_data.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/doxygen.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/doxygen.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for doxygen. # Include the progress variables for this target. include CMakeFiles/doxygen.dir/progress.make doxygen: CMakeFiles/doxygen.dir/build.make .PHONY : doxygen # Rule to build all files generated by this target. CMakeFiles/doxygen.dir/build: doxygen .PHONY : CMakeFiles/doxygen.dir/build CMakeFiles/doxygen.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/doxygen.dir/cmake_clean.cmake .PHONY : CMakeFiles/doxygen.dir/clean CMakeFiles/doxygen.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/doxygen.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/doxygen.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/doxygen.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/doxygen.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/doxygen.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/feature_tests.c ================================================ const char features[] = {"\n" "C_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 304 "1" #else "0" #endif "c_function_prototypes\n" "C_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 304 && defined(__STDC_VERSION__) && __STDC_VERSION__ >= 199901L "1" #else "0" #endif "c_restrict\n" "C_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 406 && defined(__STDC_VERSION__) && __STDC_VERSION__ >= 201000L "1" #else "0" #endif "c_static_assert\n" "C_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 304 && defined(__STDC_VERSION__) && __STDC_VERSION__ >= 199901L "1" #else "0" #endif "c_variadic_macros\n" }; int main(int argc, char** argv) { (void)argv; return features[argc]; } ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/feature_tests.cxx ================================================ const char features[] = {"\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 500 && __cplusplus >= 201402L "1" #else "0" #endif "cxx_aggregate_default_initializers\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 407 && __cplusplus >= 201103L "1" #else "0" #endif "cxx_alias_templates\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 408 && __cplusplus >= 201103L "1" #else "0" #endif "cxx_alignas\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 408 && __cplusplus >= 201103L "1" #else "0" #endif "cxx_alignof\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 408 && __cplusplus >= 201103L "1" #else "0" #endif "cxx_attributes\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 409 && __cplusplus > 201103L "1" #else "0" #endif "cxx_attribute_deprecated\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 404 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__)) "1" #else "0" #endif "cxx_auto_type\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 409 && __cplusplus > 201103L "1" #else "0" #endif "cxx_binary_literals\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 406 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__)) "1" #else "0" #endif "cxx_constexpr\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 409 && __cplusplus > 201103L "1" #else "0" #endif "cxx_contextual_conversions\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 404 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__)) "1" #else "0" #endif "cxx_decltype\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 409 && __cplusplus > 201103L "1" #else "0" #endif "cxx_decltype_auto\n" "CXX_FEATURE:" #if ((__GNUC__ * 10000 + __GNUC_MINOR__ * 100 + __GNUC_PATCHLEVEL__) >= 40801) && __cplusplus >= 201103L "1" #else "0" #endif "cxx_decltype_incomplete_return_types\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 404 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__)) "1" #else "0" #endif "cxx_default_function_template_args\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 404 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__)) "1" #else "0" #endif "cxx_defaulted_functions\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 406 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__)) "1" #else "0" #endif "cxx_defaulted_move_initializers\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 407 && __cplusplus >= 201103L "1" #else "0" #endif "cxx_delegating_constructors\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 404 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__)) "1" #else "0" #endif "cxx_deleted_functions\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 409 && __cplusplus > 201103L "1" #else "0" #endif "cxx_digit_separators\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 406 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__)) "1" #else "0" #endif "cxx_enum_forward_declarations\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 405 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__)) "1" #else "0" #endif "cxx_explicit_conversions\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 407 && __cplusplus >= 201103L "1" #else "0" #endif "cxx_extended_friend_declarations\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 404 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__)) "1" #else "0" #endif "cxx_extern_templates\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 407 && __cplusplus >= 201103L "1" #else "0" #endif "cxx_final\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 404 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__)) "1" #else "0" #endif "cxx_func_identifier\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 404 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__)) "1" #else "0" #endif "cxx_generalized_initializers\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 409 && __cplusplus > 201103L "1" #else "0" #endif "cxx_generic_lambdas\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 408 && __cplusplus >= 201103L "1" #else "0" #endif "cxx_inheriting_constructors\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 404 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__)) "1" #else "0" #endif "cxx_inline_namespaces\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 405 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__)) "1" #else "0" #endif "cxx_lambdas\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 409 && __cplusplus > 201103L "1" #else "0" #endif "cxx_lambda_init_captures\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 405 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__)) "1" #else "0" #endif "cxx_local_type_template_args\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 404 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__)) "1" #else "0" #endif "cxx_long_long_type\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 406 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__)) "1" #else "0" #endif "cxx_noexcept\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 407 && __cplusplus >= 201103L "1" #else "0" #endif "cxx_nonstatic_member_init\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 406 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__)) "1" #else "0" #endif "cxx_nullptr\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 407 && __cplusplus >= 201103L "1" #else "0" #endif "cxx_override\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 406 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__)) "1" #else "0" #endif "cxx_range_for\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 405 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__)) "1" #else "0" #endif "cxx_raw_string_literals\n" "CXX_FEATURE:" #if ((__GNUC__ * 10000 + __GNUC_MINOR__ * 100 + __GNUC_PATCHLEVEL__) >= 40801) && __cplusplus >= 201103L "1" #else "0" #endif "cxx_reference_qualified_functions\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 500 && __cplusplus >= 201402L "1" #else "0" #endif "cxx_relaxed_constexpr\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 409 && __cplusplus > 201103L "1" #else "0" #endif "cxx_return_type_deduction\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 404 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__)) "1" #else "0" #endif "cxx_right_angle_brackets\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 404 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__)) "1" #else "0" #endif "cxx_rvalue_references\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 404 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__)) "1" #else "0" #endif "cxx_sizeof_member\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 404 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__)) "1" #else "0" #endif "cxx_static_assert\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 404 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__)) "1" #else "0" #endif "cxx_strong_enums\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 404 && __cplusplus "1" #else "0" #endif "cxx_template_template_parameters\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 408 && __cplusplus >= 201103L "1" #else "0" #endif "cxx_thread_local\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 404 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__)) "1" #else "0" #endif "cxx_trailing_return_types\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 404 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__)) "1" #else "0" #endif "cxx_unicode_literals\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 404 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__)) "1" #else "0" #endif "cxx_uniform_initialization\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 406 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__)) "1" #else "0" #endif "cxx_unrestricted_unions\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 407 && __cplusplus >= 201103L "1" #else "0" #endif "cxx_user_literals\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 500 && __cplusplus >= 201402L "1" #else "0" #endif "cxx_variable_templates\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 404 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__)) "1" #else "0" #endif "cxx_variadic_macros\n" "CXX_FEATURE:" #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 404 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__)) "1" #else "0" #endif "cxx_variadic_templates\n" }; int main(int argc, char** argv) { (void)argv; return features[argc]; } ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_cpp.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_cpp.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for geometry_msgs_generate_messages_cpp. # Include the progress variables for this target. include CMakeFiles/geometry_msgs_generate_messages_cpp.dir/progress.make geometry_msgs_generate_messages_cpp: CMakeFiles/geometry_msgs_generate_messages_cpp.dir/build.make .PHONY : geometry_msgs_generate_messages_cpp # Rule to build all files generated by this target. CMakeFiles/geometry_msgs_generate_messages_cpp.dir/build: geometry_msgs_generate_messages_cpp .PHONY : CMakeFiles/geometry_msgs_generate_messages_cpp.dir/build CMakeFiles/geometry_msgs_generate_messages_cpp.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/geometry_msgs_generate_messages_cpp.dir/cmake_clean.cmake .PHONY : CMakeFiles/geometry_msgs_generate_messages_cpp.dir/clean CMakeFiles/geometry_msgs_generate_messages_cpp.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_cpp.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/geometry_msgs_generate_messages_cpp.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_cpp.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/geometry_msgs_generate_messages_cpp.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_cpp.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_eus.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_eus.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for geometry_msgs_generate_messages_eus. # Include the progress variables for this target. include CMakeFiles/geometry_msgs_generate_messages_eus.dir/progress.make geometry_msgs_generate_messages_eus: CMakeFiles/geometry_msgs_generate_messages_eus.dir/build.make .PHONY : geometry_msgs_generate_messages_eus # Rule to build all files generated by this target. CMakeFiles/geometry_msgs_generate_messages_eus.dir/build: geometry_msgs_generate_messages_eus .PHONY : CMakeFiles/geometry_msgs_generate_messages_eus.dir/build CMakeFiles/geometry_msgs_generate_messages_eus.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/geometry_msgs_generate_messages_eus.dir/cmake_clean.cmake .PHONY : CMakeFiles/geometry_msgs_generate_messages_eus.dir/clean CMakeFiles/geometry_msgs_generate_messages_eus.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_eus.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/geometry_msgs_generate_messages_eus.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_eus.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/geometry_msgs_generate_messages_eus.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_eus.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_lisp.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_lisp.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for geometry_msgs_generate_messages_lisp. # Include the progress variables for this target. include CMakeFiles/geometry_msgs_generate_messages_lisp.dir/progress.make geometry_msgs_generate_messages_lisp: CMakeFiles/geometry_msgs_generate_messages_lisp.dir/build.make .PHONY : geometry_msgs_generate_messages_lisp # Rule to build all files generated by this target. CMakeFiles/geometry_msgs_generate_messages_lisp.dir/build: geometry_msgs_generate_messages_lisp .PHONY : CMakeFiles/geometry_msgs_generate_messages_lisp.dir/build CMakeFiles/geometry_msgs_generate_messages_lisp.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/geometry_msgs_generate_messages_lisp.dir/cmake_clean.cmake .PHONY : CMakeFiles/geometry_msgs_generate_messages_lisp.dir/clean CMakeFiles/geometry_msgs_generate_messages_lisp.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_lisp.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/geometry_msgs_generate_messages_lisp.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_lisp.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/geometry_msgs_generate_messages_lisp.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_lisp.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for geometry_msgs_generate_messages_nodejs. # Include the progress variables for this target. include CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/progress.make geometry_msgs_generate_messages_nodejs: CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/build.make .PHONY : geometry_msgs_generate_messages_nodejs # Rule to build all files generated by this target. CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/build: geometry_msgs_generate_messages_nodejs .PHONY : CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/build CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/cmake_clean.cmake .PHONY : CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/clean CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_py.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_py.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for geometry_msgs_generate_messages_py. # Include the progress variables for this target. include CMakeFiles/geometry_msgs_generate_messages_py.dir/progress.make geometry_msgs_generate_messages_py: CMakeFiles/geometry_msgs_generate_messages_py.dir/build.make .PHONY : geometry_msgs_generate_messages_py # Rule to build all files generated by this target. CMakeFiles/geometry_msgs_generate_messages_py.dir/build: geometry_msgs_generate_messages_py .PHONY : CMakeFiles/geometry_msgs_generate_messages_py.dir/build CMakeFiles/geometry_msgs_generate_messages_py.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/geometry_msgs_generate_messages_py.dir/cmake_clean.cmake .PHONY : CMakeFiles/geometry_msgs_generate_messages_py.dir/clean CMakeFiles/geometry_msgs_generate_messages_py.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_py.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/geometry_msgs_generate_messages_py.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_py.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/geometry_msgs_generate_messages_py.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_py.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_cpp.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_cpp.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for nav_msgs_generate_messages_cpp. # Include the progress variables for this target. include CMakeFiles/nav_msgs_generate_messages_cpp.dir/progress.make nav_msgs_generate_messages_cpp: CMakeFiles/nav_msgs_generate_messages_cpp.dir/build.make .PHONY : nav_msgs_generate_messages_cpp # Rule to build all files generated by this target. CMakeFiles/nav_msgs_generate_messages_cpp.dir/build: nav_msgs_generate_messages_cpp .PHONY : CMakeFiles/nav_msgs_generate_messages_cpp.dir/build CMakeFiles/nav_msgs_generate_messages_cpp.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/nav_msgs_generate_messages_cpp.dir/cmake_clean.cmake .PHONY : CMakeFiles/nav_msgs_generate_messages_cpp.dir/clean CMakeFiles/nav_msgs_generate_messages_cpp.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_cpp.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/nav_msgs_generate_messages_cpp.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_cpp.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/nav_msgs_generate_messages_cpp.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_cpp.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_eus.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_eus.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for nav_msgs_generate_messages_eus. # Include the progress variables for this target. include CMakeFiles/nav_msgs_generate_messages_eus.dir/progress.make nav_msgs_generate_messages_eus: CMakeFiles/nav_msgs_generate_messages_eus.dir/build.make .PHONY : nav_msgs_generate_messages_eus # Rule to build all files generated by this target. CMakeFiles/nav_msgs_generate_messages_eus.dir/build: nav_msgs_generate_messages_eus .PHONY : CMakeFiles/nav_msgs_generate_messages_eus.dir/build CMakeFiles/nav_msgs_generate_messages_eus.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/nav_msgs_generate_messages_eus.dir/cmake_clean.cmake .PHONY : CMakeFiles/nav_msgs_generate_messages_eus.dir/clean CMakeFiles/nav_msgs_generate_messages_eus.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_eus.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/nav_msgs_generate_messages_eus.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_eus.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/nav_msgs_generate_messages_eus.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_eus.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_lisp.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_lisp.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for nav_msgs_generate_messages_lisp. # Include the progress variables for this target. include CMakeFiles/nav_msgs_generate_messages_lisp.dir/progress.make nav_msgs_generate_messages_lisp: CMakeFiles/nav_msgs_generate_messages_lisp.dir/build.make .PHONY : nav_msgs_generate_messages_lisp # Rule to build all files generated by this target. CMakeFiles/nav_msgs_generate_messages_lisp.dir/build: nav_msgs_generate_messages_lisp .PHONY : CMakeFiles/nav_msgs_generate_messages_lisp.dir/build CMakeFiles/nav_msgs_generate_messages_lisp.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/nav_msgs_generate_messages_lisp.dir/cmake_clean.cmake .PHONY : CMakeFiles/nav_msgs_generate_messages_lisp.dir/clean CMakeFiles/nav_msgs_generate_messages_lisp.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_lisp.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/nav_msgs_generate_messages_lisp.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_lisp.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/nav_msgs_generate_messages_lisp.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_lisp.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_nodejs.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_nodejs.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for nav_msgs_generate_messages_nodejs. # Include the progress variables for this target. include CMakeFiles/nav_msgs_generate_messages_nodejs.dir/progress.make nav_msgs_generate_messages_nodejs: CMakeFiles/nav_msgs_generate_messages_nodejs.dir/build.make .PHONY : nav_msgs_generate_messages_nodejs # Rule to build all files generated by this target. CMakeFiles/nav_msgs_generate_messages_nodejs.dir/build: nav_msgs_generate_messages_nodejs .PHONY : CMakeFiles/nav_msgs_generate_messages_nodejs.dir/build CMakeFiles/nav_msgs_generate_messages_nodejs.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/nav_msgs_generate_messages_nodejs.dir/cmake_clean.cmake .PHONY : CMakeFiles/nav_msgs_generate_messages_nodejs.dir/clean CMakeFiles/nav_msgs_generate_messages_nodejs.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_nodejs.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/nav_msgs_generate_messages_nodejs.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_nodejs.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/nav_msgs_generate_messages_nodejs.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_nodejs.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_py.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_py.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for nav_msgs_generate_messages_py. # Include the progress variables for this target. include CMakeFiles/nav_msgs_generate_messages_py.dir/progress.make nav_msgs_generate_messages_py: CMakeFiles/nav_msgs_generate_messages_py.dir/build.make .PHONY : nav_msgs_generate_messages_py # Rule to build all files generated by this target. CMakeFiles/nav_msgs_generate_messages_py.dir/build: nav_msgs_generate_messages_py .PHONY : CMakeFiles/nav_msgs_generate_messages_py.dir/build CMakeFiles/nav_msgs_generate_messages_py.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/nav_msgs_generate_messages_py.dir/cmake_clean.cmake .PHONY : CMakeFiles/nav_msgs_generate_messages_py.dir/clean CMakeFiles/nav_msgs_generate_messages_py.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_py.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/nav_msgs_generate_messages_py.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_py.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/nav_msgs_generate_messages_py.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_py.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/progress.marks ================================================ 2 ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rf2o_laser_odometry_node.dir/CXX.includecache ================================================ #IncludeRegexLine: ^[ ]*[#%][ ]*(include|import)[ ]*[<"]([^">]+)([">]) #IncludeRegexScan: ^.*$ #IncludeRegexComplain: ^$ #IncludeRegexTransform: ../include/rf2o_laser_odometry/CLaserOdometry2D.h ros/ros.h - tf/transform_broadcaster.h - tf/transform_listener.h - nav_msgs/Odometry.h - sensor_msgs/LaserScan.h - geometry_msgs/Twist.h - mrpt/version.h - mrpt/obs/CObservation2DRangeScan.h - mrpt/obs/CObservationOdometry.h - mrpt/utils/CTicTac.h - mrpt/slam/CObservation2DRangeScan.h - mrpt/slam/CObservationOdometry.h - mrpt/utils.h - mrpt/system/threads.h - mrpt/system/os.h - mrpt/poses/CPose3D.h - mrpt/opengl.h - mrpt/math/CHistogram.h - boost/bind.hpp - Eigen/Dense - unsupported/Eigen/MatrixFunctions - iostream - fstream - numeric - /home/zn/racecar/src/rf2o_laser_odometry/src/CLaserOdometry2D.cpp rf2o_laser_odometry/CLaserOdometry2D.h /home/zn/racecar/src/rf2o_laser_odometry/src/rf2o_laser_odometry/CLaserOdometry2D.h /opt/ros/kinetic/include/boost_161_condition_variable.h boost/thread/detail/platform.hpp - boost/thread/win32/condition_variable.hpp - boost_161_pthread_condition_variable.h /opt/ros/kinetic/include/boost_161_pthread_condition_variable.h /opt/ros/kinetic/include/boost_161_pthread_condition_variable.h boost_161_pthread_condition_variable_fwd.h /opt/ros/kinetic/include/boost_161_pthread_condition_variable_fwd.h boost/thread/pthread/timespec.hpp - boost/thread/pthread/pthread_mutex_scoped_lock.hpp - boost/thread/pthread/thread_data.hpp - boost/chrono/system_clocks.hpp - boost/chrono/ceil.hpp - boost/thread/detail/delete.hpp - boost/config/abi_prefix.hpp - boost/config/abi_suffix.hpp - /opt/ros/kinetic/include/boost_161_pthread_condition_variable_fwd.h boost/assert.hpp - boost/throw_exception.hpp - pthread.h - boost/thread/cv_status.hpp - boost/thread/mutex.hpp - boost/thread/lock_types.hpp - boost/thread/thread_time.hpp - boost/thread/pthread/timespec.hpp - boost/thread/xtime.hpp - boost/chrono/system_clocks.hpp - boost/chrono/ceil.hpp - boost/thread/detail/delete.hpp - boost/date_time/posix_time/posix_time_duration.hpp - boost/config/abi_prefix.hpp - boost/config/abi_suffix.hpp - /opt/ros/kinetic/include/geometry_msgs/Point.h string - vector - map - ros/types.h - ros/serialization.h - ros/builtin_message_traits.h - ros/message_operations.h - /opt/ros/kinetic/include/geometry_msgs/Point32.h string - vector - map - ros/types.h - ros/serialization.h - ros/builtin_message_traits.h - ros/message_operations.h - /opt/ros/kinetic/include/geometry_msgs/PointStamped.h string - vector - map - ros/types.h - ros/serialization.h - ros/builtin_message_traits.h - ros/message_operations.h - std_msgs/Header.h - geometry_msgs/Point.h - /opt/ros/kinetic/include/geometry_msgs/Pose.h string - vector - map - ros/types.h - ros/serialization.h - ros/builtin_message_traits.h - ros/message_operations.h - geometry_msgs/Point.h - geometry_msgs/Quaternion.h - /opt/ros/kinetic/include/geometry_msgs/PoseStamped.h string - vector - map - ros/types.h - ros/serialization.h - ros/builtin_message_traits.h - ros/message_operations.h - std_msgs/Header.h - geometry_msgs/Pose.h - /opt/ros/kinetic/include/geometry_msgs/PoseWithCovariance.h string - vector - map - ros/types.h - ros/serialization.h - ros/builtin_message_traits.h - ros/message_operations.h - geometry_msgs/Pose.h - /opt/ros/kinetic/include/geometry_msgs/Quaternion.h string - vector - map - ros/types.h - ros/serialization.h - ros/builtin_message_traits.h - ros/message_operations.h - /opt/ros/kinetic/include/geometry_msgs/QuaternionStamped.h string - vector - map - ros/types.h - ros/serialization.h - ros/builtin_message_traits.h - ros/message_operations.h - std_msgs/Header.h - geometry_msgs/Quaternion.h - /opt/ros/kinetic/include/geometry_msgs/Transform.h string - vector - map - ros/types.h - ros/serialization.h - ros/builtin_message_traits.h - ros/message_operations.h - geometry_msgs/Vector3.h - geometry_msgs/Quaternion.h - /opt/ros/kinetic/include/geometry_msgs/TransformStamped.h string - vector - map - ros/types.h - ros/serialization.h - ros/builtin_message_traits.h - ros/message_operations.h - std_msgs/Header.h - geometry_msgs/Transform.h - /opt/ros/kinetic/include/geometry_msgs/Twist.h string - vector - map - ros/types.h - ros/serialization.h - ros/builtin_message_traits.h - ros/message_operations.h - geometry_msgs/Vector3.h - geometry_msgs/Vector3.h - /opt/ros/kinetic/include/geometry_msgs/TwistStamped.h string - vector - map - ros/types.h - ros/serialization.h - ros/builtin_message_traits.h - ros/message_operations.h - std_msgs/Header.h - geometry_msgs/Twist.h - /opt/ros/kinetic/include/geometry_msgs/TwistWithCovariance.h string - vector - map - ros/types.h - ros/serialization.h - ros/builtin_message_traits.h - ros/message_operations.h - geometry_msgs/Twist.h - /opt/ros/kinetic/include/geometry_msgs/Vector3.h string - vector - map - ros/types.h - ros/serialization.h - ros/builtin_message_traits.h - ros/message_operations.h - /opt/ros/kinetic/include/geometry_msgs/Vector3Stamped.h string - vector - map - ros/types.h - ros/serialization.h - ros/builtin_message_traits.h - ros/message_operations.h - std_msgs/Header.h - geometry_msgs/Vector3.h - /opt/ros/kinetic/include/nav_msgs/Odometry.h string - vector - map - ros/types.h - ros/serialization.h - ros/builtin_message_traits.h - ros/message_operations.h - std_msgs/Header.h - geometry_msgs/PoseWithCovariance.h - geometry_msgs/TwistWithCovariance.h - /opt/ros/kinetic/include/ros/advertise_options.h ros/forwards.h /opt/ros/kinetic/include/ros/ros/forwards.h ros/message_traits.h /opt/ros/kinetic/include/ros/ros/message_traits.h common.h /opt/ros/kinetic/include/ros/common.h /opt/ros/kinetic/include/ros/advertise_service_options.h ros/forwards.h /opt/ros/kinetic/include/ros/ros/forwards.h ros/service_callback_helper.h /opt/ros/kinetic/include/ros/ros/service_callback_helper.h ros/service_traits.h /opt/ros/kinetic/include/ros/ros/service_traits.h ros/message_traits.h /opt/ros/kinetic/include/ros/ros/message_traits.h common.h /opt/ros/kinetic/include/ros/common.h /opt/ros/kinetic/include/ros/assert.h ros/console.h /opt/ros/kinetic/include/ros/ros/console.h ros/static_assert.h /opt/ros/kinetic/include/ros/ros/static_assert.h ros/platform.h - stdlib.h - /opt/ros/kinetic/include/ros/builtin_message_traits.h message_traits.h /opt/ros/kinetic/include/ros/message_traits.h ros/time.h /opt/ros/kinetic/include/ros/ros/time.h /opt/ros/kinetic/include/ros/callback_queue.h boost/version.hpp - boost_161_condition_variable.h /opt/ros/kinetic/include/ros/boost_161_condition_variable.h boost/thread/condition_variable.hpp - boost/thread/condition_variable.hpp - ros/callback_queue_interface.h /opt/ros/kinetic/include/ros/ros/callback_queue_interface.h ros/time.h /opt/ros/kinetic/include/ros/ros/time.h common.h /opt/ros/kinetic/include/ros/common.h boost/shared_ptr.hpp - boost/thread/mutex.hpp - boost/thread/shared_mutex.hpp - boost/thread/tss.hpp - list - deque - /opt/ros/kinetic/include/ros/callback_queue_interface.h boost/shared_ptr.hpp - common.h /opt/ros/kinetic/include/ros/common.h ros/types.h /opt/ros/kinetic/include/ros/ros/types.h /opt/ros/kinetic/include/ros/common.h stdint.h - assert.h - stddef.h - string - ros/assert.h /opt/ros/kinetic/include/ros/ros/assert.h ros/forwards.h /opt/ros/kinetic/include/ros/ros/forwards.h ros/serialized_message.h /opt/ros/kinetic/include/ros/ros/serialized_message.h boost/shared_array.hpp - ros/macros.h - /opt/ros/kinetic/include/ros/console.h console_backend.h /opt/ros/kinetic/include/ros/console_backend.h cstdio - sstream - ros/time.h - cstdarg - ros/macros.h - map - vector - log4cxx/level.h /opt/ros/kinetic/include/ros/log4cxx/level.h rosconsole/macros_generated.h /opt/ros/kinetic/include/ros/rosconsole/macros_generated.h /opt/ros/kinetic/include/ros/console_backend.h /opt/ros/kinetic/include/ros/datatypes.h string - vector - map - set - list - boost/shared_ptr.hpp - /opt/ros/kinetic/include/ros/duration.h iostream - math.h - stdexcept - climits - stdint.h - rostime_decl.h /opt/ros/kinetic/include/ros/rostime_decl.h /opt/ros/kinetic/include/ros/exception.h stdexcept - /opt/ros/kinetic/include/ros/exceptions.h ros/exception.h - /opt/ros/kinetic/include/ros/forwards.h string - vector - map - set - list - boost/shared_ptr.hpp - boost/make_shared.hpp - boost/weak_ptr.hpp - boost/function.hpp - ros/time.h - ros/macros.h - exceptions.h /opt/ros/kinetic/include/ros/exceptions.h ros/datatypes.h /opt/ros/kinetic/include/ros/ros/datatypes.h /opt/ros/kinetic/include/ros/init.h ros/forwards.h /opt/ros/kinetic/include/ros/ros/forwards.h ros/spinner.h /opt/ros/kinetic/include/ros/ros/spinner.h common.h /opt/ros/kinetic/include/ros/common.h /opt/ros/kinetic/include/ros/macros.h /opt/ros/kinetic/include/ros/master.h forwards.h /opt/ros/kinetic/include/ros/forwards.h xmlrpcpp/XmlRpcValue.h /opt/ros/kinetic/include/ros/xmlrpcpp/XmlRpcValue.h common.h /opt/ros/kinetic/include/ros/common.h /opt/ros/kinetic/include/ros/message.h ros/macros.h /opt/ros/kinetic/include/ros/ros/macros.h ros/assert.h /opt/ros/kinetic/include/ros/ros/assert.h string - string.h - boost/shared_ptr.hpp - boost/array.hpp - stdint.h - /opt/ros/kinetic/include/ros/message_event.h ros/time.h /opt/ros/kinetic/include/ros/ros/time.h ros/datatypes.h - ros/message_traits.h - boost/type_traits/is_void.hpp - boost/type_traits/is_base_of.hpp - boost/type_traits/is_const.hpp - boost/type_traits/add_const.hpp - boost/type_traits/remove_const.hpp - boost/utility/enable_if.hpp - boost/function.hpp - boost/make_shared.hpp - /opt/ros/kinetic/include/ros/message_forward.h cstddef - memory - /opt/ros/kinetic/include/ros/message_operations.h ostream - /opt/ros/kinetic/include/ros/message_traits.h message_forward.h /opt/ros/kinetic/include/ros/message_forward.h ros/time.h - string - boost/utility/enable_if.hpp - boost/type_traits/remove_const.hpp - boost/type_traits/remove_reference.hpp - /opt/ros/kinetic/include/ros/names.h forwards.h /opt/ros/kinetic/include/ros/forwards.h common.h /opt/ros/kinetic/include/ros/common.h /opt/ros/kinetic/include/ros/node_handle.h ros/forwards.h /opt/ros/kinetic/include/ros/ros/forwards.h ros/publisher.h /opt/ros/kinetic/include/ros/ros/publisher.h ros/subscriber.h /opt/ros/kinetic/include/ros/ros/subscriber.h ros/service_server.h /opt/ros/kinetic/include/ros/ros/service_server.h ros/service_client.h /opt/ros/kinetic/include/ros/ros/service_client.h ros/timer.h /opt/ros/kinetic/include/ros/ros/timer.h ros/rate.h /opt/ros/kinetic/include/ros/ros/rate.h ros/wall_timer.h /opt/ros/kinetic/include/ros/ros/wall_timer.h ros/steady_timer.h /opt/ros/kinetic/include/ros/ros/steady_timer.h ros/advertise_options.h /opt/ros/kinetic/include/ros/ros/advertise_options.h ros/advertise_service_options.h /opt/ros/kinetic/include/ros/ros/advertise_service_options.h ros/subscribe_options.h /opt/ros/kinetic/include/ros/ros/subscribe_options.h ros/service_client_options.h /opt/ros/kinetic/include/ros/ros/service_client_options.h ros/timer_options.h /opt/ros/kinetic/include/ros/ros/timer_options.h ros/wall_timer_options.h /opt/ros/kinetic/include/ros/ros/wall_timer_options.h ros/spinner.h /opt/ros/kinetic/include/ros/ros/spinner.h ros/init.h /opt/ros/kinetic/include/ros/ros/init.h common.h /opt/ros/kinetic/include/ros/common.h boost/bind.hpp - xmlrpcpp/XmlRpcValue.h - /opt/ros/kinetic/include/ros/param.h forwards.h /opt/ros/kinetic/include/ros/forwards.h common.h /opt/ros/kinetic/include/ros/common.h xmlrpcpp/XmlRpcValue.h /opt/ros/kinetic/include/ros/xmlrpcpp/XmlRpcValue.h vector - map - /opt/ros/kinetic/include/ros/parameter_adapter.h ros/forwards.h /opt/ros/kinetic/include/ros/ros/forwards.h ros/message_event.h /opt/ros/kinetic/include/ros/ros/message_event.h ros/static_assert.h - boost/type_traits/add_const.hpp - boost/type_traits/remove_const.hpp - boost/type_traits/remove_reference.hpp - /opt/ros/kinetic/include/ros/platform.h windows.h - stdlib.h - string - /opt/ros/kinetic/include/ros/publisher.h ros/forwards.h /opt/ros/kinetic/include/ros/ros/forwards.h ros/common.h /opt/ros/kinetic/include/ros/ros/common.h ros/message.h /opt/ros/kinetic/include/ros/ros/message.h ros/serialization.h /opt/ros/kinetic/include/ros/ros/serialization.h boost/bind.hpp - /opt/ros/kinetic/include/ros/rate.h ros/time.h /opt/ros/kinetic/include/ros/ros/time.h rostime_decl.h /opt/ros/kinetic/include/ros/rostime_decl.h /opt/ros/kinetic/include/ros/ros.h ros/time.h /opt/ros/kinetic/include/ros/ros/time.h ros/rate.h /opt/ros/kinetic/include/ros/ros/rate.h ros/console.h /opt/ros/kinetic/include/ros/ros/console.h ros/assert.h /opt/ros/kinetic/include/ros/ros/assert.h ros/common.h /opt/ros/kinetic/include/ros/ros/common.h ros/types.h /opt/ros/kinetic/include/ros/ros/types.h ros/node_handle.h /opt/ros/kinetic/include/ros/ros/node_handle.h ros/publisher.h /opt/ros/kinetic/include/ros/ros/publisher.h ros/single_subscriber_publisher.h /opt/ros/kinetic/include/ros/ros/single_subscriber_publisher.h ros/service_server.h /opt/ros/kinetic/include/ros/ros/service_server.h ros/subscriber.h /opt/ros/kinetic/include/ros/ros/subscriber.h ros/service.h /opt/ros/kinetic/include/ros/ros/service.h ros/init.h /opt/ros/kinetic/include/ros/ros/init.h ros/master.h /opt/ros/kinetic/include/ros/ros/master.h ros/this_node.h /opt/ros/kinetic/include/ros/ros/this_node.h ros/param.h /opt/ros/kinetic/include/ros/ros/param.h ros/topic.h /opt/ros/kinetic/include/ros/ros/topic.h ros/names.h /opt/ros/kinetic/include/ros/ros/names.h /opt/ros/kinetic/include/ros/roscpp_serialization_macros.h ros/macros.h - /opt/ros/kinetic/include/ros/rostime_decl.h ros/macros.h - /opt/ros/kinetic/include/ros/serialization.h roscpp_serialization_macros.h /opt/ros/kinetic/include/ros/roscpp_serialization_macros.h ros/types.h - ros/time.h - serialized_message.h /opt/ros/kinetic/include/ros/serialized_message.h ros/message_traits.h /opt/ros/kinetic/include/ros/ros/message_traits.h ros/builtin_message_traits.h /opt/ros/kinetic/include/ros/ros/builtin_message_traits.h ros/exception.h /opt/ros/kinetic/include/ros/ros/exception.h ros/datatypes.h /opt/ros/kinetic/include/ros/ros/datatypes.h vector - map - boost/array.hpp - boost/call_traits.hpp - boost/utility/enable_if.hpp - boost/mpl/and.hpp - boost/mpl/or.hpp - boost/mpl/not.hpp - cstring - /opt/ros/kinetic/include/ros/serialized_message.h roscpp_serialization_macros.h /opt/ros/kinetic/include/ros/roscpp_serialization_macros.h boost/shared_array.hpp - boost/shared_ptr.hpp - /opt/ros/kinetic/include/ros/service.h string - ros/common.h /opt/ros/kinetic/include/ros/ros/common.h ros/message.h /opt/ros/kinetic/include/ros/ros/message.h ros/forwards.h /opt/ros/kinetic/include/ros/ros/forwards.h ros/node_handle.h /opt/ros/kinetic/include/ros/ros/node_handle.h ros/service_traits.h /opt/ros/kinetic/include/ros/ros/service_traits.h ros/names.h /opt/ros/kinetic/include/ros/ros/names.h boost/shared_ptr.hpp - /opt/ros/kinetic/include/ros/service_callback_helper.h ros/forwards.h /opt/ros/kinetic/include/ros/ros/forwards.h ros/common.h /opt/ros/kinetic/include/ros/ros/common.h ros/message.h /opt/ros/kinetic/include/ros/ros/message.h ros/message_traits.h /opt/ros/kinetic/include/ros/ros/message_traits.h ros/service_traits.h /opt/ros/kinetic/include/ros/ros/service_traits.h ros/serialization.h /opt/ros/kinetic/include/ros/ros/serialization.h boost/type_traits/is_base_of.hpp - boost/utility/enable_if.hpp - /opt/ros/kinetic/include/ros/service_client.h ros/forwards.h /opt/ros/kinetic/include/ros/ros/forwards.h ros/common.h /opt/ros/kinetic/include/ros/ros/common.h ros/service_traits.h /opt/ros/kinetic/include/ros/ros/service_traits.h ros/serialization.h /opt/ros/kinetic/include/ros/ros/serialization.h /opt/ros/kinetic/include/ros/service_client_options.h ros/forwards.h /opt/ros/kinetic/include/ros/ros/forwards.h common.h /opt/ros/kinetic/include/ros/common.h ros/service_traits.h /opt/ros/kinetic/include/ros/ros/service_traits.h /opt/ros/kinetic/include/ros/service_server.h ros/forwards.h /opt/ros/kinetic/include/ros/ros/forwards.h common.h /opt/ros/kinetic/include/ros/common.h /opt/ros/kinetic/include/ros/service_traits.h boost/type_traits/remove_reference.hpp - boost/type_traits/remove_const.hpp - /opt/ros/kinetic/include/ros/single_subscriber_publisher.h ros/forwards.h /opt/ros/kinetic/include/ros/ros/forwards.h ros/serialization.h /opt/ros/kinetic/include/ros/ros/serialization.h common.h /opt/ros/kinetic/include/ros/common.h boost/utility.hpp - /opt/ros/kinetic/include/ros/spinner.h ros/types.h /opt/ros/kinetic/include/ros/ros/types.h common.h /opt/ros/kinetic/include/ros/common.h boost/shared_ptr.hpp - /opt/ros/kinetic/include/ros/static_assert.h boost/static_assert.hpp - /opt/ros/kinetic/include/ros/steady_timer.h common.h /opt/ros/kinetic/include/ros/common.h forwards.h /opt/ros/kinetic/include/ros/forwards.h steady_timer_options.h /opt/ros/kinetic/include/ros/steady_timer_options.h /opt/ros/kinetic/include/ros/steady_timer_options.h common.h /opt/ros/kinetic/include/ros/common.h ros/forwards.h /opt/ros/kinetic/include/ros/ros/forwards.h /opt/ros/kinetic/include/ros/subscribe_options.h ros/forwards.h /opt/ros/kinetic/include/ros/ros/forwards.h common.h /opt/ros/kinetic/include/ros/common.h ros/transport_hints.h /opt/ros/kinetic/include/ros/ros/transport_hints.h ros/message_traits.h /opt/ros/kinetic/include/ros/ros/message_traits.h subscription_callback_helper.h /opt/ros/kinetic/include/ros/subscription_callback_helper.h /opt/ros/kinetic/include/ros/subscriber.h common.h /opt/ros/kinetic/include/ros/common.h ros/forwards.h /opt/ros/kinetic/include/ros/ros/forwards.h ros/subscription_callback_helper.h /opt/ros/kinetic/include/ros/ros/subscription_callback_helper.h /opt/ros/kinetic/include/ros/subscription_callback_helper.h typeinfo - common.h /opt/ros/kinetic/include/ros/common.h ros/forwards.h /opt/ros/kinetic/include/ros/ros/forwards.h ros/parameter_adapter.h /opt/ros/kinetic/include/ros/ros/parameter_adapter.h ros/message_traits.h /opt/ros/kinetic/include/ros/ros/message_traits.h ros/builtin_message_traits.h /opt/ros/kinetic/include/ros/ros/builtin_message_traits.h ros/serialization.h /opt/ros/kinetic/include/ros/ros/serialization.h ros/message_event.h /opt/ros/kinetic/include/ros/ros/message_event.h ros/static_assert.h - boost/type_traits/add_const.hpp - boost/type_traits/remove_const.hpp - boost/type_traits/remove_reference.hpp - boost/type_traits/is_base_of.hpp - boost/utility/enable_if.hpp - boost/make_shared.hpp - /opt/ros/kinetic/include/ros/this_node.h common.h /opt/ros/kinetic/include/ros/common.h forwards.h /opt/ros/kinetic/include/ros/forwards.h /opt/ros/kinetic/include/ros/time.h ros/platform.h - iostream - cmath - ros/exception.h - duration.h /opt/ros/kinetic/include/ros/duration.h boost/math/special_functions/round.hpp - rostime_decl.h /opt/ros/kinetic/include/ros/rostime_decl.h sys/timeb.h - sys/time.h - /opt/ros/kinetic/include/ros/timer.h common.h /opt/ros/kinetic/include/ros/common.h forwards.h /opt/ros/kinetic/include/ros/forwards.h timer_options.h /opt/ros/kinetic/include/ros/timer_options.h /opt/ros/kinetic/include/ros/timer_options.h common.h /opt/ros/kinetic/include/ros/common.h ros/forwards.h /opt/ros/kinetic/include/ros/ros/forwards.h /opt/ros/kinetic/include/ros/topic.h common.h /opt/ros/kinetic/include/ros/common.h node_handle.h /opt/ros/kinetic/include/ros/node_handle.h boost/shared_ptr.hpp - /opt/ros/kinetic/include/ros/transport_hints.h common.h /opt/ros/kinetic/include/ros/common.h ros/forwards.h /opt/ros/kinetic/include/ros/ros/forwards.h boost/lexical_cast.hpp - /opt/ros/kinetic/include/ros/types.h stdint.h - /opt/ros/kinetic/include/ros/wall_timer.h common.h /opt/ros/kinetic/include/ros/common.h forwards.h /opt/ros/kinetic/include/ros/forwards.h wall_timer_options.h /opt/ros/kinetic/include/ros/wall_timer_options.h /opt/ros/kinetic/include/ros/wall_timer_options.h common.h /opt/ros/kinetic/include/ros/common.h ros/forwards.h /opt/ros/kinetic/include/ros/ros/forwards.h /opt/ros/kinetic/include/rosconsole/macros_generated.h /opt/ros/kinetic/include/sensor_msgs/ChannelFloat32.h string - vector - map - ros/types.h - ros/serialization.h - ros/builtin_message_traits.h - ros/message_operations.h - /opt/ros/kinetic/include/sensor_msgs/LaserScan.h string - vector - map - ros/types.h - ros/serialization.h - ros/builtin_message_traits.h - ros/message_operations.h - std_msgs/Header.h - /opt/ros/kinetic/include/sensor_msgs/PointCloud.h string - vector - map - ros/types.h - ros/serialization.h - ros/builtin_message_traits.h - ros/message_operations.h - std_msgs/Header.h - geometry_msgs/Point32.h - sensor_msgs/ChannelFloat32.h - /opt/ros/kinetic/include/std_msgs/Empty.h string - vector - map - ros/types.h - ros/serialization.h - ros/builtin_message_traits.h - ros/message_operations.h - /opt/ros/kinetic/include/std_msgs/Header.h string - vector - map - ros/types.h - ros/serialization.h - ros/builtin_message_traits.h - ros/message_operations.h - /opt/ros/kinetic/include/tf/FrameGraph.h ros/service_traits.h - tf/FrameGraphRequest.h - tf/FrameGraphResponse.h - /opt/ros/kinetic/include/tf/FrameGraphRequest.h string - vector - map - ros/types.h - ros/serialization.h - ros/builtin_message_traits.h - ros/message_operations.h - /opt/ros/kinetic/include/tf/FrameGraphResponse.h string - vector - map - ros/types.h - ros/serialization.h - ros/builtin_message_traits.h - ros/message_operations.h - /opt/ros/kinetic/include/tf/LinearMath/Matrix3x3.h Vector3.h /opt/ros/kinetic/include/tf/LinearMath/Vector3.h Quaternion.h /opt/ros/kinetic/include/tf/LinearMath/Quaternion.h /opt/ros/kinetic/include/tf/LinearMath/MinMax.h /opt/ros/kinetic/include/tf/LinearMath/QuadWord.h Scalar.h /opt/ros/kinetic/include/tf/LinearMath/Scalar.h MinMax.h /opt/ros/kinetic/include/tf/LinearMath/MinMax.h altivec.h - /opt/ros/kinetic/include/tf/LinearMath/Quaternion.h Vector3.h /opt/ros/kinetic/include/tf/LinearMath/Vector3.h QuadWord.h /opt/ros/kinetic/include/tf/LinearMath/QuadWord.h /opt/ros/kinetic/include/tf/LinearMath/Scalar.h math.h - stdlib.h - cstdlib - cfloat - float.h - ppcintrinsics.h - assert.h - assert.h - assert.h - assert.h - /opt/ros/kinetic/include/tf/LinearMath/Transform.h Matrix3x3.h /opt/ros/kinetic/include/tf/LinearMath/Matrix3x3.h /opt/ros/kinetic/include/tf/LinearMath/Vector3.h Scalar.h /opt/ros/kinetic/include/tf/LinearMath/Scalar.h MinMax.h /opt/ros/kinetic/include/tf/LinearMath/MinMax.h /opt/ros/kinetic/include/tf/exceptions.h stdexcept - tf2/exceptions.h - /opt/ros/kinetic/include/tf/tf.h iostream - iomanip - cmath - vector - sstream - map - tf/exceptions.h - tf/time_cache.h /opt/ros/kinetic/include/tf/tf/time_cache.h boost/unordered_map.hpp - boost/signals2.hpp - geometry_msgs/TwistStamped.h /opt/ros/kinetic/include/tf/geometry_msgs/TwistStamped.h tf2_ros/buffer.h - /opt/ros/kinetic/include/tf/tfMessage.h string - vector - map - ros/types.h - ros/serialization.h - ros/builtin_message_traits.h - ros/message_operations.h - geometry_msgs/TransformStamped.h - /opt/ros/kinetic/include/tf/time_cache.h set - boost/thread/mutex.hpp - tf/transform_datatypes.h /opt/ros/kinetic/include/tf/tf/transform_datatypes.h tf/exceptions.h /opt/ros/kinetic/include/tf/tf/exceptions.h tf/LinearMath/Transform.h /opt/ros/kinetic/include/tf/tf/LinearMath/Transform.h sstream - /opt/ros/kinetic/include/tf/transform_broadcaster.h tf/tf.h /opt/ros/kinetic/include/tf/tf/tf.h tf/tfMessage.h /opt/ros/kinetic/include/tf/tf/tfMessage.h tf2_ros/transform_broadcaster.h - /opt/ros/kinetic/include/tf/transform_datatypes.h string - geometry_msgs/PointStamped.h /opt/ros/kinetic/include/tf/geometry_msgs/PointStamped.h geometry_msgs/Vector3Stamped.h /opt/ros/kinetic/include/tf/geometry_msgs/Vector3Stamped.h geometry_msgs/QuaternionStamped.h /opt/ros/kinetic/include/tf/geometry_msgs/QuaternionStamped.h geometry_msgs/TransformStamped.h /opt/ros/kinetic/include/tf/geometry_msgs/TransformStamped.h geometry_msgs/PoseStamped.h /opt/ros/kinetic/include/tf/geometry_msgs/PoseStamped.h tf/LinearMath/Transform.h /opt/ros/kinetic/include/tf/tf/LinearMath/Transform.h ros/time.h /opt/ros/kinetic/include/tf/ros/time.h ros/console.h /opt/ros/kinetic/include/tf/ros/console.h /opt/ros/kinetic/include/tf/transform_listener.h sensor_msgs/PointCloud.h /opt/ros/kinetic/include/tf/sensor_msgs/PointCloud.h std_msgs/Empty.h /opt/ros/kinetic/include/tf/std_msgs/Empty.h tf/tfMessage.h /opt/ros/kinetic/include/tf/tf/tfMessage.h tf/tf.h /opt/ros/kinetic/include/tf/tf/tf.h ros/ros.h /opt/ros/kinetic/include/tf/ros/ros.h ros/callback_queue.h /opt/ros/kinetic/include/tf/ros/callback_queue.h tf/FrameGraph.h /opt/ros/kinetic/include/tf/tf/FrameGraph.h boost/thread.hpp /opt/ros/kinetic/include/tf/boost/thread.hpp tf2_ros/transform_listener.h - /opt/ros/kinetic/include/tf2/LinearMath/Quaternion.h Vector3.h /opt/ros/kinetic/include/tf2/LinearMath/Vector3.h QuadWord.h /opt/ros/kinetic/include/tf2/LinearMath/QuadWord.h /opt/ros/kinetic/include/tf2/LinearMath/Vector3.h Scalar.h /opt/ros/kinetic/include/tf2/LinearMath/Scalar.h MinMax.h /opt/ros/kinetic/include/tf2/LinearMath/MinMax.h /opt/ros/kinetic/include/tf2/buffer_core.h transform_storage.h /opt/ros/kinetic/include/tf2/transform_storage.h boost/signals2.hpp - string - ros/duration.h /opt/ros/kinetic/include/tf2/ros/duration.h ros/time.h /opt/ros/kinetic/include/tf2/ros/time.h geometry_msgs/TransformStamped.h /opt/ros/kinetic/include/tf2/geometry_msgs/TransformStamped.h boost/unordered_map.hpp - boost/thread/mutex.hpp - boost/function.hpp - boost/shared_ptr.hpp - /opt/ros/kinetic/include/tf2/convert.h tf2/transform_datatypes.h - tf2/exceptions.h - geometry_msgs/TransformStamped.h - tf2/impl/convert.h - /opt/ros/kinetic/include/tf2/exceptions.h stdexcept - /opt/ros/kinetic/include/tf2/impl/convert.h /opt/ros/kinetic/include/tf2/transform_datatypes.h string - ros/time.h /opt/ros/kinetic/include/tf2/ros/time.h /opt/ros/kinetic/include/tf2/transform_storage.h tf2/LinearMath/Vector3.h - tf2/LinearMath/Quaternion.h - ros/message_forward.h - ros/time.h - ros/types.h - /opt/ros/kinetic/include/tf2_msgs/FrameGraph.h ros/service_traits.h - tf2_msgs/FrameGraphRequest.h - tf2_msgs/FrameGraphResponse.h - /opt/ros/kinetic/include/tf2_msgs/FrameGraphRequest.h string - vector - map - ros/types.h - ros/serialization.h - ros/builtin_message_traits.h - ros/message_operations.h - /opt/ros/kinetic/include/tf2_msgs/FrameGraphResponse.h string - vector - map - ros/types.h - ros/serialization.h - ros/builtin_message_traits.h - ros/message_operations.h - /opt/ros/kinetic/include/tf2_msgs/TFMessage.h string - vector - map - ros/types.h - ros/serialization.h - ros/builtin_message_traits.h - ros/message_operations.h - geometry_msgs/TransformStamped.h - /opt/ros/kinetic/include/tf2_ros/buffer.h tf2_ros/buffer_interface.h - tf2/buffer_core.h - tf2_msgs/FrameGraph.h - ros/ros.h - tf2/convert.h - /opt/ros/kinetic/include/tf2_ros/buffer_interface.h tf2/buffer_core.h - tf2/transform_datatypes.h - tf2/exceptions.h - geometry_msgs/TransformStamped.h - sstream - tf2/convert.h - /opt/ros/kinetic/include/tf2_ros/transform_broadcaster.h ros/ros.h /opt/ros/kinetic/include/tf2_ros/ros/ros.h geometry_msgs/TransformStamped.h /opt/ros/kinetic/include/tf2_ros/geometry_msgs/TransformStamped.h /opt/ros/kinetic/include/tf2_ros/transform_listener.h std_msgs/Empty.h /opt/ros/kinetic/include/tf2_ros/std_msgs/Empty.h tf2_msgs/TFMessage.h /opt/ros/kinetic/include/tf2_ros/tf2_msgs/TFMessage.h ros/ros.h /opt/ros/kinetic/include/tf2_ros/ros/ros.h ros/callback_queue.h /opt/ros/kinetic/include/tf2_ros/ros/callback_queue.h tf2_ros/buffer.h /opt/ros/kinetic/include/tf2_ros/tf2_ros/buffer.h boost/thread.hpp /opt/ros/kinetic/include/tf2_ros/boost/thread.hpp /opt/ros/kinetic/include/xmlrpcpp/XmlRpcDecl.h ros/macros.h - /opt/ros/kinetic/include/xmlrpcpp/XmlRpcValue.h xmlrpcpp/XmlRpcDecl.h /opt/ros/kinetic/include/xmlrpcpp/xmlrpcpp/XmlRpcDecl.h map - string - vector - time.h - /usr/include/eigen3/Eigen/Cholesky Core /usr/include/eigen3/Eigen/Core src/Core/util/DisableStupidWarnings.h /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h src/Cholesky/LLT.h /usr/include/eigen3/Eigen/src/Cholesky/LLT.h src/Cholesky/LDLT.h /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h src/Cholesky/LLT_MKL.h /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h src/Core/util/ReenableStupidWarnings.h /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h /usr/include/eigen3/Eigen/Core src/Core/util/DisableStupidWarnings.h /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h new - src/Core/util/Macros.h /usr/include/eigen3/Eigen/src/Core/util/Macros.h complex - src/Core/util/MKL_support.h /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h malloc.h - immintrin.h - emmintrin.h - xmmintrin.h - pmmintrin.h - tmmintrin.h - smmintrin.h - nmmintrin.h - immintrin.h - altivec.h - altivec.h - arm_neon.h - vector_types.h - omp.h - cerrno - cstddef - cstdlib - cmath - cassert - functional - iosfwd - cstring - string - limits - climits - algorithm - iostream - intrin.h - src/Core/util/Constants.h /usr/include/eigen3/Eigen/src/Core/util/Constants.h src/Core/util/Meta.h /usr/include/eigen3/Eigen/src/Core/util/Meta.h src/Core/util/ForwardDeclarations.h /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h src/Core/util/StaticAssert.h /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h src/Core/util/XprHelper.h /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h src/Core/util/Memory.h /usr/include/eigen3/Eigen/src/Core/util/Memory.h src/Core/NumTraits.h /usr/include/eigen3/Eigen/src/Core/NumTraits.h src/Core/MathFunctions.h /usr/include/eigen3/Eigen/src/Core/MathFunctions.h src/Core/SpecialFunctions.h /usr/include/eigen3/Eigen/src/Core/SpecialFunctions.h src/Core/GenericPacketMath.h /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h src/Core/arch/SSE/PacketMath.h /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h src/Core/arch/SSE/Complex.h /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h src/Core/arch/SSE/MathFunctions.h /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h src/Core/arch/AVX/PacketMath.h /usr/include/eigen3/Eigen/src/Core/arch/AVX/PacketMath.h src/Core/arch/AVX/MathFunctions.h /usr/include/eigen3/Eigen/src/Core/arch/AVX/MathFunctions.h src/Core/arch/AVX/Complex.h /usr/include/eigen3/Eigen/src/Core/arch/AVX/Complex.h src/Core/arch/AVX/TypeCasting.h /usr/include/eigen3/Eigen/src/Core/arch/AVX/TypeCasting.h src/Core/arch/SSE/PacketMath.h /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h src/Core/arch/SSE/MathFunctions.h /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h src/Core/arch/SSE/Complex.h /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h src/Core/arch/SSE/TypeCasting.h /usr/include/eigen3/Eigen/src/Core/arch/SSE/TypeCasting.h src/Core/arch/AltiVec/PacketMath.h /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h src/Core/arch/AltiVec/MathFunctions.h /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/MathFunctions.h src/Core/arch/AltiVec/Complex.h /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h src/Core/arch/NEON/PacketMath.h /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h src/Core/arch/NEON/MathFunctions.h /usr/include/eigen3/Eigen/src/Core/arch/NEON/MathFunctions.h src/Core/arch/NEON/Complex.h /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h src/Core/arch/CUDA/PacketMath.h /usr/include/eigen3/Eigen/src/Core/arch/CUDA/PacketMath.h src/Core/arch/CUDA/MathFunctions.h /usr/include/eigen3/Eigen/src/Core/arch/CUDA/MathFunctions.h src/Core/arch/Default/Settings.h /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h src/Core/functors/BinaryFunctors.h /usr/include/eigen3/Eigen/src/Core/functors/BinaryFunctors.h src/Core/functors/UnaryFunctors.h /usr/include/eigen3/Eigen/src/Core/functors/UnaryFunctors.h src/Core/functors/NullaryFunctors.h /usr/include/eigen3/Eigen/src/Core/functors/NullaryFunctors.h src/Core/functors/StlFunctors.h /usr/include/eigen3/Eigen/src/Core/functors/StlFunctors.h src/Core/functors/AssignmentFunctors.h /usr/include/eigen3/Eigen/src/Core/functors/AssignmentFunctors.h src/Core/DenseCoeffsBase.h /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h src/Core/DenseBase.h /usr/include/eigen3/Eigen/src/Core/DenseBase.h src/Core/MatrixBase.h /usr/include/eigen3/Eigen/src/Core/MatrixBase.h src/Core/EigenBase.h /usr/include/eigen3/Eigen/src/Core/EigenBase.h src/Core/Product.h /usr/include/eigen3/Eigen/src/Core/Product.h src/Core/CoreEvaluators.h /usr/include/eigen3/Eigen/src/Core/CoreEvaluators.h src/Core/AssignEvaluator.h /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h src/Core/Assign.h /usr/include/eigen3/Eigen/src/Core/Assign.h src/Core/ArrayBase.h /usr/include/eigen3/Eigen/src/Core/ArrayBase.h src/Core/util/BlasUtil.h /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h src/Core/DenseStorage.h /usr/include/eigen3/Eigen/src/Core/DenseStorage.h src/Core/NestByValue.h /usr/include/eigen3/Eigen/src/Core/NestByValue.h src/Core/ReturnByValue.h /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h src/Core/NoAlias.h /usr/include/eigen3/Eigen/src/Core/NoAlias.h src/Core/PlainObjectBase.h /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h src/Core/Matrix.h /usr/include/eigen3/Eigen/src/Core/Matrix.h src/Core/Array.h /usr/include/eigen3/Eigen/src/Core/Array.h src/Core/CwiseBinaryOp.h /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h src/Core/CwiseUnaryOp.h /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h src/Core/CwiseNullaryOp.h /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h src/Core/CwiseUnaryView.h /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h src/Core/SelfCwiseBinaryOp.h /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h src/Core/Dot.h /usr/include/eigen3/Eigen/src/Core/Dot.h src/Core/StableNorm.h /usr/include/eigen3/Eigen/src/Core/StableNorm.h src/Core/Stride.h /usr/include/eigen3/Eigen/src/Core/Stride.h src/Core/MapBase.h /usr/include/eigen3/Eigen/src/Core/MapBase.h src/Core/Map.h /usr/include/eigen3/Eigen/src/Core/Map.h src/Core/Ref.h /usr/include/eigen3/Eigen/src/Core/Ref.h src/Core/Block.h /usr/include/eigen3/Eigen/src/Core/Block.h src/Core/VectorBlock.h /usr/include/eigen3/Eigen/src/Core/VectorBlock.h src/Core/Transpose.h /usr/include/eigen3/Eigen/src/Core/Transpose.h src/Core/DiagonalMatrix.h /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h src/Core/Diagonal.h /usr/include/eigen3/Eigen/src/Core/Diagonal.h src/Core/DiagonalProduct.h /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h src/Core/Redux.h /usr/include/eigen3/Eigen/src/Core/Redux.h src/Core/Visitor.h /usr/include/eigen3/Eigen/src/Core/Visitor.h src/Core/Fuzzy.h /usr/include/eigen3/Eigen/src/Core/Fuzzy.h src/Core/IO.h /usr/include/eigen3/Eigen/src/Core/IO.h src/Core/Swap.h /usr/include/eigen3/Eigen/src/Core/Swap.h src/Core/CommaInitializer.h /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h src/Core/GeneralProduct.h /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h src/Core/Solve.h /usr/include/eigen3/Eigen/src/Core/Solve.h src/Core/Inverse.h /usr/include/eigen3/Eigen/src/Core/Inverse.h src/Core/SolverBase.h /usr/include/eigen3/Eigen/src/Core/SolverBase.h src/Core/PermutationMatrix.h /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h src/Core/Transpositions.h /usr/include/eigen3/Eigen/src/Core/Transpositions.h src/Core/TriangularMatrix.h /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h src/Core/SelfAdjointView.h /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h src/Core/products/GeneralBlockPanelKernel.h /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h src/Core/products/Parallelizer.h /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h src/Core/ProductEvaluators.h /usr/include/eigen3/Eigen/src/Core/ProductEvaluators.h src/Core/products/GeneralMatrixVector.h /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h src/Core/products/GeneralMatrixMatrix.h /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h src/Core/SolveTriangular.h /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h src/Core/products/GeneralMatrixMatrixTriangular.h /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h src/Core/products/SelfadjointMatrixVector.h /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h src/Core/products/SelfadjointMatrixMatrix.h /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h src/Core/products/SelfadjointProduct.h /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h src/Core/products/SelfadjointRank2Update.h /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h src/Core/products/TriangularMatrixVector.h /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h src/Core/products/TriangularMatrixMatrix.h /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h src/Core/products/TriangularSolverMatrix.h /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h src/Core/products/TriangularSolverVector.h /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h src/Core/BandMatrix.h /usr/include/eigen3/Eigen/src/Core/BandMatrix.h src/Core/CoreIterators.h /usr/include/eigen3/Eigen/src/Core/CoreIterators.h src/Core/BooleanRedux.h /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h src/Core/Select.h /usr/include/eigen3/Eigen/src/Core/Select.h src/Core/VectorwiseOp.h /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h src/Core/Random.h /usr/include/eigen3/Eigen/src/Core/Random.h src/Core/Replicate.h /usr/include/eigen3/Eigen/src/Core/Replicate.h src/Core/Reverse.h /usr/include/eigen3/Eigen/src/Core/Reverse.h src/Core/ArrayWrapper.h /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h src/Core/products/GeneralMatrixMatrix_MKL.h /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h src/Core/products/GeneralMatrixVector_MKL.h /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h src/Core/products/GeneralMatrixMatrixTriangular_MKL.h /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h src/Core/products/SelfadjointMatrixMatrix_MKL.h /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h src/Core/products/SelfadjointMatrixVector_MKL.h /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h src/Core/products/TriangularMatrixMatrix_MKL.h /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h src/Core/products/TriangularMatrixVector_MKL.h /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h src/Core/products/TriangularSolverMatrix_MKL.h /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h src/Core/Assign_MKL.h /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h src/Core/GlobalFunctions.h /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h src/Core/util/ReenableStupidWarnings.h /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h /usr/include/eigen3/Eigen/Dense Core /usr/include/eigen3/Eigen/Core LU /usr/include/eigen3/Eigen/LU Cholesky /usr/include/eigen3/Eigen/Cholesky QR /usr/include/eigen3/Eigen/QR SVD /usr/include/eigen3/Eigen/SVD Geometry /usr/include/eigen3/Eigen/Geometry Eigenvalues /usr/include/eigen3/Eigen/Eigenvalues /usr/include/eigen3/Eigen/Eigenvalues Core /usr/include/eigen3/Eigen/Core src/Core/util/DisableStupidWarnings.h /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h Cholesky /usr/include/eigen3/Eigen/Cholesky Jacobi /usr/include/eigen3/Eigen/Jacobi Householder /usr/include/eigen3/Eigen/Householder LU /usr/include/eigen3/Eigen/LU Geometry /usr/include/eigen3/Eigen/Geometry src/Eigenvalues/Tridiagonalization.h /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h src/Eigenvalues/RealSchur.h /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h src/Eigenvalues/EigenSolver.h /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h src/Eigenvalues/SelfAdjointEigenSolver.h /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h src/Eigenvalues/HessenbergDecomposition.h /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h src/Eigenvalues/ComplexSchur.h /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h src/Eigenvalues/ComplexEigenSolver.h /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h src/Eigenvalues/RealQZ.h /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h src/Eigenvalues/GeneralizedEigenSolver.h /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h src/Eigenvalues/MatrixBaseEigenvalues.h /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h src/Eigenvalues/RealSchur_MKL.h /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h src/Eigenvalues/ComplexSchur_MKL.h /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h src/Eigenvalues/SelfAdjointEigenSolver_MKL.h /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h src/Core/util/ReenableStupidWarnings.h /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h /usr/include/eigen3/Eigen/Geometry Core /usr/include/eigen3/Eigen/Core src/Core/util/DisableStupidWarnings.h /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h SVD /usr/include/eigen3/Eigen/SVD LU /usr/include/eigen3/Eigen/LU limits - src/Geometry/OrthoMethods.h /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h src/Geometry/EulerAngles.h /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h src/Geometry/Homogeneous.h /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h src/Geometry/RotationBase.h /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h src/Geometry/Rotation2D.h /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h src/Geometry/Quaternion.h /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h src/Geometry/AngleAxis.h /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h src/Geometry/Transform.h /usr/include/eigen3/Eigen/src/Geometry/Transform.h src/Geometry/Translation.h /usr/include/eigen3/Eigen/src/Geometry/Translation.h src/Geometry/Scaling.h /usr/include/eigen3/Eigen/src/Geometry/Scaling.h src/Geometry/Hyperplane.h /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h src/Geometry/ParametrizedLine.h /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h src/Geometry/AlignedBox.h /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h src/Geometry/Umeyama.h /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h src/Geometry/arch/Geometry_SSE.h /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h src/Core/util/ReenableStupidWarnings.h /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h /usr/include/eigen3/Eigen/Householder Core /usr/include/eigen3/Eigen/Core src/Core/util/DisableStupidWarnings.h /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h src/Householder/Householder.h /usr/include/eigen3/Eigen/src/Householder/Householder.h src/Householder/HouseholderSequence.h /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h src/Householder/BlockHouseholder.h /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h src/Core/util/ReenableStupidWarnings.h /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h /usr/include/eigen3/Eigen/Jacobi Core /usr/include/eigen3/Eigen/Core src/Core/util/DisableStupidWarnings.h /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h src/Jacobi/Jacobi.h /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h src/Core/util/ReenableStupidWarnings.h /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h /usr/include/eigen3/Eigen/LU Core /usr/include/eigen3/Eigen/Core src/Core/util/DisableStupidWarnings.h /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h src/misc/Kernel.h /usr/include/eigen3/Eigen/src/misc/Kernel.h src/misc/Image.h /usr/include/eigen3/Eigen/src/misc/Image.h src/LU/FullPivLU.h /usr/include/eigen3/Eigen/src/LU/FullPivLU.h src/LU/PartialPivLU.h /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h src/LU/PartialPivLU_MKL.h /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h src/LU/Determinant.h /usr/include/eigen3/Eigen/src/LU/Determinant.h src/LU/InverseImpl.h /usr/include/eigen3/Eigen/src/LU/InverseImpl.h src/LU/arch/Inverse_SSE.h /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h src/Core/util/ReenableStupidWarnings.h /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h /usr/include/eigen3/Eigen/QR Core /usr/include/eigen3/Eigen/Core src/Core/util/DisableStupidWarnings.h /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h Cholesky /usr/include/eigen3/Eigen/Cholesky Jacobi /usr/include/eigen3/Eigen/Jacobi Householder /usr/include/eigen3/Eigen/Householder src/QR/HouseholderQR.h /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h src/QR/FullPivHouseholderQR.h /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h src/QR/ColPivHouseholderQR.h /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h src/QR/HouseholderQR_MKL.h /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h src/QR/ColPivHouseholderQR_MKL.h /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h src/Core/util/ReenableStupidWarnings.h /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h /usr/include/eigen3/Eigen/SVD QR /usr/include/eigen3/Eigen/QR Householder /usr/include/eigen3/Eigen/Householder Jacobi /usr/include/eigen3/Eigen/Jacobi src/Core/util/DisableStupidWarnings.h /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h src/SVD/UpperBidiagonalization.h /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h src/SVD/SVDBase.h /usr/include/eigen3/Eigen/src/SVD/SVDBase.h src/SVD/JacobiSVD.h /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h src/SVD/BDCSVD.h /usr/include/eigen3/Eigen/src/SVD/BDCSVD.h src/SVD/JacobiSVD_MKL.h /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h src/Core/util/ReenableStupidWarnings.h /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h /usr/include/eigen3/Eigen/StdDeque Core /usr/include/eigen3/Eigen/Core deque - src/StlSupport/StdDeque.h /usr/include/eigen3/Eigen/src/StlSupport/StdDeque.h /usr/include/eigen3/Eigen/StdVector Core /usr/include/eigen3/Eigen/Core vector - src/StlSupport/StdVector.h /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h /usr/include/eigen3/Eigen/src/Cholesky/LLT.h /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h Eigen/src/Core/util/MKL_support.h /usr/include/eigen3/Eigen/src/Cholesky/Eigen/src/Core/util/MKL_support.h iostream - /usr/include/eigen3/Eigen/src/Core/Array.h /usr/include/eigen3/Eigen/src/Core/ArrayBase.h ../plugins/CommonCwiseUnaryOps.h /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h ../plugins/MatrixCwiseUnaryOps.h /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h ../plugins/ArrayCwiseUnaryOps.h /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h ../plugins/CommonCwiseBinaryOps.h /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h ../plugins/MatrixCwiseBinaryOps.h /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h ../plugins/ArrayCwiseBinaryOps.h /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h /usr/include/eigen3/Eigen/src/Core/Assign.h /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h /usr/include/eigen3/Eigen/src/Core/BandMatrix.h /usr/include/eigen3/Eigen/src/Core/Block.h /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h /usr/include/eigen3/Eigen/src/Core/CoreEvaluators.h /usr/include/eigen3/Eigen/src/Core/CoreIterators.h /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h /usr/include/eigen3/Eigen/src/Core/DenseBase.h ../plugins/BlockMethods.h /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h /usr/include/eigen3/Eigen/src/Core/DenseStorage.h /usr/include/eigen3/Eigen/src/Core/Diagonal.h /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h /usr/include/eigen3/Eigen/src/Core/Dot.h /usr/include/eigen3/Eigen/src/Core/EigenBase.h /usr/include/eigen3/Eigen/src/Core/Fuzzy.h /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h /usr/include/eigen3/Eigen/src/Core/IO.h /usr/include/eigen3/Eigen/src/Core/Inverse.h /usr/include/eigen3/Eigen/src/Core/Map.h /usr/include/eigen3/Eigen/src/Core/MapBase.h /usr/include/eigen3/Eigen/src/Core/MathFunctions.h /usr/include/eigen3/Eigen/src/Core/Matrix.h /usr/include/eigen3/Eigen/src/Core/MatrixBase.h ../plugins/CommonCwiseUnaryOps.h /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h ../plugins/CommonCwiseBinaryOps.h /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h ../plugins/MatrixCwiseUnaryOps.h /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h ../plugins/MatrixCwiseBinaryOps.h /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h /usr/include/eigen3/Eigen/src/Core/NestByValue.h /usr/include/eigen3/Eigen/src/Core/NoAlias.h /usr/include/eigen3/Eigen/src/Core/NumTraits.h /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h /usr/include/eigen3/Eigen/src/Core/Product.h /usr/include/eigen3/Eigen/src/Core/ProductEvaluators.h /usr/include/eigen3/Eigen/src/Core/Random.h /usr/include/eigen3/Eigen/src/Core/Redux.h /usr/include/eigen3/Eigen/src/Core/Ref.h /usr/include/eigen3/Eigen/src/Core/Replicate.h /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h /usr/include/eigen3/Eigen/src/Core/Reverse.h /usr/include/eigen3/Eigen/src/Core/Select.h /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h /usr/include/eigen3/Eigen/src/Core/Solve.h /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h /usr/include/eigen3/Eigen/src/Core/SolverBase.h /usr/include/eigen3/Eigen/src/Core/SpecialFunctions.h /usr/include/eigen3/Eigen/src/Core/StableNorm.h /usr/include/eigen3/Eigen/src/Core/Stride.h /usr/include/eigen3/Eigen/src/Core/Swap.h /usr/include/eigen3/Eigen/src/Core/Transpose.h /usr/include/eigen3/Eigen/src/Core/Transpositions.h /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h /usr/include/eigen3/Eigen/src/Core/VectorBlock.h /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h /usr/include/eigen3/Eigen/src/Core/Visitor.h /usr/include/eigen3/Eigen/src/Core/arch/AVX/Complex.h /usr/include/eigen3/Eigen/src/Core/arch/AVX/MathFunctions.h /usr/include/eigen3/Eigen/src/Core/arch/AVX/PacketMath.h /usr/include/eigen3/Eigen/src/Core/arch/AVX/TypeCasting.h /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/MathFunctions.h /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h /usr/include/eigen3/Eigen/src/Core/arch/CUDA/MathFunctions.h /usr/include/eigen3/Eigen/src/Core/arch/CUDA/PacketMath.h /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h /usr/include/eigen3/Eigen/src/Core/arch/NEON/MathFunctions.h /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h /usr/include/eigen3/Eigen/src/Core/arch/SSE/TypeCasting.h /usr/include/eigen3/Eigen/src/Core/functors/AssignmentFunctors.h /usr/include/eigen3/Eigen/src/Core/functors/BinaryFunctors.h /usr/include/eigen3/Eigen/src/Core/functors/NullaryFunctors.h /usr/include/eigen3/Eigen/src/Core/functors/StlFunctors.h /usr/include/eigen3/Eigen/src/Core/functors/UnaryFunctors.h /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h /usr/include/eigen3/Eigen/src/Core/util/Constants.h /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h mkl.h - mkl_lapacke.h - /usr/include/eigen3/Eigen/src/Core/util/Macros.h cstdlib - iostream - /usr/include/eigen3/Eigen/src/Core/util/Memory.h unistd.h - /usr/include/eigen3/Eigen/src/Core/util/Meta.h cfloat - math_constants.h - /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h ./HessenbergDecomposition.h /usr/include/eigen3/Eigen/src/Eigenvalues/././HessenbergDecomposition.h /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h ./HessenbergDecomposition.h /usr/include/eigen3/Eigen/src/Eigenvalues/././HessenbergDecomposition.h /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h ./ComplexSchur.h /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h ./HessenbergDecomposition.h /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h Eigen/src/Core/util/MKL_support.h /usr/include/eigen3/Eigen/src/Eigenvalues/Eigen/src/Core/util/MKL_support.h /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h ./RealSchur.h /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h ./RealQZ.h /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h ./Tridiagonalization.h /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h ./HessenbergDecomposition.h /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h Eigen/src/Core/util/MKL_support.h /usr/include/eigen3/Eigen/src/Eigenvalues/Eigen/src/Core/util/MKL_support.h /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h ./Tridiagonalization.h /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h Eigen/src/Core/util/MKL_support.h /usr/include/eigen3/Eigen/src/Eigenvalues/Eigen/src/Core/util/MKL_support.h /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h /usr/include/eigen3/Eigen/src/Geometry/Scaling.h /usr/include/eigen3/Eigen/src/Geometry/Transform.h /usr/include/eigen3/Eigen/src/Geometry/Translation.h /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h /usr/include/eigen3/Eigen/src/Householder/Householder.h /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h /usr/include/eigen3/Eigen/src/LU/Determinant.h /usr/include/eigen3/Eigen/src/LU/FullPivLU.h /usr/include/eigen3/Eigen/src/LU/InverseImpl.h /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h Eigen/src/Core/util/MKL_support.h /usr/include/eigen3/Eigen/src/LU/Eigen/src/Core/util/MKL_support.h /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h Eigen/src/Core/util/MKL_support.h /usr/include/eigen3/Eigen/src/QR/Eigen/src/Core/util/MKL_support.h /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h ../Core/util/MKL_support.h /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h /usr/include/eigen3/Eigen/src/SVD/BDCSVD.h /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h Eigen/src/Core/util/MKL_support.h /usr/include/eigen3/Eigen/src/SVD/Eigen/src/Core/util/MKL_support.h /usr/include/eigen3/Eigen/src/SVD/SVDBase.h /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h /usr/include/eigen3/Eigen/src/StlSupport/StdDeque.h details.h /usr/include/eigen3/Eigen/src/StlSupport/details.h /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h details.h /usr/include/eigen3/Eigen/src/StlSupport/details.h /usr/include/eigen3/Eigen/src/StlSupport/details.h /usr/include/eigen3/Eigen/src/misc/Image.h /usr/include/eigen3/Eigen/src/misc/Kernel.h /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h /usr/include/eigen3/unsupported/Eigen/MatrixFunctions cfloat - list - Eigen/Core - Eigen/LU - Eigen/Eigenvalues - src/MatrixFunctions/MatrixExponential.h /usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/MatrixExponential.h src/MatrixFunctions/MatrixFunction.h /usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/MatrixFunction.h src/MatrixFunctions/MatrixSquareRoot.h /usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/MatrixSquareRoot.h src/MatrixFunctions/MatrixLogarithm.h /usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/MatrixLogarithm.h src/MatrixFunctions/MatrixPower.h /usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/MatrixPower.h unsupported/Eigen/MatrixFunctions - iostream - /usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/MatrixExponential.h StemFunction.h /usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/StemFunction.h /usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/MatrixFunction.h StemFunction.h /usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/StemFunction.h /usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/MatrixLogarithm.h /usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/MatrixPower.h /usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/MatrixSquareRoot.h /usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/StemFunction.h /usr/include/mrpt/base/include/mrpt/base/link_pragmas.h mrpt/config.h - mrpt/utils/boost_join.h - /usr/include/mrpt/base/include/mrpt/bayes/CParticleFilter.h mrpt/utils/core_defs.h - mrpt/utils/CDebugOutputCapable.h - mrpt/utils/CLoadableOptions.h - /usr/include/mrpt/base/include/mrpt/bayes/CParticleFilterCapable.h mrpt/utils/utils_defs.h - mrpt/bayes/CParticleFilter.h - /usr/include/mrpt/base/include/mrpt/bayes/CParticleFilterData.h mrpt/utils/core_defs.h - mrpt/bayes/CProbabilityParticle.h - mrpt/bayes/CParticleFilterCapable.h - deque - algorithm - /usr/include/mrpt/base/include/mrpt/bayes/CProbabilityParticle.h /usr/include/mrpt/base/include/mrpt/math/CArray.h mrpt/utils/core_defs.h - stdexcept - mrpt/utils/TTypeName.h - /usr/include/mrpt/base/include/mrpt/math/CArrayNumeric.h mrpt/utils/core_defs.h - mrpt/utils/types_math.h - mrpt/utils/TTypeName.h - mrpt/math/point_poses2vectors.h - /usr/include/mrpt/base/include/mrpt/math/CHistogram.h mrpt/utils/core_defs.h - mrpt/utils/types_math.h - vector - /usr/include/mrpt/base/include/mrpt/math/CMatrix.h mrpt/utils/CSerializable.h - mrpt/math/CMatrixTemplateNumeric.h - mrpt/math/CMatrixFixedNumeric.h - /usr/include/mrpt/base/include/mrpt/math/CMatrixD.h mrpt/utils/CSerializable.h - mrpt/math/CMatrixTemplateNumeric.h - /usr/include/mrpt/base/include/mrpt/math/CMatrixFixedNumeric.h mrpt/math/math_frwds.h - mrpt/math/eigen_frwds.h - mrpt/utils/types_math.h - mrpt/utils/CSerializable.h - mrpt/math/point_poses2vectors.h - /usr/include/mrpt/base/include/mrpt/math/CMatrixTemplate.h mrpt/utils/utils_defs.h - mrpt/system/memory.h - mrpt/math/math_frwds.h - mrpt/math/CArray.h - algorithm - /usr/include/mrpt/base/include/mrpt/math/CMatrixTemplateNumeric.h mrpt/utils/core_defs.h - mrpt/utils/types_math.h - mrpt/utils/TTypeName.h - mrpt/math/point_poses2vectors.h - /usr/include/mrpt/base/include/mrpt/math/CPolygon.h mrpt/utils/CSerializable.h - mrpt/math/lightweight_geom_data.h - /usr/include/mrpt/base/include/mrpt/math/CQuaternion.h mrpt/math/CMatrixTemplateNumeric.h - mrpt/math/CArrayNumeric.h - /usr/include/mrpt/base/include/mrpt/math/CSparseMatrixTemplate.h mrpt/utils/utils_defs.h - map - /usr/include/mrpt/base/include/mrpt/math/eigen_frwds.h mrpt/config.h - /usr/include/mrpt/base/include/mrpt/math/geometry.h mrpt/utils/utils_defs.h - mrpt/math/CMatrixTemplateNumeric.h - mrpt/poses/CPose3D.h - mrpt/math/CSparseMatrixTemplate.h - mrpt/math/math_frwds.h - mrpt/math/wrap2pi.h - /usr/include/mrpt/base/include/mrpt/math/homog_matrices.h mrpt/config.h - mrpt/utils/compiler_fixes.h - mrpt/utils/boost_join.h - mrpt/utils/mrpt_macros.h - /usr/include/mrpt/base/include/mrpt/math/lightweight_geom_data.h mrpt/utils/utils_defs.h - mrpt/config.h - mrpt/base/link_pragmas.h - mrpt/utils/TPixelCoord.h - mrpt/utils/TTypeName.h - mrpt/math/math_frwds.h - vector - stdexcept - /usr/include/mrpt/base/include/mrpt/math/math_frwds.h mrpt/config.h - mrpt/base/link_pragmas.h - mrpt/poses/poses_frwds.h - string - /usr/include/mrpt/base/include/mrpt/math/matrix_serialization.h mrpt/utils/CStream.h - mrpt/math/CMatrix.h - mrpt/math/CMatrixD.h - mrpt/math/CMatrixTemplateNumeric.h - mrpt/math/CMatrixFixedNumeric.h - /usr/include/mrpt/base/include/mrpt/math/point_poses2vectors.h mrpt/math/math_frwds.h - /usr/include/mrpt/base/include/mrpt/math/wrap2pi.h cmath - cstddef - /usr/include/mrpt/base/include/mrpt/otherlibs/stlplus/containers_fixes.hpp /usr/include/mrpt/base/include/mrpt/otherlibs/stlplus/exceptions.hpp containers_fixes.hpp /usr/include/mrpt/base/include/mrpt/otherlibs/stlplus/containers_fixes.hpp stdexcept - string - /usr/include/mrpt/base/include/mrpt/otherlibs/stlplus/smart_ptr.hpp exceptions.hpp /usr/include/mrpt/base/include/mrpt/otherlibs/stlplus/exceptions.hpp mrpt/synch/atomic_incr.h - smart_ptr.tpp /usr/include/mrpt/base/include/mrpt/otherlibs/stlplus/smart_ptr.tpp /usr/include/mrpt/base/include/mrpt/otherlibs/stlplus/smart_ptr.tpp /usr/include/mrpt/base/include/mrpt/poses.h mrpt/poses/CPoseOrPoint.h - mrpt/poses/CPose.h - mrpt/poses/CPoint.h - mrpt/poses/CPoint2D.h - mrpt/poses/CPose2D.h - mrpt/poses/CPose3D.h - mrpt/poses/CPose3DRotVec.h - mrpt/poses/CPoint3D.h - mrpt/poses/CPosePDF.h - mrpt/poses/CPose2DGridTemplate.h - mrpt/poses/CPosePDFGaussian.h - mrpt/poses/CPointPDF.h - mrpt/poses/CPose3DQuat.h - mrpt/poses/CPosePDFGrid.h - mrpt/poses/CPointPDFGaussian.h - mrpt/poses/CPoint2DPDFGaussian.h - mrpt/poses/CPose3DPDF.h - mrpt/poses/CPosePDFParticles.h - mrpt/poses/CPointPDFParticles.h - mrpt/poses/CPose3DPDFGaussian.h - mrpt/poses/CPosePDFSOG.h - mrpt/poses/CPointPDFSOG.h - mrpt/poses/CPose3DPDFParticles.h - mrpt/poses/CPoses2DSequence.h - mrpt/poses/CPose3DPDFSOG.h - mrpt/poses/CPoses3DSequence.h - mrpt/poses/CPose3DInterpolator.h - mrpt/poses/CPoseRandomSampler.h - mrpt/poses/CRobot2DPoseEstimator.h - mrpt/poses/CPose3DQuatPDFGaussian.h - mrpt/poses/CPosePDFGaussianInf.h - mrpt/poses/CPose3DPDFGaussianInf.h - mrpt/poses/CPose3DQuatPDFGaussianInf.h - mrpt/poses/SE_traits.h - /usr/include/mrpt/base/include/mrpt/poses/CPoint.h mrpt/poses/CPoseOrPoint.h - mrpt/math/CMatrixTemplateNumeric.h - /usr/include/mrpt/base/include/mrpt/poses/CPoint2D.h mrpt/utils/CSerializable.h - mrpt/poses/CPoint.h - mrpt/math/CArray.h - /usr/include/mrpt/base/include/mrpt/poses/CPoint2DPDF.h mrpt/utils/CSerializable.h - mrpt/utils/CProbabilityDensityFunction.h - mrpt/poses/CPoint2D.h - /usr/include/mrpt/base/include/mrpt/poses/CPoint2DPDFGaussian.h mrpt/poses/CPoint2DPDF.h - /usr/include/mrpt/base/include/mrpt/poses/CPoint3D.h mrpt/poses/CPoint.h - /usr/include/mrpt/base/include/mrpt/poses/CPointPDF.h mrpt/utils/CSerializable.h - mrpt/utils/CProbabilityDensityFunction.h - mrpt/poses/CPoint3D.h - mrpt/poses/CPosePDF.h - /usr/include/mrpt/base/include/mrpt/poses/CPointPDFGaussian.h mrpt/poses/CPointPDF.h - mrpt/math/CMatrix.h - /usr/include/mrpt/base/include/mrpt/poses/CPointPDFParticles.h mrpt/poses/CPointPDF.h - mrpt/math/CMatrix.h - mrpt/bayes/CParticleFilterCapable.h - mrpt/bayes/CProbabilityParticle.h - mrpt/bayes/CParticleFilterData.h - /usr/include/mrpt/base/include/mrpt/poses/CPointPDFSOG.h mrpt/poses/CPointPDF.h - mrpt/poses/CPointPDFGaussian.h - mrpt/math/CMatrix.h - mrpt/math/CMatrixD.h - /usr/include/mrpt/base/include/mrpt/poses/CPose.h mrpt/poses/CPoseOrPoint.h - /usr/include/mrpt/base/include/mrpt/poses/CPose2D.h mrpt/poses/CPose.h - mrpt/utils/aligned_containers.h - /usr/include/mrpt/base/include/mrpt/poses/CPose2DGridTemplate.h mrpt/utils/CSerializable.h - mrpt/utils/round.h - mrpt/utils/bits.h - /usr/include/mrpt/base/include/mrpt/poses/CPose3D.h mrpt/poses/CPose.h - mrpt/math/CMatrixFixedNumeric.h - mrpt/math/CQuaternion.h - /usr/include/mrpt/base/include/mrpt/poses/CPose3DInterpolator.h mrpt/utils/CSerializable.h - mrpt/system/datetime.h - mrpt/utils/TEnumType.h - mrpt/utils/aligned_containers.h - mrpt/math/math_frwds.h - mrpt/poses/CPose3D.h - /usr/include/mrpt/base/include/mrpt/poses/CPose3DPDF.h mrpt/utils/CSerializable.h - mrpt/math/math_frwds.h - mrpt/poses/CPose3D.h - mrpt/utils/CProbabilityDensityFunction.h - /usr/include/mrpt/base/include/mrpt/poses/CPose3DPDFGaussian.h mrpt/poses/CPose3DPDF.h - mrpt/poses/CPose3D.h - /usr/include/mrpt/base/include/mrpt/poses/CPose3DPDFGaussianInf.h mrpt/poses/CPose3D.h - mrpt/poses/CPose3DPDF.h - mrpt/poses/CPosePDF.h - mrpt/math/CMatrixD.h - /usr/include/mrpt/base/include/mrpt/poses/CPose3DPDFParticles.h mrpt/poses/CPose3DPDF.h - mrpt/bayes/CProbabilityParticle.h - mrpt/bayes/CParticleFilterCapable.h - mrpt/bayes/CParticleFilterData.h - /usr/include/mrpt/base/include/mrpt/poses/CPose3DPDFSOG.h mrpt/poses/CPose3DPDF.h - mrpt/poses/CPose3DPDFGaussian.h - mrpt/utils/aligned_containers.h - /usr/include/mrpt/base/include/mrpt/poses/CPose3DQuat.h mrpt/poses/CPose.h - mrpt/math/CMatrixFixedNumeric.h - mrpt/math/CQuaternion.h - mrpt/poses/CPoint3D.h - mrpt/poses/poses_frwds.h - mrpt/math/lightweight_geom_data.h - /usr/include/mrpt/base/include/mrpt/poses/CPose3DQuatPDF.h mrpt/poses/CPose3D.h - mrpt/poses/CPose3DQuat.h - mrpt/math/CMatrixD.h - mrpt/utils/CProbabilityDensityFunction.h - /usr/include/mrpt/base/include/mrpt/poses/CPose3DQuatPDFGaussian.h mrpt/poses/CPose3DQuatPDF.h - mrpt/poses/CPose3DPDF.h - mrpt/poses/CPosePDF.h - mrpt/math/CMatrixD.h - /usr/include/mrpt/base/include/mrpt/poses/CPose3DQuatPDFGaussianInf.h mrpt/poses/CPose3DQuatPDF.h - mrpt/poses/CPose3DPDF.h - mrpt/poses/CPosePDF.h - mrpt/math/CMatrixD.h - /usr/include/mrpt/base/include/mrpt/poses/CPose3DRotVec.h mrpt/poses/CPose.h - mrpt/math/CMatrixFixedNumeric.h - mrpt/math/CQuaternion.h - mrpt/poses/poses_frwds.h - /usr/include/mrpt/base/include/mrpt/poses/CPoseOrPoint.h mrpt/math/CMatrixFixedNumeric.h - mrpt/math/lightweight_geom_data.h - mrpt/math/homog_matrices.h - mrpt/math/CArrayNumeric.h - mrpt/poses/CPoseOrPoint_detail.h - /usr/include/mrpt/base/include/mrpt/poses/CPoseOrPoint_detail.h mrpt/poses/poses_frwds.h - /usr/include/mrpt/base/include/mrpt/poses/CPosePDF.h mrpt/utils/CSerializable.h - mrpt/poses/CPose2D.h - mrpt/math/CMatrixTemplateNumeric.h - mrpt/utils/CProbabilityDensityFunction.h - /usr/include/mrpt/base/include/mrpt/poses/CPosePDFGaussian.h mrpt/poses/CPosePDF.h - mrpt/math/CMatrixFixedNumeric.h - /usr/include/mrpt/base/include/mrpt/poses/CPosePDFGaussianInf.h mrpt/poses/CPosePDF.h - mrpt/math/CMatrixFixedNumeric.h - /usr/include/mrpt/base/include/mrpt/poses/CPosePDFGrid.h mrpt/poses/CPosePDF.h - mrpt/poses/CPose2DGridTemplate.h - mrpt/utils/bits.h - /usr/include/mrpt/base/include/mrpt/poses/CPosePDFParticles.h mrpt/poses/CPosePDF.h - mrpt/poses/CPoseRandomSampler.h - mrpt/bayes/CParticleFilterCapable.h - mrpt/bayes/CParticleFilterData.h - /usr/include/mrpt/base/include/mrpt/poses/CPosePDFSOG.h mrpt/poses/CPosePDF.h - mrpt/math/CMatrixFixedNumeric.h - mrpt/math/math_frwds.h - /usr/include/mrpt/base/include/mrpt/poses/CPoseRandomSampler.h mrpt/poses/CPose3D.h - mrpt/poses/CPose2D.h - mrpt/math/CMatrixTemplateNumeric.h - mrpt/math/math_frwds.h - /usr/include/mrpt/base/include/mrpt/poses/CPoses2DSequence.h mrpt/poses/CPose2D.h - mrpt/utils/CSerializable.h - /usr/include/mrpt/base/include/mrpt/poses/CPoses3DSequence.h mrpt/poses/CPose3D.h - mrpt/utils/CSerializable.h - /usr/include/mrpt/base/include/mrpt/poses/CRobot2DPoseEstimator.h mrpt/synch/CCriticalSection.h - mrpt/math/lightweight_geom_data.h - mrpt/math/CMatrixFixedNumeric.h - mrpt/system/datetime.h - /usr/include/mrpt/base/include/mrpt/poses/SE_traits.h mrpt/poses/CPose3D.h - mrpt/poses/CPose2D.h - mrpt/math/CMatrixFixedNumeric.h - /usr/include/mrpt/base/include/mrpt/poses/poses_frwds.h /usr/include/mrpt/base/include/mrpt/synch/CCriticalSection.h mrpt/utils/CReferencedMemBlock.h - string - /usr/include/mrpt/base/include/mrpt/synch/atomic_incr.h mrpt/config.h - mrpt/utils/compiler_fixes.h - mrpt/base/link_pragmas.h - /usr/include/mrpt/base/include/mrpt/system/datetime.h mrpt/base/link_pragmas.h - mrpt/utils/mrpt_stdint.h - string - /usr/include/mrpt/base/include/mrpt/system/memory.h mrpt/utils/core_defs.h - cstring - /usr/include/mrpt/base/include/mrpt/system/os.h mrpt/config.h - cstdlib - cstdarg - mrpt/base/link_pragmas.h - mrpt/utils/mrpt_stdint.h - mrpt/utils/mrpt_macros.h - /usr/include/mrpt/base/include/mrpt/system/string_utils.h mrpt/utils/utils_defs.h - deque - /usr/include/mrpt/base/include/mrpt/system/threads.h mrpt/utils/core_defs.h - /usr/include/mrpt/base/include/mrpt/utils.h mrpt/utils/utils_defs.h - mrpt/poses.h - mrpt/utils/CDebugOutputCapable.h - mrpt/utils/CStringList.h - mrpt/utils/TEnumType.h - mrpt/utils/CObject.h - mrpt/utils/CStartUpClassesRegister.h - mrpt/utils/CSerializable.h - mrpt/utils/CStream.h - mrpt/utils/CMemoryStream.h - mrpt/utils/CMemoryChunk.h - mrpt/utils/CStdOutStream.h - mrpt/utils/CFileStream.h - mrpt/utils/CFileInputStream.h - mrpt/utils/CFileOutputStream.h - mrpt/utils/CFileGZInputStream.h - mrpt/utils/CFileGZOutputStream.h - mrpt/utils/CServerTCPSocket.h - mrpt/utils/CClientTCPSocket.h - mrpt/utils/CEnhancedMetaFile.h - mrpt/utils/CCanvas.h - mrpt/utils/CImage.h - mrpt/utils/CMappedImage.h - mrpt/utils/CTicTac.h - mrpt/utils/CTimeLogger.h - mrpt/utils/CSimpleDatabase.h - mrpt/utils/CPropertiesValuesList.h - mrpt/utils/CMHPropertiesValuesList.h - mrpt/utils/CTypeSelector.h - mrpt/utils/CLoadableOptions.h - mrpt/utils/CMessage.h - mrpt/utils/CConfigFile.h - mrpt/utils/CConfigFileMemory.h - mrpt/utils/CThreadSafeQueue.h - mrpt/utils/CMessageQueue.h - mrpt/utils/CDynamicGrid.h - mrpt/utils/CProbabilityDensityFunction.h - mrpt/utils/CConsoleRedirector.h - mrpt/utils/exceptions.h - mrpt/utils/crc.h - mrpt/utils/md5.h - mrpt/utils/net_utils.h - mrpt/utils/CLog.h - mrpt/utils/CListOfClasses.h - mrpt/utils/CTextFileLinesParser.h - mrpt/utils/CRobotSimulator.h - mrpt/utils/TCamera.h - mrpt/utils/TStereoCamera.h - mrpt/utils/TMatchingPair.h - mrpt/utils/PLY_import_export.h - mrpt/utils/CObservable.h - mrpt/utils/CObserver.h - mrpt/utils/mrptEvent.h - mrpt/utils/adapters.h - /usr/include/mrpt/base/include/mrpt/utils/CCanvas.h mrpt/utils/utils_defs.h - mrpt/utils/TColor.h - mrpt/math/eigen_frwds.h - /usr/include/mrpt/base/include/mrpt/utils/CClientTCPSocket.h mrpt/utils/core_defs.h - mrpt/utils/mrpt_stdint.h - mrpt/utils/CStream.h - string - /usr/include/mrpt/base/include/mrpt/utils/CConfigFile.h mrpt/utils/utils_defs.h - mrpt/utils/CConfigFileBase.h - mrpt/utils/safe_pointers.h - /usr/include/mrpt/base/include/mrpt/utils/CConfigFileBase.h mrpt/utils/utils_defs.h - mrpt/system/string_utils.h - /usr/include/mrpt/base/include/mrpt/utils/CConfigFileMemory.h mrpt/utils/utils_defs.h - mrpt/utils/CConfigFileBase.h - mrpt/utils/CStringList.h - mrpt/utils/safe_pointers.h - /usr/include/mrpt/base/include/mrpt/utils/CConsoleRedirector.h mrpt/synch/CCriticalSection.h - mrpt/utils/core_defs.h - streambuf - iostream - fstream - cstdio - /usr/include/mrpt/base/include/mrpt/utils/CDebugOutputCapable.h mrpt/base/link_pragmas.h - /usr/include/mrpt/base/include/mrpt/utils/CDynamicGrid.h mrpt/utils/core_defs.h - mrpt/utils/round.h - vector - string - cmath - /usr/include/mrpt/base/include/mrpt/utils/CEnhancedMetaFile.h mrpt/utils/utils_defs.h - mrpt/utils/CCanvas.h - mrpt/utils/safe_pointers.h - /usr/include/mrpt/base/include/mrpt/utils/CFileGZInputStream.h mrpt/utils/CStream.h - /usr/include/mrpt/base/include/mrpt/utils/CFileGZOutputStream.h mrpt/utils/CStream.h - /usr/include/mrpt/base/include/mrpt/utils/CFileInputStream.h mrpt/utils/CStream.h - fstream - /usr/include/mrpt/base/include/mrpt/utils/CFileOutputStream.h mrpt/utils/CStream.h - fstream - /usr/include/mrpt/base/include/mrpt/utils/CFileStream.h mrpt/utils/CStream.h - mrpt/utils/CUncopiable.h - fstream - /usr/include/mrpt/base/include/mrpt/utils/CImage.h mrpt/utils/utils_defs.h - mrpt/utils/CSerializable.h - mrpt/math/eigen_frwds.h - mrpt/utils/CCanvas.h - mrpt/utils/TCamera.h - mrpt/utils/exceptions.h - /usr/include/mrpt/base/include/mrpt/utils/CListOfClasses.h mrpt/utils/CSerializable.h - mrpt/system/string_utils.h - set - /usr/include/mrpt/base/include/mrpt/utils/CLoadableOptions.h mrpt/utils/core_defs.h - string - stdexcept - /usr/include/mrpt/base/include/mrpt/utils/CLog.h mrpt/utils/utils_defs.h - mrpt/utils/CStringList.h - mrpt/synch/CCriticalSection.h - /usr/include/mrpt/base/include/mrpt/utils/CMHPropertiesValuesList.h mrpt/utils/CSerializable.h - mrpt/utils/CMemoryChunk.h - mrpt/system/string_utils.h - cstdio - /usr/include/mrpt/base/include/mrpt/utils/CMappedImage.h mrpt/utils/CImage.h - /usr/include/mrpt/base/include/mrpt/utils/CMemoryChunk.h mrpt/utils/CMemoryStream.h - mrpt/utils/CSerializable.h - /usr/include/mrpt/base/include/mrpt/utils/CMemoryStream.h mrpt/utils/CStream.h - mrpt/utils/safe_pointers.h - /usr/include/mrpt/base/include/mrpt/utils/CMessage.h mrpt/utils/core_defs.h - mrpt/utils/mrpt_stdint.h - vector - /usr/include/mrpt/base/include/mrpt/utils/CMessageQueue.h mrpt/utils/CThreadSafeQueue.h - /usr/include/mrpt/base/include/mrpt/utils/CObject.h mrpt/system/memory.h - mrpt/utils/safe_pointers.h - vector - mrpt/otherlibs/stlplus/smart_ptr.hpp - /usr/include/mrpt/base/include/mrpt/utils/CObservable.h mrpt/config.h - mrpt/base/link_pragmas.h - set - /usr/include/mrpt/base/include/mrpt/utils/CObserver.h mrpt/utils/utils_defs.h - mrpt/utils/mrptEvent.h - set - /usr/include/mrpt/base/include/mrpt/utils/CProbabilityDensityFunction.h mrpt/math/CMatrixTemplateNumeric.h - mrpt/math/CMatrixFixedNumeric.h - mrpt/math/math_frwds.h - /usr/include/mrpt/base/include/mrpt/utils/CPropertiesValuesList.h mrpt/utils/CSerializable.h - /usr/include/mrpt/base/include/mrpt/utils/CReferencedMemBlock.h mrpt/base/link_pragmas.h - vector - utility - mrpt/otherlibs/stlplus/smart_ptr.hpp - /usr/include/mrpt/base/include/mrpt/utils/CRobotSimulator.h mrpt/utils/CSerializable.h - mrpt/poses/CPose2D.h - mrpt/base/link_pragmas.h - /usr/include/mrpt/base/include/mrpt/utils/CSerializable.h mrpt/utils/CObject.h - mrpt/utils/TTypeName.h - mrpt/utils/types_simple.h - /usr/include/mrpt/base/include/mrpt/utils/CServerTCPSocket.h mrpt/utils/core_defs.h - mrpt/utils/CDebugOutputCapable.h - string - /usr/include/mrpt/base/include/mrpt/utils/CSimpleDatabase.h mrpt/utils/utils_defs.h - mrpt/utils/CSerializable.h - map - /usr/include/mrpt/base/include/mrpt/utils/CStartUpClassesRegister.h mrpt/base/link_pragmas.h - /usr/include/mrpt/base/include/mrpt/utils/CStdOutStream.h mrpt/utils/CStream.h - /usr/include/mrpt/base/include/mrpt/utils/CStream.h mrpt/utils/core_defs.h - mrpt/utils/types_simple.h - mrpt/utils/CUncopiable.h - mrpt/utils/exceptions.h - mrpt/utils/bits.h - vector - /usr/include/mrpt/base/include/mrpt/utils/CStringList.h mrpt/utils/CSerializable.h - deque - iterator - /usr/include/mrpt/base/include/mrpt/utils/CTextFileLinesParser.h mrpt/utils/utils_defs.h - mrpt/system/string_utils.h - fstream - /usr/include/mrpt/base/include/mrpt/utils/CThreadSafeQueue.h mrpt/utils/CMessage.h - mrpt/synch/CCriticalSection.h - queue - /usr/include/mrpt/base/include/mrpt/utils/CTicTac.h mrpt/base/link_pragmas.h - mrpt/utils/CUncopiable.h - /usr/include/mrpt/base/include/mrpt/utils/CTimeLogger.h mrpt/utils/CTicTac.h - mrpt/utils/CDebugOutputCapable.h - mrpt/utils/compiler_fixes.h - mrpt/utils/mrpt_macros.h - vector - stack - map - /usr/include/mrpt/base/include/mrpt/utils/CTypeSelector.h mrpt/utils/CSerializable.h - /usr/include/mrpt/base/include/mrpt/utils/CUncopiable.h mrpt/base/link_pragmas.h - /usr/include/mrpt/base/include/mrpt/utils/PLY_import_export.h mrpt/utils/core_defs.h - mrpt/utils/CStringList.h - mrpt/utils/TColor.h - mrpt/math/lightweight_geom_data.h - /usr/include/mrpt/base/include/mrpt/utils/SSE_types.h mrpt/config.h - emmintrin.h - mmintrin.h - pmmintrin.h - immintrin.h - smmintrin.h - /usr/include/mrpt/base/include/mrpt/utils/TCamera.h mrpt/math/CMatrixTemplateNumeric.h - mrpt/math/CMatrixFixedNumeric.h - mrpt/utils/CLoadableOptions.h - mrpt/utils/CConfigFileBase.h - mrpt/utils/CSerializable.h - mrpt/poses/CPose3DQuat.h - /usr/include/mrpt/base/include/mrpt/utils/TColor.h mrpt/utils/mrpt_stdint.h - mrpt/base/link_pragmas.h - iosfwd - /usr/include/mrpt/base/include/mrpt/utils/TEnumType.h mrpt/utils/core_defs.h - mrpt/utils/bimap.h - /usr/include/mrpt/base/include/mrpt/utils/TMatchingPair.h string - vector - mrpt/base/link_pragmas.h - mrpt/poses/poses_frwds.h - /usr/include/mrpt/base/include/mrpt/utils/TParameters.h cstdarg - cstdio - map - string - /usr/include/mrpt/base/include/mrpt/utils/TPixelCoord.h iosfwd - mrpt/base/link_pragmas.h - /usr/include/mrpt/base/include/mrpt/utils/TStereoCamera.h mrpt/utils/TCamera.h - /usr/include/mrpt/base/include/mrpt/utils/TTypeName.h mrpt/utils/mrpt_stdint.h - string - /usr/include/mrpt/base/include/mrpt/utils/TTypeName_impl.h mrpt/utils/TTypeName.h - list - vector - deque - set - map - /usr/include/mrpt/base/include/mrpt/utils/adapters.h mrpt/utils/utils_defs.h - /usr/include/mrpt/base/include/mrpt/utils/aligned_containers.h vector - map - list - deque - /usr/include/mrpt/base/include/mrpt/utils/bimap.h mrpt/utils/utils_defs.h - map - /usr/include/mrpt/base/include/mrpt/utils/bits.h cmath - algorithm - /usr/include/mrpt/base/include/mrpt/utils/boost_join.h /usr/include/mrpt/base/include/mrpt/utils/ci_less.h functional - cctype - string - /usr/include/mrpt/base/include/mrpt/utils/circular_buffer.h vector - stdexcept - /usr/include/mrpt/base/include/mrpt/utils/color_maps.h mrpt/base/link_pragmas.h - /usr/include/mrpt/base/include/mrpt/utils/compiler_fixes.h /usr/include/mrpt/base/include/mrpt/utils/core_defs.h mrpt/config.h - mrpt/utils/compiler_fixes.h - mrpt/utils/boost_join.h - mrpt/utils/mrpt_macros.h - mrpt/base/link_pragmas.h - /usr/include/mrpt/base/include/mrpt/utils/crc.h mrpt/utils/utils_defs.h - /usr/include/mrpt/base/include/mrpt/utils/exceptions.h stdexcept - string - /usr/include/mrpt/base/include/mrpt/utils/list_searchable.h list - algorithm - /usr/include/mrpt/base/include/mrpt/utils/map_as_vector.h mrpt/utils/aligned_containers.h - map - vector - /usr/include/mrpt/base/include/mrpt/utils/md5.h mrpt/utils/utils_defs.h - /usr/include/mrpt/base/include/mrpt/utils/metaprogramming_serialization.h /usr/include/mrpt/base/include/mrpt/utils/mrptEvent.h mrpt/system/datetime.h - /usr/include/mrpt/base/include/mrpt/utils/mrpt_macros.h mrpt/base/link_pragmas.h - sstream - stdexcept - /usr/include/mrpt/base/include/mrpt/utils/mrpt_stdint.h mrpt/config.h - stdint.h - pstdint.h /usr/include/mrpt/base/include/mrpt/utils/pstdint.h /usr/include/mrpt/base/include/mrpt/utils/net_utils.h mrpt/utils/CClientTCPSocket.h - mrpt/utils/CServerTCPSocket.h - mrpt/utils/TParameters.h - /usr/include/mrpt/base/include/mrpt/utils/printf_vector.h mrpt/math/eigen_frwds.h - string - vector - cstdio - /usr/include/mrpt/base/include/mrpt/utils/pstdint.h stddef.h - limits.h - signal.h - stdint.h - wchar.h - /usr/include/mrpt/base/include/mrpt/utils/round.h mrpt/utils/SSE_types.h - cmath - /usr/include/mrpt/base/include/mrpt/utils/safe_pointers.h mrpt/config.h - mrpt/utils/boost_join.h - mrpt/utils/mrpt_macros.h - /usr/include/mrpt/base/include/mrpt/utils/stl_containers_utils.h list - map - set - /usr/include/mrpt/base/include/mrpt/utils/stl_extensions.h mrpt/utils/circular_buffer.h - mrpt/utils/list_searchable.h - mrpt/utils/bimap.h - mrpt/utils/map_as_vector.h - mrpt/utils/traits_map.h - mrpt/utils/stl_serialization.h - mrpt/utils/printf_vector.h - mrpt/utils/stl_containers_utils.h - mrpt/utils/ci_less.h - /usr/include/mrpt/base/include/mrpt/utils/stl_serialization.h mrpt/utils/TTypeName_impl.h - mrpt/utils/metaprogramming_serialization.h - mrpt/utils/CStream.h - vector - deque - set - map - list - algorithm - /usr/include/mrpt/base/include/mrpt/utils/traits_map.h mrpt/utils/map_as_vector.h - /usr/include/mrpt/base/include/mrpt/utils/types_math.h vector - deque - mrpt/math/math_frwds.h - fstream - ctime - stdexcept - Eigen/Dense - Eigen/StdVector - Eigen/StdDeque - /usr/include/mrpt/base/include/mrpt/utils/types_simple.h vector - string - mrpt/utils/mrpt_stdint.h - /usr/include/mrpt/base/include/mrpt/utils/utils_defs.h mrpt/utils/core_defs.h - cstddef - cstdlib - cmath - vector - algorithm - iostream - exception - stdexcept - sstream - mrpt/utils/bits.h - mrpt/utils/types_simple.h - /usr/include/mrpt/mrpt-config/mrpt/config.h /usr/include/mrpt/mrpt-config/mrpt/version.h /usr/include/mrpt/obs/include/mrpt/maps/CMetricMap.h mrpt/utils/CSerializable.h - mrpt/utils/TMatchingPair.h - mrpt/utils/CObservable.h - mrpt/math/math_frwds.h - mrpt/math/lightweight_geom_data.h - mrpt/opengl/opengl_frwds.h - mrpt/maps/CMetricMapEvents.h - mrpt/maps/TMetricMapInitializer.h - mrpt/maps/metric_map_types.h - mrpt/obs/obs_frwds.h - mrpt/obs/link_pragmas.h - deque - /usr/include/mrpt/obs/include/mrpt/maps/CMetricMapEvents.h mrpt/utils/mrptEvent.h - mrpt/poses/poses_frwds.h - /usr/include/mrpt/obs/include/mrpt/maps/TMetricMapInitializer.h mrpt/utils/CLoadableOptions.h - mrpt/utils/CObject.h - mrpt/maps/TMetricMapTypesRegistry.h - mrpt/maps/metric_map_types.h - deque - mrpt/obs/link_pragmas.h - /usr/include/mrpt/obs/include/mrpt/maps/TMetricMapTypesRegistry.h mrpt/utils/core_defs.h - mrpt/obs/link_pragmas.h - mrpt/obs/obs_frwds.h - map - string - /usr/include/mrpt/obs/include/mrpt/maps/metric_map_types.h mrpt/utils/CLoadableOptions.h - mrpt/utils/CSerializable.h - mrpt/math/lightweight_geom_data.h - mrpt/obs/obs_frwds.h - mrpt/obs/link_pragmas.h - /usr/include/mrpt/obs/include/mrpt/obs/CObservation.h mrpt/obs/link_pragmas.h - mrpt/utils/CSerializable.h - mrpt/system/datetime.h - mrpt/math/math_frwds.h - /usr/include/mrpt/obs/include/mrpt/obs/CObservation2DRangeScan.h mrpt/utils/CSerializable.h - mrpt/obs/CObservation.h - mrpt/poses/CPose3D.h - mrpt/maps/CMetricMap.h - mrpt/math/CPolygon.h - /usr/include/mrpt/obs/include/mrpt/obs/CObservationOdometry.h mrpt/utils/CSerializable.h - mrpt/obs/CObservation.h - mrpt/poses/CPose2D.h - mrpt/poses/CPose3D.h - /usr/include/mrpt/obs/include/mrpt/obs/link_pragmas.h mrpt/config.h - mrpt/utils/boost_join.h - /usr/include/mrpt/obs/include/mrpt/obs/obs_frwds.h mrpt/poses/poses_frwds.h - /usr/include/mrpt/obs/include/mrpt/slam/CObservation2DRangeScan.h mrpt/obs/CObservation2DRangeScan.h - /usr/include/mrpt/obs/include/mrpt/slam/CObservationOdometry.h mrpt/obs/CObservationOdometry.h - /usr/include/mrpt/opengl/include/mrpt/opengl.h mrpt/config.h - mrpt/opengl/CRenderizable.h - mrpt/opengl/CRenderizableDisplayList.h - mrpt/opengl/COpenGLScene.h - mrpt/opengl/COpenGLViewport.h - mrpt/opengl/CArrow.h - mrpt/opengl/CAxis.h - mrpt/opengl/CBox.h - mrpt/opengl/CFrustum.h - mrpt/opengl/CCamera.h - mrpt/opengl/CDisk.h - mrpt/opengl/CEllipsoid.h - mrpt/opengl/CGridPlaneXY.h - mrpt/opengl/CGridPlaneXZ.h - mrpt/opengl/CMesh.h - mrpt/opengl/CMeshFast.h - mrpt/opengl/CPointCloud.h - mrpt/opengl/CPointCloudColoured.h - mrpt/opengl/CSetOfLines.h - mrpt/opengl/CSetOfObjects.h - mrpt/opengl/CSetOfTriangles.h - mrpt/opengl/CSetOfTexturedTriangles.h - mrpt/opengl/CSimpleLine.h - mrpt/opengl/CSphere.h - mrpt/opengl/CText.h - mrpt/opengl/CText3D.h - mrpt/opengl/CTexturedPlane.h - mrpt/opengl/C3DSScene.h - mrpt/opengl/CAssimpModel.h - mrpt/opengl/CCylinder.h - mrpt/opengl/CPolyhedron.h - mrpt/opengl/CGeneralizedCylinder.h - mrpt/opengl/COpenGLStandardObject.h - mrpt/opengl/CFBORender.h - mrpt/opengl/CEllipsoidInverseDepth2D.h - mrpt/opengl/CEllipsoidInverseDepth3D.h - mrpt/opengl/CEllipsoidRangeBearing2D.h - mrpt/opengl/COctoMapVoxels.h - mrpt/opengl/CVectorField2D.h - mrpt/opengl/CVectorField3D.h - mrpt/opengl/stock_objects.h - mrpt/opengl/pose_pdfs.h - mrpt/opengl/graph_tools.h - /usr/include/mrpt/opengl/include/mrpt/opengl/C3DSScene.h mrpt/opengl/CRenderizableDisplayList.h - mrpt/opengl/COpenGLScene.h - mrpt/utils/CMemoryChunk.h - /usr/include/mrpt/opengl/include/mrpt/opengl/CArrow.h mrpt/opengl/CRenderizableDisplayList.h - /usr/include/mrpt/opengl/include/mrpt/opengl/CAssimpModel.h mrpt/opengl/CRenderizableDisplayList.h - mrpt/opengl/COpenGLScene.h - mrpt/utils/CMemoryChunk.h - map - /usr/include/mrpt/opengl/include/mrpt/opengl/CAxis.h mrpt/opengl/CRenderizableDisplayList.h - /usr/include/mrpt/opengl/include/mrpt/opengl/CBox.h mrpt/opengl/CRenderizableDisplayList.h - mrpt/math/lightweight_geom_data.h - /usr/include/mrpt/opengl/include/mrpt/opengl/CCamera.h mrpt/opengl/CRenderizable.h - mrpt/poses/CPoseOrPoint.h - /usr/include/mrpt/opengl/include/mrpt/opengl/CCylinder.h mrpt/opengl/CRenderizableDisplayList.h - /usr/include/mrpt/opengl/include/mrpt/opengl/CDisk.h mrpt/opengl/CRenderizableDisplayList.h - mrpt/poses/CPose3D.h - mrpt/math/geometry.h - /usr/include/mrpt/opengl/include/mrpt/opengl/CEllipsoid.h mrpt/opengl/CRenderizableDisplayList.h - mrpt/math/CMatrixD.h - mrpt/math/CMatrixFixedNumeric.h - /usr/include/mrpt/opengl/include/mrpt/opengl/CEllipsoidInverseDepth2D.h mrpt/opengl/CGeneralizedEllipsoidTemplate.h - /usr/include/mrpt/opengl/include/mrpt/opengl/CEllipsoidInverseDepth3D.h mrpt/opengl/CGeneralizedEllipsoidTemplate.h - /usr/include/mrpt/opengl/include/mrpt/opengl/CEllipsoidRangeBearing2D.h mrpt/opengl/CGeneralizedEllipsoidTemplate.h - /usr/include/mrpt/opengl/include/mrpt/opengl/CFBORender.h mrpt/utils/CImage.h - mrpt/opengl/COpenGLScene.h - mrpt/opengl/CTextMessageCapable.h - /usr/include/mrpt/opengl/include/mrpt/opengl/CFrustum.h mrpt/opengl/CRenderizableDisplayList.h - mrpt/math/lightweight_geom_data.h - /usr/include/mrpt/opengl/include/mrpt/opengl/CGeneralizedCylinder.h mrpt/opengl/CRenderizableDisplayList.h - mrpt/opengl/CPolyhedron.h - mrpt/opengl/CSetOfTriangles.h - mrpt/math/geometry.h - mrpt/math/CMatrixTemplate.h - mrpt/utils/aligned_containers.h - /usr/include/mrpt/opengl/include/mrpt/opengl/CGeneralizedEllipsoidTemplate.h mrpt/opengl/CRenderizableDisplayList.h - mrpt/math/CMatrixFixedNumeric.h - mrpt/utils/types_math.h - mrpt/utils/CStream.h - mrpt/math/matrix_serialization.h - mrpt/opengl/link_pragmas.h - /usr/include/mrpt/opengl/include/mrpt/opengl/CGridPlaneXY.h mrpt/opengl/CRenderizableDisplayList.h - /usr/include/mrpt/opengl/include/mrpt/opengl/CGridPlaneXZ.h mrpt/opengl/CRenderizableDisplayList.h - /usr/include/mrpt/opengl/include/mrpt/opengl/CLight.h mrpt/utils/utils_defs.h - mrpt/utils/TTypeName.h - mrpt/opengl/link_pragmas.h - /usr/include/mrpt/opengl/include/mrpt/opengl/CMesh.h mrpt/opengl/CRenderizableDisplayList.h - mrpt/math/CMatrix.h - mrpt/utils/CImage.h - mrpt/utils/color_maps.h - mrpt/opengl/CSetOfTriangles.h - /usr/include/mrpt/opengl/include/mrpt/opengl/CMeshFast.h mrpt/opengl/CRenderizableDisplayList.h - mrpt/math/CMatrix.h - mrpt/utils/CImage.h - mrpt/utils/color_maps.h - /usr/include/mrpt/opengl/include/mrpt/opengl/COctoMapVoxels.h mrpt/opengl/CRenderizableDisplayList.h - mrpt/math/lightweight_geom_data.h - /usr/include/mrpt/opengl/include/mrpt/opengl/COctreePointRenderer.h mrpt/opengl/CRenderizable.h - mrpt/opengl/CSetOfObjects.h - mrpt/opengl/CBox.h - mrpt/opengl/gl_utils.h - mrpt/utils/aligned_containers.h - /usr/include/mrpt/opengl/include/mrpt/opengl/COpenGLScene.h mrpt/opengl/CRenderizable.h - mrpt/opengl/COpenGLViewport.h - mrpt/utils/CStringList.h - /usr/include/mrpt/opengl/include/mrpt/opengl/COpenGLStandardObject.h mrpt/opengl/CRenderizableDisplayList.h - mrpt/math/geometry.h - /usr/include/mrpt/opengl/include/mrpt/opengl/COpenGLViewport.h mrpt/utils/CSerializable.h - mrpt/utils/safe_pointers.h - mrpt/utils/CImage.h - mrpt/opengl/CCamera.h - mrpt/opengl/CSetOfObjects.h - mrpt/opengl/CLight.h - mrpt/math/lightweight_geom_data.h - mrpt/utils/CObservable.h - mrpt/utils/CStringList.h - mrpt/utils/mrptEvent.h - /usr/include/mrpt/opengl/include/mrpt/opengl/CPointCloud.h mrpt/opengl/CRenderizable.h - mrpt/opengl/COctreePointRenderer.h - mrpt/utils/PLY_import_export.h - mrpt/utils/adapters.h - /usr/include/mrpt/opengl/include/mrpt/opengl/CPointCloudColoured.h mrpt/opengl/CRenderizable.h - mrpt/opengl/COctreePointRenderer.h - mrpt/utils/PLY_import_export.h - mrpt/utils/adapters.h - /usr/include/mrpt/opengl/include/mrpt/opengl/CPolyhedron.h mrpt/opengl/CRenderizableDisplayList.h - mrpt/math/geometry.h - /usr/include/mrpt/opengl/include/mrpt/opengl/CRenderizable.h mrpt/utils/CSerializable.h - mrpt/utils/TColor.h - mrpt/math/math_frwds.h - mrpt/poses/CPose3D.h - mrpt/opengl/opengl_fonts.h - mrpt/opengl/link_pragmas.h - mrpt/math/lightweight_geom_data.h - deque - /usr/include/mrpt/opengl/include/mrpt/opengl/CRenderizableDisplayList.h mrpt/opengl/CRenderizable.h - /usr/include/mrpt/opengl/include/mrpt/opengl/CSetOfLines.h mrpt/opengl/CRenderizableDisplayList.h - mrpt/math/lightweight_geom_data.h - /usr/include/mrpt/opengl/include/mrpt/opengl/CSetOfObjects.h mrpt/opengl/CRenderizable.h - mrpt/poses/poses_frwds.h - mrpt/utils/CStringList.h - /usr/include/mrpt/opengl/include/mrpt/opengl/CSetOfTexturedTriangles.h mrpt/opengl/CTexturedObject.h - /usr/include/mrpt/opengl/include/mrpt/opengl/CSetOfTriangles.h mrpt/opengl/CRenderizableDisplayList.h - mrpt/math/geometry.h - /usr/include/mrpt/opengl/include/mrpt/opengl/CSimpleLine.h mrpt/opengl/CRenderizableDisplayList.h - /usr/include/mrpt/opengl/include/mrpt/opengl/CSphere.h mrpt/opengl/CRenderizableDisplayList.h - /usr/include/mrpt/opengl/include/mrpt/opengl/CText.h mrpt/opengl/CRenderizable.h - /usr/include/mrpt/opengl/include/mrpt/opengl/CText3D.h mrpt/opengl/CRenderizableDisplayList.h - /usr/include/mrpt/opengl/include/mrpt/opengl/CTextMessageCapable.h mrpt/opengl/CRenderizable.h - mrpt/opengl/opengl_fonts.h - map - /usr/include/mrpt/opengl/include/mrpt/opengl/CTexturedObject.h mrpt/opengl/CRenderizableDisplayList.h - mrpt/utils/CImage.h - mrpt/math/geometry.h - /usr/include/mrpt/opengl/include/mrpt/opengl/CTexturedPlane.h mrpt/opengl/CTexturedObject.h - /usr/include/mrpt/opengl/include/mrpt/opengl/CVectorField2D.h mrpt/opengl/CRenderizableDisplayList.h - mrpt/math/lightweight_geom_data.h - mrpt/math/CMatrix.h - /usr/include/mrpt/opengl/include/mrpt/opengl/CVectorField3D.h mrpt/opengl/CRenderizableDisplayList.h - mrpt/math/lightweight_geom_data.h - mrpt/math/CMatrix.h - mrpt/utils/stl_extensions.h - Eigen/Dense - /usr/include/mrpt/opengl/include/mrpt/opengl/gl_utils.h mrpt/utils/utils_defs.h - mrpt/opengl/opengl_fonts.h - mrpt/opengl/CRenderizable.h - mrpt/opengl/link_pragmas.h - /usr/include/mrpt/opengl/include/mrpt/opengl/graph_tools.h mrpt/opengl/CSetOfObjects.h - mrpt/utils/TParameters.h - graph_tools_impl.h /usr/include/mrpt/opengl/include/mrpt/opengl/graph_tools_impl.h /usr/include/mrpt/opengl/include/mrpt/opengl/graph_tools_impl.h mrpt/opengl/CGridPlaneXY.h - mrpt/opengl/CPointCloud.h - mrpt/opengl/CSetOfObjects.h - mrpt/opengl/CSimpleLine.h - mrpt/opengl/CSetOfLines.h - mrpt/opengl/stock_objects.h - /usr/include/mrpt/opengl/include/mrpt/opengl/link_pragmas.h mrpt/config.h - mrpt/utils/boost_join.h - /usr/include/mrpt/opengl/include/mrpt/opengl/opengl_fonts.h mrpt/utils/TColor.h - mrpt/utils/compiler_fixes.h - mrpt/opengl/link_pragmas.h - string - /usr/include/mrpt/opengl/include/mrpt/opengl/opengl_frwds.h /usr/include/mrpt/opengl/include/mrpt/opengl/pose_pdfs.h mrpt/opengl/CSetOfObjects.h - /usr/include/mrpt/opengl/include/mrpt/opengl/stock_objects.h mrpt/opengl/CSetOfObjects.h - ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rf2o_laser_odometry_node.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES "CXX" ) # The set of files for implicit dependencies of each language: set(CMAKE_DEPENDS_CHECK_CXX "/home/zn/racecar/src/rf2o_laser_odometry/src/CLaserOdometry2D.cpp" "/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o" ) set(CMAKE_CXX_COMPILER_ID "GNU") # Preprocessor definitions for this target. set(CMAKE_TARGET_DEFINITIONS_CXX "ROSCONSOLE_BACKEND_LOG4CXX" "ROS_PACKAGE_NAME=\"rf2o_laser_odometry\"" ) # The include file search paths: set(CMAKE_CXX_TARGET_INCLUDE_PATH "/usr/include/eigen3" "/usr/include/mrpt/mrpt-config" "/usr/include/mrpt/bayes/include" "/usr/include/mrpt/graphs/include" "/usr/include/mrpt/vision/include" "/usr/include/mrpt/tfest/include" "/usr/include/mrpt/maps/include" "/usr/include/mrpt/obs/include" "/usr/include/mrpt/opengl/include" "/usr/include/mrpt/base/include" "/usr/include/mrpt/slam/include" "/usr/include/mrpt/topography/include" "../include" "/opt/ros/kinetic/include" "/opt/ros/kinetic/share/xmlrpcpp/cmake/../../../include/xmlrpcpp" ) # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rf2o_laser_odometry_node.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Include any dependencies generated for this target. include CMakeFiles/rf2o_laser_odometry_node.dir/depend.make # Include the progress variables for this target. include CMakeFiles/rf2o_laser_odometry_node.dir/progress.make # Include the compile flags for this target's objects. include CMakeFiles/rf2o_laser_odometry_node.dir/flags.make CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: CMakeFiles/rf2o_laser_odometry_node.dir/flags.make CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: ../src/CLaserOdometry2D.cpp @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num=$(CMAKE_PROGRESS_1) "Building CXX object CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o" /usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -o CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o -c /home/zn/racecar/src/rf2o_laser_odometry/src/CLaserOdometry2D.cpp CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.i: cmake_force @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.i" /usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -E /home/zn/racecar/src/rf2o_laser_odometry/src/CLaserOdometry2D.cpp > CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.i CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.s: cmake_force @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.s" /usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -S /home/zn/racecar/src/rf2o_laser_odometry/src/CLaserOdometry2D.cpp -o CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.s CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o.requires: .PHONY : CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o.requires CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o.provides: CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o.requires $(MAKE) -f CMakeFiles/rf2o_laser_odometry_node.dir/build.make CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o.provides.build .PHONY : CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o.provides CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o.provides.build: CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o # Object files for target rf2o_laser_odometry_node rf2o_laser_odometry_node_OBJECTS = \ "CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o" # External object files for target rf2o_laser_odometry_node rf2o_laser_odometry_node_EXTERNAL_OBJECTS = devel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o devel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: CMakeFiles/rf2o_laser_odometry_node.dir/build.make devel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /opt/ros/kinetic/lib/libtf.so devel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /opt/ros/kinetic/lib/libtf2_ros.so devel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /opt/ros/kinetic/lib/libactionlib.so devel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /opt/ros/kinetic/lib/libmessage_filters.so devel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /opt/ros/kinetic/lib/libroscpp.so devel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /usr/lib/x86_64-linux-gnu/libboost_filesystem.so devel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /usr/lib/x86_64-linux-gnu/libboost_signals.so devel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /opt/ros/kinetic/lib/libxmlrpcpp.so devel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /opt/ros/kinetic/lib/libtf2.so devel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /opt/ros/kinetic/lib/libroscpp_serialization.so devel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /opt/ros/kinetic/lib/librosconsole.so devel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /opt/ros/kinetic/lib/librosconsole_log4cxx.so devel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /opt/ros/kinetic/lib/librosconsole_backend_interface.so devel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /usr/lib/x86_64-linux-gnu/liblog4cxx.so devel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /usr/lib/x86_64-linux-gnu/libboost_regex.so devel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /opt/ros/kinetic/lib/librostime.so devel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /opt/ros/kinetic/lib/libcpp_common.so devel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /usr/lib/x86_64-linux-gnu/libboost_system.so devel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /usr/lib/x86_64-linux-gnu/libboost_thread.so devel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /usr/lib/x86_64-linux-gnu/libboost_chrono.so devel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /usr/lib/x86_64-linux-gnu/libboost_date_time.so devel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /usr/lib/x86_64-linux-gnu/libboost_atomic.so devel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /usr/lib/x86_64-linux-gnu/libpthread.so devel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /usr/lib/x86_64-linux-gnu/libconsole_bridge.so devel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /usr/lib/x86_64-linux-gnu/libboost_system.so devel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /usr/lib/x86_64-linux-gnu/libboost_thread.so devel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /usr/lib/x86_64-linux-gnu/libboost_chrono.so devel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /usr/lib/x86_64-linux-gnu/libboost_date_time.so devel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /usr/lib/x86_64-linux-gnu/libboost_atomic.so devel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /usr/lib/x86_64-linux-gnu/libpthread.so devel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /usr/lib/x86_64-linux-gnu/libconsole_bridge.so devel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: CMakeFiles/rf2o_laser_odometry_node.dir/link.txt @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --bold --progress-dir=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles --progress-num=$(CMAKE_PROGRESS_2) "Linking CXX executable devel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node" $(CMAKE_COMMAND) -E cmake_link_script CMakeFiles/rf2o_laser_odometry_node.dir/link.txt --verbose=$(VERBOSE) # Rule to build all files generated by this target. CMakeFiles/rf2o_laser_odometry_node.dir/build: devel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node .PHONY : CMakeFiles/rf2o_laser_odometry_node.dir/build CMakeFiles/rf2o_laser_odometry_node.dir/requires: CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o.requires .PHONY : CMakeFiles/rf2o_laser_odometry_node.dir/requires CMakeFiles/rf2o_laser_odometry_node.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/rf2o_laser_odometry_node.dir/cmake_clean.cmake .PHONY : CMakeFiles/rf2o_laser_odometry_node.dir/clean CMakeFiles/rf2o_laser_odometry_node.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rf2o_laser_odometry_node.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/rf2o_laser_odometry_node.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rf2o_laser_odometry_node.dir/cmake_clean.cmake ================================================ file(REMOVE_RECURSE "CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o" "devel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node.pdb" "devel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node" ) # Per-language clean rules from dependency scanning. foreach(lang CXX) include(CMakeFiles/rf2o_laser_odometry_node.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rf2o_laser_odometry_node.dir/depend.internal ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o ../include/rf2o_laser_odometry/CLaserOdometry2D.h /home/zn/racecar/src/rf2o_laser_odometry/src/CLaserOdometry2D.cpp /opt/ros/kinetic/include/boost_161_condition_variable.h /opt/ros/kinetic/include/boost_161_pthread_condition_variable.h /opt/ros/kinetic/include/boost_161_pthread_condition_variable_fwd.h /opt/ros/kinetic/include/geometry_msgs/Point.h /opt/ros/kinetic/include/geometry_msgs/Point32.h /opt/ros/kinetic/include/geometry_msgs/PointStamped.h /opt/ros/kinetic/include/geometry_msgs/Pose.h /opt/ros/kinetic/include/geometry_msgs/PoseStamped.h /opt/ros/kinetic/include/geometry_msgs/PoseWithCovariance.h /opt/ros/kinetic/include/geometry_msgs/Quaternion.h /opt/ros/kinetic/include/geometry_msgs/QuaternionStamped.h /opt/ros/kinetic/include/geometry_msgs/Transform.h /opt/ros/kinetic/include/geometry_msgs/TransformStamped.h /opt/ros/kinetic/include/geometry_msgs/Twist.h /opt/ros/kinetic/include/geometry_msgs/TwistStamped.h /opt/ros/kinetic/include/geometry_msgs/TwistWithCovariance.h /opt/ros/kinetic/include/geometry_msgs/Vector3.h /opt/ros/kinetic/include/geometry_msgs/Vector3Stamped.h /opt/ros/kinetic/include/nav_msgs/Odometry.h /opt/ros/kinetic/include/ros/advertise_options.h /opt/ros/kinetic/include/ros/advertise_service_options.h /opt/ros/kinetic/include/ros/assert.h /opt/ros/kinetic/include/ros/builtin_message_traits.h /opt/ros/kinetic/include/ros/callback_queue.h /opt/ros/kinetic/include/ros/callback_queue_interface.h /opt/ros/kinetic/include/ros/common.h /opt/ros/kinetic/include/ros/console.h /opt/ros/kinetic/include/ros/console_backend.h /opt/ros/kinetic/include/ros/datatypes.h /opt/ros/kinetic/include/ros/duration.h /opt/ros/kinetic/include/ros/exception.h /opt/ros/kinetic/include/ros/exceptions.h /opt/ros/kinetic/include/ros/forwards.h /opt/ros/kinetic/include/ros/init.h /opt/ros/kinetic/include/ros/macros.h /opt/ros/kinetic/include/ros/master.h /opt/ros/kinetic/include/ros/message.h /opt/ros/kinetic/include/ros/message_event.h /opt/ros/kinetic/include/ros/message_forward.h /opt/ros/kinetic/include/ros/message_operations.h /opt/ros/kinetic/include/ros/message_traits.h /opt/ros/kinetic/include/ros/names.h /opt/ros/kinetic/include/ros/node_handle.h /opt/ros/kinetic/include/ros/param.h /opt/ros/kinetic/include/ros/parameter_adapter.h /opt/ros/kinetic/include/ros/platform.h /opt/ros/kinetic/include/ros/publisher.h /opt/ros/kinetic/include/ros/rate.h /opt/ros/kinetic/include/ros/ros.h /opt/ros/kinetic/include/ros/roscpp_serialization_macros.h /opt/ros/kinetic/include/ros/rostime_decl.h /opt/ros/kinetic/include/ros/serialization.h /opt/ros/kinetic/include/ros/serialized_message.h /opt/ros/kinetic/include/ros/service.h /opt/ros/kinetic/include/ros/service_callback_helper.h /opt/ros/kinetic/include/ros/service_client.h /opt/ros/kinetic/include/ros/service_client_options.h /opt/ros/kinetic/include/ros/service_server.h /opt/ros/kinetic/include/ros/service_traits.h /opt/ros/kinetic/include/ros/single_subscriber_publisher.h /opt/ros/kinetic/include/ros/spinner.h /opt/ros/kinetic/include/ros/static_assert.h /opt/ros/kinetic/include/ros/steady_timer.h /opt/ros/kinetic/include/ros/steady_timer_options.h /opt/ros/kinetic/include/ros/subscribe_options.h /opt/ros/kinetic/include/ros/subscriber.h /opt/ros/kinetic/include/ros/subscription_callback_helper.h /opt/ros/kinetic/include/ros/this_node.h /opt/ros/kinetic/include/ros/time.h /opt/ros/kinetic/include/ros/timer.h /opt/ros/kinetic/include/ros/timer_options.h /opt/ros/kinetic/include/ros/topic.h /opt/ros/kinetic/include/ros/transport_hints.h /opt/ros/kinetic/include/ros/types.h /opt/ros/kinetic/include/ros/wall_timer.h /opt/ros/kinetic/include/ros/wall_timer_options.h /opt/ros/kinetic/include/rosconsole/macros_generated.h /opt/ros/kinetic/include/sensor_msgs/ChannelFloat32.h /opt/ros/kinetic/include/sensor_msgs/LaserScan.h /opt/ros/kinetic/include/sensor_msgs/PointCloud.h /opt/ros/kinetic/include/std_msgs/Empty.h /opt/ros/kinetic/include/std_msgs/Header.h /opt/ros/kinetic/include/tf/FrameGraph.h /opt/ros/kinetic/include/tf/FrameGraphRequest.h /opt/ros/kinetic/include/tf/FrameGraphResponse.h /opt/ros/kinetic/include/tf/LinearMath/Matrix3x3.h /opt/ros/kinetic/include/tf/LinearMath/MinMax.h /opt/ros/kinetic/include/tf/LinearMath/QuadWord.h /opt/ros/kinetic/include/tf/LinearMath/Quaternion.h /opt/ros/kinetic/include/tf/LinearMath/Scalar.h /opt/ros/kinetic/include/tf/LinearMath/Transform.h /opt/ros/kinetic/include/tf/LinearMath/Vector3.h /opt/ros/kinetic/include/tf/exceptions.h /opt/ros/kinetic/include/tf/tf.h /opt/ros/kinetic/include/tf/tfMessage.h /opt/ros/kinetic/include/tf/time_cache.h /opt/ros/kinetic/include/tf/transform_broadcaster.h /opt/ros/kinetic/include/tf/transform_datatypes.h /opt/ros/kinetic/include/tf/transform_listener.h /opt/ros/kinetic/include/tf2/LinearMath/Quaternion.h /opt/ros/kinetic/include/tf2/LinearMath/Vector3.h /opt/ros/kinetic/include/tf2/buffer_core.h /opt/ros/kinetic/include/tf2/convert.h /opt/ros/kinetic/include/tf2/exceptions.h /opt/ros/kinetic/include/tf2/impl/convert.h /opt/ros/kinetic/include/tf2/transform_datatypes.h /opt/ros/kinetic/include/tf2/transform_storage.h /opt/ros/kinetic/include/tf2_msgs/FrameGraph.h /opt/ros/kinetic/include/tf2_msgs/FrameGraphRequest.h /opt/ros/kinetic/include/tf2_msgs/FrameGraphResponse.h /opt/ros/kinetic/include/tf2_msgs/TFMessage.h /opt/ros/kinetic/include/tf2_ros/buffer.h /opt/ros/kinetic/include/tf2_ros/buffer_interface.h /opt/ros/kinetic/include/tf2_ros/transform_broadcaster.h /opt/ros/kinetic/include/tf2_ros/transform_listener.h /opt/ros/kinetic/include/xmlrpcpp/XmlRpcDecl.h /opt/ros/kinetic/include/xmlrpcpp/XmlRpcValue.h /usr/include/eigen3/Eigen/Cholesky /usr/include/eigen3/Eigen/Core /usr/include/eigen3/Eigen/Dense /usr/include/eigen3/Eigen/Eigenvalues /usr/include/eigen3/Eigen/Geometry /usr/include/eigen3/Eigen/Householder /usr/include/eigen3/Eigen/Jacobi /usr/include/eigen3/Eigen/LU /usr/include/eigen3/Eigen/QR /usr/include/eigen3/Eigen/SVD /usr/include/eigen3/Eigen/StdDeque /usr/include/eigen3/Eigen/StdVector /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h /usr/include/eigen3/Eigen/src/Cholesky/LLT.h /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h /usr/include/eigen3/Eigen/src/Core/Array.h /usr/include/eigen3/Eigen/src/Core/ArrayBase.h /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h /usr/include/eigen3/Eigen/src/Core/Assign.h /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h /usr/include/eigen3/Eigen/src/Core/BandMatrix.h /usr/include/eigen3/Eigen/src/Core/Block.h /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h /usr/include/eigen3/Eigen/src/Core/CoreEvaluators.h /usr/include/eigen3/Eigen/src/Core/CoreIterators.h /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h /usr/include/eigen3/Eigen/src/Core/DenseBase.h /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h /usr/include/eigen3/Eigen/src/Core/DenseStorage.h /usr/include/eigen3/Eigen/src/Core/Diagonal.h /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h /usr/include/eigen3/Eigen/src/Core/Dot.h /usr/include/eigen3/Eigen/src/Core/EigenBase.h /usr/include/eigen3/Eigen/src/Core/Fuzzy.h /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h /usr/include/eigen3/Eigen/src/Core/IO.h /usr/include/eigen3/Eigen/src/Core/Inverse.h /usr/include/eigen3/Eigen/src/Core/Map.h /usr/include/eigen3/Eigen/src/Core/MapBase.h /usr/include/eigen3/Eigen/src/Core/MathFunctions.h /usr/include/eigen3/Eigen/src/Core/Matrix.h /usr/include/eigen3/Eigen/src/Core/MatrixBase.h /usr/include/eigen3/Eigen/src/Core/NestByValue.h /usr/include/eigen3/Eigen/src/Core/NoAlias.h /usr/include/eigen3/Eigen/src/Core/NumTraits.h /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h /usr/include/eigen3/Eigen/src/Core/Product.h /usr/include/eigen3/Eigen/src/Core/ProductEvaluators.h /usr/include/eigen3/Eigen/src/Core/Random.h /usr/include/eigen3/Eigen/src/Core/Redux.h /usr/include/eigen3/Eigen/src/Core/Ref.h /usr/include/eigen3/Eigen/src/Core/Replicate.h /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h /usr/include/eigen3/Eigen/src/Core/Reverse.h /usr/include/eigen3/Eigen/src/Core/Select.h /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h /usr/include/eigen3/Eigen/src/Core/Solve.h /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h /usr/include/eigen3/Eigen/src/Core/SolverBase.h /usr/include/eigen3/Eigen/src/Core/SpecialFunctions.h /usr/include/eigen3/Eigen/src/Core/StableNorm.h /usr/include/eigen3/Eigen/src/Core/Stride.h /usr/include/eigen3/Eigen/src/Core/Swap.h /usr/include/eigen3/Eigen/src/Core/Transpose.h /usr/include/eigen3/Eigen/src/Core/Transpositions.h /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h /usr/include/eigen3/Eigen/src/Core/VectorBlock.h /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h /usr/include/eigen3/Eigen/src/Core/Visitor.h /usr/include/eigen3/Eigen/src/Core/arch/AVX/Complex.h /usr/include/eigen3/Eigen/src/Core/arch/AVX/MathFunctions.h /usr/include/eigen3/Eigen/src/Core/arch/AVX/PacketMath.h /usr/include/eigen3/Eigen/src/Core/arch/AVX/TypeCasting.h /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/MathFunctions.h /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h /usr/include/eigen3/Eigen/src/Core/arch/CUDA/MathFunctions.h /usr/include/eigen3/Eigen/src/Core/arch/CUDA/PacketMath.h /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h /usr/include/eigen3/Eigen/src/Core/arch/NEON/MathFunctions.h /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h /usr/include/eigen3/Eigen/src/Core/arch/SSE/TypeCasting.h /usr/include/eigen3/Eigen/src/Core/functors/AssignmentFunctors.h /usr/include/eigen3/Eigen/src/Core/functors/BinaryFunctors.h /usr/include/eigen3/Eigen/src/Core/functors/NullaryFunctors.h /usr/include/eigen3/Eigen/src/Core/functors/StlFunctors.h /usr/include/eigen3/Eigen/src/Core/functors/UnaryFunctors.h /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h /usr/include/eigen3/Eigen/src/Core/util/Constants.h /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h /usr/include/eigen3/Eigen/src/Core/util/Macros.h /usr/include/eigen3/Eigen/src/Core/util/Memory.h /usr/include/eigen3/Eigen/src/Core/util/Meta.h /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h /usr/include/eigen3/Eigen/src/Geometry/Scaling.h /usr/include/eigen3/Eigen/src/Geometry/Transform.h /usr/include/eigen3/Eigen/src/Geometry/Translation.h /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h /usr/include/eigen3/Eigen/src/Householder/Householder.h /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h /usr/include/eigen3/Eigen/src/LU/Determinant.h /usr/include/eigen3/Eigen/src/LU/FullPivLU.h /usr/include/eigen3/Eigen/src/LU/InverseImpl.h /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h /usr/include/eigen3/Eigen/src/SVD/BDCSVD.h /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h /usr/include/eigen3/Eigen/src/SVD/SVDBase.h /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h /usr/include/eigen3/Eigen/src/StlSupport/StdDeque.h /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h /usr/include/eigen3/Eigen/src/StlSupport/details.h /usr/include/eigen3/Eigen/src/misc/Image.h /usr/include/eigen3/Eigen/src/misc/Kernel.h /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h /usr/include/eigen3/unsupported/Eigen/MatrixFunctions /usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/MatrixExponential.h /usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/MatrixFunction.h /usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/MatrixLogarithm.h /usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/MatrixPower.h /usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/MatrixSquareRoot.h /usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/StemFunction.h /usr/include/mrpt/base/include/mrpt/base/link_pragmas.h /usr/include/mrpt/base/include/mrpt/bayes/CParticleFilter.h /usr/include/mrpt/base/include/mrpt/bayes/CParticleFilterCapable.h /usr/include/mrpt/base/include/mrpt/bayes/CParticleFilterData.h /usr/include/mrpt/base/include/mrpt/bayes/CProbabilityParticle.h /usr/include/mrpt/base/include/mrpt/math/CArray.h /usr/include/mrpt/base/include/mrpt/math/CArrayNumeric.h /usr/include/mrpt/base/include/mrpt/math/CHistogram.h /usr/include/mrpt/base/include/mrpt/math/CMatrix.h /usr/include/mrpt/base/include/mrpt/math/CMatrixD.h /usr/include/mrpt/base/include/mrpt/math/CMatrixFixedNumeric.h /usr/include/mrpt/base/include/mrpt/math/CMatrixTemplate.h /usr/include/mrpt/base/include/mrpt/math/CMatrixTemplateNumeric.h /usr/include/mrpt/base/include/mrpt/math/CPolygon.h /usr/include/mrpt/base/include/mrpt/math/CQuaternion.h /usr/include/mrpt/base/include/mrpt/math/CSparseMatrixTemplate.h /usr/include/mrpt/base/include/mrpt/math/eigen_frwds.h /usr/include/mrpt/base/include/mrpt/math/geometry.h /usr/include/mrpt/base/include/mrpt/math/homog_matrices.h /usr/include/mrpt/base/include/mrpt/math/lightweight_geom_data.h /usr/include/mrpt/base/include/mrpt/math/math_frwds.h /usr/include/mrpt/base/include/mrpt/math/matrix_serialization.h /usr/include/mrpt/base/include/mrpt/math/point_poses2vectors.h /usr/include/mrpt/base/include/mrpt/math/wrap2pi.h /usr/include/mrpt/base/include/mrpt/otherlibs/stlplus/containers_fixes.hpp /usr/include/mrpt/base/include/mrpt/otherlibs/stlplus/exceptions.hpp /usr/include/mrpt/base/include/mrpt/otherlibs/stlplus/smart_ptr.hpp /usr/include/mrpt/base/include/mrpt/otherlibs/stlplus/smart_ptr.tpp /usr/include/mrpt/base/include/mrpt/poses.h /usr/include/mrpt/base/include/mrpt/poses/CPoint.h /usr/include/mrpt/base/include/mrpt/poses/CPoint2D.h /usr/include/mrpt/base/include/mrpt/poses/CPoint2DPDF.h /usr/include/mrpt/base/include/mrpt/poses/CPoint2DPDFGaussian.h /usr/include/mrpt/base/include/mrpt/poses/CPoint3D.h /usr/include/mrpt/base/include/mrpt/poses/CPointPDF.h /usr/include/mrpt/base/include/mrpt/poses/CPointPDFGaussian.h /usr/include/mrpt/base/include/mrpt/poses/CPointPDFParticles.h /usr/include/mrpt/base/include/mrpt/poses/CPointPDFSOG.h /usr/include/mrpt/base/include/mrpt/poses/CPose.h /usr/include/mrpt/base/include/mrpt/poses/CPose2D.h /usr/include/mrpt/base/include/mrpt/poses/CPose2DGridTemplate.h /usr/include/mrpt/base/include/mrpt/poses/CPose3D.h /usr/include/mrpt/base/include/mrpt/poses/CPose3DInterpolator.h /usr/include/mrpt/base/include/mrpt/poses/CPose3DPDF.h /usr/include/mrpt/base/include/mrpt/poses/CPose3DPDFGaussian.h /usr/include/mrpt/base/include/mrpt/poses/CPose3DPDFGaussianInf.h /usr/include/mrpt/base/include/mrpt/poses/CPose3DPDFParticles.h /usr/include/mrpt/base/include/mrpt/poses/CPose3DPDFSOG.h /usr/include/mrpt/base/include/mrpt/poses/CPose3DQuat.h /usr/include/mrpt/base/include/mrpt/poses/CPose3DQuatPDF.h /usr/include/mrpt/base/include/mrpt/poses/CPose3DQuatPDFGaussian.h /usr/include/mrpt/base/include/mrpt/poses/CPose3DQuatPDFGaussianInf.h /usr/include/mrpt/base/include/mrpt/poses/CPose3DRotVec.h /usr/include/mrpt/base/include/mrpt/poses/CPoseOrPoint.h /usr/include/mrpt/base/include/mrpt/poses/CPoseOrPoint_detail.h /usr/include/mrpt/base/include/mrpt/poses/CPosePDF.h /usr/include/mrpt/base/include/mrpt/poses/CPosePDFGaussian.h /usr/include/mrpt/base/include/mrpt/poses/CPosePDFGaussianInf.h /usr/include/mrpt/base/include/mrpt/poses/CPosePDFGrid.h /usr/include/mrpt/base/include/mrpt/poses/CPosePDFParticles.h /usr/include/mrpt/base/include/mrpt/poses/CPosePDFSOG.h /usr/include/mrpt/base/include/mrpt/poses/CPoseRandomSampler.h /usr/include/mrpt/base/include/mrpt/poses/CPoses2DSequence.h /usr/include/mrpt/base/include/mrpt/poses/CPoses3DSequence.h /usr/include/mrpt/base/include/mrpt/poses/CRobot2DPoseEstimator.h /usr/include/mrpt/base/include/mrpt/poses/SE_traits.h /usr/include/mrpt/base/include/mrpt/poses/poses_frwds.h /usr/include/mrpt/base/include/mrpt/synch/CCriticalSection.h /usr/include/mrpt/base/include/mrpt/synch/atomic_incr.h /usr/include/mrpt/base/include/mrpt/system/datetime.h /usr/include/mrpt/base/include/mrpt/system/memory.h /usr/include/mrpt/base/include/mrpt/system/os.h /usr/include/mrpt/base/include/mrpt/system/string_utils.h /usr/include/mrpt/base/include/mrpt/system/threads.h /usr/include/mrpt/base/include/mrpt/utils.h /usr/include/mrpt/base/include/mrpt/utils/CCanvas.h /usr/include/mrpt/base/include/mrpt/utils/CClientTCPSocket.h /usr/include/mrpt/base/include/mrpt/utils/CConfigFile.h /usr/include/mrpt/base/include/mrpt/utils/CConfigFileBase.h /usr/include/mrpt/base/include/mrpt/utils/CConfigFileMemory.h /usr/include/mrpt/base/include/mrpt/utils/CConsoleRedirector.h /usr/include/mrpt/base/include/mrpt/utils/CDebugOutputCapable.h /usr/include/mrpt/base/include/mrpt/utils/CDynamicGrid.h /usr/include/mrpt/base/include/mrpt/utils/CEnhancedMetaFile.h /usr/include/mrpt/base/include/mrpt/utils/CFileGZInputStream.h /usr/include/mrpt/base/include/mrpt/utils/CFileGZOutputStream.h /usr/include/mrpt/base/include/mrpt/utils/CFileInputStream.h /usr/include/mrpt/base/include/mrpt/utils/CFileOutputStream.h /usr/include/mrpt/base/include/mrpt/utils/CFileStream.h /usr/include/mrpt/base/include/mrpt/utils/CImage.h /usr/include/mrpt/base/include/mrpt/utils/CListOfClasses.h /usr/include/mrpt/base/include/mrpt/utils/CLoadableOptions.h /usr/include/mrpt/base/include/mrpt/utils/CLog.h /usr/include/mrpt/base/include/mrpt/utils/CMHPropertiesValuesList.h /usr/include/mrpt/base/include/mrpt/utils/CMappedImage.h /usr/include/mrpt/base/include/mrpt/utils/CMemoryChunk.h /usr/include/mrpt/base/include/mrpt/utils/CMemoryStream.h /usr/include/mrpt/base/include/mrpt/utils/CMessage.h /usr/include/mrpt/base/include/mrpt/utils/CMessageQueue.h /usr/include/mrpt/base/include/mrpt/utils/CObject.h /usr/include/mrpt/base/include/mrpt/utils/CObservable.h /usr/include/mrpt/base/include/mrpt/utils/CObserver.h /usr/include/mrpt/base/include/mrpt/utils/CProbabilityDensityFunction.h /usr/include/mrpt/base/include/mrpt/utils/CPropertiesValuesList.h /usr/include/mrpt/base/include/mrpt/utils/CReferencedMemBlock.h /usr/include/mrpt/base/include/mrpt/utils/CRobotSimulator.h /usr/include/mrpt/base/include/mrpt/utils/CSerializable.h /usr/include/mrpt/base/include/mrpt/utils/CServerTCPSocket.h /usr/include/mrpt/base/include/mrpt/utils/CSimpleDatabase.h /usr/include/mrpt/base/include/mrpt/utils/CStartUpClassesRegister.h /usr/include/mrpt/base/include/mrpt/utils/CStdOutStream.h /usr/include/mrpt/base/include/mrpt/utils/CStream.h /usr/include/mrpt/base/include/mrpt/utils/CStringList.h /usr/include/mrpt/base/include/mrpt/utils/CTextFileLinesParser.h /usr/include/mrpt/base/include/mrpt/utils/CThreadSafeQueue.h /usr/include/mrpt/base/include/mrpt/utils/CTicTac.h /usr/include/mrpt/base/include/mrpt/utils/CTimeLogger.h /usr/include/mrpt/base/include/mrpt/utils/CTypeSelector.h /usr/include/mrpt/base/include/mrpt/utils/CUncopiable.h /usr/include/mrpt/base/include/mrpt/utils/PLY_import_export.h /usr/include/mrpt/base/include/mrpt/utils/SSE_types.h /usr/include/mrpt/base/include/mrpt/utils/TCamera.h /usr/include/mrpt/base/include/mrpt/utils/TColor.h /usr/include/mrpt/base/include/mrpt/utils/TEnumType.h /usr/include/mrpt/base/include/mrpt/utils/TMatchingPair.h /usr/include/mrpt/base/include/mrpt/utils/TParameters.h /usr/include/mrpt/base/include/mrpt/utils/TPixelCoord.h /usr/include/mrpt/base/include/mrpt/utils/TStereoCamera.h /usr/include/mrpt/base/include/mrpt/utils/TTypeName.h /usr/include/mrpt/base/include/mrpt/utils/TTypeName_impl.h /usr/include/mrpt/base/include/mrpt/utils/adapters.h /usr/include/mrpt/base/include/mrpt/utils/aligned_containers.h /usr/include/mrpt/base/include/mrpt/utils/bimap.h /usr/include/mrpt/base/include/mrpt/utils/bits.h /usr/include/mrpt/base/include/mrpt/utils/boost_join.h /usr/include/mrpt/base/include/mrpt/utils/ci_less.h /usr/include/mrpt/base/include/mrpt/utils/circular_buffer.h /usr/include/mrpt/base/include/mrpt/utils/color_maps.h /usr/include/mrpt/base/include/mrpt/utils/compiler_fixes.h /usr/include/mrpt/base/include/mrpt/utils/core_defs.h /usr/include/mrpt/base/include/mrpt/utils/crc.h /usr/include/mrpt/base/include/mrpt/utils/exceptions.h /usr/include/mrpt/base/include/mrpt/utils/list_searchable.h /usr/include/mrpt/base/include/mrpt/utils/map_as_vector.h /usr/include/mrpt/base/include/mrpt/utils/md5.h /usr/include/mrpt/base/include/mrpt/utils/metaprogramming_serialization.h /usr/include/mrpt/base/include/mrpt/utils/mrptEvent.h /usr/include/mrpt/base/include/mrpt/utils/mrpt_macros.h /usr/include/mrpt/base/include/mrpt/utils/mrpt_stdint.h /usr/include/mrpt/base/include/mrpt/utils/net_utils.h /usr/include/mrpt/base/include/mrpt/utils/printf_vector.h /usr/include/mrpt/base/include/mrpt/utils/pstdint.h /usr/include/mrpt/base/include/mrpt/utils/round.h /usr/include/mrpt/base/include/mrpt/utils/safe_pointers.h /usr/include/mrpt/base/include/mrpt/utils/stl_containers_utils.h /usr/include/mrpt/base/include/mrpt/utils/stl_extensions.h /usr/include/mrpt/base/include/mrpt/utils/stl_serialization.h /usr/include/mrpt/base/include/mrpt/utils/traits_map.h /usr/include/mrpt/base/include/mrpt/utils/types_math.h /usr/include/mrpt/base/include/mrpt/utils/types_simple.h /usr/include/mrpt/base/include/mrpt/utils/utils_defs.h /usr/include/mrpt/mrpt-config/mrpt/config.h /usr/include/mrpt/mrpt-config/mrpt/version.h /usr/include/mrpt/obs/include/mrpt/maps/CMetricMap.h /usr/include/mrpt/obs/include/mrpt/maps/CMetricMapEvents.h /usr/include/mrpt/obs/include/mrpt/maps/TMetricMapInitializer.h /usr/include/mrpt/obs/include/mrpt/maps/TMetricMapTypesRegistry.h /usr/include/mrpt/obs/include/mrpt/maps/metric_map_types.h /usr/include/mrpt/obs/include/mrpt/obs/CObservation.h /usr/include/mrpt/obs/include/mrpt/obs/CObservation2DRangeScan.h /usr/include/mrpt/obs/include/mrpt/obs/CObservationOdometry.h /usr/include/mrpt/obs/include/mrpt/obs/link_pragmas.h /usr/include/mrpt/obs/include/mrpt/obs/obs_frwds.h /usr/include/mrpt/obs/include/mrpt/slam/CObservation2DRangeScan.h /usr/include/mrpt/obs/include/mrpt/slam/CObservationOdometry.h /usr/include/mrpt/opengl/include/mrpt/opengl.h /usr/include/mrpt/opengl/include/mrpt/opengl/C3DSScene.h /usr/include/mrpt/opengl/include/mrpt/opengl/CArrow.h /usr/include/mrpt/opengl/include/mrpt/opengl/CAssimpModel.h /usr/include/mrpt/opengl/include/mrpt/opengl/CAxis.h /usr/include/mrpt/opengl/include/mrpt/opengl/CBox.h /usr/include/mrpt/opengl/include/mrpt/opengl/CCamera.h /usr/include/mrpt/opengl/include/mrpt/opengl/CCylinder.h /usr/include/mrpt/opengl/include/mrpt/opengl/CDisk.h /usr/include/mrpt/opengl/include/mrpt/opengl/CEllipsoid.h /usr/include/mrpt/opengl/include/mrpt/opengl/CEllipsoidInverseDepth2D.h /usr/include/mrpt/opengl/include/mrpt/opengl/CEllipsoidInverseDepth3D.h /usr/include/mrpt/opengl/include/mrpt/opengl/CEllipsoidRangeBearing2D.h /usr/include/mrpt/opengl/include/mrpt/opengl/CFBORender.h /usr/include/mrpt/opengl/include/mrpt/opengl/CFrustum.h /usr/include/mrpt/opengl/include/mrpt/opengl/CGeneralizedCylinder.h /usr/include/mrpt/opengl/include/mrpt/opengl/CGeneralizedEllipsoidTemplate.h /usr/include/mrpt/opengl/include/mrpt/opengl/CGridPlaneXY.h /usr/include/mrpt/opengl/include/mrpt/opengl/CGridPlaneXZ.h /usr/include/mrpt/opengl/include/mrpt/opengl/CLight.h /usr/include/mrpt/opengl/include/mrpt/opengl/CMesh.h /usr/include/mrpt/opengl/include/mrpt/opengl/CMeshFast.h /usr/include/mrpt/opengl/include/mrpt/opengl/COctoMapVoxels.h /usr/include/mrpt/opengl/include/mrpt/opengl/COctreePointRenderer.h /usr/include/mrpt/opengl/include/mrpt/opengl/COpenGLScene.h /usr/include/mrpt/opengl/include/mrpt/opengl/COpenGLStandardObject.h /usr/include/mrpt/opengl/include/mrpt/opengl/COpenGLViewport.h /usr/include/mrpt/opengl/include/mrpt/opengl/CPointCloud.h /usr/include/mrpt/opengl/include/mrpt/opengl/CPointCloudColoured.h /usr/include/mrpt/opengl/include/mrpt/opengl/CPolyhedron.h /usr/include/mrpt/opengl/include/mrpt/opengl/CRenderizable.h /usr/include/mrpt/opengl/include/mrpt/opengl/CRenderizableDisplayList.h /usr/include/mrpt/opengl/include/mrpt/opengl/CSetOfLines.h /usr/include/mrpt/opengl/include/mrpt/opengl/CSetOfObjects.h /usr/include/mrpt/opengl/include/mrpt/opengl/CSetOfTexturedTriangles.h /usr/include/mrpt/opengl/include/mrpt/opengl/CSetOfTriangles.h /usr/include/mrpt/opengl/include/mrpt/opengl/CSimpleLine.h /usr/include/mrpt/opengl/include/mrpt/opengl/CSphere.h /usr/include/mrpt/opengl/include/mrpt/opengl/CText.h /usr/include/mrpt/opengl/include/mrpt/opengl/CText3D.h /usr/include/mrpt/opengl/include/mrpt/opengl/CTextMessageCapable.h /usr/include/mrpt/opengl/include/mrpt/opengl/CTexturedObject.h /usr/include/mrpt/opengl/include/mrpt/opengl/CTexturedPlane.h /usr/include/mrpt/opengl/include/mrpt/opengl/CVectorField2D.h /usr/include/mrpt/opengl/include/mrpt/opengl/CVectorField3D.h /usr/include/mrpt/opengl/include/mrpt/opengl/gl_utils.h /usr/include/mrpt/opengl/include/mrpt/opengl/graph_tools.h /usr/include/mrpt/opengl/include/mrpt/opengl/graph_tools_impl.h /usr/include/mrpt/opengl/include/mrpt/opengl/link_pragmas.h /usr/include/mrpt/opengl/include/mrpt/opengl/opengl_fonts.h /usr/include/mrpt/opengl/include/mrpt/opengl/opengl_frwds.h /usr/include/mrpt/opengl/include/mrpt/opengl/pose_pdfs.h /usr/include/mrpt/opengl/include/mrpt/opengl/stock_objects.h ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rf2o_laser_odometry_node.dir/depend.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: ../include/rf2o_laser_odometry/CLaserOdometry2D.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: ../src/CLaserOdometry2D.cpp CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/boost_161_condition_variable.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/boost_161_pthread_condition_variable.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/boost_161_pthread_condition_variable_fwd.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/geometry_msgs/Point.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/geometry_msgs/Point32.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/geometry_msgs/PointStamped.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/geometry_msgs/Pose.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/geometry_msgs/PoseStamped.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/geometry_msgs/PoseWithCovariance.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/geometry_msgs/Quaternion.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/geometry_msgs/QuaternionStamped.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/geometry_msgs/Transform.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/geometry_msgs/TransformStamped.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/geometry_msgs/Twist.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/geometry_msgs/TwistStamped.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/geometry_msgs/TwistWithCovariance.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/geometry_msgs/Vector3.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/geometry_msgs/Vector3Stamped.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/nav_msgs/Odometry.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/advertise_options.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/advertise_service_options.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/assert.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/builtin_message_traits.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/callback_queue.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/callback_queue_interface.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/common.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/console.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/console_backend.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/datatypes.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/duration.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/exception.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/exceptions.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/forwards.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/init.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/macros.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/master.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/message.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/message_event.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/message_forward.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/message_operations.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/message_traits.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/names.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/node_handle.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/param.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/parameter_adapter.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/platform.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/publisher.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/rate.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/ros.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/roscpp_serialization_macros.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/rostime_decl.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/serialization.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/serialized_message.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/service.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/service_callback_helper.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/service_client.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/service_client_options.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/service_server.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/service_traits.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/single_subscriber_publisher.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/spinner.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/static_assert.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/steady_timer.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/steady_timer_options.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/subscribe_options.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/subscriber.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/subscription_callback_helper.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/this_node.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/time.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/timer.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/timer_options.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/topic.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/transport_hints.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/types.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/wall_timer.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/wall_timer_options.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/rosconsole/macros_generated.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/sensor_msgs/ChannelFloat32.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/sensor_msgs/LaserScan.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/sensor_msgs/PointCloud.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/std_msgs/Empty.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/std_msgs/Header.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf/FrameGraph.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf/FrameGraphRequest.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf/FrameGraphResponse.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf/LinearMath/Matrix3x3.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf/LinearMath/MinMax.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf/LinearMath/QuadWord.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf/LinearMath/Quaternion.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf/LinearMath/Scalar.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf/LinearMath/Transform.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf/LinearMath/Vector3.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf/exceptions.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf/tf.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf/tfMessage.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf/time_cache.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf/transform_broadcaster.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf/transform_datatypes.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf/transform_listener.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf2/LinearMath/Quaternion.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf2/LinearMath/Vector3.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf2/buffer_core.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf2/convert.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf2/exceptions.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf2/impl/convert.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf2/transform_datatypes.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf2/transform_storage.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf2_msgs/FrameGraph.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf2_msgs/FrameGraphRequest.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf2_msgs/FrameGraphResponse.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf2_msgs/TFMessage.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf2_ros/buffer.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf2_ros/buffer_interface.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf2_ros/transform_broadcaster.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf2_ros/transform_listener.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/xmlrpcpp/XmlRpcDecl.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/xmlrpcpp/XmlRpcValue.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/Cholesky CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/Core CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/Dense CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/Eigenvalues CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/Geometry CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/Householder CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/Jacobi CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/LU CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/QR CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/SVD CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/StdDeque CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/StdVector CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/Array.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayBase.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/BandMatrix.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/Block.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/CoreEvaluators.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/CoreIterators.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseBase.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseStorage.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/Diagonal.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/Dot.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/EigenBase.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/Fuzzy.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/IO.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/Inverse.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/Map.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/MapBase.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/MathFunctions.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/Matrix.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/MatrixBase.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/NestByValue.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/NoAlias.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/NumTraits.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/Product.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/ProductEvaluators.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/Random.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/Redux.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/Ref.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/Replicate.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/Reverse.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/Select.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/Solve.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/SolverBase.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/SpecialFunctions.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/StableNorm.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/Stride.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/Swap.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpose.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpositions.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorBlock.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/Visitor.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AVX/Complex.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AVX/MathFunctions.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AVX/PacketMath.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AVX/TypeCasting.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/MathFunctions.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/CUDA/MathFunctions.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/CUDA/PacketMath.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/MathFunctions.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/TypeCasting.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/functors/AssignmentFunctors.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/functors/BinaryFunctors.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/functors/NullaryFunctors.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/functors/StlFunctors.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/functors/UnaryFunctors.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Constants.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Macros.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Memory.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Meta.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Scaling.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Transform.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Translation.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Householder/Householder.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/LU/Determinant.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/LU/FullPivLU.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/LU/InverseImpl.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/SVD/BDCSVD.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/SVD/SVDBase.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/StdDeque.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/details.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/misc/Image.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/misc/Kernel.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/unsupported/Eigen/MatrixFunctions CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/MatrixExponential.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/MatrixFunction.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/MatrixLogarithm.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/MatrixPower.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/MatrixSquareRoot.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/StemFunction.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/base/link_pragmas.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/bayes/CParticleFilter.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/bayes/CParticleFilterCapable.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/bayes/CParticleFilterData.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/bayes/CProbabilityParticle.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/math/CArray.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/math/CArrayNumeric.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/math/CHistogram.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/math/CMatrix.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/math/CMatrixD.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/math/CMatrixFixedNumeric.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/math/CMatrixTemplate.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/math/CMatrixTemplateNumeric.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/math/CPolygon.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/math/CQuaternion.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/math/CSparseMatrixTemplate.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/math/eigen_frwds.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/math/geometry.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/math/homog_matrices.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/math/lightweight_geom_data.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/math/math_frwds.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/math/matrix_serialization.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/math/point_poses2vectors.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/math/wrap2pi.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/otherlibs/stlplus/containers_fixes.hpp CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/otherlibs/stlplus/exceptions.hpp CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/otherlibs/stlplus/smart_ptr.hpp CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/otherlibs/stlplus/smart_ptr.tpp CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPoint.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPoint2D.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPoint2DPDF.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPoint2DPDFGaussian.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPoint3D.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPointPDF.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPointPDFGaussian.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPointPDFParticles.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPointPDFSOG.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPose.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPose2D.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPose2DGridTemplate.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPose3D.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPose3DInterpolator.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPose3DPDF.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPose3DPDFGaussian.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPose3DPDFGaussianInf.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPose3DPDFParticles.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPose3DPDFSOG.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPose3DQuat.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPose3DQuatPDF.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPose3DQuatPDFGaussian.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPose3DQuatPDFGaussianInf.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPose3DRotVec.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPoseOrPoint.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPoseOrPoint_detail.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPosePDF.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPosePDFGaussian.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPosePDFGaussianInf.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPosePDFGrid.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPosePDFParticles.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPosePDFSOG.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPoseRandomSampler.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPoses2DSequence.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPoses3DSequence.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CRobot2DPoseEstimator.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/SE_traits.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/poses_frwds.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/synch/CCriticalSection.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/synch/atomic_incr.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/system/datetime.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/system/memory.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/system/os.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/system/string_utils.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/system/threads.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CCanvas.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CClientTCPSocket.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CConfigFile.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CConfigFileBase.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CConfigFileMemory.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CConsoleRedirector.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CDebugOutputCapable.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CDynamicGrid.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CEnhancedMetaFile.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CFileGZInputStream.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CFileGZOutputStream.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CFileInputStream.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CFileOutputStream.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CFileStream.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CImage.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CListOfClasses.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CLoadableOptions.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CLog.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CMHPropertiesValuesList.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CMappedImage.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CMemoryChunk.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CMemoryStream.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CMessage.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CMessageQueue.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CObject.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CObservable.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CObserver.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CProbabilityDensityFunction.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CPropertiesValuesList.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CReferencedMemBlock.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CRobotSimulator.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CSerializable.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CServerTCPSocket.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CSimpleDatabase.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CStartUpClassesRegister.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CStdOutStream.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CStream.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CStringList.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CTextFileLinesParser.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CThreadSafeQueue.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CTicTac.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CTimeLogger.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CTypeSelector.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CUncopiable.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/PLY_import_export.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/SSE_types.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/TCamera.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/TColor.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/TEnumType.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/TMatchingPair.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/TParameters.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/TPixelCoord.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/TStereoCamera.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/TTypeName.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/TTypeName_impl.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/adapters.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/aligned_containers.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/bimap.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/bits.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/boost_join.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/ci_less.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/circular_buffer.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/color_maps.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/compiler_fixes.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/core_defs.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/crc.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/exceptions.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/list_searchable.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/map_as_vector.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/md5.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/metaprogramming_serialization.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/mrptEvent.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/mrpt_macros.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/mrpt_stdint.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/net_utils.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/printf_vector.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/pstdint.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/round.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/safe_pointers.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/stl_containers_utils.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/stl_extensions.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/stl_serialization.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/traits_map.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/types_math.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/types_simple.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/utils_defs.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/mrpt-config/mrpt/config.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/mrpt-config/mrpt/version.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/obs/include/mrpt/maps/CMetricMap.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/obs/include/mrpt/maps/CMetricMapEvents.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/obs/include/mrpt/maps/TMetricMapInitializer.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/obs/include/mrpt/maps/TMetricMapTypesRegistry.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/obs/include/mrpt/maps/metric_map_types.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/obs/include/mrpt/obs/CObservation.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/obs/include/mrpt/obs/CObservation2DRangeScan.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/obs/include/mrpt/obs/CObservationOdometry.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/obs/include/mrpt/obs/link_pragmas.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/obs/include/mrpt/obs/obs_frwds.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/obs/include/mrpt/slam/CObservation2DRangeScan.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/obs/include/mrpt/slam/CObservationOdometry.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/C3DSScene.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CArrow.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CAssimpModel.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CAxis.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CBox.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CCamera.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CCylinder.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CDisk.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CEllipsoid.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CEllipsoidInverseDepth2D.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CEllipsoidInverseDepth3D.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CEllipsoidRangeBearing2D.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CFBORender.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CFrustum.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CGeneralizedCylinder.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CGeneralizedEllipsoidTemplate.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CGridPlaneXY.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CGridPlaneXZ.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CLight.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CMesh.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CMeshFast.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/COctoMapVoxels.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/COctreePointRenderer.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/COpenGLScene.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/COpenGLStandardObject.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/COpenGLViewport.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CPointCloud.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CPointCloudColoured.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CPolyhedron.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CRenderizable.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CRenderizableDisplayList.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CSetOfLines.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CSetOfObjects.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CSetOfTexturedTriangles.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CSetOfTriangles.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CSimpleLine.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CSphere.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CText.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CText3D.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CTextMessageCapable.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CTexturedObject.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CTexturedPlane.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CVectorField2D.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CVectorField3D.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/gl_utils.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/graph_tools.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/graph_tools_impl.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/link_pragmas.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/opengl_fonts.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/opengl_frwds.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/pose_pdfs.h CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/stock_objects.h ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rf2o_laser_odometry_node.dir/flags.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # compile CXX with /usr/bin/c++ CXX_FLAGS = -Wno-long-long -Wno-variadic-macros -Wno-long-long -Wno-variadic-macros -g -std=gnu++1z CXX_DEFINES = -DROSCONSOLE_BACKEND_LOG4CXX -DROS_PACKAGE_NAME=\"rf2o_laser_odometry\" CXX_INCLUDES = -I/usr/include/eigen3 -I/usr/include/mrpt/mrpt-config -I/usr/include/mrpt/bayes/include -I/usr/include/mrpt/graphs/include -I/usr/include/mrpt/vision/include -I/usr/include/mrpt/tfest/include -I/usr/include/mrpt/maps/include -I/usr/include/mrpt/obs/include -I/usr/include/mrpt/opengl/include -I/usr/include/mrpt/base/include -I/usr/include/mrpt/slam/include -I/usr/include/mrpt/topography/include -I/home/zn/racecar/src/rf2o_laser_odometry/include -I/opt/ros/kinetic/include -I/opt/ros/kinetic/share/xmlrpcpp/cmake/../../../include/xmlrpcpp ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rf2o_laser_odometry_node.dir/link.txt ================================================ /usr/bin/c++ -Wno-long-long -Wno-variadic-macros -Wno-long-long -Wno-variadic-macros -g -rdynamic CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o -o devel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node -Wl,-rpath,/opt/ros/kinetic/lib /opt/ros/kinetic/lib/libtf.so /opt/ros/kinetic/lib/libtf2_ros.so /opt/ros/kinetic/lib/libactionlib.so /opt/ros/kinetic/lib/libmessage_filters.so /opt/ros/kinetic/lib/libroscpp.so /usr/lib/x86_64-linux-gnu/libboost_filesystem.so /usr/lib/x86_64-linux-gnu/libboost_signals.so /opt/ros/kinetic/lib/libxmlrpcpp.so /opt/ros/kinetic/lib/libtf2.so /opt/ros/kinetic/lib/libroscpp_serialization.so /opt/ros/kinetic/lib/librosconsole.so /opt/ros/kinetic/lib/librosconsole_log4cxx.so /opt/ros/kinetic/lib/librosconsole_backend_interface.so /usr/lib/x86_64-linux-gnu/liblog4cxx.so /usr/lib/x86_64-linux-gnu/libboost_regex.so /opt/ros/kinetic/lib/librostime.so /opt/ros/kinetic/lib/libcpp_common.so /usr/lib/x86_64-linux-gnu/libboost_system.so /usr/lib/x86_64-linux-gnu/libboost_thread.so /usr/lib/x86_64-linux-gnu/libboost_chrono.so /usr/lib/x86_64-linux-gnu/libboost_date_time.so /usr/lib/x86_64-linux-gnu/libboost_atomic.so -lpthread /usr/lib/x86_64-linux-gnu/libconsole_bridge.so /usr/lib/x86_64-linux-gnu/libboost_system.so -lmrpt-base-dbg -lmrpt-opengl-dbg -lmrpt-obs-dbg -lmrpt-maps-dbg -lmrpt-vision-dbg -lmrpt-tfest-dbg -lmrpt-slam-dbg /usr/lib/x86_64-linux-gnu/libboost_thread.so /usr/lib/x86_64-linux-gnu/libboost_chrono.so /usr/lib/x86_64-linux-gnu/libboost_date_time.so /usr/lib/x86_64-linux-gnu/libboost_atomic.so -lpthread /usr/lib/x86_64-linux-gnu/libconsole_bridge.so -lmrpt-base-dbg -lmrpt-opengl-dbg -lmrpt-obs-dbg -lmrpt-maps-dbg -lmrpt-vision-dbg -lmrpt-tfest-dbg -lmrpt-slam-dbg ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rf2o_laser_odometry_node.dir/progress.make ================================================ CMAKE_PROGRESS_1 = 1 CMAKE_PROGRESS_2 = 2 ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o ================================================ [File too large to display: 47.3 MB] ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_cpp.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_cpp.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for roscpp_generate_messages_cpp. # Include the progress variables for this target. include CMakeFiles/roscpp_generate_messages_cpp.dir/progress.make roscpp_generate_messages_cpp: CMakeFiles/roscpp_generate_messages_cpp.dir/build.make .PHONY : roscpp_generate_messages_cpp # Rule to build all files generated by this target. CMakeFiles/roscpp_generate_messages_cpp.dir/build: roscpp_generate_messages_cpp .PHONY : CMakeFiles/roscpp_generate_messages_cpp.dir/build CMakeFiles/roscpp_generate_messages_cpp.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/roscpp_generate_messages_cpp.dir/cmake_clean.cmake .PHONY : CMakeFiles/roscpp_generate_messages_cpp.dir/clean CMakeFiles/roscpp_generate_messages_cpp.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_cpp.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/roscpp_generate_messages_cpp.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_cpp.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/roscpp_generate_messages_cpp.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_cpp.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_eus.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_eus.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for roscpp_generate_messages_eus. # Include the progress variables for this target. include CMakeFiles/roscpp_generate_messages_eus.dir/progress.make roscpp_generate_messages_eus: CMakeFiles/roscpp_generate_messages_eus.dir/build.make .PHONY : roscpp_generate_messages_eus # Rule to build all files generated by this target. CMakeFiles/roscpp_generate_messages_eus.dir/build: roscpp_generate_messages_eus .PHONY : CMakeFiles/roscpp_generate_messages_eus.dir/build CMakeFiles/roscpp_generate_messages_eus.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/roscpp_generate_messages_eus.dir/cmake_clean.cmake .PHONY : CMakeFiles/roscpp_generate_messages_eus.dir/clean CMakeFiles/roscpp_generate_messages_eus.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_eus.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/roscpp_generate_messages_eus.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_eus.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/roscpp_generate_messages_eus.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_eus.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_lisp.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_lisp.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for roscpp_generate_messages_lisp. # Include the progress variables for this target. include CMakeFiles/roscpp_generate_messages_lisp.dir/progress.make roscpp_generate_messages_lisp: CMakeFiles/roscpp_generate_messages_lisp.dir/build.make .PHONY : roscpp_generate_messages_lisp # Rule to build all files generated by this target. CMakeFiles/roscpp_generate_messages_lisp.dir/build: roscpp_generate_messages_lisp .PHONY : CMakeFiles/roscpp_generate_messages_lisp.dir/build CMakeFiles/roscpp_generate_messages_lisp.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/roscpp_generate_messages_lisp.dir/cmake_clean.cmake .PHONY : CMakeFiles/roscpp_generate_messages_lisp.dir/clean CMakeFiles/roscpp_generate_messages_lisp.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_lisp.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/roscpp_generate_messages_lisp.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_lisp.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/roscpp_generate_messages_lisp.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_lisp.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_nodejs.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_nodejs.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for roscpp_generate_messages_nodejs. # Include the progress variables for this target. include CMakeFiles/roscpp_generate_messages_nodejs.dir/progress.make roscpp_generate_messages_nodejs: CMakeFiles/roscpp_generate_messages_nodejs.dir/build.make .PHONY : roscpp_generate_messages_nodejs # Rule to build all files generated by this target. CMakeFiles/roscpp_generate_messages_nodejs.dir/build: roscpp_generate_messages_nodejs .PHONY : CMakeFiles/roscpp_generate_messages_nodejs.dir/build CMakeFiles/roscpp_generate_messages_nodejs.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/roscpp_generate_messages_nodejs.dir/cmake_clean.cmake .PHONY : CMakeFiles/roscpp_generate_messages_nodejs.dir/clean CMakeFiles/roscpp_generate_messages_nodejs.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_nodejs.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/roscpp_generate_messages_nodejs.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_nodejs.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/roscpp_generate_messages_nodejs.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_nodejs.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_py.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_py.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for roscpp_generate_messages_py. # Include the progress variables for this target. include CMakeFiles/roscpp_generate_messages_py.dir/progress.make roscpp_generate_messages_py: CMakeFiles/roscpp_generate_messages_py.dir/build.make .PHONY : roscpp_generate_messages_py # Rule to build all files generated by this target. CMakeFiles/roscpp_generate_messages_py.dir/build: roscpp_generate_messages_py .PHONY : CMakeFiles/roscpp_generate_messages_py.dir/build CMakeFiles/roscpp_generate_messages_py.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/roscpp_generate_messages_py.dir/cmake_clean.cmake .PHONY : CMakeFiles/roscpp_generate_messages_py.dir/clean CMakeFiles/roscpp_generate_messages_py.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_py.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/roscpp_generate_messages_py.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_py.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/roscpp_generate_messages_py.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_py.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for rosgraph_msgs_generate_messages_cpp. # Include the progress variables for this target. include CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/progress.make rosgraph_msgs_generate_messages_cpp: CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/build.make .PHONY : rosgraph_msgs_generate_messages_cpp # Rule to build all files generated by this target. CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/build: rosgraph_msgs_generate_messages_cpp .PHONY : CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/build CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/cmake_clean.cmake .PHONY : CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/clean CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for rosgraph_msgs_generate_messages_eus. # Include the progress variables for this target. include CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/progress.make rosgraph_msgs_generate_messages_eus: CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/build.make .PHONY : rosgraph_msgs_generate_messages_eus # Rule to build all files generated by this target. CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/build: rosgraph_msgs_generate_messages_eus .PHONY : CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/build CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/cmake_clean.cmake .PHONY : CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/clean CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for rosgraph_msgs_generate_messages_lisp. # Include the progress variables for this target. include CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/progress.make rosgraph_msgs_generate_messages_lisp: CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/build.make .PHONY : rosgraph_msgs_generate_messages_lisp # Rule to build all files generated by this target. CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/build: rosgraph_msgs_generate_messages_lisp .PHONY : CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/build CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/cmake_clean.cmake .PHONY : CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/clean CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for rosgraph_msgs_generate_messages_nodejs. # Include the progress variables for this target. include CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/progress.make rosgraph_msgs_generate_messages_nodejs: CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/build.make .PHONY : rosgraph_msgs_generate_messages_nodejs # Rule to build all files generated by this target. CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/build: rosgraph_msgs_generate_messages_nodejs .PHONY : CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/build CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/cmake_clean.cmake .PHONY : CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/clean CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_py.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_py.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for rosgraph_msgs_generate_messages_py. # Include the progress variables for this target. include CMakeFiles/rosgraph_msgs_generate_messages_py.dir/progress.make rosgraph_msgs_generate_messages_py: CMakeFiles/rosgraph_msgs_generate_messages_py.dir/build.make .PHONY : rosgraph_msgs_generate_messages_py # Rule to build all files generated by this target. CMakeFiles/rosgraph_msgs_generate_messages_py.dir/build: rosgraph_msgs_generate_messages_py .PHONY : CMakeFiles/rosgraph_msgs_generate_messages_py.dir/build CMakeFiles/rosgraph_msgs_generate_messages_py.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/rosgraph_msgs_generate_messages_py.dir/cmake_clean.cmake .PHONY : CMakeFiles/rosgraph_msgs_generate_messages_py.dir/clean CMakeFiles/rosgraph_msgs_generate_messages_py.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_py.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/rosgraph_msgs_generate_messages_py.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_py.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/rosgraph_msgs_generate_messages_py.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_py.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/run_tests.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/run_tests.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for run_tests. # Include the progress variables for this target. include CMakeFiles/run_tests.dir/progress.make run_tests: CMakeFiles/run_tests.dir/build.make .PHONY : run_tests # Rule to build all files generated by this target. CMakeFiles/run_tests.dir/build: run_tests .PHONY : CMakeFiles/run_tests.dir/build CMakeFiles/run_tests.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/run_tests.dir/cmake_clean.cmake .PHONY : CMakeFiles/run_tests.dir/clean CMakeFiles/run_tests.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/run_tests.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/run_tests.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/run_tests.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/run_tests.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/run_tests.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_cpp.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_cpp.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for sensor_msgs_generate_messages_cpp. # Include the progress variables for this target. include CMakeFiles/sensor_msgs_generate_messages_cpp.dir/progress.make sensor_msgs_generate_messages_cpp: CMakeFiles/sensor_msgs_generate_messages_cpp.dir/build.make .PHONY : sensor_msgs_generate_messages_cpp # Rule to build all files generated by this target. CMakeFiles/sensor_msgs_generate_messages_cpp.dir/build: sensor_msgs_generate_messages_cpp .PHONY : CMakeFiles/sensor_msgs_generate_messages_cpp.dir/build CMakeFiles/sensor_msgs_generate_messages_cpp.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/sensor_msgs_generate_messages_cpp.dir/cmake_clean.cmake .PHONY : CMakeFiles/sensor_msgs_generate_messages_cpp.dir/clean CMakeFiles/sensor_msgs_generate_messages_cpp.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_cpp.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/sensor_msgs_generate_messages_cpp.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_cpp.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/sensor_msgs_generate_messages_cpp.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_cpp.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_eus.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_eus.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for sensor_msgs_generate_messages_eus. # Include the progress variables for this target. include CMakeFiles/sensor_msgs_generate_messages_eus.dir/progress.make sensor_msgs_generate_messages_eus: CMakeFiles/sensor_msgs_generate_messages_eus.dir/build.make .PHONY : sensor_msgs_generate_messages_eus # Rule to build all files generated by this target. CMakeFiles/sensor_msgs_generate_messages_eus.dir/build: sensor_msgs_generate_messages_eus .PHONY : CMakeFiles/sensor_msgs_generate_messages_eus.dir/build CMakeFiles/sensor_msgs_generate_messages_eus.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/sensor_msgs_generate_messages_eus.dir/cmake_clean.cmake .PHONY : CMakeFiles/sensor_msgs_generate_messages_eus.dir/clean CMakeFiles/sensor_msgs_generate_messages_eus.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_eus.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/sensor_msgs_generate_messages_eus.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_eus.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/sensor_msgs_generate_messages_eus.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_eus.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_lisp.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_lisp.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for sensor_msgs_generate_messages_lisp. # Include the progress variables for this target. include CMakeFiles/sensor_msgs_generate_messages_lisp.dir/progress.make sensor_msgs_generate_messages_lisp: CMakeFiles/sensor_msgs_generate_messages_lisp.dir/build.make .PHONY : sensor_msgs_generate_messages_lisp # Rule to build all files generated by this target. CMakeFiles/sensor_msgs_generate_messages_lisp.dir/build: sensor_msgs_generate_messages_lisp .PHONY : CMakeFiles/sensor_msgs_generate_messages_lisp.dir/build CMakeFiles/sensor_msgs_generate_messages_lisp.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/sensor_msgs_generate_messages_lisp.dir/cmake_clean.cmake .PHONY : CMakeFiles/sensor_msgs_generate_messages_lisp.dir/clean CMakeFiles/sensor_msgs_generate_messages_lisp.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_lisp.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/sensor_msgs_generate_messages_lisp.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_lisp.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/sensor_msgs_generate_messages_lisp.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_lisp.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for sensor_msgs_generate_messages_nodejs. # Include the progress variables for this target. include CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/progress.make sensor_msgs_generate_messages_nodejs: CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/build.make .PHONY : sensor_msgs_generate_messages_nodejs # Rule to build all files generated by this target. CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/build: sensor_msgs_generate_messages_nodejs .PHONY : CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/build CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/cmake_clean.cmake .PHONY : CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/clean CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_py.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_py.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for sensor_msgs_generate_messages_py. # Include the progress variables for this target. include CMakeFiles/sensor_msgs_generate_messages_py.dir/progress.make sensor_msgs_generate_messages_py: CMakeFiles/sensor_msgs_generate_messages_py.dir/build.make .PHONY : sensor_msgs_generate_messages_py # Rule to build all files generated by this target. CMakeFiles/sensor_msgs_generate_messages_py.dir/build: sensor_msgs_generate_messages_py .PHONY : CMakeFiles/sensor_msgs_generate_messages_py.dir/build CMakeFiles/sensor_msgs_generate_messages_py.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/sensor_msgs_generate_messages_py.dir/cmake_clean.cmake .PHONY : CMakeFiles/sensor_msgs_generate_messages_py.dir/clean CMakeFiles/sensor_msgs_generate_messages_py.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_py.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/sensor_msgs_generate_messages_py.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_py.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/sensor_msgs_generate_messages_py.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_py.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_cpp.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_cpp.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for std_msgs_generate_messages_cpp. # Include the progress variables for this target. include CMakeFiles/std_msgs_generate_messages_cpp.dir/progress.make std_msgs_generate_messages_cpp: CMakeFiles/std_msgs_generate_messages_cpp.dir/build.make .PHONY : std_msgs_generate_messages_cpp # Rule to build all files generated by this target. CMakeFiles/std_msgs_generate_messages_cpp.dir/build: std_msgs_generate_messages_cpp .PHONY : CMakeFiles/std_msgs_generate_messages_cpp.dir/build CMakeFiles/std_msgs_generate_messages_cpp.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/std_msgs_generate_messages_cpp.dir/cmake_clean.cmake .PHONY : CMakeFiles/std_msgs_generate_messages_cpp.dir/clean CMakeFiles/std_msgs_generate_messages_cpp.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_cpp.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/std_msgs_generate_messages_cpp.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_cpp.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/std_msgs_generate_messages_cpp.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_cpp.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_eus.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_eus.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for std_msgs_generate_messages_eus. # Include the progress variables for this target. include CMakeFiles/std_msgs_generate_messages_eus.dir/progress.make std_msgs_generate_messages_eus: CMakeFiles/std_msgs_generate_messages_eus.dir/build.make .PHONY : std_msgs_generate_messages_eus # Rule to build all files generated by this target. CMakeFiles/std_msgs_generate_messages_eus.dir/build: std_msgs_generate_messages_eus .PHONY : CMakeFiles/std_msgs_generate_messages_eus.dir/build CMakeFiles/std_msgs_generate_messages_eus.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/std_msgs_generate_messages_eus.dir/cmake_clean.cmake .PHONY : CMakeFiles/std_msgs_generate_messages_eus.dir/clean CMakeFiles/std_msgs_generate_messages_eus.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_eus.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/std_msgs_generate_messages_eus.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_eus.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/std_msgs_generate_messages_eus.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_eus.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_lisp.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_lisp.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for std_msgs_generate_messages_lisp. # Include the progress variables for this target. include CMakeFiles/std_msgs_generate_messages_lisp.dir/progress.make std_msgs_generate_messages_lisp: CMakeFiles/std_msgs_generate_messages_lisp.dir/build.make .PHONY : std_msgs_generate_messages_lisp # Rule to build all files generated by this target. CMakeFiles/std_msgs_generate_messages_lisp.dir/build: std_msgs_generate_messages_lisp .PHONY : CMakeFiles/std_msgs_generate_messages_lisp.dir/build CMakeFiles/std_msgs_generate_messages_lisp.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/std_msgs_generate_messages_lisp.dir/cmake_clean.cmake .PHONY : CMakeFiles/std_msgs_generate_messages_lisp.dir/clean CMakeFiles/std_msgs_generate_messages_lisp.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_lisp.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/std_msgs_generate_messages_lisp.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_lisp.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/std_msgs_generate_messages_lisp.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_lisp.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_nodejs.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_nodejs.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for std_msgs_generate_messages_nodejs. # Include the progress variables for this target. include CMakeFiles/std_msgs_generate_messages_nodejs.dir/progress.make std_msgs_generate_messages_nodejs: CMakeFiles/std_msgs_generate_messages_nodejs.dir/build.make .PHONY : std_msgs_generate_messages_nodejs # Rule to build all files generated by this target. CMakeFiles/std_msgs_generate_messages_nodejs.dir/build: std_msgs_generate_messages_nodejs .PHONY : CMakeFiles/std_msgs_generate_messages_nodejs.dir/build CMakeFiles/std_msgs_generate_messages_nodejs.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/std_msgs_generate_messages_nodejs.dir/cmake_clean.cmake .PHONY : CMakeFiles/std_msgs_generate_messages_nodejs.dir/clean CMakeFiles/std_msgs_generate_messages_nodejs.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_nodejs.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/std_msgs_generate_messages_nodejs.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_nodejs.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/std_msgs_generate_messages_nodejs.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_nodejs.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_py.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_py.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for std_msgs_generate_messages_py. # Include the progress variables for this target. include CMakeFiles/std_msgs_generate_messages_py.dir/progress.make std_msgs_generate_messages_py: CMakeFiles/std_msgs_generate_messages_py.dir/build.make .PHONY : std_msgs_generate_messages_py # Rule to build all files generated by this target. CMakeFiles/std_msgs_generate_messages_py.dir/build: std_msgs_generate_messages_py .PHONY : CMakeFiles/std_msgs_generate_messages_py.dir/build CMakeFiles/std_msgs_generate_messages_py.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/std_msgs_generate_messages_py.dir/cmake_clean.cmake .PHONY : CMakeFiles/std_msgs_generate_messages_py.dir/clean CMakeFiles/std_msgs_generate_messages_py.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_py.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/std_msgs_generate_messages_py.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_py.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/std_msgs_generate_messages_py.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_py.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tests.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tests.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for tests. # Include the progress variables for this target. include CMakeFiles/tests.dir/progress.make tests: CMakeFiles/tests.dir/build.make .PHONY : tests # Rule to build all files generated by this target. CMakeFiles/tests.dir/build: tests .PHONY : CMakeFiles/tests.dir/build CMakeFiles/tests.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/tests.dir/cmake_clean.cmake .PHONY : CMakeFiles/tests.dir/clean CMakeFiles/tests.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tests.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/tests.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tests.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/tests.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tests.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_cpp.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_cpp.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for tf2_msgs_generate_messages_cpp. # Include the progress variables for this target. include CMakeFiles/tf2_msgs_generate_messages_cpp.dir/progress.make tf2_msgs_generate_messages_cpp: CMakeFiles/tf2_msgs_generate_messages_cpp.dir/build.make .PHONY : tf2_msgs_generate_messages_cpp # Rule to build all files generated by this target. CMakeFiles/tf2_msgs_generate_messages_cpp.dir/build: tf2_msgs_generate_messages_cpp .PHONY : CMakeFiles/tf2_msgs_generate_messages_cpp.dir/build CMakeFiles/tf2_msgs_generate_messages_cpp.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/tf2_msgs_generate_messages_cpp.dir/cmake_clean.cmake .PHONY : CMakeFiles/tf2_msgs_generate_messages_cpp.dir/clean CMakeFiles/tf2_msgs_generate_messages_cpp.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_cpp.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/tf2_msgs_generate_messages_cpp.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_cpp.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/tf2_msgs_generate_messages_cpp.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_cpp.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_eus.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_eus.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for tf2_msgs_generate_messages_eus. # Include the progress variables for this target. include CMakeFiles/tf2_msgs_generate_messages_eus.dir/progress.make tf2_msgs_generate_messages_eus: CMakeFiles/tf2_msgs_generate_messages_eus.dir/build.make .PHONY : tf2_msgs_generate_messages_eus # Rule to build all files generated by this target. CMakeFiles/tf2_msgs_generate_messages_eus.dir/build: tf2_msgs_generate_messages_eus .PHONY : CMakeFiles/tf2_msgs_generate_messages_eus.dir/build CMakeFiles/tf2_msgs_generate_messages_eus.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/tf2_msgs_generate_messages_eus.dir/cmake_clean.cmake .PHONY : CMakeFiles/tf2_msgs_generate_messages_eus.dir/clean CMakeFiles/tf2_msgs_generate_messages_eus.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_eus.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/tf2_msgs_generate_messages_eus.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_eus.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/tf2_msgs_generate_messages_eus.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_eus.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_lisp.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_lisp.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for tf2_msgs_generate_messages_lisp. # Include the progress variables for this target. include CMakeFiles/tf2_msgs_generate_messages_lisp.dir/progress.make tf2_msgs_generate_messages_lisp: CMakeFiles/tf2_msgs_generate_messages_lisp.dir/build.make .PHONY : tf2_msgs_generate_messages_lisp # Rule to build all files generated by this target. CMakeFiles/tf2_msgs_generate_messages_lisp.dir/build: tf2_msgs_generate_messages_lisp .PHONY : CMakeFiles/tf2_msgs_generate_messages_lisp.dir/build CMakeFiles/tf2_msgs_generate_messages_lisp.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/tf2_msgs_generate_messages_lisp.dir/cmake_clean.cmake .PHONY : CMakeFiles/tf2_msgs_generate_messages_lisp.dir/clean CMakeFiles/tf2_msgs_generate_messages_lisp.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_lisp.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/tf2_msgs_generate_messages_lisp.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_lisp.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/tf2_msgs_generate_messages_lisp.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_lisp.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for tf2_msgs_generate_messages_nodejs. # Include the progress variables for this target. include CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/progress.make tf2_msgs_generate_messages_nodejs: CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/build.make .PHONY : tf2_msgs_generate_messages_nodejs # Rule to build all files generated by this target. CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/build: tf2_msgs_generate_messages_nodejs .PHONY : CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/build CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/cmake_clean.cmake .PHONY : CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/clean CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_py.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_py.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for tf2_msgs_generate_messages_py. # Include the progress variables for this target. include CMakeFiles/tf2_msgs_generate_messages_py.dir/progress.make tf2_msgs_generate_messages_py: CMakeFiles/tf2_msgs_generate_messages_py.dir/build.make .PHONY : tf2_msgs_generate_messages_py # Rule to build all files generated by this target. CMakeFiles/tf2_msgs_generate_messages_py.dir/build: tf2_msgs_generate_messages_py .PHONY : CMakeFiles/tf2_msgs_generate_messages_py.dir/build CMakeFiles/tf2_msgs_generate_messages_py.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/tf2_msgs_generate_messages_py.dir/cmake_clean.cmake .PHONY : CMakeFiles/tf2_msgs_generate_messages_py.dir/clean CMakeFiles/tf2_msgs_generate_messages_py.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_py.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/tf2_msgs_generate_messages_py.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_py.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/tf2_msgs_generate_messages_py.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_py.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_cpp.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_cpp.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for tf_generate_messages_cpp. # Include the progress variables for this target. include CMakeFiles/tf_generate_messages_cpp.dir/progress.make tf_generate_messages_cpp: CMakeFiles/tf_generate_messages_cpp.dir/build.make .PHONY : tf_generate_messages_cpp # Rule to build all files generated by this target. CMakeFiles/tf_generate_messages_cpp.dir/build: tf_generate_messages_cpp .PHONY : CMakeFiles/tf_generate_messages_cpp.dir/build CMakeFiles/tf_generate_messages_cpp.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/tf_generate_messages_cpp.dir/cmake_clean.cmake .PHONY : CMakeFiles/tf_generate_messages_cpp.dir/clean CMakeFiles/tf_generate_messages_cpp.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_cpp.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/tf_generate_messages_cpp.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_cpp.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/tf_generate_messages_cpp.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_cpp.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_eus.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_eus.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for tf_generate_messages_eus. # Include the progress variables for this target. include CMakeFiles/tf_generate_messages_eus.dir/progress.make tf_generate_messages_eus: CMakeFiles/tf_generate_messages_eus.dir/build.make .PHONY : tf_generate_messages_eus # Rule to build all files generated by this target. CMakeFiles/tf_generate_messages_eus.dir/build: tf_generate_messages_eus .PHONY : CMakeFiles/tf_generate_messages_eus.dir/build CMakeFiles/tf_generate_messages_eus.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/tf_generate_messages_eus.dir/cmake_clean.cmake .PHONY : CMakeFiles/tf_generate_messages_eus.dir/clean CMakeFiles/tf_generate_messages_eus.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_eus.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/tf_generate_messages_eus.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_eus.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/tf_generate_messages_eus.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_eus.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_lisp.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_lisp.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for tf_generate_messages_lisp. # Include the progress variables for this target. include CMakeFiles/tf_generate_messages_lisp.dir/progress.make tf_generate_messages_lisp: CMakeFiles/tf_generate_messages_lisp.dir/build.make .PHONY : tf_generate_messages_lisp # Rule to build all files generated by this target. CMakeFiles/tf_generate_messages_lisp.dir/build: tf_generate_messages_lisp .PHONY : CMakeFiles/tf_generate_messages_lisp.dir/build CMakeFiles/tf_generate_messages_lisp.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/tf_generate_messages_lisp.dir/cmake_clean.cmake .PHONY : CMakeFiles/tf_generate_messages_lisp.dir/clean CMakeFiles/tf_generate_messages_lisp.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_lisp.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/tf_generate_messages_lisp.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_lisp.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/tf_generate_messages_lisp.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_lisp.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_nodejs.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_nodejs.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for tf_generate_messages_nodejs. # Include the progress variables for this target. include CMakeFiles/tf_generate_messages_nodejs.dir/progress.make tf_generate_messages_nodejs: CMakeFiles/tf_generate_messages_nodejs.dir/build.make .PHONY : tf_generate_messages_nodejs # Rule to build all files generated by this target. CMakeFiles/tf_generate_messages_nodejs.dir/build: tf_generate_messages_nodejs .PHONY : CMakeFiles/tf_generate_messages_nodejs.dir/build CMakeFiles/tf_generate_messages_nodejs.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/tf_generate_messages_nodejs.dir/cmake_clean.cmake .PHONY : CMakeFiles/tf_generate_messages_nodejs.dir/clean CMakeFiles/tf_generate_messages_nodejs.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_nodejs.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/tf_generate_messages_nodejs.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_nodejs.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/tf_generate_messages_nodejs.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_nodejs.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_py.dir/DependInfo.cmake ================================================ # The set of languages for which implicit dependencies are needed: set(CMAKE_DEPENDS_LANGUAGES ) # The set of files for implicit dependencies of each language: # Targets to which this target links. set(CMAKE_TARGET_LINKED_INFO_FILES ) # Fortran module output directory. set(CMAKE_Fortran_TARGET_MODULE_DIR "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_py.dir/build.make ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Delete rule output on recipe failure. .DELETE_ON_ERROR: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # Utility rule file for tf_generate_messages_py. # Include the progress variables for this target. include CMakeFiles/tf_generate_messages_py.dir/progress.make tf_generate_messages_py: CMakeFiles/tf_generate_messages_py.dir/build.make .PHONY : tf_generate_messages_py # Rule to build all files generated by this target. CMakeFiles/tf_generate_messages_py.dir/build: tf_generate_messages_py .PHONY : CMakeFiles/tf_generate_messages_py.dir/build CMakeFiles/tf_generate_messages_py.dir/clean: $(CMAKE_COMMAND) -P CMakeFiles/tf_generate_messages_py.dir/cmake_clean.cmake .PHONY : CMakeFiles/tf_generate_messages_py.dir/clean CMakeFiles/tf_generate_messages_py.dir/depend: cd /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_py.dir/DependInfo.cmake --color=$(COLOR) .PHONY : CMakeFiles/tf_generate_messages_py.dir/depend ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_py.dir/cmake_clean.cmake ================================================ # Per-language clean rules from dependency scanning. foreach(lang ) include(CMakeFiles/tf_generate_messages_py.dir/cmake_clean_${lang}.cmake OPTIONAL) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_py.dir/progress.make ================================================ ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/CTestTestfile.cmake ================================================ # CMake generated Testfile for # Source directory: /home/zn/racecar/src/rf2o_laser_odometry # Build directory: /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug # # This file includes the relevant testing commands required for # testing this directory and lists subdirectories to be tested as well. ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/Makefile ================================================ # CMAKE generated file: DO NOT EDIT! # Generated by "Unix Makefiles" Generator, CMake Version 3.9 # Default target executed when no arguments are given to make. default_target: all .PHONY : default_target # Allow only one "make -f Makefile2" at a time, but pass parallelism. .NOTPARALLEL: #============================================================================= # Special targets provided by cmake. # Disable implicit rules so canonical targets will work. .SUFFIXES: # Remove some rules from gmake that .SUFFIXES does not remove. SUFFIXES = .SUFFIXES: .hpux_make_needs_suffix_list # Suppress display of executed commands. $(VERBOSE).SILENT: # A target that is always out of date. cmake_force: .PHONY : cmake_force #============================================================================= # Set environment variables for the build. # The shell in which to execute make rules. SHELL = /bin/sh # The CMake executable. CMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake # The command to remove a file. RM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f # Escaping for special characters. EQUALS = = # The top-level source directory on which CMake was run. CMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry # The top-level build directory on which CMake was run. CMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug #============================================================================= # Targets provided globally by CMake. # Special rule for the target install/local install/local: preinstall @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Installing only the local directory..." /home/zn/.ide/clion/bin/cmake/bin/cmake -DCMAKE_INSTALL_LOCAL_ONLY=1 -P cmake_install.cmake .PHONY : install/local # Special rule for the target install/local install/local/fast: preinstall/fast @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Installing only the local directory..." /home/zn/.ide/clion/bin/cmake/bin/cmake -DCMAKE_INSTALL_LOCAL_ONLY=1 -P cmake_install.cmake .PHONY : install/local/fast # Special rule for the target edit_cache edit_cache: @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "No interactive CMake dialog available..." /home/zn/.ide/clion/bin/cmake/bin/cmake -E echo No\ interactive\ CMake\ dialog\ available. .PHONY : edit_cache # Special rule for the target edit_cache edit_cache/fast: edit_cache .PHONY : edit_cache/fast # Special rule for the target install/strip install/strip: preinstall @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Installing the project stripped..." /home/zn/.ide/clion/bin/cmake/bin/cmake -DCMAKE_INSTALL_DO_STRIP=1 -P cmake_install.cmake .PHONY : install/strip # Special rule for the target install/strip install/strip/fast: preinstall/fast @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Installing the project stripped..." /home/zn/.ide/clion/bin/cmake/bin/cmake -DCMAKE_INSTALL_DO_STRIP=1 -P cmake_install.cmake .PHONY : install/strip/fast # Special rule for the target rebuild_cache rebuild_cache: @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running CMake to regenerate build system..." /home/zn/.ide/clion/bin/cmake/bin/cmake -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) .PHONY : rebuild_cache # Special rule for the target rebuild_cache rebuild_cache/fast: rebuild_cache .PHONY : rebuild_cache/fast # Special rule for the target install install: preinstall @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Install the project..." /home/zn/.ide/clion/bin/cmake/bin/cmake -P cmake_install.cmake .PHONY : install # Special rule for the target install install/fast: preinstall/fast @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Install the project..." /home/zn/.ide/clion/bin/cmake/bin/cmake -P cmake_install.cmake .PHONY : install/fast # Special rule for the target list_install_components list_install_components: @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Available install components are: \"Unspecified\"" .PHONY : list_install_components # Special rule for the target list_install_components list_install_components/fast: list_install_components .PHONY : list_install_components/fast # Special rule for the target test test: @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running tests..." /home/zn/.ide/clion/bin/cmake/bin/ctest --force-new-ctest-process $(ARGS) .PHONY : test # Special rule for the target test test/fast: test .PHONY : test/fast # The main all target all: cmake_check_build_system $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/progress.marks $(MAKE) -f CMakeFiles/Makefile2 all $(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0 .PHONY : all # The main clean target clean: $(MAKE) -f CMakeFiles/Makefile2 clean .PHONY : clean # The main clean target clean/fast: clean .PHONY : clean/fast # Prepare targets for installation. preinstall: all $(MAKE) -f CMakeFiles/Makefile2 preinstall .PHONY : preinstall # Prepare targets for installation. preinstall/fast: $(MAKE) -f CMakeFiles/Makefile2 preinstall .PHONY : preinstall/fast # clear depends depend: $(CMAKE_COMMAND) -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 1 .PHONY : depend #============================================================================= # Target rules for targets named tf2_msgs_generate_messages_nodejs # Build rule for target. tf2_msgs_generate_messages_nodejs: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 tf2_msgs_generate_messages_nodejs .PHONY : tf2_msgs_generate_messages_nodejs # fast build rule for target. tf2_msgs_generate_messages_nodejs/fast: $(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/build .PHONY : tf2_msgs_generate_messages_nodejs/fast #============================================================================= # Target rules for targets named tf2_msgs_generate_messages_lisp # Build rule for target. tf2_msgs_generate_messages_lisp: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 tf2_msgs_generate_messages_lisp .PHONY : tf2_msgs_generate_messages_lisp # fast build rule for target. tf2_msgs_generate_messages_lisp/fast: $(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_lisp.dir/build.make CMakeFiles/tf2_msgs_generate_messages_lisp.dir/build .PHONY : tf2_msgs_generate_messages_lisp/fast #============================================================================= # Target rules for targets named tf2_msgs_generate_messages_eus # Build rule for target. tf2_msgs_generate_messages_eus: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 tf2_msgs_generate_messages_eus .PHONY : tf2_msgs_generate_messages_eus # fast build rule for target. tf2_msgs_generate_messages_eus/fast: $(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_eus.dir/build.make CMakeFiles/tf2_msgs_generate_messages_eus.dir/build .PHONY : tf2_msgs_generate_messages_eus/fast #============================================================================= # Target rules for targets named tf2_msgs_generate_messages_cpp # Build rule for target. tf2_msgs_generate_messages_cpp: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 tf2_msgs_generate_messages_cpp .PHONY : tf2_msgs_generate_messages_cpp # fast build rule for target. tf2_msgs_generate_messages_cpp/fast: $(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_cpp.dir/build.make CMakeFiles/tf2_msgs_generate_messages_cpp.dir/build .PHONY : tf2_msgs_generate_messages_cpp/fast #============================================================================= # Target rules for targets named actionlib_generate_messages_py # Build rule for target. actionlib_generate_messages_py: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 actionlib_generate_messages_py .PHONY : actionlib_generate_messages_py # fast build rule for target. actionlib_generate_messages_py/fast: $(MAKE) -f CMakeFiles/actionlib_generate_messages_py.dir/build.make CMakeFiles/actionlib_generate_messages_py.dir/build .PHONY : actionlib_generate_messages_py/fast #============================================================================= # Target rules for targets named actionlib_generate_messages_eus # Build rule for target. actionlib_generate_messages_eus: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 actionlib_generate_messages_eus .PHONY : actionlib_generate_messages_eus # fast build rule for target. actionlib_generate_messages_eus/fast: $(MAKE) -f CMakeFiles/actionlib_generate_messages_eus.dir/build.make CMakeFiles/actionlib_generate_messages_eus.dir/build .PHONY : actionlib_generate_messages_eus/fast #============================================================================= # Target rules for targets named nav_msgs_generate_messages_eus # Build rule for target. nav_msgs_generate_messages_eus: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 nav_msgs_generate_messages_eus .PHONY : nav_msgs_generate_messages_eus # fast build rule for target. nav_msgs_generate_messages_eus/fast: $(MAKE) -f CMakeFiles/nav_msgs_generate_messages_eus.dir/build.make CMakeFiles/nav_msgs_generate_messages_eus.dir/build .PHONY : nav_msgs_generate_messages_eus/fast #============================================================================= # Target rules for targets named std_msgs_generate_messages_eus # Build rule for target. std_msgs_generate_messages_eus: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 std_msgs_generate_messages_eus .PHONY : std_msgs_generate_messages_eus # fast build rule for target. std_msgs_generate_messages_eus/fast: $(MAKE) -f CMakeFiles/std_msgs_generate_messages_eus.dir/build.make CMakeFiles/std_msgs_generate_messages_eus.dir/build .PHONY : std_msgs_generate_messages_eus/fast #============================================================================= # Target rules for targets named roscpp_generate_messages_lisp # Build rule for target. roscpp_generate_messages_lisp: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 roscpp_generate_messages_lisp .PHONY : roscpp_generate_messages_lisp # fast build rule for target. roscpp_generate_messages_lisp/fast: $(MAKE) -f CMakeFiles/roscpp_generate_messages_lisp.dir/build.make CMakeFiles/roscpp_generate_messages_lisp.dir/build .PHONY : roscpp_generate_messages_lisp/fast #============================================================================= # Target rules for targets named rosgraph_msgs_generate_messages_lisp # Build rule for target. rosgraph_msgs_generate_messages_lisp: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 rosgraph_msgs_generate_messages_lisp .PHONY : rosgraph_msgs_generate_messages_lisp # fast build rule for target. rosgraph_msgs_generate_messages_lisp/fast: $(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/build .PHONY : rosgraph_msgs_generate_messages_lisp/fast #============================================================================= # Target rules for targets named tests # Build rule for target. tests: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 tests .PHONY : tests # fast build rule for target. tests/fast: $(MAKE) -f CMakeFiles/tests.dir/build.make CMakeFiles/tests.dir/build .PHONY : tests/fast #============================================================================= # Target rules for targets named rf2o_laser_odometry_node # Build rule for target. rf2o_laser_odometry_node: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 rf2o_laser_odometry_node .PHONY : rf2o_laser_odometry_node # fast build rule for target. rf2o_laser_odometry_node/fast: $(MAKE) -f CMakeFiles/rf2o_laser_odometry_node.dir/build.make CMakeFiles/rf2o_laser_odometry_node.dir/build .PHONY : rf2o_laser_odometry_node/fast #============================================================================= # Target rules for targets named roscpp_generate_messages_nodejs # Build rule for target. roscpp_generate_messages_nodejs: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 roscpp_generate_messages_nodejs .PHONY : roscpp_generate_messages_nodejs # fast build rule for target. roscpp_generate_messages_nodejs/fast: $(MAKE) -f CMakeFiles/roscpp_generate_messages_nodejs.dir/build.make CMakeFiles/roscpp_generate_messages_nodejs.dir/build .PHONY : roscpp_generate_messages_nodejs/fast #============================================================================= # Target rules for targets named tf_generate_messages_eus # Build rule for target. tf_generate_messages_eus: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 tf_generate_messages_eus .PHONY : tf_generate_messages_eus # fast build rule for target. tf_generate_messages_eus/fast: $(MAKE) -f CMakeFiles/tf_generate_messages_eus.dir/build.make CMakeFiles/tf_generate_messages_eus.dir/build .PHONY : tf_generate_messages_eus/fast #============================================================================= # Target rules for targets named rosgraph_msgs_generate_messages_nodejs # Build rule for target. rosgraph_msgs_generate_messages_nodejs: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 rosgraph_msgs_generate_messages_nodejs .PHONY : rosgraph_msgs_generate_messages_nodejs # fast build rule for target. rosgraph_msgs_generate_messages_nodejs/fast: $(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/build .PHONY : rosgraph_msgs_generate_messages_nodejs/fast #============================================================================= # Target rules for targets named nav_msgs_generate_messages_cpp # Build rule for target. nav_msgs_generate_messages_cpp: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 nav_msgs_generate_messages_cpp .PHONY : nav_msgs_generate_messages_cpp # fast build rule for target. nav_msgs_generate_messages_cpp/fast: $(MAKE) -f CMakeFiles/nav_msgs_generate_messages_cpp.dir/build.make CMakeFiles/nav_msgs_generate_messages_cpp.dir/build .PHONY : nav_msgs_generate_messages_cpp/fast #============================================================================= # Target rules for targets named std_msgs_generate_messages_lisp # Build rule for target. std_msgs_generate_messages_lisp: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 std_msgs_generate_messages_lisp .PHONY : std_msgs_generate_messages_lisp # fast build rule for target. std_msgs_generate_messages_lisp/fast: $(MAKE) -f CMakeFiles/std_msgs_generate_messages_lisp.dir/build.make CMakeFiles/std_msgs_generate_messages_lisp.dir/build .PHONY : std_msgs_generate_messages_lisp/fast #============================================================================= # Target rules for targets named geometry_msgs_generate_messages_lisp # Build rule for target. geometry_msgs_generate_messages_lisp: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 geometry_msgs_generate_messages_lisp .PHONY : geometry_msgs_generate_messages_lisp # fast build rule for target. geometry_msgs_generate_messages_lisp/fast: $(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_lisp.dir/build.make CMakeFiles/geometry_msgs_generate_messages_lisp.dir/build .PHONY : geometry_msgs_generate_messages_lisp/fast #============================================================================= # Target rules for targets named rosgraph_msgs_generate_messages_cpp # Build rule for target. rosgraph_msgs_generate_messages_cpp: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 rosgraph_msgs_generate_messages_cpp .PHONY : rosgraph_msgs_generate_messages_cpp # fast build rule for target. rosgraph_msgs_generate_messages_cpp/fast: $(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/build .PHONY : rosgraph_msgs_generate_messages_cpp/fast #============================================================================= # Target rules for targets named run_tests # Build rule for target. run_tests: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 run_tests .PHONY : run_tests # fast build rule for target. run_tests/fast: $(MAKE) -f CMakeFiles/run_tests.dir/build.make CMakeFiles/run_tests.dir/build .PHONY : run_tests/fast #============================================================================= # Target rules for targets named actionlib_generate_messages_lisp # Build rule for target. actionlib_generate_messages_lisp: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 actionlib_generate_messages_lisp .PHONY : actionlib_generate_messages_lisp # fast build rule for target. actionlib_generate_messages_lisp/fast: $(MAKE) -f CMakeFiles/actionlib_generate_messages_lisp.dir/build.make CMakeFiles/actionlib_generate_messages_lisp.dir/build .PHONY : actionlib_generate_messages_lisp/fast #============================================================================= # Target rules for targets named actionlib_msgs_generate_messages_eus # Build rule for target. actionlib_msgs_generate_messages_eus: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 actionlib_msgs_generate_messages_eus .PHONY : actionlib_msgs_generate_messages_eus # fast build rule for target. actionlib_msgs_generate_messages_eus/fast: $(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_eus.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_eus.dir/build .PHONY : actionlib_msgs_generate_messages_eus/fast #============================================================================= # Target rules for targets named roscpp_generate_messages_eus # Build rule for target. roscpp_generate_messages_eus: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 roscpp_generate_messages_eus .PHONY : roscpp_generate_messages_eus # fast build rule for target. roscpp_generate_messages_eus/fast: $(MAKE) -f CMakeFiles/roscpp_generate_messages_eus.dir/build.make CMakeFiles/roscpp_generate_messages_eus.dir/build .PHONY : roscpp_generate_messages_eus/fast #============================================================================= # Target rules for targets named roscpp_generate_messages_cpp # Build rule for target. roscpp_generate_messages_cpp: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 roscpp_generate_messages_cpp .PHONY : roscpp_generate_messages_cpp # fast build rule for target. roscpp_generate_messages_cpp/fast: $(MAKE) -f CMakeFiles/roscpp_generate_messages_cpp.dir/build.make CMakeFiles/roscpp_generate_messages_cpp.dir/build .PHONY : roscpp_generate_messages_cpp/fast #============================================================================= # Target rules for targets named geometry_msgs_generate_messages_eus # Build rule for target. geometry_msgs_generate_messages_eus: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 geometry_msgs_generate_messages_eus .PHONY : geometry_msgs_generate_messages_eus # fast build rule for target. geometry_msgs_generate_messages_eus/fast: $(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_eus.dir/build.make CMakeFiles/geometry_msgs_generate_messages_eus.dir/build .PHONY : geometry_msgs_generate_messages_eus/fast #============================================================================= # Target rules for targets named actionlib_msgs_generate_messages_py # Build rule for target. actionlib_msgs_generate_messages_py: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 actionlib_msgs_generate_messages_py .PHONY : actionlib_msgs_generate_messages_py # fast build rule for target. actionlib_msgs_generate_messages_py/fast: $(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_py.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_py.dir/build .PHONY : actionlib_msgs_generate_messages_py/fast #============================================================================= # Target rules for targets named clean_test_results # Build rule for target. clean_test_results: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 clean_test_results .PHONY : clean_test_results # fast build rule for target. clean_test_results/fast: $(MAKE) -f CMakeFiles/clean_test_results.dir/build.make CMakeFiles/clean_test_results.dir/build .PHONY : clean_test_results/fast #============================================================================= # Target rules for targets named geometry_msgs_generate_messages_nodejs # Build rule for target. geometry_msgs_generate_messages_nodejs: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 geometry_msgs_generate_messages_nodejs .PHONY : geometry_msgs_generate_messages_nodejs # fast build rule for target. geometry_msgs_generate_messages_nodejs/fast: $(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/build .PHONY : geometry_msgs_generate_messages_nodejs/fast #============================================================================= # Target rules for targets named rosgraph_msgs_generate_messages_eus # Build rule for target. rosgraph_msgs_generate_messages_eus: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 rosgraph_msgs_generate_messages_eus .PHONY : rosgraph_msgs_generate_messages_eus # fast build rule for target. rosgraph_msgs_generate_messages_eus/fast: $(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/build .PHONY : rosgraph_msgs_generate_messages_eus/fast #============================================================================= # Target rules for targets named doxygen # Build rule for target. doxygen: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 doxygen .PHONY : doxygen # fast build rule for target. doxygen/fast: $(MAKE) -f CMakeFiles/doxygen.dir/build.make CMakeFiles/doxygen.dir/build .PHONY : doxygen/fast #============================================================================= # Target rules for targets named tf_generate_messages_cpp # Build rule for target. tf_generate_messages_cpp: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 tf_generate_messages_cpp .PHONY : tf_generate_messages_cpp # fast build rule for target. tf_generate_messages_cpp/fast: $(MAKE) -f CMakeFiles/tf_generate_messages_cpp.dir/build.make CMakeFiles/tf_generate_messages_cpp.dir/build .PHONY : tf_generate_messages_cpp/fast #============================================================================= # Target rules for targets named nav_msgs_generate_messages_lisp # Build rule for target. nav_msgs_generate_messages_lisp: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 nav_msgs_generate_messages_lisp .PHONY : nav_msgs_generate_messages_lisp # fast build rule for target. nav_msgs_generate_messages_lisp/fast: $(MAKE) -f CMakeFiles/nav_msgs_generate_messages_lisp.dir/build.make CMakeFiles/nav_msgs_generate_messages_lisp.dir/build .PHONY : nav_msgs_generate_messages_lisp/fast #============================================================================= # Target rules for targets named nav_msgs_generate_messages_nodejs # Build rule for target. nav_msgs_generate_messages_nodejs: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 nav_msgs_generate_messages_nodejs .PHONY : nav_msgs_generate_messages_nodejs # fast build rule for target. nav_msgs_generate_messages_nodejs/fast: $(MAKE) -f CMakeFiles/nav_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/nav_msgs_generate_messages_nodejs.dir/build .PHONY : nav_msgs_generate_messages_nodejs/fast #============================================================================= # Target rules for targets named std_msgs_generate_messages_py # Build rule for target. std_msgs_generate_messages_py: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 std_msgs_generate_messages_py .PHONY : std_msgs_generate_messages_py # fast build rule for target. std_msgs_generate_messages_py/fast: $(MAKE) -f CMakeFiles/std_msgs_generate_messages_py.dir/build.make CMakeFiles/std_msgs_generate_messages_py.dir/build .PHONY : std_msgs_generate_messages_py/fast #============================================================================= # Target rules for targets named nav_msgs_generate_messages_py # Build rule for target. nav_msgs_generate_messages_py: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 nav_msgs_generate_messages_py .PHONY : nav_msgs_generate_messages_py # fast build rule for target. nav_msgs_generate_messages_py/fast: $(MAKE) -f CMakeFiles/nav_msgs_generate_messages_py.dir/build.make CMakeFiles/nav_msgs_generate_messages_py.dir/build .PHONY : nav_msgs_generate_messages_py/fast #============================================================================= # Target rules for targets named geometry_msgs_generate_messages_cpp # Build rule for target. geometry_msgs_generate_messages_cpp: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 geometry_msgs_generate_messages_cpp .PHONY : geometry_msgs_generate_messages_cpp # fast build rule for target. geometry_msgs_generate_messages_cpp/fast: $(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_cpp.dir/build.make CMakeFiles/geometry_msgs_generate_messages_cpp.dir/build .PHONY : geometry_msgs_generate_messages_cpp/fast #============================================================================= # Target rules for targets named sensor_msgs_generate_messages_nodejs # Build rule for target. sensor_msgs_generate_messages_nodejs: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 sensor_msgs_generate_messages_nodejs .PHONY : sensor_msgs_generate_messages_nodejs # fast build rule for target. sensor_msgs_generate_messages_nodejs/fast: $(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/build .PHONY : sensor_msgs_generate_messages_nodejs/fast #============================================================================= # Target rules for targets named std_msgs_generate_messages_nodejs # Build rule for target. std_msgs_generate_messages_nodejs: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 std_msgs_generate_messages_nodejs .PHONY : std_msgs_generate_messages_nodejs # fast build rule for target. std_msgs_generate_messages_nodejs/fast: $(MAKE) -f CMakeFiles/std_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/std_msgs_generate_messages_nodejs.dir/build .PHONY : std_msgs_generate_messages_nodejs/fast #============================================================================= # Target rules for targets named geometry_msgs_generate_messages_py # Build rule for target. geometry_msgs_generate_messages_py: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 geometry_msgs_generate_messages_py .PHONY : geometry_msgs_generate_messages_py # fast build rule for target. geometry_msgs_generate_messages_py/fast: $(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_py.dir/build.make CMakeFiles/geometry_msgs_generate_messages_py.dir/build .PHONY : geometry_msgs_generate_messages_py/fast #============================================================================= # Target rules for targets named actionlib_msgs_generate_messages_lisp # Build rule for target. actionlib_msgs_generate_messages_lisp: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 actionlib_msgs_generate_messages_lisp .PHONY : actionlib_msgs_generate_messages_lisp # fast build rule for target. actionlib_msgs_generate_messages_lisp/fast: $(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/build .PHONY : actionlib_msgs_generate_messages_lisp/fast #============================================================================= # Target rules for targets named tf2_msgs_generate_messages_py # Build rule for target. tf2_msgs_generate_messages_py: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 tf2_msgs_generate_messages_py .PHONY : tf2_msgs_generate_messages_py # fast build rule for target. tf2_msgs_generate_messages_py/fast: $(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_py.dir/build.make CMakeFiles/tf2_msgs_generate_messages_py.dir/build .PHONY : tf2_msgs_generate_messages_py/fast #============================================================================= # Target rules for targets named actionlib_msgs_generate_messages_nodejs # Build rule for target. actionlib_msgs_generate_messages_nodejs: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 actionlib_msgs_generate_messages_nodejs .PHONY : actionlib_msgs_generate_messages_nodejs # fast build rule for target. actionlib_msgs_generate_messages_nodejs/fast: $(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/build .PHONY : actionlib_msgs_generate_messages_nodejs/fast #============================================================================= # Target rules for targets named sensor_msgs_generate_messages_cpp # Build rule for target. sensor_msgs_generate_messages_cpp: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 sensor_msgs_generate_messages_cpp .PHONY : sensor_msgs_generate_messages_cpp # fast build rule for target. sensor_msgs_generate_messages_cpp/fast: $(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_cpp.dir/build.make CMakeFiles/sensor_msgs_generate_messages_cpp.dir/build .PHONY : sensor_msgs_generate_messages_cpp/fast #============================================================================= # Target rules for targets named actionlib_generate_messages_nodejs # Build rule for target. actionlib_generate_messages_nodejs: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 actionlib_generate_messages_nodejs .PHONY : actionlib_generate_messages_nodejs # fast build rule for target. actionlib_generate_messages_nodejs/fast: $(MAKE) -f CMakeFiles/actionlib_generate_messages_nodejs.dir/build.make CMakeFiles/actionlib_generate_messages_nodejs.dir/build .PHONY : actionlib_generate_messages_nodejs/fast #============================================================================= # Target rules for targets named actionlib_msgs_generate_messages_cpp # Build rule for target. actionlib_msgs_generate_messages_cpp: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 actionlib_msgs_generate_messages_cpp .PHONY : actionlib_msgs_generate_messages_cpp # fast build rule for target. actionlib_msgs_generate_messages_cpp/fast: $(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/build .PHONY : actionlib_msgs_generate_messages_cpp/fast #============================================================================= # Target rules for targets named std_msgs_generate_messages_cpp # Build rule for target. std_msgs_generate_messages_cpp: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 std_msgs_generate_messages_cpp .PHONY : std_msgs_generate_messages_cpp # fast build rule for target. std_msgs_generate_messages_cpp/fast: $(MAKE) -f CMakeFiles/std_msgs_generate_messages_cpp.dir/build.make CMakeFiles/std_msgs_generate_messages_cpp.dir/build .PHONY : std_msgs_generate_messages_cpp/fast #============================================================================= # Target rules for targets named sensor_msgs_generate_messages_eus # Build rule for target. sensor_msgs_generate_messages_eus: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 sensor_msgs_generate_messages_eus .PHONY : sensor_msgs_generate_messages_eus # fast build rule for target. sensor_msgs_generate_messages_eus/fast: $(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_eus.dir/build.make CMakeFiles/sensor_msgs_generate_messages_eus.dir/build .PHONY : sensor_msgs_generate_messages_eus/fast #============================================================================= # Target rules for targets named download_extra_data # Build rule for target. download_extra_data: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 download_extra_data .PHONY : download_extra_data # fast build rule for target. download_extra_data/fast: $(MAKE) -f CMakeFiles/download_extra_data.dir/build.make CMakeFiles/download_extra_data.dir/build .PHONY : download_extra_data/fast #============================================================================= # Target rules for targets named sensor_msgs_generate_messages_lisp # Build rule for target. sensor_msgs_generate_messages_lisp: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 sensor_msgs_generate_messages_lisp .PHONY : sensor_msgs_generate_messages_lisp # fast build rule for target. sensor_msgs_generate_messages_lisp/fast: $(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_lisp.dir/build.make CMakeFiles/sensor_msgs_generate_messages_lisp.dir/build .PHONY : sensor_msgs_generate_messages_lisp/fast #============================================================================= # Target rules for targets named actionlib_generate_messages_cpp # Build rule for target. actionlib_generate_messages_cpp: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 actionlib_generate_messages_cpp .PHONY : actionlib_generate_messages_cpp # fast build rule for target. actionlib_generate_messages_cpp/fast: $(MAKE) -f CMakeFiles/actionlib_generate_messages_cpp.dir/build.make CMakeFiles/actionlib_generate_messages_cpp.dir/build .PHONY : actionlib_generate_messages_cpp/fast #============================================================================= # Target rules for targets named sensor_msgs_generate_messages_py # Build rule for target. sensor_msgs_generate_messages_py: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 sensor_msgs_generate_messages_py .PHONY : sensor_msgs_generate_messages_py # fast build rule for target. sensor_msgs_generate_messages_py/fast: $(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_py.dir/build.make CMakeFiles/sensor_msgs_generate_messages_py.dir/build .PHONY : sensor_msgs_generate_messages_py/fast #============================================================================= # Target rules for targets named rosgraph_msgs_generate_messages_py # Build rule for target. rosgraph_msgs_generate_messages_py: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 rosgraph_msgs_generate_messages_py .PHONY : rosgraph_msgs_generate_messages_py # fast build rule for target. rosgraph_msgs_generate_messages_py/fast: $(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_py.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_py.dir/build .PHONY : rosgraph_msgs_generate_messages_py/fast #============================================================================= # Target rules for targets named tf_generate_messages_lisp # Build rule for target. tf_generate_messages_lisp: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 tf_generate_messages_lisp .PHONY : tf_generate_messages_lisp # fast build rule for target. tf_generate_messages_lisp/fast: $(MAKE) -f CMakeFiles/tf_generate_messages_lisp.dir/build.make CMakeFiles/tf_generate_messages_lisp.dir/build .PHONY : tf_generate_messages_lisp/fast #============================================================================= # Target rules for targets named roscpp_generate_messages_py # Build rule for target. roscpp_generate_messages_py: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 roscpp_generate_messages_py .PHONY : roscpp_generate_messages_py # fast build rule for target. roscpp_generate_messages_py/fast: $(MAKE) -f CMakeFiles/roscpp_generate_messages_py.dir/build.make CMakeFiles/roscpp_generate_messages_py.dir/build .PHONY : roscpp_generate_messages_py/fast #============================================================================= # Target rules for targets named tf_generate_messages_nodejs # Build rule for target. tf_generate_messages_nodejs: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 tf_generate_messages_nodejs .PHONY : tf_generate_messages_nodejs # fast build rule for target. tf_generate_messages_nodejs/fast: $(MAKE) -f CMakeFiles/tf_generate_messages_nodejs.dir/build.make CMakeFiles/tf_generate_messages_nodejs.dir/build .PHONY : tf_generate_messages_nodejs/fast #============================================================================= # Target rules for targets named tf_generate_messages_py # Build rule for target. tf_generate_messages_py: cmake_check_build_system $(MAKE) -f CMakeFiles/Makefile2 tf_generate_messages_py .PHONY : tf_generate_messages_py # fast build rule for target. tf_generate_messages_py/fast: $(MAKE) -f CMakeFiles/tf_generate_messages_py.dir/build.make CMakeFiles/tf_generate_messages_py.dir/build .PHONY : tf_generate_messages_py/fast src/CLaserOdometry2D.o: src/CLaserOdometry2D.cpp.o .PHONY : src/CLaserOdometry2D.o # target to build an object file src/CLaserOdometry2D.cpp.o: $(MAKE) -f CMakeFiles/rf2o_laser_odometry_node.dir/build.make CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o .PHONY : src/CLaserOdometry2D.cpp.o src/CLaserOdometry2D.i: src/CLaserOdometry2D.cpp.i .PHONY : src/CLaserOdometry2D.i # target to preprocess a source file src/CLaserOdometry2D.cpp.i: $(MAKE) -f CMakeFiles/rf2o_laser_odometry_node.dir/build.make CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.i .PHONY : src/CLaserOdometry2D.cpp.i src/CLaserOdometry2D.s: src/CLaserOdometry2D.cpp.s .PHONY : src/CLaserOdometry2D.s # target to generate assembly for a file src/CLaserOdometry2D.cpp.s: $(MAKE) -f CMakeFiles/rf2o_laser_odometry_node.dir/build.make CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.s .PHONY : src/CLaserOdometry2D.cpp.s # Help Target help: @echo "The following are some of the valid targets for this Makefile:" @echo "... all (the default if no target is provided)" @echo "... clean" @echo "... depend" @echo "... install/local" @echo "... edit_cache" @echo "... tf2_msgs_generate_messages_nodejs" @echo "... tf2_msgs_generate_messages_lisp" @echo "... tf2_msgs_generate_messages_eus" @echo "... tf2_msgs_generate_messages_cpp" @echo "... actionlib_generate_messages_py" @echo "... actionlib_generate_messages_eus" @echo "... install/strip" @echo "... nav_msgs_generate_messages_eus" @echo "... std_msgs_generate_messages_eus" @echo "... roscpp_generate_messages_lisp" @echo "... rosgraph_msgs_generate_messages_lisp" @echo "... tests" @echo "... rf2o_laser_odometry_node" @echo "... roscpp_generate_messages_nodejs" @echo "... rebuild_cache" @echo "... tf_generate_messages_eus" @echo "... rosgraph_msgs_generate_messages_nodejs" @echo "... nav_msgs_generate_messages_cpp" @echo "... install" @echo "... std_msgs_generate_messages_lisp" @echo "... geometry_msgs_generate_messages_lisp" @echo "... rosgraph_msgs_generate_messages_cpp" @echo "... run_tests" @echo "... actionlib_generate_messages_lisp" @echo "... actionlib_msgs_generate_messages_eus" @echo "... list_install_components" @echo "... roscpp_generate_messages_eus" @echo "... roscpp_generate_messages_cpp" @echo "... geometry_msgs_generate_messages_eus" @echo "... actionlib_msgs_generate_messages_py" @echo "... clean_test_results" @echo "... geometry_msgs_generate_messages_nodejs" @echo "... rosgraph_msgs_generate_messages_eus" @echo "... doxygen" @echo "... tf_generate_messages_cpp" @echo "... nav_msgs_generate_messages_lisp" @echo "... nav_msgs_generate_messages_nodejs" @echo "... std_msgs_generate_messages_py" @echo "... nav_msgs_generate_messages_py" @echo "... test" @echo "... geometry_msgs_generate_messages_cpp" @echo "... sensor_msgs_generate_messages_nodejs" @echo "... std_msgs_generate_messages_nodejs" @echo "... geometry_msgs_generate_messages_py" @echo "... actionlib_msgs_generate_messages_lisp" @echo "... tf2_msgs_generate_messages_py" @echo "... actionlib_msgs_generate_messages_nodejs" @echo "... sensor_msgs_generate_messages_cpp" @echo "... actionlib_generate_messages_nodejs" @echo "... actionlib_msgs_generate_messages_cpp" @echo "... std_msgs_generate_messages_cpp" @echo "... sensor_msgs_generate_messages_eus" @echo "... download_extra_data" @echo "... sensor_msgs_generate_messages_lisp" @echo "... actionlib_generate_messages_cpp" @echo "... sensor_msgs_generate_messages_py" @echo "... rosgraph_msgs_generate_messages_py" @echo "... tf_generate_messages_lisp" @echo "... roscpp_generate_messages_py" @echo "... tf_generate_messages_nodejs" @echo "... tf_generate_messages_py" @echo "... src/CLaserOdometry2D.o" @echo "... src/CLaserOdometry2D.i" @echo "... src/CLaserOdometry2D.s" .PHONY : help #============================================================================= # Special targets to cleanup operation of make. # Special rule to run CMake to check the build system integrity. # No rule that depends on this can have commands that come from listfiles # because they might be regenerated. cmake_check_build_system: $(CMAKE_COMMAND) -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 0 .PHONY : cmake_check_build_system ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/catkin/catkin_generated/version/package.cmake ================================================ set(_CATKIN_CURRENT_PACKAGE "catkin") set(catkin_VERSION "0.7.11") set(catkin_MAINTAINER "Dirk Thomas ") set(catkin_PACKAGE_FORMAT "2") set(catkin_BUILD_DEPENDS "python-empy" "python-argparse" "python-catkin-pkg") set(catkin_BUILD_DEPENDS_python-catkin-pkg_VERSION_GT "0.2.9") set(catkin_BUILD_EXPORT_DEPENDS "google-mock" "gtest" "python-empy" "python-nose" "python-argparse" "python-catkin-pkg") set(catkin_BUILD_EXPORT_DEPENDS_python-catkin-pkg_VERSION_GT "0.2.9") set(catkin_BUILDTOOL_DEPENDS "cmake") set(catkin_BUILDTOOL_EXPORT_DEPENDS "cmake") set(catkin_EXEC_DEPENDS "python-argparse" "python-catkin-pkg") set(catkin_EXEC_DEPENDS_python-catkin-pkg_VERSION_GT "0.2.9") set(catkin_RUN_DEPENDS "python-argparse" "python-catkin-pkg" "google-mock" "gtest" "python-empy" "python-nose") set(catkin_RUN_DEPENDS_python-catkin-pkg_VERSION_GT "0.2.9") set(catkin_TEST_DEPENDS "python-mock" "python-nose") set(catkin_DOC_DEPENDS ) set(catkin_URL_WEBSITE "http://www.ros.org/wiki/catkin") set(catkin_URL_BUGTRACKER "https://github.com/ros/catkin/issues") set(catkin_URL_REPOSITORY "https://github.com/ros/catkin") set(catkin_DEPRECATED "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/env_cached.sh ================================================ #!/usr/bin/env sh # generated from catkin/cmake/templates/env.sh.in if [ $# -eq 0 ] ; then /bin/echo "Usage: env.sh COMMANDS" /bin/echo "Calling env.sh without arguments is not supported anymore. Instead spawn a subshell and source a setup file manually." exit 1 fi # ensure to not use different shell type which was set before CATKIN_SHELL=sh # source setup_cached.sh from same directory as this file _CATKIN_SETUP_DIR=$(cd "`dirname "$0"`" > /dev/null && pwd) . "$_CATKIN_SETUP_DIR/setup_cached.sh" exec "$@" ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/generate_cached_setup.py ================================================ # -*- coding: utf-8 -*- from __future__ import print_function import argparse import os import stat import sys # find the import for catkin's python package - either from source space or from an installed underlay if os.path.exists(os.path.join('/opt/ros/kinetic/share/catkin/cmake', 'catkinConfig.cmake.in')): sys.path.insert(0, os.path.join('/opt/ros/kinetic/share/catkin/cmake', '..', 'python')) try: from catkin.environment_cache import generate_environment_script except ImportError: # search for catkin package in all workspaces and prepend to path for workspace in "/home/zn/artrobot/devel;/opt/ros/kinetic".split(';'): python_path = os.path.join(workspace, 'lib/python2.7/dist-packages') if os.path.isdir(os.path.join(python_path, 'catkin')): sys.path.insert(0, python_path) break from catkin.environment_cache import generate_environment_script code = generate_environment_script('/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/devel/env.sh') output_filename = '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/setup_cached.sh' with open(output_filename, 'w') as f: #print('Generate script for cached setup "%s"' % output_filename) f.write('\n'.join(code)) mode = os.stat(output_filename).st_mode os.chmod(output_filename, mode | stat.S_IXUSR) ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/installspace/.rosinstall ================================================ - setup-file: local-name: /usr/local/setup.sh ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/installspace/_setup_util.py ================================================ #!/usr/bin/python # -*- coding: utf-8 -*- # Software License Agreement (BSD License) # # Copyright (c) 2012, Willow Garage, Inc. # All rights reserved. # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions # are met: # # * Redistributions of source code must retain the above copyright # notice, this list of conditions and the following disclaimer. # * Redistributions in binary form must reproduce the above # copyright notice, this list of conditions and the following # disclaimer in the documentation and/or other materials provided # with the distribution. # * Neither the name of Willow Garage, Inc. nor the names of its # contributors may be used to endorse or promote products derived # from this software without specific prior written permission. # # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. '''This file generates shell code for the setup.SHELL scripts to set environment variables''' from __future__ import print_function import argparse import copy import errno import os import platform import sys CATKIN_MARKER_FILE = '.catkin' system = platform.system() IS_DARWIN = (system == 'Darwin') IS_WINDOWS = (system == 'Windows') # subfolder of workspace prepended to CMAKE_PREFIX_PATH ENV_VAR_SUBFOLDERS = { 'CMAKE_PREFIX_PATH': '', 'LD_LIBRARY_PATH' if not IS_DARWIN else 'DYLD_LIBRARY_PATH': ['lib', os.path.join('lib', 'x86_64-linux-gnu')], 'PATH': 'bin', 'PKG_CONFIG_PATH': [os.path.join('lib', 'pkgconfig'), os.path.join('lib', 'x86_64-linux-gnu', 'pkgconfig')], 'PYTHONPATH': 'lib/python2.7/dist-packages', } def rollback_env_variables(environ, env_var_subfolders): ''' Generate shell code to reset environment variables by unrolling modifications based on all workspaces in CMAKE_PREFIX_PATH. This does not cover modifications performed by environment hooks. ''' lines = [] unmodified_environ = copy.copy(environ) for key in sorted(env_var_subfolders.keys()): subfolders = env_var_subfolders[key] if not isinstance(subfolders, list): subfolders = [subfolders] value = _rollback_env_variable(unmodified_environ, key, subfolders) if value is not None: environ[key] = value lines.append(assignment(key, value)) if lines: lines.insert(0, comment('reset environment variables by unrolling modifications based on all workspaces in CMAKE_PREFIX_PATH')) return lines def _rollback_env_variable(environ, name, subfolders): ''' For each catkin workspace in CMAKE_PREFIX_PATH remove the first entry from env[NAME] matching workspace + subfolder. :param subfolders: list of str '' or subfoldername that may start with '/' :returns: the updated value of the environment variable. ''' value = environ[name] if name in environ else '' env_paths = [path for path in value.split(os.pathsep) if path] value_modified = False for subfolder in subfolders: if subfolder: if subfolder.startswith(os.path.sep) or (os.path.altsep and subfolder.startswith(os.path.altsep)): subfolder = subfolder[1:] if subfolder.endswith(os.path.sep) or (os.path.altsep and subfolder.endswith(os.path.altsep)): subfolder = subfolder[:-1] for ws_path in _get_workspaces(environ, include_fuerte=True, include_non_existing=True): path_to_find = os.path.join(ws_path, subfolder) if subfolder else ws_path path_to_remove = None for env_path in env_paths: env_path_clean = env_path[:-1] if env_path and env_path[-1] in [os.path.sep, os.path.altsep] else env_path if env_path_clean == path_to_find: path_to_remove = env_path break if path_to_remove: env_paths.remove(path_to_remove) value_modified = True new_value = os.pathsep.join(env_paths) return new_value if value_modified else None def _get_workspaces(environ, include_fuerte=False, include_non_existing=False): ''' Based on CMAKE_PREFIX_PATH return all catkin workspaces. :param include_fuerte: The flag if paths starting with '/opt/ros/fuerte' should be considered workspaces, ``bool`` ''' # get all cmake prefix paths env_name = 'CMAKE_PREFIX_PATH' value = environ[env_name] if env_name in environ else '' paths = [path for path in value.split(os.pathsep) if path] # remove non-workspace paths workspaces = [path for path in paths if os.path.isfile(os.path.join(path, CATKIN_MARKER_FILE)) or (include_fuerte and path.startswith('/opt/ros/fuerte')) or (include_non_existing and not os.path.exists(path))] return workspaces def prepend_env_variables(environ, env_var_subfolders, workspaces): ''' Generate shell code to prepend environment variables for the all workspaces. ''' lines = [] lines.append(comment('prepend folders of workspaces to environment variables')) paths = [path for path in workspaces.split(os.pathsep) if path] prefix = _prefix_env_variable(environ, 'CMAKE_PREFIX_PATH', paths, '') lines.append(prepend(environ, 'CMAKE_PREFIX_PATH', prefix)) for key in sorted([key for key in env_var_subfolders.keys() if key != 'CMAKE_PREFIX_PATH']): subfolder = env_var_subfolders[key] prefix = _prefix_env_variable(environ, key, paths, subfolder) lines.append(prepend(environ, key, prefix)) return lines def _prefix_env_variable(environ, name, paths, subfolders): ''' Return the prefix to prepend to the environment variable NAME, adding any path in NEW_PATHS_STR without creating duplicate or empty items. ''' value = environ[name] if name in environ else '' environ_paths = [path for path in value.split(os.pathsep) if path] checked_paths = [] for path in paths: if not isinstance(subfolders, list): subfolders = [subfolders] for subfolder in subfolders: path_tmp = path if subfolder: path_tmp = os.path.join(path_tmp, subfolder) # skip nonexistent paths if not os.path.exists(path_tmp): continue # exclude any path already in env and any path we already added if path_tmp not in environ_paths and path_tmp not in checked_paths: checked_paths.append(path_tmp) prefix_str = os.pathsep.join(checked_paths) if prefix_str != '' and environ_paths: prefix_str += os.pathsep return prefix_str def assignment(key, value): if not IS_WINDOWS: return 'export %s="%s"' % (key, value) else: return 'set %s=%s' % (key, value) def comment(msg): if not IS_WINDOWS: return '# %s' % msg else: return 'REM %s' % msg def prepend(environ, key, prefix): if key not in environ or not environ[key]: return assignment(key, prefix) if not IS_WINDOWS: return 'export %s="%s$%s"' % (key, prefix, key) else: return 'set %s=%s%%%s%%' % (key, prefix, key) def find_env_hooks(environ, cmake_prefix_path): ''' Generate shell code with found environment hooks for the all workspaces. ''' lines = [] lines.append(comment('found environment hooks in workspaces')) generic_env_hooks = [] generic_env_hooks_workspace = [] specific_env_hooks = [] specific_env_hooks_workspace = [] generic_env_hooks_by_filename = {} specific_env_hooks_by_filename = {} generic_env_hook_ext = 'bat' if IS_WINDOWS else 'sh' specific_env_hook_ext = environ['CATKIN_SHELL'] if not IS_WINDOWS and 'CATKIN_SHELL' in environ and environ['CATKIN_SHELL'] else None # remove non-workspace paths workspaces = [path for path in cmake_prefix_path.split(os.pathsep) if path and os.path.isfile(os.path.join(path, CATKIN_MARKER_FILE))] for workspace in reversed(workspaces): env_hook_dir = os.path.join(workspace, 'etc', 'catkin', 'profile.d') if os.path.isdir(env_hook_dir): for filename in sorted(os.listdir(env_hook_dir)): if filename.endswith('.%s' % generic_env_hook_ext): # remove previous env hook with same name if present if filename in generic_env_hooks_by_filename: i = generic_env_hooks.index(generic_env_hooks_by_filename[filename]) generic_env_hooks.pop(i) generic_env_hooks_workspace.pop(i) # append env hook generic_env_hooks.append(os.path.join(env_hook_dir, filename)) generic_env_hooks_workspace.append(workspace) generic_env_hooks_by_filename[filename] = generic_env_hooks[-1] elif specific_env_hook_ext is not None and filename.endswith('.%s' % specific_env_hook_ext): # remove previous env hook with same name if present if filename in specific_env_hooks_by_filename: i = specific_env_hooks.index(specific_env_hooks_by_filename[filename]) specific_env_hooks.pop(i) specific_env_hooks_workspace.pop(i) # append env hook specific_env_hooks.append(os.path.join(env_hook_dir, filename)) specific_env_hooks_workspace.append(workspace) specific_env_hooks_by_filename[filename] = specific_env_hooks[-1] env_hooks = generic_env_hooks + specific_env_hooks env_hooks_workspace = generic_env_hooks_workspace + specific_env_hooks_workspace count = len(env_hooks) lines.append(assignment('_CATKIN_ENVIRONMENT_HOOKS_COUNT', count)) for i in range(count): lines.append(assignment('_CATKIN_ENVIRONMENT_HOOKS_%d' % i, env_hooks[i])) lines.append(assignment('_CATKIN_ENVIRONMENT_HOOKS_%d_WORKSPACE' % i, env_hooks_workspace[i])) return lines def _parse_arguments(args=None): parser = argparse.ArgumentParser(description='Generates code blocks for the setup.SHELL script.') parser.add_argument('--extend', action='store_true', help='Skip unsetting previous environment variables to extend context') return parser.parse_known_args(args=args)[0] if __name__ == '__main__': try: try: args = _parse_arguments() except Exception as e: print(e, file=sys.stderr) sys.exit(1) # environment at generation time CMAKE_PREFIX_PATH = '/home/zn/artrobot/devel;/opt/ros/kinetic'.split(';') # prepend current workspace if not already part of CPP base_path = os.path.dirname(__file__) if base_path not in CMAKE_PREFIX_PATH: CMAKE_PREFIX_PATH.insert(0, base_path) CMAKE_PREFIX_PATH = os.pathsep.join(CMAKE_PREFIX_PATH) environ = dict(os.environ) lines = [] if not args.extend: lines += rollback_env_variables(environ, ENV_VAR_SUBFOLDERS) lines += prepend_env_variables(environ, ENV_VAR_SUBFOLDERS, CMAKE_PREFIX_PATH) lines += find_env_hooks(environ, CMAKE_PREFIX_PATH) print('\n'.join(lines)) # need to explicitly flush the output sys.stdout.flush() except IOError as e: # and catch potential "broken pipe" if stdout is not writable # which can happen when piping the output to a file but the disk is full if e.errno == errno.EPIPE: print(e, file=sys.stderr) sys.exit(2) raise sys.exit(0) ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/installspace/env.sh ================================================ #!/usr/bin/env sh # generated from catkin/cmake/templates/env.sh.in if [ $# -eq 0 ] ; then /bin/echo "Usage: env.sh COMMANDS" /bin/echo "Calling env.sh without arguments is not supported anymore. Instead spawn a subshell and source a setup file manually." exit 1 fi # ensure to not use different shell type which was set before CATKIN_SHELL=sh # source setup.sh from same directory as this file _CATKIN_SETUP_DIR=$(cd "`dirname "$0"`" > /dev/null && pwd) . "$_CATKIN_SETUP_DIR/setup.sh" exec "$@" ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/installspace/rf2o_laser_odometry.pc ================================================ prefix=/usr/local Name: rf2o_laser_odometry Description: Description of rf2o_laser_odometry Version: 1.0.0 Cflags: -I/usr/local/include Libs: -L/usr/local/lib -llaser_odometry Requires: nav_msgs roscpp sensor_msgs std_msgs tf ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/installspace/rf2o_laser_odometryConfig-version.cmake ================================================ # generated from catkin/cmake/template/pkgConfig-version.cmake.in set(PACKAGE_VERSION "1.0.0") set(PACKAGE_VERSION_EXACT False) set(PACKAGE_VERSION_COMPATIBLE False) if("${PACKAGE_FIND_VERSION}" VERSION_EQUAL "${PACKAGE_VERSION}") set(PACKAGE_VERSION_EXACT True) set(PACKAGE_VERSION_COMPATIBLE True) endif() if("${PACKAGE_FIND_VERSION}" VERSION_LESS "${PACKAGE_VERSION}") set(PACKAGE_VERSION_COMPATIBLE True) endif() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/installspace/rf2o_laser_odometryConfig.cmake ================================================ # generated from catkin/cmake/template/pkgConfig.cmake.in # append elements to a list and remove existing duplicates from the list # copied from catkin/cmake/list_append_deduplicate.cmake to keep pkgConfig # self contained macro(_list_append_deduplicate listname) if(NOT "${ARGN}" STREQUAL "") if(${listname}) list(REMOVE_ITEM ${listname} ${ARGN}) endif() list(APPEND ${listname} ${ARGN}) endif() endmacro() # append elements to a list if they are not already in the list # copied from catkin/cmake/list_append_unique.cmake to keep pkgConfig # self contained macro(_list_append_unique listname) foreach(_item ${ARGN}) list(FIND ${listname} ${_item} _index) if(_index EQUAL -1) list(APPEND ${listname} ${_item}) endif() endforeach() endmacro() # pack a list of libraries with optional build configuration keywords # copied from catkin/cmake/catkin_libraries.cmake to keep pkgConfig # self contained macro(_pack_libraries_with_build_configuration VAR) set(${VAR} "") set(_argn ${ARGN}) list(LENGTH _argn _count) set(_index 0) while(${_index} LESS ${_count}) list(GET _argn ${_index} lib) if("${lib}" MATCHES "^(debug|optimized|general)$") math(EXPR _index "${_index} + 1") if(${_index} EQUAL ${_count}) message(FATAL_ERROR "_pack_libraries_with_build_configuration() the list of libraries '${ARGN}' ends with '${lib}' which is a build configuration keyword and must be followed by a library") endif() list(GET _argn ${_index} library) list(APPEND ${VAR} "${lib}${CATKIN_BUILD_CONFIGURATION_KEYWORD_SEPARATOR}${library}") else() list(APPEND ${VAR} "${lib}") endif() math(EXPR _index "${_index} + 1") endwhile() endmacro() # unpack a list of libraries with optional build configuration keyword prefixes # copied from catkin/cmake/catkin_libraries.cmake to keep pkgConfig # self contained macro(_unpack_libraries_with_build_configuration VAR) set(${VAR} "") foreach(lib ${ARGN}) string(REGEX REPLACE "^(debug|optimized|general)${CATKIN_BUILD_CONFIGURATION_KEYWORD_SEPARATOR}(.+)$" "\\1;\\2" lib "${lib}") list(APPEND ${VAR} "${lib}") endforeach() endmacro() if(rf2o_laser_odometry_CONFIG_INCLUDED) return() endif() set(rf2o_laser_odometry_CONFIG_INCLUDED TRUE) # set variables for source/devel/install prefixes if("FALSE" STREQUAL "TRUE") set(rf2o_laser_odometry_SOURCE_PREFIX /home/zn/racecar/src/rf2o_laser_odometry) set(rf2o_laser_odometry_DEVEL_PREFIX /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/devel) set(rf2o_laser_odometry_INSTALL_PREFIX "") set(rf2o_laser_odometry_PREFIX ${rf2o_laser_odometry_DEVEL_PREFIX}) else() set(rf2o_laser_odometry_SOURCE_PREFIX "") set(rf2o_laser_odometry_DEVEL_PREFIX "") set(rf2o_laser_odometry_INSTALL_PREFIX /usr/local) set(rf2o_laser_odometry_PREFIX ${rf2o_laser_odometry_INSTALL_PREFIX}) endif() # warn when using a deprecated package if(NOT "" STREQUAL "") set(_msg "WARNING: package 'rf2o_laser_odometry' is deprecated") # append custom deprecation text if available if(NOT "" STREQUAL "TRUE") set(_msg "${_msg} ()") endif() message("${_msg}") endif() # flag project as catkin-based to distinguish if a find_package()-ed project is a catkin project set(rf2o_laser_odometry_FOUND_CATKIN_PROJECT TRUE) if(NOT "include " STREQUAL " ") set(rf2o_laser_odometry_INCLUDE_DIRS "") set(_include_dirs "include") if(NOT " " STREQUAL " ") set(_report "Check the issue tracker '' and consider creating a ticket if the problem has not been reported yet.") elseif(NOT " " STREQUAL " ") set(_report "Check the website '' for information and consider reporting the problem.") else() set(_report "Report the problem to the maintainer 'Javier G. Monroy ' and request to fix the problem.") endif() foreach(idir ${_include_dirs}) if(IS_ABSOLUTE ${idir} AND IS_DIRECTORY ${idir}) set(include ${idir}) elseif("${idir} " STREQUAL "include ") get_filename_component(include "${rf2o_laser_odometry_DIR}/../../../include" ABSOLUTE) if(NOT IS_DIRECTORY ${include}) message(FATAL_ERROR "Project 'rf2o_laser_odometry' specifies '${idir}' as an include dir, which is not found. It does not exist in '${include}'. ${_report}") endif() else() message(FATAL_ERROR "Project 'rf2o_laser_odometry' specifies '${idir}' as an include dir, which is not found. It does neither exist as an absolute directory nor in '/usr/local/${idir}'. ${_report}") endif() _list_append_unique(rf2o_laser_odometry_INCLUDE_DIRS ${include}) endforeach() endif() set(libraries "laser_odometry") foreach(library ${libraries}) # keep build configuration keywords, target names and absolute libraries as-is if("${library}" MATCHES "^(debug|optimized|general)$") list(APPEND rf2o_laser_odometry_LIBRARIES ${library}) elseif(TARGET ${library}) list(APPEND rf2o_laser_odometry_LIBRARIES ${library}) elseif(IS_ABSOLUTE ${library}) list(APPEND rf2o_laser_odometry_LIBRARIES ${library}) else() set(lib_path "") set(lib "${library}-NOTFOUND") # since the path where the library is found is returned we have to iterate over the paths manually foreach(path /usr/local/lib;/home/zn/artrobot/devel/lib;/opt/ros/kinetic/lib) find_library(lib ${library} PATHS ${path} NO_DEFAULT_PATH NO_CMAKE_FIND_ROOT_PATH) if(lib) set(lib_path ${path}) break() endif() endforeach() if(lib) _list_append_unique(rf2o_laser_odometry_LIBRARY_DIRS ${lib_path}) list(APPEND rf2o_laser_odometry_LIBRARIES ${lib}) else() # as a fall back for non-catkin libraries try to search globally find_library(lib ${library}) if(NOT lib) message(FATAL_ERROR "Project '${PROJECT_NAME}' tried to find library '${library}'. The library is neither a target nor built/installed properly. Did you compile project 'rf2o_laser_odometry'? Did you find_package() it before the subdirectory containing its code is included?") endif() list(APPEND rf2o_laser_odometry_LIBRARIES ${lib}) endif() endif() endforeach() set(rf2o_laser_odometry_EXPORTED_TARGETS "") # create dummy targets for exported code generation targets to make life of users easier foreach(t ${rf2o_laser_odometry_EXPORTED_TARGETS}) if(NOT TARGET ${t}) add_custom_target(${t}) endif() endforeach() set(depends "nav_msgs;roscpp;sensor_msgs;std_msgs;tf") foreach(depend ${depends}) string(REPLACE " " ";" depend_list ${depend}) # the package name of the dependency must be kept in a unique variable so that it is not overwritten in recursive calls list(GET depend_list 0 rf2o_laser_odometry_dep) list(LENGTH depend_list count) if(${count} EQUAL 1) # simple dependencies must only be find_package()-ed once if(NOT ${rf2o_laser_odometry_dep}_FOUND) find_package(${rf2o_laser_odometry_dep} REQUIRED NO_MODULE) endif() else() # dependencies with components must be find_package()-ed again list(REMOVE_AT depend_list 0) find_package(${rf2o_laser_odometry_dep} REQUIRED NO_MODULE ${depend_list}) endif() _list_append_unique(rf2o_laser_odometry_INCLUDE_DIRS ${${rf2o_laser_odometry_dep}_INCLUDE_DIRS}) # merge build configuration keywords with library names to correctly deduplicate _pack_libraries_with_build_configuration(rf2o_laser_odometry_LIBRARIES ${rf2o_laser_odometry_LIBRARIES}) _pack_libraries_with_build_configuration(_libraries ${${rf2o_laser_odometry_dep}_LIBRARIES}) _list_append_deduplicate(rf2o_laser_odometry_LIBRARIES ${_libraries}) # undo build configuration keyword merging after deduplication _unpack_libraries_with_build_configuration(rf2o_laser_odometry_LIBRARIES ${rf2o_laser_odometry_LIBRARIES}) _list_append_unique(rf2o_laser_odometry_LIBRARY_DIRS ${${rf2o_laser_odometry_dep}_LIBRARY_DIRS}) list(APPEND rf2o_laser_odometry_EXPORTED_TARGETS ${${rf2o_laser_odometry_dep}_EXPORTED_TARGETS}) endforeach() set(pkg_cfg_extras "") foreach(extra ${pkg_cfg_extras}) if(NOT IS_ABSOLUTE ${extra}) set(extra ${rf2o_laser_odometry_DIR}/${extra}) endif() include(${extra}) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/installspace/setup.bash ================================================ #!/usr/bin/env bash # generated from catkin/cmake/templates/setup.bash.in CATKIN_SHELL=bash # source setup.sh from same directory as this file _CATKIN_SETUP_DIR=$(builtin cd "`dirname "${BASH_SOURCE[0]}"`" > /dev/null && pwd) . "$_CATKIN_SETUP_DIR/setup.sh" ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/installspace/setup.sh ================================================ #!/usr/bin/env sh # generated from catkin/cmake/template/setup.sh.in # Sets various environment variables and sources additional environment hooks. # It tries it's best to undo changes from a previously sourced setup file before. # Supported command line options: # --extend: skips the undoing of changes from a previously sourced setup file # (in plain sh shell which does't support arguments for sourced scripts you # can set the environment variable `CATKIN_SETUP_UTIL_ARGS=--extend` instead) # since this file is sourced either use the provided _CATKIN_SETUP_DIR # or fall back to the destination set at configure time : ${_CATKIN_SETUP_DIR:=/usr/local} _SETUP_UTIL="$_CATKIN_SETUP_DIR/_setup_util.py" unset _CATKIN_SETUP_DIR if [ ! -f "$_SETUP_UTIL" ]; then echo "Missing Python script: $_SETUP_UTIL" return 22 fi # detect if running on Darwin platform _UNAME=`uname -s` _IS_DARWIN=0 if [ "$_UNAME" = "Darwin" ]; then _IS_DARWIN=1 fi unset _UNAME # make sure to export all environment variables export CMAKE_PREFIX_PATH if [ $_IS_DARWIN -eq 0 ]; then export LD_LIBRARY_PATH else export DYLD_LIBRARY_PATH fi unset _IS_DARWIN export PATH export PKG_CONFIG_PATH export PYTHONPATH # remember type of shell if not already set if [ -z "$CATKIN_SHELL" ]; then CATKIN_SHELL=sh fi # invoke Python script to generate necessary exports of environment variables # use TMPDIR if it exists, otherwise fall back to /tmp if [ -d "${TMPDIR:-}" ]; then _TMPDIR="${TMPDIR}" else _TMPDIR=/tmp fi _SETUP_TMP=`mktemp "${_TMPDIR}/setup.sh.XXXXXXXXXX"` unset _TMPDIR if [ $? -ne 0 -o ! -f "$_SETUP_TMP" ]; then echo "Could not create temporary file: $_SETUP_TMP" return 1 fi CATKIN_SHELL=$CATKIN_SHELL "$_SETUP_UTIL" $@ ${CATKIN_SETUP_UTIL_ARGS:-} >> "$_SETUP_TMP" _RC=$? if [ $_RC -ne 0 ]; then if [ $_RC -eq 2 ]; then echo "Could not write the output of '$_SETUP_UTIL' to temporary file '$_SETUP_TMP': may be the disk if full?" else echo "Failed to run '\"$_SETUP_UTIL\" $@': return code $_RC" fi unset _RC unset _SETUP_UTIL rm -f "$_SETUP_TMP" unset _SETUP_TMP return 1 fi unset _RC unset _SETUP_UTIL . "$_SETUP_TMP" rm -f "$_SETUP_TMP" unset _SETUP_TMP # source all environment hooks _i=0 while [ $_i -lt $_CATKIN_ENVIRONMENT_HOOKS_COUNT ]; do eval _envfile=\$_CATKIN_ENVIRONMENT_HOOKS_$_i unset _CATKIN_ENVIRONMENT_HOOKS_$_i eval _envfile_workspace=\$_CATKIN_ENVIRONMENT_HOOKS_${_i}_WORKSPACE unset _CATKIN_ENVIRONMENT_HOOKS_${_i}_WORKSPACE # set workspace for environment hook CATKIN_ENV_HOOK_WORKSPACE=$_envfile_workspace . "$_envfile" unset CATKIN_ENV_HOOK_WORKSPACE _i=$((_i + 1)) done unset _i unset _CATKIN_ENVIRONMENT_HOOKS_COUNT ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/installspace/setup.zsh ================================================ #!/usr/bin/env zsh # generated from catkin/cmake/templates/setup.zsh.in CATKIN_SHELL=zsh # source setup.sh from same directory as this file _CATKIN_SETUP_DIR=$(builtin cd -q "`dirname "$0"`" > /dev/null && pwd) emulate -R zsh -c 'source "$_CATKIN_SETUP_DIR/setup.sh"' ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/ordered_paths.cmake ================================================ set(ORDERED_PATHS "/opt/ros/kinetic/lib") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/package.cmake ================================================ set(_CATKIN_CURRENT_PACKAGE "rf2o_laser_odometry") set(rf2o_laser_odometry_VERSION "1.0.0") set(rf2o_laser_odometry_MAINTAINER "Javier G. Monroy ") set(rf2o_laser_odometry_PACKAGE_FORMAT "1") set(rf2o_laser_odometry_BUILD_DEPENDS "nav_msgs" "roscpp" "sensor_msgs" "std_msgs" "tf" "cmake_modules" "mrpt") set(rf2o_laser_odometry_BUILD_EXPORT_DEPENDS "nav_msgs" "roscpp" "sensor_msgs" "std_msgs" "tf" "cmake_modules" "mrpt") set(rf2o_laser_odometry_BUILDTOOL_DEPENDS "catkin") set(rf2o_laser_odometry_BUILDTOOL_EXPORT_DEPENDS ) set(rf2o_laser_odometry_EXEC_DEPENDS "nav_msgs" "roscpp" "sensor_msgs" "std_msgs" "tf" "cmake_modules" "mrpt") set(rf2o_laser_odometry_RUN_DEPENDS "nav_msgs" "roscpp" "sensor_msgs" "std_msgs" "tf" "cmake_modules" "mrpt") set(rf2o_laser_odometry_TEST_DEPENDS ) set(rf2o_laser_odometry_DOC_DEPENDS ) set(rf2o_laser_odometry_URL_WEBSITE "") set(rf2o_laser_odometry_URL_BUGTRACKER "") set(rf2o_laser_odometry_URL_REPOSITORY "") set(rf2o_laser_odometry_DEPRECATED "") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/pkg.develspace.context.pc.py ================================================ # generated from catkin/cmake/template/pkg.context.pc.in CATKIN_PACKAGE_PREFIX = "" PROJECT_PKG_CONFIG_INCLUDE_DIRS = "/home/zn/racecar/src/rf2o_laser_odometry/include".split(';') if "/home/zn/racecar/src/rf2o_laser_odometry/include" != "" else [] PROJECT_CATKIN_DEPENDS = "nav_msgs;roscpp;sensor_msgs;std_msgs;tf".replace(';', ' ') PKG_CONFIG_LIBRARIES_WITH_PREFIX = "-llaser_odometry".split(';') if "-llaser_odometry" != "" else [] PROJECT_NAME = "rf2o_laser_odometry" PROJECT_SPACE_DIR = "/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/devel" PROJECT_VERSION = "1.0.0" ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/pkg.installspace.context.pc.py ================================================ # generated from catkin/cmake/template/pkg.context.pc.in CATKIN_PACKAGE_PREFIX = "" PROJECT_PKG_CONFIG_INCLUDE_DIRS = "/usr/local/include".split(';') if "/usr/local/include" != "" else [] PROJECT_CATKIN_DEPENDS = "nav_msgs;roscpp;sensor_msgs;std_msgs;tf".replace(';', ' ') PKG_CONFIG_LIBRARIES_WITH_PREFIX = "-llaser_odometry".split(';') if "-llaser_odometry" != "" else [] PROJECT_NAME = "rf2o_laser_odometry" PROJECT_SPACE_DIR = "/usr/local" PROJECT_VERSION = "1.0.0" ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/setup_cached.sh ================================================ #!/usr/bin/env sh # generated from catkin/python/catkin/environment_cache.py # based on a snapshot of the environment before and after calling the setup script # it emulates the modifications of the setup script without recurring computations # new environment variables # modified environment variables export CMAKE_PREFIX_PATH="/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/devel:$CMAKE_PREFIX_PATH" export ROSLISP_PACKAGE_DIRECTORIES="/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/devel/share/common-lisp:$ROSLISP_PACKAGE_DIRECTORIES" export ROS_PACKAGE_PATH="/home/zn/racecar/src/rf2o_laser_odometry:$ROS_PACKAGE_PATH" ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/stamps/rf2o_laser_odometry/_setup_util.py.stamp ================================================ #!/usr/bin/python # -*- coding: utf-8 -*- # Software License Agreement (BSD License) # # Copyright (c) 2012, Willow Garage, Inc. # All rights reserved. # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions # are met: # # * Redistributions of source code must retain the above copyright # notice, this list of conditions and the following disclaimer. # * Redistributions in binary form must reproduce the above # copyright notice, this list of conditions and the following # disclaimer in the documentation and/or other materials provided # with the distribution. # * Neither the name of Willow Garage, Inc. nor the names of its # contributors may be used to endorse or promote products derived # from this software without specific prior written permission. # # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. '''This file generates shell code for the setup.SHELL scripts to set environment variables''' from __future__ import print_function import argparse import copy import errno import os import platform import sys CATKIN_MARKER_FILE = '.catkin' system = platform.system() IS_DARWIN = (system == 'Darwin') IS_WINDOWS = (system == 'Windows') # subfolder of workspace prepended to CMAKE_PREFIX_PATH ENV_VAR_SUBFOLDERS = { 'CMAKE_PREFIX_PATH': '', 'LD_LIBRARY_PATH' if not IS_DARWIN else 'DYLD_LIBRARY_PATH': ['lib', os.path.join('lib', 'x86_64-linux-gnu')], 'PATH': 'bin', 'PKG_CONFIG_PATH': [os.path.join('lib', 'pkgconfig'), os.path.join('lib', 'x86_64-linux-gnu', 'pkgconfig')], 'PYTHONPATH': 'lib/python2.7/dist-packages', } def rollback_env_variables(environ, env_var_subfolders): ''' Generate shell code to reset environment variables by unrolling modifications based on all workspaces in CMAKE_PREFIX_PATH. This does not cover modifications performed by environment hooks. ''' lines = [] unmodified_environ = copy.copy(environ) for key in sorted(env_var_subfolders.keys()): subfolders = env_var_subfolders[key] if not isinstance(subfolders, list): subfolders = [subfolders] value = _rollback_env_variable(unmodified_environ, key, subfolders) if value is not None: environ[key] = value lines.append(assignment(key, value)) if lines: lines.insert(0, comment('reset environment variables by unrolling modifications based on all workspaces in CMAKE_PREFIX_PATH')) return lines def _rollback_env_variable(environ, name, subfolders): ''' For each catkin workspace in CMAKE_PREFIX_PATH remove the first entry from env[NAME] matching workspace + subfolder. :param subfolders: list of str '' or subfoldername that may start with '/' :returns: the updated value of the environment variable. ''' value = environ[name] if name in environ else '' env_paths = [path for path in value.split(os.pathsep) if path] value_modified = False for subfolder in subfolders: if subfolder: if subfolder.startswith(os.path.sep) or (os.path.altsep and subfolder.startswith(os.path.altsep)): subfolder = subfolder[1:] if subfolder.endswith(os.path.sep) or (os.path.altsep and subfolder.endswith(os.path.altsep)): subfolder = subfolder[:-1] for ws_path in _get_workspaces(environ, include_fuerte=True, include_non_existing=True): path_to_find = os.path.join(ws_path, subfolder) if subfolder else ws_path path_to_remove = None for env_path in env_paths: env_path_clean = env_path[:-1] if env_path and env_path[-1] in [os.path.sep, os.path.altsep] else env_path if env_path_clean == path_to_find: path_to_remove = env_path break if path_to_remove: env_paths.remove(path_to_remove) value_modified = True new_value = os.pathsep.join(env_paths) return new_value if value_modified else None def _get_workspaces(environ, include_fuerte=False, include_non_existing=False): ''' Based on CMAKE_PREFIX_PATH return all catkin workspaces. :param include_fuerte: The flag if paths starting with '/opt/ros/fuerte' should be considered workspaces, ``bool`` ''' # get all cmake prefix paths env_name = 'CMAKE_PREFIX_PATH' value = environ[env_name] if env_name in environ else '' paths = [path for path in value.split(os.pathsep) if path] # remove non-workspace paths workspaces = [path for path in paths if os.path.isfile(os.path.join(path, CATKIN_MARKER_FILE)) or (include_fuerte and path.startswith('/opt/ros/fuerte')) or (include_non_existing and not os.path.exists(path))] return workspaces def prepend_env_variables(environ, env_var_subfolders, workspaces): ''' Generate shell code to prepend environment variables for the all workspaces. ''' lines = [] lines.append(comment('prepend folders of workspaces to environment variables')) paths = [path for path in workspaces.split(os.pathsep) if path] prefix = _prefix_env_variable(environ, 'CMAKE_PREFIX_PATH', paths, '') lines.append(prepend(environ, 'CMAKE_PREFIX_PATH', prefix)) for key in sorted([key for key in env_var_subfolders.keys() if key != 'CMAKE_PREFIX_PATH']): subfolder = env_var_subfolders[key] prefix = _prefix_env_variable(environ, key, paths, subfolder) lines.append(prepend(environ, key, prefix)) return lines def _prefix_env_variable(environ, name, paths, subfolders): ''' Return the prefix to prepend to the environment variable NAME, adding any path in NEW_PATHS_STR without creating duplicate or empty items. ''' value = environ[name] if name in environ else '' environ_paths = [path for path in value.split(os.pathsep) if path] checked_paths = [] for path in paths: if not isinstance(subfolders, list): subfolders = [subfolders] for subfolder in subfolders: path_tmp = path if subfolder: path_tmp = os.path.join(path_tmp, subfolder) # skip nonexistent paths if not os.path.exists(path_tmp): continue # exclude any path already in env and any path we already added if path_tmp not in environ_paths and path_tmp not in checked_paths: checked_paths.append(path_tmp) prefix_str = os.pathsep.join(checked_paths) if prefix_str != '' and environ_paths: prefix_str += os.pathsep return prefix_str def assignment(key, value): if not IS_WINDOWS: return 'export %s="%s"' % (key, value) else: return 'set %s=%s' % (key, value) def comment(msg): if not IS_WINDOWS: return '# %s' % msg else: return 'REM %s' % msg def prepend(environ, key, prefix): if key not in environ or not environ[key]: return assignment(key, prefix) if not IS_WINDOWS: return 'export %s="%s$%s"' % (key, prefix, key) else: return 'set %s=%s%%%s%%' % (key, prefix, key) def find_env_hooks(environ, cmake_prefix_path): ''' Generate shell code with found environment hooks for the all workspaces. ''' lines = [] lines.append(comment('found environment hooks in workspaces')) generic_env_hooks = [] generic_env_hooks_workspace = [] specific_env_hooks = [] specific_env_hooks_workspace = [] generic_env_hooks_by_filename = {} specific_env_hooks_by_filename = {} generic_env_hook_ext = 'bat' if IS_WINDOWS else 'sh' specific_env_hook_ext = environ['CATKIN_SHELL'] if not IS_WINDOWS and 'CATKIN_SHELL' in environ and environ['CATKIN_SHELL'] else None # remove non-workspace paths workspaces = [path for path in cmake_prefix_path.split(os.pathsep) if path and os.path.isfile(os.path.join(path, CATKIN_MARKER_FILE))] for workspace in reversed(workspaces): env_hook_dir = os.path.join(workspace, 'etc', 'catkin', 'profile.d') if os.path.isdir(env_hook_dir): for filename in sorted(os.listdir(env_hook_dir)): if filename.endswith('.%s' % generic_env_hook_ext): # remove previous env hook with same name if present if filename in generic_env_hooks_by_filename: i = generic_env_hooks.index(generic_env_hooks_by_filename[filename]) generic_env_hooks.pop(i) generic_env_hooks_workspace.pop(i) # append env hook generic_env_hooks.append(os.path.join(env_hook_dir, filename)) generic_env_hooks_workspace.append(workspace) generic_env_hooks_by_filename[filename] = generic_env_hooks[-1] elif specific_env_hook_ext is not None and filename.endswith('.%s' % specific_env_hook_ext): # remove previous env hook with same name if present if filename in specific_env_hooks_by_filename: i = specific_env_hooks.index(specific_env_hooks_by_filename[filename]) specific_env_hooks.pop(i) specific_env_hooks_workspace.pop(i) # append env hook specific_env_hooks.append(os.path.join(env_hook_dir, filename)) specific_env_hooks_workspace.append(workspace) specific_env_hooks_by_filename[filename] = specific_env_hooks[-1] env_hooks = generic_env_hooks + specific_env_hooks env_hooks_workspace = generic_env_hooks_workspace + specific_env_hooks_workspace count = len(env_hooks) lines.append(assignment('_CATKIN_ENVIRONMENT_HOOKS_COUNT', count)) for i in range(count): lines.append(assignment('_CATKIN_ENVIRONMENT_HOOKS_%d' % i, env_hooks[i])) lines.append(assignment('_CATKIN_ENVIRONMENT_HOOKS_%d_WORKSPACE' % i, env_hooks_workspace[i])) return lines def _parse_arguments(args=None): parser = argparse.ArgumentParser(description='Generates code blocks for the setup.SHELL script.') parser.add_argument('--extend', action='store_true', help='Skip unsetting previous environment variables to extend context') return parser.parse_known_args(args=args)[0] if __name__ == '__main__': try: try: args = _parse_arguments() except Exception as e: print(e, file=sys.stderr) sys.exit(1) # environment at generation time CMAKE_PREFIX_PATH = '/home/zn/artrobot/devel;/opt/ros/kinetic'.split(';') # prepend current workspace if not already part of CPP base_path = os.path.dirname(__file__) if base_path not in CMAKE_PREFIX_PATH: CMAKE_PREFIX_PATH.insert(0, base_path) CMAKE_PREFIX_PATH = os.pathsep.join(CMAKE_PREFIX_PATH) environ = dict(os.environ) lines = [] if not args.extend: lines += rollback_env_variables(environ, ENV_VAR_SUBFOLDERS) lines += prepend_env_variables(environ, ENV_VAR_SUBFOLDERS, CMAKE_PREFIX_PATH) lines += find_env_hooks(environ, CMAKE_PREFIX_PATH) print('\n'.join(lines)) # need to explicitly flush the output sys.stdout.flush() except IOError as e: # and catch potential "broken pipe" if stdout is not writable # which can happen when piping the output to a file but the disk is full if e.errno == errno.EPIPE: print(e, file=sys.stderr) sys.exit(2) raise sys.exit(0) ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/stamps/rf2o_laser_odometry/interrogate_setup_dot_py.py.stamp ================================================ #!/usr/bin/env python # Software License Agreement (BSD License) # # Copyright (c) 2012, Willow Garage, Inc. # All rights reserved. # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions # are met: # # * Redistributions of source code must retain the above copyright # notice, this list of conditions and the following disclaimer. # * Redistributions in binary form must reproduce the above # copyright notice, this list of conditions and the following # disclaimer in the documentation and/or other materials provided # with the distribution. # * Neither the name of Willow Garage, Inc. nor the names of its # contributors may be used to endorse or promote products derived # from this software without specific prior written permission. # # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. from __future__ import print_function import os import runpy import sys import distutils.core try: import setuptools except ImportError: pass from argparse import ArgumentParser def _get_locations(pkgs, package_dir): """ based on setuptools logic and the package_dir dict, builds a dict of location roots for each pkg in pkgs. See http://docs.python.org/distutils/setupscript.html :returns: a dict {pkgname: root} for each pkgname in pkgs (and each of their parents) """ # package_dir contains a dict {package_name: relativepath} # Example {'': 'src', 'foo': 'lib', 'bar': 'lib2'} # # '' means where to look for any package unless a parent package # is listed so package bar.pot is expected at lib2/bar/pot, # whereas package sup.dee is expected at src/sup/dee # # if package_dir does not state anything about a package, # setuptool expects the package folder to be in the root of the # project locations = {} allprefix = package_dir.get('', '') for pkg in pkgs: parent_location = None splits = pkg.split('.') # we iterate over compound name from parent to child # so once we found parent, children just append to their parent for key_len in range(len(splits)): key = '.'.join(splits[:key_len + 1]) if key not in locations: if key in package_dir: locations[key] = package_dir[key] elif parent_location is not None: locations[key] = os.path.join(parent_location, splits[key_len]) else: locations[key] = os.path.join(allprefix, key) parent_location = locations[key] return locations def generate_cmake_file(package_name, version, scripts, package_dir, pkgs, modules): """ Generates lines to add to a cmake file which will set variables :param version: str, format 'int.int.int' :param scripts: [list of str]: relative paths to scripts :param package_dir: {modulename: path} :pkgs: [list of str] python_packages declared in catkin package :modules: [list of str] python modules """ prefix = '%s_SETUP_PY' % package_name result = [] result.append(r'set(%s_VERSION "%s")' % (prefix, version)) result.append(r'set(%s_SCRIPTS "%s")' % (prefix, ';'.join(scripts))) # Remove packages with '.' separators. # # setuptools allows specifying submodules in other folders than # their parent # # The symlink approach of catkin does not work with such submodules. # In the common case, this does not matter as the submodule is # within the containing module. We verify this assumption, and if # it passes, we remove submodule packages. locations = _get_locations(pkgs, package_dir) for pkgname, location in locations.items(): if not '.' in pkgname: continue splits = pkgname.split('.') # hack: ignore write-combining setup.py files for msg and srv files if splits[1] in ['msg', 'srv']: continue # check every child has the same root folder as its parent root_name = splits[0] root_location = location for _ in range(len(splits) - 1): root_location = os.path.dirname(root_location) if root_location != locations[root_name]: raise RuntimeError( "catkin_export_python does not support setup.py files that combine across multiple directories: %s in %s, %s in %s" % (pkgname, location, root_name, locations[root_name])) # If checks pass, remove all submodules pkgs = [p for p in pkgs if '.' not in p] resolved_pkgs = [] for pkg in pkgs: resolved_pkgs += [locations[pkg]] result.append(r'set(%s_PACKAGES "%s")' % (prefix, ';'.join(pkgs))) result.append(r'set(%s_PACKAGE_DIRS "%s")' % (prefix, ';'.join(resolved_pkgs).replace("\\", "/"))) # skip modules which collide with package names filtered_modules = [] for modname in modules: splits = modname.split('.') # check all parents too equals_package = [('.'.join(splits[:-i]) in locations) for i in range(len(splits))] if any(equals_package): continue filtered_modules.append(modname) module_locations = _get_locations(filtered_modules, package_dir) result.append(r'set(%s_MODULES "%s")' % (prefix, ';'.join(['%s.py' % m.replace('.', '/') for m in filtered_modules]))) result.append(r'set(%s_MODULE_DIRS "%s")' % (prefix, ';'.join([module_locations[m] for m in filtered_modules]).replace("\\", "/"))) return result def _create_mock_setup_function(package_name, outfile): """ Creates a function to call instead of distutils.core.setup or setuptools.setup, which just captures some args and writes them into a file that can be used from cmake :param package_name: name of the package :param outfile: filename that cmake will use afterwards :returns: a function to replace disutils.core.setup and setuptools.setup """ def setup(*args, **kwargs): ''' Checks kwargs and writes a scriptfile ''' if 'version' not in kwargs: sys.stderr.write("\n*** Unable to find 'version' in setup.py of %s\n" % package_name) raise RuntimeError("version not found in setup.py") version = kwargs['version'] package_dir = kwargs.get('package_dir', {}) pkgs = kwargs.get('packages', []) scripts = kwargs.get('scripts', []) modules = kwargs.get('py_modules', []) unsupported_args = [ 'entry_points', 'exclude_package_data', 'ext_modules ', 'ext_package', 'include_package_data', 'namespace_packages', 'setup_requires', 'use_2to3', 'zip_safe'] used_unsupported_args = [arg for arg in unsupported_args if arg in kwargs] if used_unsupported_args: sys.stderr.write("*** Arguments %s to setup() not supported in catkin devel space in setup.py of %s\n" % (used_unsupported_args, package_name)) result = generate_cmake_file(package_name=package_name, version=version, scripts=scripts, package_dir=package_dir, pkgs=pkgs, modules=modules) with open(outfile, 'w') as out: out.write('\n'.join(result)) return setup def main(): """ Script main, parses arguments and invokes Dummy.setup indirectly. """ parser = ArgumentParser(description='Utility to read setup.py values from cmake macros. Creates a file with CMake set commands setting variables.') parser.add_argument('package_name', help='Name of catkin package') parser.add_argument('setupfile_path', help='Full path to setup.py') parser.add_argument('outfile', help='Where to write result to') args = parser.parse_args() # print("%s" % sys.argv) # PACKAGE_NAME = sys.argv[1] # OUTFILE = sys.argv[3] # print("Interrogating setup.py for package %s into %s " % (PACKAGE_NAME, OUTFILE), # file=sys.stderr) # print("executing %s" % args.setupfile_path) # be sure you're in the directory containing # setup.py so the sys.path manipulation works, # so the import of __version__ works os.chdir(os.path.dirname(os.path.abspath(args.setupfile_path))) # patch setup() function of distutils and setuptools for the # context of evaluating setup.py try: fake_setup = _create_mock_setup_function(package_name=args.package_name, outfile=args.outfile) distutils_backup = distutils.core.setup distutils.core.setup = fake_setup try: setuptools_backup = setuptools.setup setuptools.setup = fake_setup except NameError: pass runpy.run_path(args.setupfile_path) finally: distutils.core.setup = distutils_backup try: setuptools.setup = setuptools_backup except NameError: pass if __name__ == '__main__': main() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/stamps/rf2o_laser_odometry/package.xml.stamp ================================================ rf2o_laser_odometry 1.0.0 Estimation of 2D odometry based on planar laser scans. Useful for mobile robots with innacurate base odometry. For full description of the algorithm, please refer to: Planar Odometry from a Radial Laser Scanner. A Range Flow-based Approach. ICRA 2016 Available at: http://mapir.isa.uma.es/mapirwebsite/index.php/mapir-downloads/papers/217 Javier G. Monroy Mariano Jaimez Javier G. Monroy GPL v3 catkin nav_msgs roscpp sensor_msgs std_msgs tf cmake_modules mrpt nav_msgs roscpp sensor_msgs std_msgs tf cmake_modules mrpt ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/stamps/rf2o_laser_odometry/pkg.pc.em.stamp ================================================ prefix=@PROJECT_SPACE_DIR Name: @(CATKIN_PACKAGE_PREFIX + PROJECT_NAME) Description: Description of @PROJECT_NAME Version: @PROJECT_VERSION Cflags: @(' '.join(['-I%s' % include for include in PROJECT_PKG_CONFIG_INCLUDE_DIRS])) Libs: -L@PROJECT_SPACE_DIR/lib @(' '.join(PKG_CONFIG_LIBRARIES_WITH_PREFIX)) Requires: @(PROJECT_CATKIN_DEPENDS) ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/cmake_install.cmake ================================================ # Install script for directory: /home/zn/racecar/src/rf2o_laser_odometry # Set the install prefix if(NOT DEFINED CMAKE_INSTALL_PREFIX) set(CMAKE_INSTALL_PREFIX "/usr/local") endif() string(REGEX REPLACE "/$" "" CMAKE_INSTALL_PREFIX "${CMAKE_INSTALL_PREFIX}") # Set the install configuration name. if(NOT DEFINED CMAKE_INSTALL_CONFIG_NAME) if(BUILD_TYPE) string(REGEX REPLACE "^[^A-Za-z0-9_]+" "" CMAKE_INSTALL_CONFIG_NAME "${BUILD_TYPE}") else() set(CMAKE_INSTALL_CONFIG_NAME "Debug") endif() message(STATUS "Install configuration: \"${CMAKE_INSTALL_CONFIG_NAME}\"") endif() # Set the component getting installed. if(NOT CMAKE_INSTALL_COMPONENT) if(COMPONENT) message(STATUS "Install component: \"${COMPONENT}\"") set(CMAKE_INSTALL_COMPONENT "${COMPONENT}") else() set(CMAKE_INSTALL_COMPONENT) endif() endif() # Install shared libraries without execute permission? if(NOT DEFINED CMAKE_INSTALL_SO_NO_EXE) set(CMAKE_INSTALL_SO_NO_EXE "1") endif() if("${CMAKE_INSTALL_COMPONENT}" STREQUAL "Unspecified" OR NOT CMAKE_INSTALL_COMPONENT) if (NOT EXISTS "$ENV{DESTDIR}${CMAKE_INSTALL_PREFIX}") file(MAKE_DIRECTORY "$ENV{DESTDIR}${CMAKE_INSTALL_PREFIX}") endif() if (NOT EXISTS "$ENV{DESTDIR}${CMAKE_INSTALL_PREFIX}/.catkin") file(WRITE "$ENV{DESTDIR}${CMAKE_INSTALL_PREFIX}/.catkin" "") endif() endif() if("${CMAKE_INSTALL_COMPONENT}" STREQUAL "Unspecified" OR NOT CMAKE_INSTALL_COMPONENT) list(APPEND CMAKE_ABSOLUTE_DESTINATION_FILES "/usr/local/_setup_util.py") if(CMAKE_WARN_ON_ABSOLUTE_INSTALL_DESTINATION) message(WARNING "ABSOLUTE path INSTALL DESTINATION : ${CMAKE_ABSOLUTE_DESTINATION_FILES}") endif() if(CMAKE_ERROR_ON_ABSOLUTE_INSTALL_DESTINATION) message(FATAL_ERROR "ABSOLUTE path INSTALL DESTINATION forbidden (by caller): ${CMAKE_ABSOLUTE_DESTINATION_FILES}") endif() file(INSTALL DESTINATION "/usr/local" TYPE PROGRAM FILES "/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/installspace/_setup_util.py") endif() if("${CMAKE_INSTALL_COMPONENT}" STREQUAL "Unspecified" OR NOT CMAKE_INSTALL_COMPONENT) list(APPEND CMAKE_ABSOLUTE_DESTINATION_FILES "/usr/local/env.sh") if(CMAKE_WARN_ON_ABSOLUTE_INSTALL_DESTINATION) message(WARNING "ABSOLUTE path INSTALL DESTINATION : ${CMAKE_ABSOLUTE_DESTINATION_FILES}") endif() if(CMAKE_ERROR_ON_ABSOLUTE_INSTALL_DESTINATION) message(FATAL_ERROR "ABSOLUTE path INSTALL DESTINATION forbidden (by caller): ${CMAKE_ABSOLUTE_DESTINATION_FILES}") endif() file(INSTALL DESTINATION "/usr/local" TYPE PROGRAM FILES "/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/installspace/env.sh") endif() if("${CMAKE_INSTALL_COMPONENT}" STREQUAL "Unspecified" OR NOT CMAKE_INSTALL_COMPONENT) list(APPEND CMAKE_ABSOLUTE_DESTINATION_FILES "/usr/local/setup.bash") if(CMAKE_WARN_ON_ABSOLUTE_INSTALL_DESTINATION) message(WARNING "ABSOLUTE path INSTALL DESTINATION : ${CMAKE_ABSOLUTE_DESTINATION_FILES}") endif() if(CMAKE_ERROR_ON_ABSOLUTE_INSTALL_DESTINATION) message(FATAL_ERROR "ABSOLUTE path INSTALL DESTINATION forbidden (by caller): ${CMAKE_ABSOLUTE_DESTINATION_FILES}") endif() file(INSTALL DESTINATION "/usr/local" TYPE FILE FILES "/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/installspace/setup.bash") endif() if("${CMAKE_INSTALL_COMPONENT}" STREQUAL "Unspecified" OR NOT CMAKE_INSTALL_COMPONENT) list(APPEND CMAKE_ABSOLUTE_DESTINATION_FILES "/usr/local/setup.sh") if(CMAKE_WARN_ON_ABSOLUTE_INSTALL_DESTINATION) message(WARNING "ABSOLUTE path INSTALL DESTINATION : ${CMAKE_ABSOLUTE_DESTINATION_FILES}") endif() if(CMAKE_ERROR_ON_ABSOLUTE_INSTALL_DESTINATION) message(FATAL_ERROR "ABSOLUTE path INSTALL DESTINATION forbidden (by caller): ${CMAKE_ABSOLUTE_DESTINATION_FILES}") endif() file(INSTALL DESTINATION "/usr/local" TYPE FILE FILES "/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/installspace/setup.sh") endif() if("${CMAKE_INSTALL_COMPONENT}" STREQUAL "Unspecified" OR NOT CMAKE_INSTALL_COMPONENT) list(APPEND CMAKE_ABSOLUTE_DESTINATION_FILES "/usr/local/setup.zsh") if(CMAKE_WARN_ON_ABSOLUTE_INSTALL_DESTINATION) message(WARNING "ABSOLUTE path INSTALL DESTINATION : ${CMAKE_ABSOLUTE_DESTINATION_FILES}") endif() if(CMAKE_ERROR_ON_ABSOLUTE_INSTALL_DESTINATION) message(FATAL_ERROR "ABSOLUTE path INSTALL DESTINATION forbidden (by caller): ${CMAKE_ABSOLUTE_DESTINATION_FILES}") endif() file(INSTALL DESTINATION "/usr/local" TYPE FILE FILES "/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/installspace/setup.zsh") endif() if("${CMAKE_INSTALL_COMPONENT}" STREQUAL "Unspecified" OR NOT CMAKE_INSTALL_COMPONENT) list(APPEND CMAKE_ABSOLUTE_DESTINATION_FILES "/usr/local/.rosinstall") if(CMAKE_WARN_ON_ABSOLUTE_INSTALL_DESTINATION) message(WARNING "ABSOLUTE path INSTALL DESTINATION : ${CMAKE_ABSOLUTE_DESTINATION_FILES}") endif() if(CMAKE_ERROR_ON_ABSOLUTE_INSTALL_DESTINATION) message(FATAL_ERROR "ABSOLUTE path INSTALL DESTINATION forbidden (by caller): ${CMAKE_ABSOLUTE_DESTINATION_FILES}") endif() file(INSTALL DESTINATION "/usr/local" TYPE FILE FILES "/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/installspace/.rosinstall") endif() if("${CMAKE_INSTALL_COMPONENT}" STREQUAL "Unspecified" OR NOT CMAKE_INSTALL_COMPONENT) file(INSTALL DESTINATION "${CMAKE_INSTALL_PREFIX}/lib/pkgconfig" TYPE FILE FILES "/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/installspace/rf2o_laser_odometry.pc") endif() if("${CMAKE_INSTALL_COMPONENT}" STREQUAL "Unspecified" OR NOT CMAKE_INSTALL_COMPONENT) file(INSTALL DESTINATION "${CMAKE_INSTALL_PREFIX}/share/rf2o_laser_odometry/cmake" TYPE FILE FILES "/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/installspace/rf2o_laser_odometryConfig.cmake" "/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/installspace/rf2o_laser_odometryConfig-version.cmake" ) endif() if("${CMAKE_INSTALL_COMPONENT}" STREQUAL "Unspecified" OR NOT CMAKE_INSTALL_COMPONENT) file(INSTALL DESTINATION "${CMAKE_INSTALL_PREFIX}/share/rf2o_laser_odometry" TYPE FILE FILES "/home/zn/racecar/src/rf2o_laser_odometry/package.xml") endif() if(CMAKE_INSTALL_COMPONENT) set(CMAKE_INSTALL_MANIFEST "install_manifest_${CMAKE_INSTALL_COMPONENT}.txt") else() set(CMAKE_INSTALL_MANIFEST "install_manifest.txt") endif() string(REPLACE ";" "\n" CMAKE_INSTALL_MANIFEST_CONTENT "${CMAKE_INSTALL_MANIFEST_FILES}") file(WRITE "/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/${CMAKE_INSTALL_MANIFEST}" "${CMAKE_INSTALL_MANIFEST_CONTENT}") ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/devel/.catkin ================================================ /home/zn/racecar/src/rf2o_laser_odometry ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/devel/.rosinstall ================================================ - setup-file: local-name: /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/devel/setup.sh ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/devel/_setup_util.py ================================================ #!/usr/bin/python # -*- coding: utf-8 -*- # Software License Agreement (BSD License) # # Copyright (c) 2012, Willow Garage, Inc. # All rights reserved. # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions # are met: # # * Redistributions of source code must retain the above copyright # notice, this list of conditions and the following disclaimer. # * Redistributions in binary form must reproduce the above # copyright notice, this list of conditions and the following # disclaimer in the documentation and/or other materials provided # with the distribution. # * Neither the name of Willow Garage, Inc. nor the names of its # contributors may be used to endorse or promote products derived # from this software without specific prior written permission. # # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. '''This file generates shell code for the setup.SHELL scripts to set environment variables''' from __future__ import print_function import argparse import copy import errno import os import platform import sys CATKIN_MARKER_FILE = '.catkin' system = platform.system() IS_DARWIN = (system == 'Darwin') IS_WINDOWS = (system == 'Windows') # subfolder of workspace prepended to CMAKE_PREFIX_PATH ENV_VAR_SUBFOLDERS = { 'CMAKE_PREFIX_PATH': '', 'LD_LIBRARY_PATH' if not IS_DARWIN else 'DYLD_LIBRARY_PATH': ['lib', os.path.join('lib', 'x86_64-linux-gnu')], 'PATH': 'bin', 'PKG_CONFIG_PATH': [os.path.join('lib', 'pkgconfig'), os.path.join('lib', 'x86_64-linux-gnu', 'pkgconfig')], 'PYTHONPATH': 'lib/python2.7/dist-packages', } def rollback_env_variables(environ, env_var_subfolders): ''' Generate shell code to reset environment variables by unrolling modifications based on all workspaces in CMAKE_PREFIX_PATH. This does not cover modifications performed by environment hooks. ''' lines = [] unmodified_environ = copy.copy(environ) for key in sorted(env_var_subfolders.keys()): subfolders = env_var_subfolders[key] if not isinstance(subfolders, list): subfolders = [subfolders] value = _rollback_env_variable(unmodified_environ, key, subfolders) if value is not None: environ[key] = value lines.append(assignment(key, value)) if lines: lines.insert(0, comment('reset environment variables by unrolling modifications based on all workspaces in CMAKE_PREFIX_PATH')) return lines def _rollback_env_variable(environ, name, subfolders): ''' For each catkin workspace in CMAKE_PREFIX_PATH remove the first entry from env[NAME] matching workspace + subfolder. :param subfolders: list of str '' or subfoldername that may start with '/' :returns: the updated value of the environment variable. ''' value = environ[name] if name in environ else '' env_paths = [path for path in value.split(os.pathsep) if path] value_modified = False for subfolder in subfolders: if subfolder: if subfolder.startswith(os.path.sep) or (os.path.altsep and subfolder.startswith(os.path.altsep)): subfolder = subfolder[1:] if subfolder.endswith(os.path.sep) or (os.path.altsep and subfolder.endswith(os.path.altsep)): subfolder = subfolder[:-1] for ws_path in _get_workspaces(environ, include_fuerte=True, include_non_existing=True): path_to_find = os.path.join(ws_path, subfolder) if subfolder else ws_path path_to_remove = None for env_path in env_paths: env_path_clean = env_path[:-1] if env_path and env_path[-1] in [os.path.sep, os.path.altsep] else env_path if env_path_clean == path_to_find: path_to_remove = env_path break if path_to_remove: env_paths.remove(path_to_remove) value_modified = True new_value = os.pathsep.join(env_paths) return new_value if value_modified else None def _get_workspaces(environ, include_fuerte=False, include_non_existing=False): ''' Based on CMAKE_PREFIX_PATH return all catkin workspaces. :param include_fuerte: The flag if paths starting with '/opt/ros/fuerte' should be considered workspaces, ``bool`` ''' # get all cmake prefix paths env_name = 'CMAKE_PREFIX_PATH' value = environ[env_name] if env_name in environ else '' paths = [path for path in value.split(os.pathsep) if path] # remove non-workspace paths workspaces = [path for path in paths if os.path.isfile(os.path.join(path, CATKIN_MARKER_FILE)) or (include_fuerte and path.startswith('/opt/ros/fuerte')) or (include_non_existing and not os.path.exists(path))] return workspaces def prepend_env_variables(environ, env_var_subfolders, workspaces): ''' Generate shell code to prepend environment variables for the all workspaces. ''' lines = [] lines.append(comment('prepend folders of workspaces to environment variables')) paths = [path for path in workspaces.split(os.pathsep) if path] prefix = _prefix_env_variable(environ, 'CMAKE_PREFIX_PATH', paths, '') lines.append(prepend(environ, 'CMAKE_PREFIX_PATH', prefix)) for key in sorted([key for key in env_var_subfolders.keys() if key != 'CMAKE_PREFIX_PATH']): subfolder = env_var_subfolders[key] prefix = _prefix_env_variable(environ, key, paths, subfolder) lines.append(prepend(environ, key, prefix)) return lines def _prefix_env_variable(environ, name, paths, subfolders): ''' Return the prefix to prepend to the environment variable NAME, adding any path in NEW_PATHS_STR without creating duplicate or empty items. ''' value = environ[name] if name in environ else '' environ_paths = [path for path in value.split(os.pathsep) if path] checked_paths = [] for path in paths: if not isinstance(subfolders, list): subfolders = [subfolders] for subfolder in subfolders: path_tmp = path if subfolder: path_tmp = os.path.join(path_tmp, subfolder) # skip nonexistent paths if not os.path.exists(path_tmp): continue # exclude any path already in env and any path we already added if path_tmp not in environ_paths and path_tmp not in checked_paths: checked_paths.append(path_tmp) prefix_str = os.pathsep.join(checked_paths) if prefix_str != '' and environ_paths: prefix_str += os.pathsep return prefix_str def assignment(key, value): if not IS_WINDOWS: return 'export %s="%s"' % (key, value) else: return 'set %s=%s' % (key, value) def comment(msg): if not IS_WINDOWS: return '# %s' % msg else: return 'REM %s' % msg def prepend(environ, key, prefix): if key not in environ or not environ[key]: return assignment(key, prefix) if not IS_WINDOWS: return 'export %s="%s$%s"' % (key, prefix, key) else: return 'set %s=%s%%%s%%' % (key, prefix, key) def find_env_hooks(environ, cmake_prefix_path): ''' Generate shell code with found environment hooks for the all workspaces. ''' lines = [] lines.append(comment('found environment hooks in workspaces')) generic_env_hooks = [] generic_env_hooks_workspace = [] specific_env_hooks = [] specific_env_hooks_workspace = [] generic_env_hooks_by_filename = {} specific_env_hooks_by_filename = {} generic_env_hook_ext = 'bat' if IS_WINDOWS else 'sh' specific_env_hook_ext = environ['CATKIN_SHELL'] if not IS_WINDOWS and 'CATKIN_SHELL' in environ and environ['CATKIN_SHELL'] else None # remove non-workspace paths workspaces = [path for path in cmake_prefix_path.split(os.pathsep) if path and os.path.isfile(os.path.join(path, CATKIN_MARKER_FILE))] for workspace in reversed(workspaces): env_hook_dir = os.path.join(workspace, 'etc', 'catkin', 'profile.d') if os.path.isdir(env_hook_dir): for filename in sorted(os.listdir(env_hook_dir)): if filename.endswith('.%s' % generic_env_hook_ext): # remove previous env hook with same name if present if filename in generic_env_hooks_by_filename: i = generic_env_hooks.index(generic_env_hooks_by_filename[filename]) generic_env_hooks.pop(i) generic_env_hooks_workspace.pop(i) # append env hook generic_env_hooks.append(os.path.join(env_hook_dir, filename)) generic_env_hooks_workspace.append(workspace) generic_env_hooks_by_filename[filename] = generic_env_hooks[-1] elif specific_env_hook_ext is not None and filename.endswith('.%s' % specific_env_hook_ext): # remove previous env hook with same name if present if filename in specific_env_hooks_by_filename: i = specific_env_hooks.index(specific_env_hooks_by_filename[filename]) specific_env_hooks.pop(i) specific_env_hooks_workspace.pop(i) # append env hook specific_env_hooks.append(os.path.join(env_hook_dir, filename)) specific_env_hooks_workspace.append(workspace) specific_env_hooks_by_filename[filename] = specific_env_hooks[-1] env_hooks = generic_env_hooks + specific_env_hooks env_hooks_workspace = generic_env_hooks_workspace + specific_env_hooks_workspace count = len(env_hooks) lines.append(assignment('_CATKIN_ENVIRONMENT_HOOKS_COUNT', count)) for i in range(count): lines.append(assignment('_CATKIN_ENVIRONMENT_HOOKS_%d' % i, env_hooks[i])) lines.append(assignment('_CATKIN_ENVIRONMENT_HOOKS_%d_WORKSPACE' % i, env_hooks_workspace[i])) return lines def _parse_arguments(args=None): parser = argparse.ArgumentParser(description='Generates code blocks for the setup.SHELL script.') parser.add_argument('--extend', action='store_true', help='Skip unsetting previous environment variables to extend context') return parser.parse_known_args(args=args)[0] if __name__ == '__main__': try: try: args = _parse_arguments() except Exception as e: print(e, file=sys.stderr) sys.exit(1) # environment at generation time CMAKE_PREFIX_PATH = '/home/zn/artrobot/devel;/opt/ros/kinetic'.split(';') # prepend current workspace if not already part of CPP base_path = os.path.dirname(__file__) if base_path not in CMAKE_PREFIX_PATH: CMAKE_PREFIX_PATH.insert(0, base_path) CMAKE_PREFIX_PATH = os.pathsep.join(CMAKE_PREFIX_PATH) environ = dict(os.environ) lines = [] if not args.extend: lines += rollback_env_variables(environ, ENV_VAR_SUBFOLDERS) lines += prepend_env_variables(environ, ENV_VAR_SUBFOLDERS, CMAKE_PREFIX_PATH) lines += find_env_hooks(environ, CMAKE_PREFIX_PATH) print('\n'.join(lines)) # need to explicitly flush the output sys.stdout.flush() except IOError as e: # and catch potential "broken pipe" if stdout is not writable # which can happen when piping the output to a file but the disk is full if e.errno == errno.EPIPE: print(e, file=sys.stderr) sys.exit(2) raise sys.exit(0) ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/devel/env.sh ================================================ #!/usr/bin/env sh # generated from catkin/cmake/templates/env.sh.in if [ $# -eq 0 ] ; then /bin/echo "Usage: env.sh COMMANDS" /bin/echo "Calling env.sh without arguments is not supported anymore. Instead spawn a subshell and source a setup file manually." exit 1 fi # ensure to not use different shell type which was set before CATKIN_SHELL=sh # source setup.sh from same directory as this file _CATKIN_SETUP_DIR=$(cd "`dirname "$0"`" > /dev/null && pwd) . "$_CATKIN_SETUP_DIR/setup.sh" exec "$@" ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/devel/lib/pkgconfig/rf2o_laser_odometry.pc ================================================ prefix=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/devel Name: rf2o_laser_odometry Description: Description of rf2o_laser_odometry Version: 1.0.0 Cflags: -I/home/zn/racecar/src/rf2o_laser_odometry/include Libs: -L/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/devel/lib -llaser_odometry Requires: nav_msgs roscpp sensor_msgs std_msgs tf ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/devel/setup.bash ================================================ #!/usr/bin/env bash # generated from catkin/cmake/templates/setup.bash.in CATKIN_SHELL=bash # source setup.sh from same directory as this file _CATKIN_SETUP_DIR=$(builtin cd "`dirname "${BASH_SOURCE[0]}"`" > /dev/null && pwd) . "$_CATKIN_SETUP_DIR/setup.sh" ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/devel/setup.sh ================================================ #!/usr/bin/env sh # generated from catkin/cmake/template/setup.sh.in # Sets various environment variables and sources additional environment hooks. # It tries it's best to undo changes from a previously sourced setup file before. # Supported command line options: # --extend: skips the undoing of changes from a previously sourced setup file # (in plain sh shell which does't support arguments for sourced scripts you # can set the environment variable `CATKIN_SETUP_UTIL_ARGS=--extend` instead) # since this file is sourced either use the provided _CATKIN_SETUP_DIR # or fall back to the destination set at configure time : ${_CATKIN_SETUP_DIR:=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/devel} _SETUP_UTIL="$_CATKIN_SETUP_DIR/_setup_util.py" unset _CATKIN_SETUP_DIR if [ ! -f "$_SETUP_UTIL" ]; then echo "Missing Python script: $_SETUP_UTIL" return 22 fi # detect if running on Darwin platform _UNAME=`uname -s` _IS_DARWIN=0 if [ "$_UNAME" = "Darwin" ]; then _IS_DARWIN=1 fi unset _UNAME # make sure to export all environment variables export CMAKE_PREFIX_PATH if [ $_IS_DARWIN -eq 0 ]; then export LD_LIBRARY_PATH else export DYLD_LIBRARY_PATH fi unset _IS_DARWIN export PATH export PKG_CONFIG_PATH export PYTHONPATH # remember type of shell if not already set if [ -z "$CATKIN_SHELL" ]; then CATKIN_SHELL=sh fi # invoke Python script to generate necessary exports of environment variables # use TMPDIR if it exists, otherwise fall back to /tmp if [ -d "${TMPDIR:-}" ]; then _TMPDIR="${TMPDIR}" else _TMPDIR=/tmp fi _SETUP_TMP=`mktemp "${_TMPDIR}/setup.sh.XXXXXXXXXX"` unset _TMPDIR if [ $? -ne 0 -o ! -f "$_SETUP_TMP" ]; then echo "Could not create temporary file: $_SETUP_TMP" return 1 fi CATKIN_SHELL=$CATKIN_SHELL "$_SETUP_UTIL" $@ ${CATKIN_SETUP_UTIL_ARGS:-} >> "$_SETUP_TMP" _RC=$? if [ $_RC -ne 0 ]; then if [ $_RC -eq 2 ]; then echo "Could not write the output of '$_SETUP_UTIL' to temporary file '$_SETUP_TMP': may be the disk if full?" else echo "Failed to run '\"$_SETUP_UTIL\" $@': return code $_RC" fi unset _RC unset _SETUP_UTIL rm -f "$_SETUP_TMP" unset _SETUP_TMP return 1 fi unset _RC unset _SETUP_UTIL . "$_SETUP_TMP" rm -f "$_SETUP_TMP" unset _SETUP_TMP # source all environment hooks _i=0 while [ $_i -lt $_CATKIN_ENVIRONMENT_HOOKS_COUNT ]; do eval _envfile=\$_CATKIN_ENVIRONMENT_HOOKS_$_i unset _CATKIN_ENVIRONMENT_HOOKS_$_i eval _envfile_workspace=\$_CATKIN_ENVIRONMENT_HOOKS_${_i}_WORKSPACE unset _CATKIN_ENVIRONMENT_HOOKS_${_i}_WORKSPACE # set workspace for environment hook CATKIN_ENV_HOOK_WORKSPACE=$_envfile_workspace . "$_envfile" unset CATKIN_ENV_HOOK_WORKSPACE _i=$((_i + 1)) done unset _i unset _CATKIN_ENVIRONMENT_HOOKS_COUNT ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/devel/setup.zsh ================================================ #!/usr/bin/env zsh # generated from catkin/cmake/templates/setup.zsh.in CATKIN_SHELL=zsh # source setup.sh from same directory as this file _CATKIN_SETUP_DIR=$(builtin cd -q "`dirname "$0"`" > /dev/null && pwd) emulate -R zsh -c 'source "$_CATKIN_SETUP_DIR/setup.sh"' ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/devel/share/rf2o_laser_odometry/cmake/rf2o_laser_odometryConfig-version.cmake ================================================ # generated from catkin/cmake/template/pkgConfig-version.cmake.in set(PACKAGE_VERSION "1.0.0") set(PACKAGE_VERSION_EXACT False) set(PACKAGE_VERSION_COMPATIBLE False) if("${PACKAGE_FIND_VERSION}" VERSION_EQUAL "${PACKAGE_VERSION}") set(PACKAGE_VERSION_EXACT True) set(PACKAGE_VERSION_COMPATIBLE True) endif() if("${PACKAGE_FIND_VERSION}" VERSION_LESS "${PACKAGE_VERSION}") set(PACKAGE_VERSION_COMPATIBLE True) endif() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/devel/share/rf2o_laser_odometry/cmake/rf2o_laser_odometryConfig.cmake ================================================ # generated from catkin/cmake/template/pkgConfig.cmake.in # append elements to a list and remove existing duplicates from the list # copied from catkin/cmake/list_append_deduplicate.cmake to keep pkgConfig # self contained macro(_list_append_deduplicate listname) if(NOT "${ARGN}" STREQUAL "") if(${listname}) list(REMOVE_ITEM ${listname} ${ARGN}) endif() list(APPEND ${listname} ${ARGN}) endif() endmacro() # append elements to a list if they are not already in the list # copied from catkin/cmake/list_append_unique.cmake to keep pkgConfig # self contained macro(_list_append_unique listname) foreach(_item ${ARGN}) list(FIND ${listname} ${_item} _index) if(_index EQUAL -1) list(APPEND ${listname} ${_item}) endif() endforeach() endmacro() # pack a list of libraries with optional build configuration keywords # copied from catkin/cmake/catkin_libraries.cmake to keep pkgConfig # self contained macro(_pack_libraries_with_build_configuration VAR) set(${VAR} "") set(_argn ${ARGN}) list(LENGTH _argn _count) set(_index 0) while(${_index} LESS ${_count}) list(GET _argn ${_index} lib) if("${lib}" MATCHES "^(debug|optimized|general)$") math(EXPR _index "${_index} + 1") if(${_index} EQUAL ${_count}) message(FATAL_ERROR "_pack_libraries_with_build_configuration() the list of libraries '${ARGN}' ends with '${lib}' which is a build configuration keyword and must be followed by a library") endif() list(GET _argn ${_index} library) list(APPEND ${VAR} "${lib}${CATKIN_BUILD_CONFIGURATION_KEYWORD_SEPARATOR}${library}") else() list(APPEND ${VAR} "${lib}") endif() math(EXPR _index "${_index} + 1") endwhile() endmacro() # unpack a list of libraries with optional build configuration keyword prefixes # copied from catkin/cmake/catkin_libraries.cmake to keep pkgConfig # self contained macro(_unpack_libraries_with_build_configuration VAR) set(${VAR} "") foreach(lib ${ARGN}) string(REGEX REPLACE "^(debug|optimized|general)${CATKIN_BUILD_CONFIGURATION_KEYWORD_SEPARATOR}(.+)$" "\\1;\\2" lib "${lib}") list(APPEND ${VAR} "${lib}") endforeach() endmacro() if(rf2o_laser_odometry_CONFIG_INCLUDED) return() endif() set(rf2o_laser_odometry_CONFIG_INCLUDED TRUE) # set variables for source/devel/install prefixes if("TRUE" STREQUAL "TRUE") set(rf2o_laser_odometry_SOURCE_PREFIX /home/zn/racecar/src/rf2o_laser_odometry) set(rf2o_laser_odometry_DEVEL_PREFIX /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/devel) set(rf2o_laser_odometry_INSTALL_PREFIX "") set(rf2o_laser_odometry_PREFIX ${rf2o_laser_odometry_DEVEL_PREFIX}) else() set(rf2o_laser_odometry_SOURCE_PREFIX "") set(rf2o_laser_odometry_DEVEL_PREFIX "") set(rf2o_laser_odometry_INSTALL_PREFIX /usr/local) set(rf2o_laser_odometry_PREFIX ${rf2o_laser_odometry_INSTALL_PREFIX}) endif() # warn when using a deprecated package if(NOT "" STREQUAL "") set(_msg "WARNING: package 'rf2o_laser_odometry' is deprecated") # append custom deprecation text if available if(NOT "" STREQUAL "TRUE") set(_msg "${_msg} ()") endif() message("${_msg}") endif() # flag project as catkin-based to distinguish if a find_package()-ed project is a catkin project set(rf2o_laser_odometry_FOUND_CATKIN_PROJECT TRUE) if(NOT "/home/zn/racecar/src/rf2o_laser_odometry/include " STREQUAL " ") set(rf2o_laser_odometry_INCLUDE_DIRS "") set(_include_dirs "/home/zn/racecar/src/rf2o_laser_odometry/include") if(NOT " " STREQUAL " ") set(_report "Check the issue tracker '' and consider creating a ticket if the problem has not been reported yet.") elseif(NOT " " STREQUAL " ") set(_report "Check the website '' for information and consider reporting the problem.") else() set(_report "Report the problem to the maintainer 'Javier G. Monroy ' and request to fix the problem.") endif() foreach(idir ${_include_dirs}) if(IS_ABSOLUTE ${idir} AND IS_DIRECTORY ${idir}) set(include ${idir}) elseif("${idir} " STREQUAL "include ") get_filename_component(include "${rf2o_laser_odometry_DIR}/../../../include" ABSOLUTE) if(NOT IS_DIRECTORY ${include}) message(FATAL_ERROR "Project 'rf2o_laser_odometry' specifies '${idir}' as an include dir, which is not found. It does not exist in '${include}'. ${_report}") endif() else() message(FATAL_ERROR "Project 'rf2o_laser_odometry' specifies '${idir}' as an include dir, which is not found. It does neither exist as an absolute directory nor in '/home/zn/racecar/src/rf2o_laser_odometry/${idir}'. ${_report}") endif() _list_append_unique(rf2o_laser_odometry_INCLUDE_DIRS ${include}) endforeach() endif() set(libraries "laser_odometry") foreach(library ${libraries}) # keep build configuration keywords, target names and absolute libraries as-is if("${library}" MATCHES "^(debug|optimized|general)$") list(APPEND rf2o_laser_odometry_LIBRARIES ${library}) elseif(TARGET ${library}) list(APPEND rf2o_laser_odometry_LIBRARIES ${library}) elseif(IS_ABSOLUTE ${library}) list(APPEND rf2o_laser_odometry_LIBRARIES ${library}) else() set(lib_path "") set(lib "${library}-NOTFOUND") # since the path where the library is found is returned we have to iterate over the paths manually foreach(path /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/devel/lib;/home/zn/artrobot/devel/lib;/opt/ros/kinetic/lib) find_library(lib ${library} PATHS ${path} NO_DEFAULT_PATH NO_CMAKE_FIND_ROOT_PATH) if(lib) set(lib_path ${path}) break() endif() endforeach() if(lib) _list_append_unique(rf2o_laser_odometry_LIBRARY_DIRS ${lib_path}) list(APPEND rf2o_laser_odometry_LIBRARIES ${lib}) else() # as a fall back for non-catkin libraries try to search globally find_library(lib ${library}) if(NOT lib) message(FATAL_ERROR "Project '${PROJECT_NAME}' tried to find library '${library}'. The library is neither a target nor built/installed properly. Did you compile project 'rf2o_laser_odometry'? Did you find_package() it before the subdirectory containing its code is included?") endif() list(APPEND rf2o_laser_odometry_LIBRARIES ${lib}) endif() endif() endforeach() set(rf2o_laser_odometry_EXPORTED_TARGETS "") # create dummy targets for exported code generation targets to make life of users easier foreach(t ${rf2o_laser_odometry_EXPORTED_TARGETS}) if(NOT TARGET ${t}) add_custom_target(${t}) endif() endforeach() set(depends "nav_msgs;roscpp;sensor_msgs;std_msgs;tf") foreach(depend ${depends}) string(REPLACE " " ";" depend_list ${depend}) # the package name of the dependency must be kept in a unique variable so that it is not overwritten in recursive calls list(GET depend_list 0 rf2o_laser_odometry_dep) list(LENGTH depend_list count) if(${count} EQUAL 1) # simple dependencies must only be find_package()-ed once if(NOT ${rf2o_laser_odometry_dep}_FOUND) find_package(${rf2o_laser_odometry_dep} REQUIRED NO_MODULE) endif() else() # dependencies with components must be find_package()-ed again list(REMOVE_AT depend_list 0) find_package(${rf2o_laser_odometry_dep} REQUIRED NO_MODULE ${depend_list}) endif() _list_append_unique(rf2o_laser_odometry_INCLUDE_DIRS ${${rf2o_laser_odometry_dep}_INCLUDE_DIRS}) # merge build configuration keywords with library names to correctly deduplicate _pack_libraries_with_build_configuration(rf2o_laser_odometry_LIBRARIES ${rf2o_laser_odometry_LIBRARIES}) _pack_libraries_with_build_configuration(_libraries ${${rf2o_laser_odometry_dep}_LIBRARIES}) _list_append_deduplicate(rf2o_laser_odometry_LIBRARIES ${_libraries}) # undo build configuration keyword merging after deduplication _unpack_libraries_with_build_configuration(rf2o_laser_odometry_LIBRARIES ${rf2o_laser_odometry_LIBRARIES}) _list_append_unique(rf2o_laser_odometry_LIBRARY_DIRS ${${rf2o_laser_odometry_dep}_LIBRARY_DIRS}) list(APPEND rf2o_laser_odometry_EXPORTED_TARGETS ${${rf2o_laser_odometry_dep}_EXPORTED_TARGETS}) endforeach() set(pkg_cfg_extras "") foreach(extra ${pkg_cfg_extras}) if(NOT IS_ABSOLUTE ${extra}) set(extra ${rf2o_laser_odometry_DIR}/${extra}) endif() include(${extra}) endforeach() ================================================ FILE: src/rf2o_laser_odometry/cmake-build-debug/rf2o_laser_odometry.cbp ================================================ ================================================ FILE: src/rf2o_laser_odometry/include/rf2o_laser_odometry/CLaserOdometry2D.h ================================================ /** **************************************************************************************** * This node presents a fast and precise method to estimate the planar motion of a lidar * from consecutive range scans. It is very useful for the estimation of the robot odometry from * 2D laser range measurements. * This module is developed for mobile robots with innacurate or inexistent built-in odometry. * It allows the estimation of a precise odometry with low computational cost. * For more information, please refer to: * * Planar Odometry from a Radial Laser Scanner. A Range Flow-based Approach. ICRA'16. * Available at: http://mapir.isa.uma.es/mapirwebsite/index.php/mapir-downloads/papers/217 * * Maintainer: Javier G. Monroy * MAPIR group: http://mapir.isa.uma.es/ ******************************************************************************************** */ #ifndef CLaserOdometry2D_H #define CLaserOdometry2D_H #include #include #include #include #include #include // MRPT related headers #include #if MRPT_VERSION>=0x130 #include #include #include using namespace mrpt::obs; #else # include # include using namespace mrpt::slam; #include #endif #if MRPT_VERSION<0x150 # include #endif #include #include #include #include #include #include #include #include #include #include class CLaserOdometry2D { public: CLaserOdometry2D(); ~CLaserOdometry2D(); bool is_initialized(); bool scan_available(); void Init(); void odometryCalculation(); std::string laser_scan_topic; std::string odom_topic; bool publish_tf; std::string base_frame_id; std::string odom_frame_id; std::string init_pose_from_topic; double freq; protected: ros::NodeHandle n; sensor_msgs::LaserScan last_scan; bool module_initialized,first_laser_scan,new_scan_available, GT_pose_initialized, verbose; tf::TransformListener tf_listener; //Do not put inside the callback tf::TransformBroadcaster odom_broadcaster; nav_msgs::Odometry initial_robot_pose; //Subscriptions & Publishers ros::Subscriber laser_sub, initPose_sub; ros::Publisher odom_pub; //CallBacks void LaserCallBack(const sensor_msgs::LaserScan::ConstPtr& new_scan); void initPoseCallBack(const nav_msgs::Odometry::ConstPtr& new_initPose); // Internal Data std::vector range; std::vector range_old; std::vector range_inter; std::vector range_warped; std::vector xx; std::vector xx_inter; std::vector xx_old; std::vector xx_warped; std::vector yy; std::vector yy_inter; std::vector yy_old; std::vector yy_warped; std::vector transformations; Eigen::MatrixXf range_wf; Eigen::MatrixXf dtita; Eigen::MatrixXf dt; Eigen::MatrixXf rtita; Eigen::MatrixXf normx, normy, norm_ang; Eigen::MatrixXf weights; Eigen::MatrixXi null; Eigen::MatrixXf A,Aw; Eigen::MatrixXf B,Bw; Eigen::Matrix Var; //3 unknowns: vx, vy, w Eigen::Matrix cov_odo; //std::string LaserVarName; //Name of the topic containing the scan lasers \laser_scan float fps; //In Hz float fovh; //Horizontal FOV unsigned int cols; unsigned int cols_i; unsigned int width; unsigned int ctf_levels; unsigned int image_level, level; unsigned int num_valid_range; unsigned int iter_irls; float g_mask[5]; //mrpt::gui::CDisplayWindowPlots window; mrpt::utils::CTicTac m_clock; float m_runtime; ros::Time last_odom_time; mrpt::math::CMatrixFloat31 kai_abs; mrpt::math::CMatrixFloat31 kai_loc; mrpt::math::CMatrixFloat31 kai_loc_old; mrpt::math::CMatrixFloat31 kai_loc_level; mrpt::poses::CPose3D laser_pose; mrpt::poses::CPose3D laser_oldpose; mrpt::poses::CPose3D robot_pose; mrpt::poses::CPose3D robot_oldpose; bool test; std::vector last_m_lin_speeds; std::vector last_m_ang_speeds; // Methods void createImagePyramid(); void calculateCoord(); void performWarping(); void calculaterangeDerivativesSurface(); void computeNormals(); void computeWeights(); void findNullPoints(); void solveSystemOneLevel(); void solveSystemNonLinear(); void filterLevelSolution(); void PoseUpdate(); void Reset(mrpt::poses::CPose3D ini_pose, CObservation2DRangeScan scan); }; #endif ================================================ FILE: src/rf2o_laser_odometry/launch/rf2o_laser_odometry.launch ================================================ # topic where the lidar scans are being published # topic where tu publish the odometry estimations # wheter or not to publish the tf::transform (base->odom) # frame_id (tf) of the mobile robot base. A tf transform from the laser_frame to the base_frame is mandatory # frame_id (tf) to publish the odometry estimations # (Odom topic) Leave empty to start at point (0,0) # Execution frequency. # verbose ================================================ FILE: src/rf2o_laser_odometry/package.xml ================================================ rf2o_laser_odometry 1.0.0 Estimation of 2D odometry based on planar laser scans. Useful for mobile robots with innacurate base odometry. For full description of the algorithm, please refer to: Planar Odometry from a Radial Laser Scanner. A Range Flow-based Approach. ICRA 2016 Available at: http://mapir.isa.uma.es/mapirwebsite/index.php/mapir-downloads/papers/217 Javier G. Monroy Mariano Jaimez Javier G. Monroy GPL v3 catkin nav_msgs roscpp sensor_msgs std_msgs tf cmake_modules mrpt nav_msgs roscpp sensor_msgs std_msgs tf cmake_modules mrpt ================================================ FILE: src/rf2o_laser_odometry/src/CLaserOdometry2D.cpp ================================================ /** **************************************************************************************** * This node presents a fast and precise method to estimate the planar motion of a lidar * from consecutive range scans. It is very useful for the estimation of the robot odometry from * 2D laser range measurements. * This module is developed for mobile robots with innacurate or inexistent built-in odometry. * It allows the estimation of a precise odometry with low computational cost. * For more information, please refer to: * * Planar Odometry from a Radial Laser Scanner. A Range Flow-based Approach. ICRA'16. * Available at: http://mapir.isa.uma.es/mapirwebsite/index.php/mapir-downloads/papers/217 * * Maintainer: Javier G. Monroy * MAPIR group: http://mapir.isa.uma.es/ ******************************************************************************************** */ //#define rplidar #include "rf2o_laser_odometry/CLaserOdometry2D.h" using namespace mrpt; using namespace mrpt::math; using namespace mrpt::utils; using namespace mrpt::poses; using namespace std; using namespace Eigen; // -------------------------------------------- // CLaserOdometry2D //--------------------------------------------- CLaserOdometry2D::CLaserOdometry2D() { ROS_INFO("Initializing RF2O node..."); //Read Parameters //---------------- ros::NodeHandle pn("~"); pn.param("laser_scan_topic",laser_scan_topic,"/laser_scan"); pn.param("base_frame_id", base_frame_id, "/base_link"); pn.param("odom_frame_id", odom_frame_id, "/odom"); pn.param("freq",freq,10.0); //Publishers and Subscribers //-------------------------- odom_pub = pn.advertise(odom_frame_id, 5); laser_sub = n.subscribe(laser_scan_topic,1,&CLaserOdometry2D::LaserCallBack,this); //Init variables module_initialized = false; first_laser_scan = true; } CLaserOdometry2D::~CLaserOdometry2D() { } bool CLaserOdometry2D::is_initialized() { return module_initialized; } bool CLaserOdometry2D::scan_available() { return new_scan_available; } void CLaserOdometry2D::Init() { //Got an initial scan laser, obtain its parametes ROS_INFO("Got first Laser Scan .... Configuring node"); width = last_scan.ranges.size(); // Num of samples (size) of the scan laser cols = width; // Max reolution. Should be similar to the width parameter fovh = fabs(last_scan.angle_max - last_scan.angle_min); // Horizontal Laser's FOV ctf_levels = 5; // Coarse-to-Fine levels iter_irls = 5; //Num iterations to solve iterative reweighted least squares //Set laser pose on the robot (through tF) // This allow estimation of the odometry with respect to the robot base reference system. mrpt::poses::CPose3D LaserPoseOnTheRobot; tf::StampedTransform transform; try { tf_listener.lookupTransform("/base_link", last_scan.header.frame_id, ros::Time(0), transform); } catch (tf::TransformException &ex) { ROS_ERROR("%s",ex.what()); ros::Duration(1.0).sleep(); } //TF:transform -> mrpt::CPose3D (see mrpt-ros-bridge) const tf::Vector3 &t = transform.getOrigin(); LaserPoseOnTheRobot.x() = t[0]; LaserPoseOnTheRobot.y() = t[1]; LaserPoseOnTheRobot.z() = t[2]; const tf::Matrix3x3 &basis = transform.getBasis(); mrpt::math::CMatrixDouble33 R; for(int r = 0; r < 3; r++) for(int c = 0; c < 3; c++) R(r,c) = basis[r][c]; LaserPoseOnTheRobot.setRotationMatrix(R); //Set the initial pose laser_pose = LaserPoseOnTheRobot; laser_oldpose = LaserPoseOnTheRobot; // Init module //------------- range_wf.setSize(1, width); //Resize vectors according to levels transformations.resize(ctf_levels); for (unsigned int i = 0; i < ctf_levels; i++) transformations[i].resize(3, 3); //Resize pyramid unsigned int s, cols_i; const unsigned int pyr_levels = round(log2(round(float(width) / float(cols)))) + ctf_levels; range.resize(pyr_levels); range_old.resize(pyr_levels); range_inter.resize(pyr_levels); xx.resize(pyr_levels); xx_inter.resize(pyr_levels); xx_old.resize(pyr_levels); yy.resize(pyr_levels); yy_inter.resize(pyr_levels); yy_old.resize(pyr_levels); range_warped.resize(pyr_levels); xx_warped.resize(pyr_levels); yy_warped.resize(pyr_levels); for (unsigned int i = 0; i < pyr_levels; i++) { s = pow(2.f, int(i)); cols_i = ceil(float(width) / float(s)); range[i].resize(1, cols_i); range_inter[i].resize(1, cols_i); range_old[i].resize(1, cols_i); range[i].assign(0.0f); range_old[i].assign(0.0f); xx[i].resize(1, cols_i); xx_inter[i].resize(1, cols_i); xx_old[i].resize(1, cols_i); xx[i].assign(0.0f); xx_old[i].assign(0.0f); yy[i].resize(1, cols_i); yy_inter[i].resize(1, cols_i); yy_old[i].resize(1, cols_i); yy[i].assign(0.f); yy_old[i].assign(0.f); if (cols_i <= cols) { range_warped[i].resize(1, cols_i); xx_warped[i].resize(1, cols_i); yy_warped[i].resize(1, cols_i); } } dt.resize(1, cols); dtita.resize(1, cols); normx.resize(1, cols); normy.resize(1, cols); norm_ang.resize(1, cols); weights.setSize(1, cols); null.setSize(1, cols); null.assign(0); cov_odo.assign(0.f); fps = 1.f; //In Hz num_valid_range = 0; //Compute gaussian mask g_mask[0] = 1.f / 16.f; g_mask[1] = 0.25f; g_mask[2] = 6.f / 16.f; g_mask[3] = g_mask[1]; g_mask[4] = g_mask[0]; kai_abs.assign(0.f); kai_loc_old.assign(0.f); module_initialized = true; last_odom_time = ros::Time::now(); } void CLaserOdometry2D::odometryCalculation() { //================================================================================== // DIFERENTIAL ODOMETRY MULTILEVEL //================================================================================== m_clock.Tic(); createImagePyramid(); //Coarse-to-fine scheme for (unsigned int i=0; i 3) { solveSystemNonLinear(); //solveSystemOneLevel(); //without robust-function } //8. Filter solution filterLevelSolution(); } m_runtime = 1000*m_clock.Tac(); ROS_INFO("Time odometry (ms): %f", m_runtime); //Update poses PoseUpdate(); new_scan_available = false; //avoids the possibility to run twice on the same laser scan } void CLaserOdometry2D::createImagePyramid() { const float max_range_dif = 0.3f; //Push the frames back range_old.swap(range); xx_old.swap(xx); yy_old.swap(yy); //The number of levels of the pyramid does not match the number of levels used //in the odometry computation (because we sometimes want to finish with lower resolutions) unsigned int pyr_levels = round(log2(round(float(width)/float(cols)))) + ctf_levels; //Generate levels for (unsigned int i = 0; i Filter (not downsampling); if (i == 0) { for (unsigned int u = 0; u < cols_i; u++) { const float dcenter = range_wf(u); //Inner pixels if ((u>1)&&(u 0.f) { float sum = 0.f; float weight = 0.f; for (int l=-2; l<3; l++) { const float abs_dif = abs(range_wf(u+l)-dcenter); if (abs_dif < max_range_dif) { const float aux_w = g_mask[2+l]*(max_range_dif - abs_dif); weight += aux_w; sum += aux_w*range_wf(u+l); } } range[i](u) = sum/weight; } else range[i](u) = 0.f; } //Boundary else { if (dcenter > 0.f) { float sum = 0.f; float weight = 0.f; for (int l=-2; l<3; l++) { const int indu = u+l; if ((indu>=0)&&(indu0)&&(u 0.f) { float sum = 0.f; float weight = 0.f; for (int l=-2; l<3; l++) { const float abs_dif = abs(range[i_1](u2+l)-dcenter); if (abs_dif < max_range_dif) { const float aux_w = g_mask[2+l]*(max_range_dif - abs_dif); weight += aux_w; sum += aux_w*range[i_1](u2+l); } } range[i](u) = sum/weight; } else range[i](u) = 0.f; } //Boundary else { if (dcenter > 0.f) { float sum = 0.f; float weight = 0.f; const unsigned int cols_i2 = range[i_1].cols(); for (int l=-2; l<3; l++) { const int indu = u2+l; if ((indu>=0)&&(indu 0.f) { const float tita = -0.5*fovh + float(u)*fovh/float(cols_i-1); xx[i](u) = range[i](u)*cos(tita); yy[i](u) = range[i](u)*sin(tita); } else { xx[i](u) = 0.f; yy[i](u) = 0.f; } } } } void CLaserOdometry2D::calculateCoord() { for (unsigned int u = 0; u < cols_i; u++) { if ((range_old[image_level](u) == 0.f) || (range_warped[image_level](u) == 0.f)) { range_inter[image_level](u) = 0.f; xx_inter[image_level](u) = 0.f; yy_inter[image_level](u) = 0.f; } else { range_inter[image_level](u) = 0.5f*(range_old[image_level](u) + range_warped[image_level](u)); xx_inter[image_level](u) = 0.5f*(xx_old[image_level](u) + xx_warped[image_level](u)); yy_inter[image_level](u) = 0.5f*(yy_old[image_level](u) + yy_warped[image_level](u)); } } } void CLaserOdometry2D::calculaterangeDerivativesSurface() { //The gradient size ir reserved at the maximum size (at the constructor) //Compute connectivity rtita.resize(1,cols_i); //Defined in a different way now, without inversion rtita.assign(1.f); for (unsigned int u = 0; u < cols_i-1; u++) { const float dist = square(xx_inter[image_level](u+1) - xx_inter[image_level](u)) + square(yy_inter[image_level](u+1) - yy_inter[image_level](u)); if (dist > 0.f) rtita(u) = sqrt(dist); } //Spatial derivatives for (unsigned int u = 1; u < cols_i-1; u++) dtita(u) = (rtita(u-1)*(range_inter[image_level](u+1)-range_inter[image_level](u)) + rtita(u)*(range_inter[image_level](u) - range_inter[image_level](u-1)))/(rtita(u)+rtita(u-1)); dtita(0) = dtita(1); dtita(cols_i-1) = dtita(cols_i-2); //Temporal derivative for (unsigned int u = 0; u < cols_i; u++) dt(u) = fps*(range_warped[image_level](u) - range_old[image_level](u)); //Apply median filter to the range derivatives //MatrixXf dtitamed = dtita, dtmed = dt; //vector svector(3); //for (unsigned int u=1; u M_PI) norm_ang(u) -= M_PI; normx(u) = cos(tita + alfa); normy(u) = sin(tita + alfa); } } } void CLaserOdometry2D::computeWeights() { //The maximum weight size is reserved at the constructor weights.assign(0.f); //Parameters for error_linearization const float kdtita = 1.f; const float kdt = kdtita/square(fps); const float k2d = 0.2f; for (unsigned int u = 1; u < cols_i-1; u++) if (null(u) == 0) { // Compute derivatives //----------------------------------------------------------------------- const float ini_dtita = range_old[image_level](u+1) - range_old[image_level](u-1); const float final_dtita = range_warped[image_level](u+1) - range_warped[image_level](u-1); const float dtitat = ini_dtita - final_dtita; const float dtita2 = dtita(u+1) - dtita(u-1); const float w_der = kdt*square(dt(u)) + kdtita*square(dtita(u)) + k2d*(abs(dtitat) + abs(dtita2)); weights(u) = sqrt(1.f/w_der); } const float inv_max = 1.f/weights.maximum(); weights = inv_max*weights; } void CLaserOdometry2D::findNullPoints() { //Size of null matrix is set to its maximum size (constructor) num_valid_range = 0; for (unsigned int u = 1; u < cols_i-1; u++) { if (range_inter[image_level](u) == 0.f) null(u) = 1; else { num_valid_range++; null(u) = 0; } } } // Solves the system without considering any robust-function void CLaserOdometry2D::solveSystemOneLevel() { A.resize(num_valid_range,3); B.setSize(num_valid_range,1); unsigned int cont = 0; const float kdtita = (cols_i-1)/fovh; //Fill the matrix A and the vector B //The order of the variables will be (vx, vy, wz) for (unsigned int u = 1; u < cols_i-1; u++) if (null(u) == 0) { // Precomputed expressions const float tw = weights(u); const float tita = -0.5*fovh + u/kdtita; //Fill the matrix A A(cont, 0) = tw*(cos(tita) + dtita(u)*kdtita*sin(tita)/range_inter[image_level](u)); A(cont, 1) = tw*(sin(tita) - dtita(u)*kdtita*cos(tita)/range_inter[image_level](u)); A(cont, 2) = tw*(-yy[image_level](u)*cos(tita) + xx[image_level](u)*sin(tita) - dtita(u)*kdtita); B(cont,0) = tw*(-dt(u)); cont++; } //Solve the linear system of equations using a minimum least squares method MatrixXf AtA, AtB; AtA.multiply_AtA(A); AtB.multiply_AtB(A,B); Var = AtA.ldlt().solve(AtB); //Covariance matrix calculation Cov Order -> vx,vy,wz MatrixXf res(num_valid_range,1); res = A*Var - B; cov_odo = (1.f/float(num_valid_range-3))*AtA.inverse()*res.squaredNorm(); kai_loc_level = Var; } // Solves the system by considering the Cauchy M-estimatorrobust-function void CLaserOdometry2D::solveSystemNonLinear() { A.resize(num_valid_range,3); Aw.resize(num_valid_range,3); B.setSize(num_valid_range,1); Bw.setSize(num_valid_range,1); unsigned int cont = 0; const float kdtita = float(cols_i-1)/fovh; //Fill the matrix A and the vector B //The order of the variables will be (vx, vy, wz) for (unsigned int u = 1; u < cols_i-1; u++) if (null(u) == 0) { // Precomputed expressions const float tw = weights(u); const float tita = -0.5*fovh + u/kdtita; //Fill the matrix A A(cont, 0) = tw*(cos(tita) + dtita(u)*kdtita*sin(tita)/range_inter[image_level](u)); A(cont, 1) = tw*(sin(tita) - dtita(u)*kdtita*cos(tita)/range_inter[image_level](u)); A(cont, 2) = tw*(-yy[image_level](u)*cos(tita) + xx[image_level](u)*sin(tita) - dtita(u)*kdtita); B(cont,0) = tw*(-dt(u)); cont++; } //Solve the linear system of equations using a minimum least squares method MatrixXf AtA, AtB; AtA.multiply_AtA(A); AtB.multiply_AtB(A,B); Var = AtA.ldlt().solve(AtB); //Covariance matrix calculation Cov Order -> vx,vy,wz MatrixXf res(num_valid_range,1); res = A*Var - B; //cout << endl << "max res: " << res.maxCoeff(); //cout << endl << "min res: " << res.minCoeff(); ////Compute the energy //Compute the average dt float aver_dt = 0.f, aver_res = 0.f; unsigned int ind = 0; for (unsigned int u = 1; u < cols_i-1; u++) if (null(u) == 0) { aver_dt += fabsf(dt(u)); aver_res += fabsf(res(ind++)); } aver_dt /= cont; aver_res /= cont; // printf("\n Aver dt = %f, aver res = %f", aver_dt, aver_res); const float k = 10.f/aver_dt; //200 //float energy = 0.f; //for (unsigned int i=0; i 0.f) { //Transform point to the warped reference frame const float x_w = acu_trans(0,0)*xx[image_level](j) + acu_trans(0,1)*yy[image_level](j) + acu_trans(0,2); const float y_w = acu_trans(1,0)*xx[image_level](j) + acu_trans(1,1)*yy[image_level](j) + acu_trans(1,2); const float tita_w = atan2(y_w, x_w); const float range_w = sqrt(x_w*x_w + y_w*y_w); //Calculate warping const float uwarp = kdtita*(tita_w + 0.5*fovh); //The warped pixel (which is not integer in general) contributes to all the surrounding ones if (( uwarp >= 0.f)&&( uwarp < cols_lim)) { const int uwarp_l = uwarp; const int uwarp_r = uwarp_l + 1; const float delta_r = float(uwarp_r) - uwarp; const float delta_l = uwarp - float(uwarp_l); //Very close pixel if (abs(round(uwarp) - uwarp) < 0.05f) { range_warped[image_level](round(uwarp)) += range_w; wacu(round(uwarp)) += 1.f; } else { const float w_r = square(delta_l); range_warped[image_level](uwarp_r) += w_r*range_w; wacu(uwarp_r) += w_r; const float w_l = square(delta_r); range_warped[image_level](uwarp_l) += w_l*range_w; wacu(uwarp_l) += w_l; } } } } //Scale the averaged range and compute coordinates for (unsigned int u = 0; u 0.f) { const float tita = -0.5f*fovh + float(u)/kdtita; range_warped[image_level](u) /= wacu(u); xx_warped[image_level](u) = range_warped[image_level](u)*cos(tita); yy_warped[image_level](u) = range_warped[image_level](u)*sin(tita); } else { range_warped[image_level](u) = 0.f; xx_warped[image_level](u) = 0.f; yy_warped[image_level](u) = 0.f; } } } void CLaserOdometry2D::filterLevelSolution() { // Calculate Eigenvalues and Eigenvectors //---------------------------------------------------------- SelfAdjointEigenSolver eigensolver(cov_odo); if (eigensolver.info() != Success) { printf("Eigensolver couldn't find a solution. Pose is not updated"); return; } //First, we have to describe both the new linear and angular speeds in the "eigenvector" basis //------------------------------------------------------------------------------------------------- Matrix Bii; Matrix kai_b; Bii = eigensolver.eigenvectors(); kai_b = Bii.colPivHouseholderQr().solve(kai_loc_level); //Second, we have to describe both the old linear and angular speeds in the "eigenvector" basis too //------------------------------------------------------------------------------------------------- CMatrixFloat31 kai_loc_sub; //Important: we have to substract the solutions from previous levels Matrix3f acu_trans; acu_trans.setIdentity(); for (unsigned int i=0; i 1.f) kai_loc_sub(2) = 0.f; else kai_loc_sub(2) = -fps*acos(acu_trans(0,0))*sign(acu_trans(1,0)); kai_loc_sub += kai_loc_old; Matrix kai_b_old; kai_b_old = Bii.colPivHouseholderQr().solve(kai_loc_sub); //Filter speed const float cf = 15e3f*expf(-int(level)), df = 0.05f*expf(-int(level)); Matrix kai_b_fil; for (unsigned int i=0; i<3; i++) { kai_b_fil(i,0) = (kai_b(i,0) + (cf*eigensolver.eigenvalues()(i,0) + df)*kai_b_old(i,0))/(1.f + cf*eigensolver.eigenvalues()(i,0) + df); //kai_b_fil_f(i,0) = (1.f*kai_b(i,0) + 0.f*kai_b_old_f(i,0))/(1.0f + 0.f); } //Transform filtered speed to local reference frame and compute transformation Matrix kai_loc_fil = Bii.inverse().colPivHouseholderQr().solve(kai_b_fil); //transformation const float incrx = kai_loc_fil(0)/fps; const float incry = kai_loc_fil(1)/fps; const float rot = kai_loc_fil(2)/fps; transformations[level](0,0) = cos(rot); transformations[level](0,1) = -sin(rot); transformations[level](1,0) = sin(rot); transformations[level](1,1) = cos(rot); transformations[level](0,2) = incrx; transformations[level](1,2) = incry; } void CLaserOdometry2D::PoseUpdate() { //First, compute the overall transformation //--------------------------------------------------- Matrix3f acu_trans; acu_trans.setIdentity(); for (unsigned int i=1; i<=ctf_levels; i++) acu_trans = transformations[i-1]*acu_trans; // Compute kai_loc and kai_abs //-------------------------------------------------------- kai_loc(0) = fps*acu_trans(0,2); kai_loc(1) = fps*acu_trans(1,2); if (acu_trans(0,0) > 1.f) kai_loc(2) = 0.f; else kai_loc(2) = fps*acos(acu_trans(0,0))*sign(acu_trans(1,0)); //cout << endl << "Arc cos (incr tita): " << kai_loc(2); float phi = laser_pose.yaw(); kai_abs(0) = kai_loc(0)*cos(phi) - kai_loc(1)*sin(phi); kai_abs(1) = kai_loc(0)*sin(phi) + kai_loc(1)*cos(phi); kai_abs(2) = kai_loc(2); // Update poses //------------------------------------------------------- laser_oldpose = laser_pose; math::CMatrixDouble33 aux_acu = acu_trans; poses::CPose3D pose_aux_2D(acu_trans(0,2), acu_trans(1,2),0, kai_loc(2)/fps,0,0); laser_pose = laser_pose + pose_aux_2D; //laser_pose = laser_pose + pose_aux_2D; // Compute kai_loc_old //------------------------------------------------------- //phi = laser_pose.yaw(); phi = laser_pose.yaw() + pose_aux_2D.y(); kai_loc_old(0) = kai_abs(0)*cos(phi) + kai_abs(1)*sin(phi); kai_loc_old(1) = -kai_abs(0)*sin(phi) + kai_abs(1)*cos(phi); kai_loc_old(2) = kai_abs(2); ROS_INFO("LASERodom = [%f %f %f]",laser_pose.x(),laser_pose.y(),laser_pose.yaw()); // GET ROBOT POSE from LASER POSE //------------------------------ mrpt::poses::CPose3D LaserPoseOnTheRobot_inv; tf::StampedTransform transform; try { tf_listener.lookupTransform(last_scan.header.frame_id, "/base_link", ros::Time(0), transform); } catch (tf::TransformException &ex) { ROS_ERROR("%s",ex.what()); ros::Duration(1.0).sleep(); } //TF:transform -> mrpt::CPose3D (see mrpt-ros-bridge) const tf::Vector3 &t = transform.getOrigin(); LaserPoseOnTheRobot_inv.x() = t[0]; LaserPoseOnTheRobot_inv.y() = t[1]; LaserPoseOnTheRobot_inv.z() = t[2]; const tf::Matrix3x3 &basis = transform.getBasis(); mrpt::math::CMatrixDouble33 R; for(int r = 0; r < 3; r++) for(int c = 0; c < 3; c++) R(r,c) = basis[r][c]; LaserPoseOnTheRobot_inv.setRotationMatrix(R); //Compose Transformations robot_pose = laser_pose + LaserPoseOnTheRobot_inv; ROS_INFO("BASEodom = [%f %f %f]",robot_pose.x(),robot_pose.y(),robot_pose.yaw()); // Estimate linear/angular speeds (mandatory for base_local_planner) // last_scan -> the last scan received // last_odom_time -> The time of the previous scan lasser used to estimate the pose //------------------------------------------------------------------------------------- double time_inc_sec = (last_scan.header.stamp - last_odom_time).toSec(); last_odom_time = last_scan.header.stamp; double lin_speed = acu_trans(0,2) / time_inc_sec; //double lin_speed = sqrt( square(robot_oldpose.x()-robot_pose.x()) + square(robot_oldpose.y()-robot_pose.y()) )/time_inc_sec; double ang_inc = robot_pose.yaw() - robot_oldpose.yaw(); if (ang_inc > 3.14159) ang_inc -= 2*3.14159; if (ang_inc < -3.14159) ang_inc += 2*3.14159; double ang_speed = ang_inc/time_inc_sec; robot_oldpose = robot_pose; //filter speeds /* last_m_lin_speeds.push_back(lin_speed); if (last_m_lin_speeds.size()>4) last_m_lin_speeds.erase(last_m_lin_speeds.begin()); double sum = std::accumulate(last_m_lin_speeds.begin(), last_m_lin_speeds.end(), 0.0); lin_speed = sum / last_m_lin_speeds.size(); last_m_ang_speeds.push_back(ang_speed); if (last_m_ang_speeds.size()>4) last_m_ang_speeds.erase(last_m_ang_speeds.begin()); double sum2 = std::accumulate(last_m_ang_speeds.begin(), last_m_ang_speeds.end(), 0.0); ang_speed = sum2 / last_m_ang_speeds.size(); */ //first, we'll publish the odometry over tf //--------------------------------------- geometry_msgs::TransformStamped odom_trans; odom_trans.header.stamp = ros::Time::now(); odom_trans.header.frame_id = odom_frame_id; odom_trans.child_frame_id = base_frame_id; odom_trans.transform.translation.x = robot_pose.x(); odom_trans.transform.translation.y = robot_pose.y(); odom_trans.transform.translation.z = 0.0; odom_trans.transform.rotation = tf::createQuaternionMsgFromYaw(robot_pose.yaw()); //send the transform //odom_broadcaster.sendTransform(odom_trans); //next, we'll publish the odometry message over ROS //------------------------------------------------- nav_msgs::Odometry odom; odom.header.stamp = ros::Time::now(); odom.header.frame_id = odom_frame_id; //set the position odom.pose.pose.position.x = robot_pose.x(); odom.pose.pose.position.y = robot_pose.y(); odom.pose.pose.position.z = 0.0; odom.pose.pose.orientation = tf::createQuaternionMsgFromYaw(robot_pose.yaw()); //set the velocity odom.child_frame_id = base_frame_id; #ifdef rplidar odom.twist.twist.linear.x = lin_speed; //linear speed #else odom.twist.twist.linear.x = -lin_speed; //linear speed #endif odom.twist.twist.linear.y = 0.0; odom.twist.twist.angular.z = ang_speed; //angular speed odom.pose.covariance[0] = 0.1; odom.pose.covariance[7] = 0.1; odom.pose.covariance[14] = 0.1; odom.pose.covariance[21] = 0.0025; odom.pose.covariance[28] = 0.0025; odom.pose.covariance[25] = 0.0025; odom.twist.covariance[0] = 0.25; odom.twist.covariance[7] = 0.25; odom.twist.covariance[14] = 0.1; odom.twist.covariance[21] = 0.02; odom.twist.covariance[28] = 0.02; odom.twist.covariance[25] = 0.02; /* //set the pose covariance DAVID odom.pose.covariance = {0.1, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0025, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0025, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0025}; //set the twist covariance DAVID odom.twist.covariance = {0.25, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.02, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.02, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.02}; */ //publish the message odom_pub.publish(odom); } //----------------------------------------------------------------------------------- // CALLBACKS //----------------------------------------------------------------------------------- void CLaserOdometry2D::LaserCallBack(const sensor_msgs::LaserScan::ConstPtr& new_scan) { //Keep in memory the last received laser_scan last_scan = *new_scan; //Initialize module on first scan if (first_laser_scan) { Init(); first_laser_scan = false; } else { //copy laser scan to internal variable for (unsigned int i = 0; iranges[i]; new_scan_available = true; } } //----------------------------------------------------------------------------------- // MAIN //----------------------------------------------------------------------------------- int main(int argc, char** argv) { ros::init(argc, argv, "RF2O_LaserOdom"); CLaserOdometry2D myLaserOdom; //Main Loop //---------- ROS_INFO("initialization complete...Looping"); ros::Rate loop_rate(myLaserOdom.freq); while (ros::ok()) { ros::spinOnce(); //Check for new laser scans ROS_INFO("LOOP"); if( myLaserOdom.is_initialized() && myLaserOdom.scan_available() ) { //Process odometry estimation myLaserOdom.odometryCalculation(); ROS_INFO("odom calc"); } else { ROS_WARN("Waiting for laser_scans....") ; } loop_rate.sleep(); } return(0); } ================================================ FILE: src/robot_localization/CHANGELOG.rst ================================================ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package robot_localization ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2.4.3 (2018-04-11) ------------------ * Add published accel topic to documentation * Adding log statements for nans in the invertable matrix * Fixing issue with potential seg fault * Contributors: Oleg Kalachev, Tom Moore, stevemacenski 2.4.2 (2018-01-03) ------------------ * Fixing CMakeLists * Contributors: Tom Moore 2.4.1 (2017-12-15) ------------------ * Fixing datum precision * Fixing state history reversion * Silencing unnecessary errors and warnings * Fixing critical bug with dynamic process noise covariance * Some trivial changes to lessen the differences to lunar * Fix typo in reading Mahalanobis thresholds. * Zero out rotation in GPS to base_link transform * Update xmlrpcpp includes for Indigo support * Removing lastUpdateTime * Fixing timestamps in map->odom transform * Simplify enabledAtStartup logic * Add std_srvs dependency * Add enabling service * Ensure all raw sensor input orientations are normalized even if messages are not * Install params directory * Add robot localization estimator * Contributors: Jacob Perron, Jacob Seibert, Jiri Hubacek, Mike Purvis, Miquel Massot, Pavlo Kolomiiets, Rein Appeldoorn, Rokus Ottervanger, Tom Moore, stevemacenski 2.4.0 (2017-06-12) ------------------ * Updated documentation * Added reset_on_time_jump option * Added feature to optionally publish utm frame as parent in navsat_transform_node * Moved global callback queue reset * Added initial_state parameter and documentation * Fixed ac/deceleration gains default logic * Added gravity parameter * Added delay and throttle if tf lookup fails * Fixed UKF IMUTwistBasicIO test * Added transform_timeout parameter * Set gps_odom timestamp before tf2 lookuptransform * Removed non-portable sincos calls * Simplified logic to account for correlated error * Added dynamic process noise covariance calculation * Fixed catkin_package Eigen warning * Added optional publication of acceleration state * Contributors: Brian Gerkey, Enrique Fernandez, Jochen Sprickerhof, Rein Appeldoorn, Simon Gene Gottlieb, Tom Moore 2.3.1 (2016-10-27) ------------------ * Adding gitignore * Adding remaining wiki pages * Adding config and prep pages * Adding navsat_transform_node documentation * use_odometry_yaw fix for n_t_n * Fixing issue with manual pose reset when history is not empty * Getting inverse transform when looking up robot's pose. * Sphinx documentation * Removing forward slashes from navsat_transform input topics for template launch file * Adding example launch and parameter files for a two-level EKF setup with navsat_transform_node * Adding yaml file for navsat_transform_node, and moving parameter documentation to it. * Updating EKF and UKF parameter templates with usage comments * Contributors: Tom Moore, asimay 2.3.0 (2016-07-28) ------------------ * Fixed issues with datum usage and frame_ids * Fixed comment for wait_for_datum * Fixing issue with non-zero navsat sensor orientation offsets * Fixing issue with base_link->gps transform wrecking the 'true' UTM position computation * Using correct covariance for filtered GPS * Fixed unitialized odometry covariance bug * Added filter history and measurement queue behavior * Changing output timestamp to more accurately use the time stamp of the most recently-processed measurement * Added TcpNoDelay() * Added parameter to make transform publishing optional * Fixed differential handling for pose data so that it doesn't care about the message's frame_id * Updated UKF config and launch * Added a test case for the timestamp diagnostics * Added reporting of bad timestamps via diagnostics * Updated tests to match new method signatures * Added control term * Added smoothing capability for delayed measurements * Making variables in navsat_transform conform to ROS coding standards * Contributors: Adel Fakih, Ivor Wanders, Marc Essinger, Tobias Tueylue, Tom Moore 2.2.3 (2016-04-24) ------------------ * Cleaning up callback data structure and callbacks and updating doxygen comments in headers * Removing MessageFilters * Removing deprecated parameters * Adding the ability to handle GPS offsets from the vehicle's origin * Cleaning up navsat_transform.h * Making variables in navsat_transform conform to ROS coding standards 2.2.2 (2016-02-04) ------------------ * Updating trig functions to use sincos for efficiency * Updating licensing information and adding Eigen MPL-only flag * Added state to imu frame transformation * Using state orientation if imu orientation is missing * Manually adding second spin for odometry and IMU data that is passed to message filters * Reducing delay between measurement reception and filter output * Zero altitute in intital transform too, when zero altitude param is set * Fixing regression with conversion back to GPS coordinates * Switched cropping of orientation data in inovationSubset with mahalanobis check to prevent excluding measurements with orientations bigger/smaller than ± PI * Fix Jacobian for EKF. * Removing warning about orientation variables when only their velocities are measured * Checking for -1 in IMU covariances and ignoring relevant message data * roslint and catkin_lint applied * Adding base_link to datum specification, and fixing bug with order of measurement handling when a datum is specified. Also added check to make sure IMU data is transformable before using it. * Contributors: Adnan Ademovic, Jit Ray Chowdhury, Philipp Tscholl, Tom Moore, ayrton04, kphil 2.2.1 (2015-05-27) ------------------ * Fixed handling of IMU data w.r.t. differential mode and relative mode 2.2.0 (2015-05-22) ------------------ * Added tf2-friendly tf_prefix appending * Corrected for IMU orientation in navsat_transform * Fixed issue with out-of-order measurements and pose resets * Nodes now assume ENU standard for yaw data * Removed gps_common dependency * Adding option to navsat_transform_node that enables the use of the heading from the odometry message instead of an IMU. * Changed frame_id used in setPoseCallback to be the world_frame * Optimized Eigen arithmetic for signficiant performance boost * Migrated to tf2 * Code refactoring and reorganization * Removed roll and pitch from navsat_transform calculations * Fixed transform for IMU data to better support mounting IMUs in non-standard orientations * Added feature to navsat_transform_node whereby filtered odometry data can be coverted back into navsat data * Added a parameter to allow future dating the world_frame->base_link_frame transform. * Removed deprecated differential setting handler * Added relative mode * Updated and improved tests * Fixing source frame_id in pose data handling * Added initial covariance parameter * Fixed bug in covariance copyinh * Added parameters for topic queue sizes * Improved motion model's handling of angular velocities when robot has non-zero roll and pitch * Changed the way differential measurements are handled * Added diagnostics 2.1.7 (2015-01-05) ------------------ * Added some checks to eliminate unnecessary callbacks * Updated launch file templates * Added measurement outlier rejection * Added failure callbacks for tf message filters * Added optional broadcast of world_frame->utm transform for navsat_transform_node * Bug fixes for differential mode and handling of Z acceleration in 2D mode 2.1.6 (2014-11-06) ------------------ * Added unscented Kalman filter (UKF) localization node * Fixed map->odom tf calculation * Acceleration data from IMUs is now used in computing the state estimate * Added 2D mode 2.1.5 (2014-10-07) ------------------ * Changed initial estimate error covariance to be much smaller * Fixed some debug output * Added test suite * Better compliance with REP-105 * Fixed differential measurement handling * Implemented message filters * Added navsat_transform_node 2.1.4 (2014-08-22) ------------------ * Adding utm_transform_node to install targets 2.1.3 (2014-06-22) ------------------ * Some changes to ease GPS integration * Addition of differential integration of pose data * Some documentation cleanup * Added UTM transform node and launch file * Bug fixes 2.1.2 (2014-04-11) ------------------ * Updated covariance correction formulation to "Joseph form" to improve filter stability. * Implemented new versioning scheme. 2.1.1 (2014-04-11) ------------------ * Added cmake_modules dependency for Eigen support, and added include to silence boost::signals warning from tf include ================================================ FILE: src/robot_localization/CMakeLists.txt ================================================ cmake_minimum_required(VERSION 2.8.3) project(robot_localization) find_package(catkin REQUIRED COMPONENTS diagnostic_msgs diagnostic_updater eigen_conversions geographic_msgs geometry_msgs message_filters message_generation nav_msgs roscpp roslint sensor_msgs std_msgs std_srvs tf2 tf2_geometry_msgs tf2_ros xmlrpcpp) find_package(PkgConfig REQUIRED) pkg_check_modules(YAML_CPP yaml-cpp) # Attempt to find Eigen using its own CMake module. # If that fails, fall back to cmake_modules package. find_package(Eigen3) set(EIGEN_PACKAGE EIGEN3) if(NOT EIGEN3_FOUND) find_package(cmake_modules REQUIRED) find_package(Eigen REQUIRED) set(EIGEN3_INCLUDE_DIRS ${EIGEN_INCLUDE_DIRS}) set(EIGEN3_LIBRARIES ${EIGEN_LIBRARIES}) set(EIGEN_PACKAGE Eigen) endif() add_definitions(-DEIGEN_NO_DEBUG -DEIGEN_MPL2_ONLY) roslint_cpp() ################################### ## catkin specific configuration ## ################################### add_service_files( FILES GetState.srv SetDatum.srv SetPose.srv ) generate_messages( DEPENDENCIES geographic_msgs geometry_msgs std_msgs ) catkin_package( INCLUDE_DIRS include LIBRARIES ekf filter_base filter_utilities navsat_transform ros_filter ros_filter_utilities robot_localization_estimator ros_robot_localization_listener ukf CATKIN_DEPENDS cmake_modules diagnostic_msgs diagnostic_updater eigen_conversions geographic_msgs geometry_msgs message_filters message_runtime nav_msgs roscpp sensor_msgs std_msgs std_srvs tf2 tf2_geometry_msgs tf2_ros xmlrpcpp DEPENDS ${EIGEN_PACKAGE} YAML_CPP ) ########### ## Build ## ########### include_directories( include ${catkin_INCLUDE_DIRS} ${EIGEN3_INCLUDE_DIRS} ${YAML_CPP_INCLUDE_DIRS}) link_directories(${YAML_CPP_LIBRARY_DIRS}) # Library definitions add_library(filter_utilities src/filter_utilities.cpp) add_library(filter_base src/filter_base.cpp) add_library(ekf src/ekf.cpp) add_library(ukf src/ukf.cpp) add_library(robot_localization_estimator src/robot_localization_estimator.cpp) add_library(ros_robot_localization_listener src/ros_robot_localization_listener.cpp) add_library(ros_filter_utilities src/ros_filter_utilities.cpp) add_library(ros_filter src/ros_filter.cpp) add_library(navsat_transform src/navsat_transform.cpp) # Executables add_executable(ekf_localization_node src/ekf_localization_node.cpp) add_executable(ukf_localization_node src/ukf_localization_node.cpp) add_executable(navsat_transform_node src/navsat_transform_node.cpp) add_executable(robot_localization_listener_node src/robot_localization_listener_node.cpp) # Dependencies add_dependencies(filter_base ${PROJECT_NAME}_gencpp) add_dependencies(navsat_transform ${PROJECT_NAME}_gencpp) add_dependencies(robot_localization_listener_node ${PROJECT_NAME}_gencpp) # Linking target_link_libraries(ros_filter_utilities ${catkin_LIBRARIES} ${EIGEN3_LIBRARIES}) target_link_libraries(filter_utilities ${catkin_LIBRARIES} ${EIGEN3_LIBRARIES}) target_link_libraries(filter_base filter_utilities ${catkin_LIBRARIES} ${EIGEN3_LIBRARIES}) target_link_libraries(ekf filter_base ${catkin_LIBRARIES} ${EIGEN3_LIBRARIES}) target_link_libraries(ukf filter_base ${catkin_LIBRARIES} ${EIGEN3_LIBRARIES}) target_link_libraries(ros_filter ekf ukf ros_filter_utilities ${catkin_LIBRARIES} ${EIGEN3_LIBRARIES}) target_link_libraries(robot_localization_estimator filter_utilities filter_base ekf ukf ${EIGEN3_LIBRARIES}) target_link_libraries(ros_robot_localization_listener robot_localization_estimator ros_filter_utilities ${catkin_LIBRARIES} ${EIGEN3_LIBRARIES} ${YAML_CPP_LIBRARIES}) target_link_libraries(robot_localization_listener_node ros_robot_localization_listener ${catkin_LIBRARIES}) target_link_libraries(ekf_localization_node ros_filter ${catkin_LIBRARIES}) target_link_libraries(ukf_localization_node ros_filter ${catkin_LIBRARIES}) target_link_libraries(navsat_transform filter_utilities ros_filter_utilities ${catkin_LIBRARIES} ${EIGEN3_LIBRARIES}) target_link_libraries(navsat_transform_node navsat_transform ${catkin_LIBRARIES}) ############# ## Install ## ############# ## Mark executables and/or libraries for installation install(TARGETS ekf ekf_localization_node filter_base filter_utilities navsat_transform navsat_transform_node ros_filter ros_filter_utilities robot_localization_estimator ros_robot_localization_listener robot_localization_listener_node ukf ukf_localization_node ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) ## Mark cpp header files for installation install(DIRECTORY include/${PROJECT_NAME}/ DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} FILES_MATCHING PATTERN "*.h" PATTERN ".svn" EXCLUDE) install(DIRECTORY launch/ DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch FILES_MATCHING PATTERN "*.launch") install(DIRECTORY params/ DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/params) install(FILES LICENSE DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} ) ############# ## Testing ## ############# if (CATKIN_ENABLE_TESTING) # Not really necessary, but it will cause the build to fail if it's # missing, rather than failing once the tests are being executed find_package(rosbag REQUIRED) find_package(rostest REQUIRED) #### FILTER BASE TESTS #### catkin_add_gtest(filter_base-test test/test_filter_base.cpp) target_link_libraries(filter_base-test filter_base ${catkin_LIBRARIES}) # This test uses ekf_localization node for convenience. add_rostest_gtest(test_filter_base_diagnostics_timestamps test/test_filter_base_diagnostics_timestamps.test test/test_filter_base_diagnostics_timestamps.cpp) target_link_libraries(test_filter_base_diagnostics_timestamps ${catkin_LIBRARIES} ${rostest_LIBRARIES}) add_dependencies(test_filter_base_diagnostics_timestamps ekf_localization_node) #### EKF TESTS ##### add_rostest_gtest(test_ekf test/test_ekf.test test/test_ekf.cpp) target_link_libraries(test_ekf ros_filter ekf ${catkin_LIBRARIES} ${rostest_LIBRARIES}) add_rostest_gtest(test_ekf_localization_node_interfaces test/test_ekf_localization_node_interfaces.test test/test_ekf_localization_node_interfaces.cpp) target_link_libraries(test_ekf_localization_node_interfaces ${catkin_LIBRARIES} ${rostest_LIBRARIES}) add_rostest_gtest(test_ekf_localization_node_bag1 test/test_ekf_localization_node_bag1.test test/test_localization_node_bag_pose_tester.cpp) target_link_libraries(test_ekf_localization_node_bag1 ${catkin_LIBRARIES} ${rostest_LIBRARIES}) add_rostest_gtest(test_ekf_localization_node_bag2 test/test_ekf_localization_node_bag2.test test/test_localization_node_bag_pose_tester.cpp) target_link_libraries(test_ekf_localization_node_bag2 ${catkin_LIBRARIES} ${rostest_LIBRARIES}) add_rostest_gtest(test_ekf_localization_node_bag3 test/test_ekf_localization_node_bag3.test test/test_localization_node_bag_pose_tester.cpp) target_link_libraries(test_ekf_localization_node_bag3 ${catkin_LIBRARIES} ${rostest_LIBRARIES}) #### UKF TESTS ##### add_rostest_gtest(test_ukf test/test_ukf.test test/test_ukf.cpp) target_link_libraries(test_ukf ros_filter ukf ${catkin_LIBRARIES} ${rostest_LIBRARIES}) add_rostest_gtest(test_ukf_localization_node_interfaces test/test_ukf_localization_node_interfaces.test test/test_ukf_localization_node_interfaces.cpp) target_link_libraries(test_ukf_localization_node_interfaces ${catkin_LIBRARIES} ${rostest_LIBRARIES}) add_rostest_gtest(test_ukf_localization_node_bag1 test/test_ukf_localization_node_bag1.test test/test_localization_node_bag_pose_tester.cpp) target_link_libraries(test_ukf_localization_node_bag1 ${catkin_LIBRARIES} ${rostest_LIBRARIES}) add_rostest_gtest(test_ukf_localization_node_bag2 test/test_ukf_localization_node_bag2.test test/test_localization_node_bag_pose_tester.cpp) target_link_libraries(test_ukf_localization_node_bag2 ${catkin_LIBRARIES} ${rostest_LIBRARIES}) add_rostest_gtest(test_ukf_localization_node_bag3 test/test_ukf_localization_node_bag3.test test/test_localization_node_bag_pose_tester.cpp) target_link_libraries(test_ukf_localization_node_bag3 ${catkin_LIBRARIES} ${rostest_LIBRARIES}) #### RLE/RLL TESTS ##### add_rostest_gtest(test_robot_localization_estimator test/test_robot_localization_estimator.test test/test_robot_localization_estimator.cpp) target_link_libraries(test_robot_localization_estimator robot_localization_estimator ${catkin_LIBRARIES} ${rostest_LIBRARIES}) add_executable(test_ros_robot_localization_listener_publisher test/test_ros_robot_localization_listener_publisher.cpp) target_link_libraries(test_ros_robot_localization_listener_publisher ${catkin_LIBRARIES}) add_rostest_gtest(test_ros_robot_localization_listener test/test_ros_robot_localization_listener.test test/test_ros_robot_localization_listener.cpp) target_link_libraries(test_ros_robot_localization_listener ros_robot_localization_listener ${catkin_LIBRARIES} ${rostest_LIBRARIES}) endif() ================================================ FILE: src/robot_localization/LICENSE ================================================ All code within the robot_localization package that was developed by Charles River Analytics is released under the BSD license: Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. All rights reserved. Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: * Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. * Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. * Neither the name of the {organization} nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT 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. ========================================================================== The robot_localization package also makes use of code written by The University of Texas at Austin. This code is released under a modified BSD license: Copyright (C) 2010 Austin Robot Technology, and others All rights reserved. Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: * Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. * Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. * Neither the names of the University of Texas at Austin, nor Austin Robot Technology, nor the names of other contributors may be used to endorse or promote products derived from this software without specific prior written permission. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ================================================ FILE: src/robot_localization/README.md ================================================ robot_localization ================== robot_localization is a package of nonlinear state estimation nodes. The package was developed by Charles River Analytics, Inc. Please see documentation here: http://wiki.ros.org/robot_localization ================================================ FILE: src/robot_localization/doc/.templates/full_globaltoc.html ================================================

{{ _('Table Of Contents') }}

{{ toctree(includehidden=True) }}

{{ _('Further Documentation') }}

================================================ FILE: src/robot_localization/doc/Makefile ================================================ # Makefile for Sphinx documentation # # You can set these variables from the command line. SPHINXOPTS = SPHINXBUILD = sphinx-build PAPER = BUILDDIR = .build # User-friendly check for sphinx-build ifeq ($(shell which $(SPHINXBUILD) >/dev/null 2>&1; echo $$?), 1) $(error The '$(SPHINXBUILD)' command was not found. Make sure you have Sphinx installed, then set the SPHINXBUILD environment variable to point to the full path of the '$(SPHINXBUILD)' executable. Alternatively you can add the directory with the executable to your PATH. If you don't have Sphinx installed, grab it from http://sphinx-doc.org/) endif # Internal variables. PAPEROPT_a4 = -D latex_paper_size=a4 PAPEROPT_letter = -D latex_paper_size=letter ALLSPHINXOPTS = -d $(BUILDDIR)/doctrees $(PAPEROPT_$(PAPER)) $(SPHINXOPTS) . # the i18n builder cannot share the environment and doctrees with the others I18NSPHINXOPTS = $(PAPEROPT_$(PAPER)) $(SPHINXOPTS) . .PHONY: help help: @echo "Please use \`make ' where is one of" @echo " html to make standalone HTML files" @echo " dirhtml to make HTML files named index.html in directories" @echo " singlehtml to make a single large HTML file" @echo " pickle to make pickle files" @echo " json to make JSON files" @echo " htmlhelp to make HTML files and a HTML help project" @echo " qthelp to make HTML files and a qthelp project" @echo " applehelp to make an Apple Help Book" @echo " devhelp to make HTML files and a Devhelp project" @echo " epub to make an epub" @echo " latex to make LaTeX files, you can set PAPER=a4 or PAPER=letter" @echo " latexpdf to make LaTeX files and run them through pdflatex" @echo " latexpdfja to make LaTeX files and run them through platex/dvipdfmx" @echo " text to make text files" @echo " man to make manual pages" @echo " texinfo to make Texinfo files" @echo " info to make Texinfo files and run them through makeinfo" @echo " gettext to make PO message catalogs" @echo " changes to make an overview of all changed/added/deprecated items" @echo " xml to make Docutils-native XML files" @echo " pseudoxml to make pseudoxml-XML files for display purposes" @echo " linkcheck to check all external links for integrity" @echo " doctest to run all doctests embedded in the documentation (if enabled)" @echo " coverage to run coverage check of the documentation (if enabled)" .PHONY: clean clean: rm -rf $(BUILDDIR)/* .PHONY: html html: $(SPHINXBUILD) -b html $(ALLSPHINXOPTS) $(BUILDDIR)/html @echo @echo "Build finished. The HTML pages are in $(BUILDDIR)/html." .PHONY: dirhtml dirhtml: $(SPHINXBUILD) -b dirhtml $(ALLSPHINXOPTS) $(BUILDDIR)/dirhtml @echo @echo "Build finished. The HTML pages are in $(BUILDDIR)/dirhtml." .PHONY: singlehtml singlehtml: $(SPHINXBUILD) -b singlehtml $(ALLSPHINXOPTS) $(BUILDDIR)/singlehtml @echo @echo "Build finished. The HTML page is in $(BUILDDIR)/singlehtml." .PHONY: pickle pickle: $(SPHINXBUILD) -b pickle $(ALLSPHINXOPTS) $(BUILDDIR)/pickle @echo @echo "Build finished; now you can process the pickle files." .PHONY: json json: $(SPHINXBUILD) -b json $(ALLSPHINXOPTS) $(BUILDDIR)/json @echo @echo "Build finished; now you can process the JSON files." .PHONY: htmlhelp htmlhelp: $(SPHINXBUILD) -b htmlhelp $(ALLSPHINXOPTS) $(BUILDDIR)/htmlhelp @echo @echo "Build finished; now you can run HTML Help Workshop with the" \ ".hhp project file in $(BUILDDIR)/htmlhelp." .PHONY: qthelp qthelp: $(SPHINXBUILD) -b qthelp $(ALLSPHINXOPTS) $(BUILDDIR)/qthelp @echo @echo "Build finished; now you can run "qcollectiongenerator" with the" \ ".qhcp project file in $(BUILDDIR)/qthelp, like this:" @echo "# qcollectiongenerator $(BUILDDIR)/qthelp/robot_localization.qhcp" @echo "To view the help file:" @echo "# assistant -collectionFile $(BUILDDIR)/qthelp/robot_localization.qhc" .PHONY: applehelp applehelp: $(SPHINXBUILD) -b applehelp $(ALLSPHINXOPTS) $(BUILDDIR)/applehelp @echo @echo "Build finished. The help book is in $(BUILDDIR)/applehelp." @echo "N.B. You won't be able to view it unless you put it in" \ "~/Library/Documentation/Help or install it in your application" \ "bundle." .PHONY: devhelp devhelp: $(SPHINXBUILD) -b devhelp $(ALLSPHINXOPTS) $(BUILDDIR)/devhelp @echo @echo "Build finished." @echo "To view the help file:" @echo "# mkdir -p $$HOME/.local/share/devhelp/robot_localization" @echo "# ln -s $(BUILDDIR)/devhelp $$HOME/.local/share/devhelp/robot_localization" @echo "# devhelp" .PHONY: epub epub: $(SPHINXBUILD) -b epub $(ALLSPHINXOPTS) $(BUILDDIR)/epub @echo @echo "Build finished. The epub file is in $(BUILDDIR)/epub." .PHONY: latex latex: $(SPHINXBUILD) -b latex $(ALLSPHINXOPTS) $(BUILDDIR)/latex @echo @echo "Build finished; the LaTeX files are in $(BUILDDIR)/latex." @echo "Run \`make' in that directory to run these through (pdf)latex" \ "(use \`make latexpdf' here to do that automatically)." .PHONY: latexpdf latexpdf: $(SPHINXBUILD) -b latex $(ALLSPHINXOPTS) $(BUILDDIR)/latex @echo "Running LaTeX files through pdflatex..." $(MAKE) -C $(BUILDDIR)/latex all-pdf @echo "pdflatex finished; the PDF files are in $(BUILDDIR)/latex." .PHONY: latexpdfja latexpdfja: $(SPHINXBUILD) -b latex $(ALLSPHINXOPTS) $(BUILDDIR)/latex @echo "Running LaTeX files through platex and dvipdfmx..." $(MAKE) -C $(BUILDDIR)/latex all-pdf-ja @echo "pdflatex finished; the PDF files are in $(BUILDDIR)/latex." .PHONY: text text: $(SPHINXBUILD) -b text $(ALLSPHINXOPTS) $(BUILDDIR)/text @echo @echo "Build finished. The text files are in $(BUILDDIR)/text." .PHONY: man man: $(SPHINXBUILD) -b man $(ALLSPHINXOPTS) $(BUILDDIR)/man @echo @echo "Build finished. The manual pages are in $(BUILDDIR)/man." .PHONY: texinfo texinfo: $(SPHINXBUILD) -b texinfo $(ALLSPHINXOPTS) $(BUILDDIR)/texinfo @echo @echo "Build finished. The Texinfo files are in $(BUILDDIR)/texinfo." @echo "Run \`make' in that directory to run these through makeinfo" \ "(use \`make info' here to do that automatically)." .PHONY: info info: $(SPHINXBUILD) -b texinfo $(ALLSPHINXOPTS) $(BUILDDIR)/texinfo @echo "Running Texinfo files through makeinfo..." make -C $(BUILDDIR)/texinfo info @echo "makeinfo finished; the Info files are in $(BUILDDIR)/texinfo." .PHONY: gettext gettext: $(SPHINXBUILD) -b gettext $(I18NSPHINXOPTS) $(BUILDDIR)/locale @echo @echo "Build finished. The message catalogs are in $(BUILDDIR)/locale." .PHONY: changes changes: $(SPHINXBUILD) -b changes $(ALLSPHINXOPTS) $(BUILDDIR)/changes @echo @echo "The overview file is in $(BUILDDIR)/changes." .PHONY: linkcheck linkcheck: $(SPHINXBUILD) -b linkcheck $(ALLSPHINXOPTS) $(BUILDDIR)/linkcheck @echo @echo "Link check complete; look for any errors in the above output " \ "or in $(BUILDDIR)/linkcheck/output.txt." .PHONY: doctest doctest: $(SPHINXBUILD) -b doctest $(ALLSPHINXOPTS) $(BUILDDIR)/doctest @echo "Testing of doctests in the sources finished, look at the " \ "results in $(BUILDDIR)/doctest/output.txt." .PHONY: coverage coverage: $(SPHINXBUILD) -b coverage $(ALLSPHINXOPTS) $(BUILDDIR)/coverage @echo "Testing of coverage in the sources finished, look at the " \ "results in $(BUILDDIR)/coverage/python.txt." .PHONY: xml xml: $(SPHINXBUILD) -b xml $(ALLSPHINXOPTS) $(BUILDDIR)/xml @echo @echo "Build finished. The XML files are in $(BUILDDIR)/xml." .PHONY: pseudoxml pseudoxml: $(SPHINXBUILD) -b pseudoxml $(ALLSPHINXOPTS) $(BUILDDIR)/pseudoxml @echo @echo "Build finished. The pseudo-XML files are in $(BUILDDIR)/pseudoxml." ================================================ FILE: src/robot_localization/doc/conf.py ================================================ import sys import os import catkin_pkg.package catkin_dir = os.path.dirname(os.path.dirname(os.path.abspath(__file__))) catkin_package = catkin_pkg.package.parse_package(os.path.join(catkin_dir, catkin_pkg.package.PACKAGE_MANIFEST_FILENAME)) extensions = [ 'sphinx.ext.autodoc', 'sphinx.ext.doctest', 'sphinx.ext.intersphinx', 'sphinx.ext.todo', 'sphinx.ext.coverage', 'sphinx.ext.mathjax', ] templates_path = ['.templates'] source_suffix = '.rst' master_doc = 'index' project = u'robot_localization' copyright = u'2016, Tom Moore' author = u'Tom Moore' version = catkin_package.version release = catkin_package.version language = None exclude_patterns = ['.build'] pygments_style = 'sphinx' todo_include_todos = True html_theme = 'nature' html_theme_options = { "sidebarwidth": "350" } # The name of an image file (relative to this directory) to place at the top # of the sidebar. html_logo = 'images/rl_small.png' # The name of an image file (relative to this directory) to use as a favicon of # the docs. This file should be a Windows icon file (.ico) being 16x16 or 32x32 # pixels large. #html_favicon = None # Add any paths that contain custom static files (such as style sheets) here, # relative to this directory. They are copied after the builtin static files, # so a file named "default.css" will overwrite the builtin "default.css". #html_static_path = ['.static'] # Add any extra paths that contain custom files (such as robots.txt or # .htaccess) here, relative to this directory. These files are copied # directly to the root of the documentation. #html_extra_path = [] # If not '', a 'Last updated on:' timestamp is inserted at every page bottom, # using the given strftime format. #html_last_updated_fmt = '%b %d, %Y' # If true, SmartyPants will be used to convert quotes and dashes to # typographically correct entities. #html_use_smartypants = True # Custom sidebar templates, maps document names to template names. html_sidebars = { '**': ['full_globaltoc.html', 'sourcelink.html', 'searchbox.html'], } # Additional templates that should be rendered to pages, maps page names to # template names. #html_additional_pages = {} # If false, no module index is generated. #html_domain_indices = True # If false, no index is generated. #html_use_index = True # If true, the index is split into individual pages for each letter. #html_split_index = False # If true, links to the reST sources are added to the pages. #html_show_sourcelink = True # If true, "Created using Sphinx" is shown in the HTML footer. Default is True. #html_show_sphinx = True # If true, "(C) Copyright ..." is shown in the HTML footer. Default is True. #html_show_copyright = True # If true, an OpenSearch description file will be output, and all pages will # contain a tag referring to it. The value of this option must be the # base URL from which the finished HTML is served. #html_use_opensearch = '' # This is the file name suffix for HTML files (e.g. ".xhtml"). #html_file_suffix = None # Language to be used for generating the HTML full-text search index. # Sphinx supports the following languages: # 'da', 'de', 'en', 'es', 'fi', 'fr', 'hu', 'it', 'ja' # 'nl', 'no', 'pt', 'ro', 'ru', 'sv', 'tr' #html_search_language = 'en' # A dictionary with options for the search language support, empty by default. # Now only 'ja' uses this config value #html_search_options = {'type': 'default'} # The name of a javascript file (relative to the configuration directory) that # implements a search results scorer. If empty, the default will be used. #html_search_scorer = 'scorer.js' # Output file base name for HTML help builder. htmlhelp_basename = 'robot_localizationdoc' # -- Options for LaTeX output --------------------------------------------- latex_elements = { # The paper size ('letterpaper' or 'a4paper'). #'papersize': 'letterpaper', # The font size ('10pt', '11pt' or '12pt'). #'pointsize': '10pt', # Additional stuff for the LaTeX preamble. #'preamble': '', # Latex figure (float) alignment #'figure_align': 'htbp', } # Grouping the document tree into LaTeX files. List of tuples # (source start file, target name, title, # author, documentclass [howto, manual, or own class]). latex_documents = [ (master_doc, 'robot_localization.tex', u'robot\\_localization Documentation', u'Tom Moore', 'manual'), ] # The name of an image file (relative to this directory) to place at the top of # the title page. #latex_logo = None # For "manual" documents, if this is true, then toplevel headings are parts, # not chapters. #latex_use_parts = False # If true, show page references after internal links. #latex_show_pagerefs = False # If true, show URL addresses after external links. #latex_show_urls = False # Documents to append as an appendix to all manuals. #latex_appendices = [] # If false, no module index is generated. #latex_domain_indices = True # -- Options for manual page output --------------------------------------- # One entry per manual page. List of tuples # (source start file, name, description, authors, manual section). man_pages = [ (master_doc, 'robot_localization', u'robot_localization Documentation', [author], 1) ] # If true, show URL addresses after external links. #man_show_urls = False # -- Options for Texinfo output ------------------------------------------- # Grouping the document tree into Texinfo files. List of tuples # (source start file, target name, title, author, # dir menu entry, description, category) texinfo_documents = [ (master_doc, 'robot_localization', u'robot_localization Documentation', author, 'robot_localization', 'One line description of project.', 'Miscellaneous'), ] # Documents to append as an appendix to all manuals. #texinfo_appendices = [] # If false, no module index is generated. #texinfo_domain_indices = True # How to display URL addresses: 'footnote', 'no', or 'inline'. #texinfo_show_urls = 'footnote' # If true, do not generate a @detailmenu in the "Top" node's menu. #texinfo_no_detailmenu = False # Example configuration for intersphinx: refer to the Python standard library. intersphinx_mapping = {'https://docs.python.org/': None} ================================================ FILE: src/robot_localization/doc/configuring_robot_localization.rst ================================================ .. _configuring_robot_localization: Configuring robot_localization ############################## When incorporating sensor data into the position estimate of any of ``robot_localization``'s state estimation nodes, it is important to extract as much information as possible. This tutorial details the best practices for sensor integration. For additional information, users are encouraged to watch this `presentation `_ from ROSCon 2015. Sensor Configuration ******************** The configuration vector format is the same for all sensors, even if the message type in question doesn't contain some of the variables in the configuration vector (e.g., a <> lacks any pose data, but the configuration vector still has values for pose variables). Unused variables are simply ignored. Note that the configuration vector is given in the ``frame_id`` of the input message. For example, consider a velocity sensor that produces a `geometry_msgs/TwistWithCovarianceStamped `_ message with a ``frame_id`` of *velocity_sensor_frame*. In this example, we'll assume that a transform exists from *velocity_sensor_frame* to your robot's ``base_link_frame`` (e.g., *base_link*), and that the transform would convert :math:`X` velocity in the *velocity_sensor_frame* to :math:`Z` velocity in the ``base_link_frame``. To include the :math:`X` velocity data from the sensor into the filter, the configuration vector should set the :math:`X` velocity value to *true*, and **not** the :math:`\dot{Z}` velocity value: .. code-block:: xml [false, false, false, false, false, false, true, false, false, false, false, false, false, false, false] .. note:: The order of the boolean values are :math:`(X, Y, Z, roll, pitch, yaw, \dot{X}, \dot{Y}, \dot{Z}, \dot{roll}, \dot{pitch}, \dot{yaw}, \ddot{X}, \ddot{Y}, \ddot{Z})`. Operating in 2D? **************** The first decision to make when configuring your sensors is whether or not your robot is operating in a planar environment, and you're comfortable with ignoring subtle effects of variations in the ground plane as might be reported from an IMU. If so, please set the ``two_d_mode`` parameter to *true*. This effectively zeros out the 3D pose variables in every measurement and forces them to be fused in the state estimate. Fusing Unmeasured Variables *************************** Let's start with an example. Let's say you have a wheeled, nonholonomic robot that works in a planar environment. Your robot has some wheel encoders that are used to estimate instantaneous X velocity as well as absolute pose information. This information is reported in an `nav_msgs/Odometry `_ message. Additionally, your robot has an IMU that measures rotational velocity, vehicle attitude, and linear acceleration. Its data is reported in a `sensor_msgs/Imu `_ message. As we are operating in a planar environment, we set the ``two_d_mode`` parameter to *true*. This will automatically zero out all 3D variables, such as :math:`Z`, :math:`roll`, :math:`pitch`, their respective velocities, and :math:`Z` acceleration. We start with this configuration: .. code-block:: xml [true, true, false, false, false, true, true, false, false, false, false, true, false, false, false] [false, false, false, false, false, true, false, false, false, false, false, true, true, false, false] As a first pass, this makes sense, as a planar robot only needs to concern itself with :math:`X`, :math:`Y`, :math:`\dot{X}`, :math:`\dot{Y}`, :math:`\ddot{X}`, :math:`\ddot{Y}`, :math:`yaw`, and :math:`\dot{yaw}`. However, there are a few things to note here. 1. For ``odom0``, we are including :math:`X` and :math:`Y` (reported in a world coordinate frame), :math:`yaw`, :math:`\dot{X}` (reported in the body frame), and :math:`\dot{yaw}`. However, unless your robot is internally using an IMU, it is most likely simply using wheel encoder data to generate the values in its measurements. Therefore, its velocity, heading, and position data are all generated from the same source. In that instance, we don't want to use all the values, as you're feeding duplicate information into the filter. Instead, it's best to just use the velocities: .. code-block:: xml [false, false, false, false, false, false, true, false, false, false, false, true, false, false, false] [false, false, false, false, false, true, false, false, false, false, false, true, true, false, false] 2. Next, we note that we are not fusing :math:`\dot{Y}`. At first glance, this is the right choice, as our robot cannot move instantaneously sideways. However, if the `nav_msgs/Odometry `_ message reports a :math:`0` value for :math:`\dot{Y}` (and the :math:`\dot{Y}` covariance is NOT inflated to a large value), it's best to feed that value to the filter. As a :math:`0` measurement in this case indicates that the robot cannot ever move in that direction, it serves as a perfectly valid measurement: .. code-block:: xml [false, false, false, false, false, false, true, true, false, false, false, true, false, false, false] [false, false, false, false, false, true, false, false, false, false, false, true, true, false, false] You may wonder why did we not fuse :math:`\dot{Z}` velocity for the same reason. The answer is that we did when we set ``two_d_mode`` to *false*. If we hadn't, we could, in fact, fuse the :math:`0` measurement for :math:`\dot{Z}` velocity into the filter. 3. Last, we come to the IMU. You may notice that we have set the :math:`\ddot{Y}` to *false*. This is due to the fact that many systems, including the hypothetical one we are discussing here, will not undergo instantaneous :math:`Y` acceleration. However, the IMU will likely report non-zero, noisy values for Y acceleration, which can cause your estimate to drift rapidly. The *differential* and *relative* Parameters ******************************************** The state estimation nodes in ''robot_localization'' allow users to fuse as many sensors as they like. This allows users to measure certain state vector variables - in particular, pose variables - using more than one source. For example, your robot may obtain absolute orientation information from multiple IMUs, or it may have multiple data sources providing an estimate its absolute position. In this case, users have two options: 1. Fuse all the absolute position/orientation data as-is, e.g., .. code-block:: xml [false, false, false, true, true, true, false, false, false, false, false, false, false, false, false] [false, false, false, true, true, true, false, false, false, false, false, false, false, false, false] In this case, users should be **very** careful and ensure that the covariances on each measured orientation variable are set correctly. If each IMU advertises a yaw variance of, for example, :math:`0.1`, yet the delta between the IMUs' yaw measurements is :math:`> 0.1`, then the output of the filter will oscillate back and forth between the values provided by each sensor. Users should make sure that the noise distributions around each measurement overlap. 2. Alternatively, users can make use of the ``_differential`` parameter. By setting this to *true* for a given sensor, all pose (position and orientation) data is converted to a velocity by calculating the change in the measurement value between two consecutive time steps. The data is then fused as a velocity. Again, though, users should take care: when measurements are fused absolutely (especially IMUs), if the measurement has a static or non-increasing variance for a given variable, then the variance in the estimate's covariance matrix will be bounded. If that information is converted to a velocity, then at each time step, the estimate will gain some small amount of error, and the variance for the variable in question will grow without bound. For position :math:`(X, Y, Z)` information, this isn't an issue, but for orientation data, it is a problem. For example, it is acceptable for a robot to move around its environment and accumulate :math:`1.5` meters of error in the :math:`X` direction after some time. If that same robot moves around and accumulates :math:`1.5` radians of error in yaw, then when the robot next drives forward, its position error will explode. The general rule of thumb for the ``_differential`` parameter is that if a give robot has only one source of orientation data, then the differential parameter should be set to *false*. If there are :math:`N` sources, users can set the ``_differential`` parameter to *true* for :math:`N-1` of them, or simply ensure that the covariance values are large enough to eliminate oscillations. ================================================ FILE: src/robot_localization/doc/index.rst ================================================ .. _index: robot_localization wiki *********************** ``robot_localization`` is a collection of state estimation nodes, each of which is an implementation of a nonlinear state estimator for robots moving in 3D space. It contains two state estimation nodes, ``ekf_localization_node`` and ``ukf_localization_node``. In addition, ``robot_localization`` provides ``navsat_transform_node``, which aids in the integration of GPS data. .. toctree:: :hidden: state_estimation_nodes navsat_transform_node preparing_sensor_data configuring_robot_localization migrating_from_robot_pose_ekf integrating_gps CHANGELOG Features ======== All the state estimation nodes in ``robot_localization`` share common features, namely: * Fusion of an arbitrary number of sensors. The nodes do not restrict the number of input sources. If, for example, your robot has multiple IMUs or multiple sources of odometry information, the state estimation nodes within ``robot_localization`` can support all of them. * Support for multiple ROS message types. All state estimation nodes in ``robot_localization`` can take in `nav_msgs/Odometry `_, `sensor_msgs/Imu `_, `geometry_msgs/PoseWithCovarianceStamped `_, or `geometry_msgs/TwistWithCovarianceStamped `_ messages. * Per-sensor input customization. If a given sensor message contains data that you don't want to include in your state estimate, the state estimation nodes in ``robot_localization`` allow you to exclude that data on a per-sensor basis. * Continuous estimation. Each state estimation node in ``robot_localization`` begins estimating the vehicle's state as soon as it receives a single measurement. If there is a holiday in the sensor data (i.e., a long period in which no data is received), the filter will continue to estimate the robot's state via an internal motion model. All state estimation nodes track the 15-dimensional state of the vehicle: :math:`(X, Y, Z, roll, pitch, yaw, \dot{X}, \dot{Y}, \dot{Z}, \dot{roll}, \dot{pitch}, \dot{yaw}, \ddot{X}, \ddot{Y}, \ddot{Z})`. Other Resources =============== If you're new to ``robot_localization``, check out the `2015 ROSCon talk `_ for some pointers on getting started. Further details can be found in :download:`this paper `: .. code-block:: none @inproceedings{MooreStouchKeneralizedEkf2014, author = {T. Moore and D. Stouch}, title = {A Generalized Extended Kalman Filter Implementation for the Robot Operating System}, year = {2014}, month = {July}, booktitle = {Proceedings of the 13th International Conference on Intelligent Autonomous Systems (IAS-13)}, publisher = {Springer} } Indices and tables ================== * :ref:`genindex` * :ref:`search` ================================================ FILE: src/robot_localization/doc/integrating_gps.rst ================================================ Integrating GPS Data #################### Integration of GPS data is a common request from users. ``robot_localization`` contains a node, ``navsat_transform_node``, that transforms GPS data into a frame that is consistent with your robot's starting pose (position and orientation) in its world frame. This greatly simplifies fusion of GPS data. This tutorial explains how to use ``navsat_transform_node``, and delves into some of the math behind it. For additional information, users are encouraged to watch this `presentation `_ from ROSCon 2015. Notes on Fusing GPS Data ************************ Before beginning this tutorial, users should be sure to familiarize themselves with `REP-105 `_. It is important for users to realize that using a position estimate that includes GPS data will likely be unfit for use by navigation modules, owing to the fact that GPS data is subject to discrete discontinuities ("jumps"). If you want to fuse data from a GPS into your position estimate, one potential solution is to do the following: 1. Run one instance of a ``robot_localization`` state estimation node that fuses only continuous data, such as odometry and IMU data. Set the ``world_frame`` parameter for this instance to the same value as the ``odom_frame`` parameter. Execute local path plans and motions in this frame. 2. Run another instance of a ``robot_localization`` state estimation node that fuses all sources of data, including the GPS. Set the ``world_frame`` parameter for this instance to the same value as the ``map_frame`` parameter. This is just a suggestion, however, and users are free to fuse the GPS data into a single instance of a ``robot_localization`` state estimation node. Using navsat_transform_node *************************** Required Inputs =============== ``navsat_transform_node`` requires three sources of information: the robot's current pose estimate in its world frame, an earth-referenced heading, and a geographic coordinate expressed as a latitude/longitude pair (with optional altitude). These data can be obtained in three different ways: 1. (Default behavior) The data can come entirely from the robot's sensors and pose estimation software. To enable this mode, make sure the ``wait_for_datum`` parameter is set to *false* (its default value). The required messages are: * A `sensor_msgs/NavSatFix `_ message with raw GPS coordinates in it. * A `sensor_msgs/Imu `_ message with an absolute (earth-referenced) heading. * A `nav_msgs/Odometry `_ message that contains the robot's current position estimate in the frame specified by its start location (typically the output of a ``robot_localization`` state estimation node). 2. The datum (global frame origin) can be specified via the ``datum`` parameter. .. note:: In order to use this mode, the ``wait_for_datum`` parameter must be set to *true*. The ``datum`` parameter takes this form: .. code-block:: xml [55.944904, -3.186693, 0.0, map, base_link] The parameter order is ``latitude`` in decimal degrees, ``longitude`` in decimal degrees, ``heading`` in radians) the ``frame_id`` of your robot's world frame (i.e., the value of the ``world_frame`` parameter in a ``robot_localization`` state estimation node), and the ``frame_id`` of your robot's body frame (i.e., the value of the ``base_link_frame`` parameter in a ``robot_localization`` state estimation node). When this mode is used, the robot assumes that your robot's world frame origin is at the specified latitude and longitude and with a heading of :math:`0` (east). 3. The datum can be set manually via the ``set_datum`` service and using the `robot_localization/SetDatum `_ service message. GPS Data ^^^^^^^^ Please note that all development of ``navsat_transform_node`` was done using a Garmin 18x GPS unit, so there may be intricacies of the data generated by other units that need to be handled. The excellent `nmea_navsat_driver `_ package provides the required `sensor_msgs/NavSatFix `_ message. Here is the ``nmea_navsat_driver`` launch file we'll use for this tutorial: .. code-block:: xml This information is only relevant if the user is not manually specifying the origin via the ``datum`` parameter or the ``set_datum`` service. IMU Data ^^^^^^^^ .. note:: Since version 2.2.1, ``navsat_transform_node`` has moved to a standard wherein all heading data is assumed to start with its zero point facing east. If your IMU does not conform to this standard and instead reports zero when facing north, you can still use the ``yaw_offset`` parameter to correct this. In this case, the value for ``yaw_offset`` would be :math:`\pi / 2` (approximately :math:`1.5707963`). Users should make sure their IMUs conform to `REP-105 `_. In particular, check that the signs of your orientation angles increase in the right direction. In addition, users should look up the `magnetic declination `_ for their robot's operating area, convert it to radians, and then use that value for the ``magnetic_declination_radians`` parameter. This information is only relevant if the user is not manually specifying the origin via the ``datum`` parameter or the ``set_datum`` service. Odometry Data ^^^^^^^^^^^^^ This should just be the output of whichever ``robot_localization`` state estimation node instance you are using to fuse GPS data. Configuring navsat_transform_node ================================= Below is the ``navsat_transform_node`` launch file we'll use for this tutorial: .. code-block:: xml These parameters are discussed on the :ref:`main page `. Configuring robot_localization ============================== Integration with ``robot_localization`` is straightforward at this point. Simply add this block to your state estimation node launch file: .. code-block:: xml [true, true, false, false, false, false, false, false, false, false, false, false, false, false, false] Make sure to change ``odomN`` to whatever your odometry input values is (e.g., *odom1*, *odom2*, etc.). Also, if you wish to include altitude data, set ``odomN_config``'s third value to ``true``. .. note:: If you are operating in 2D don't have any sensor measuring Z or Z velocity, you can either: * Set ``navsat_transform_node's`` ``zero_altitude`` parameter to *true*, and then set ``odomN_config``'s third value to *true* * Set ``two_d_mode`` to *true* in your ``robot_localization`` state estimation node You should have no need to modify the ``_differential`` setting within the state estimation node. The GPS is an absolute position sensor, and enabling differential integration defeats the purpose of using it. Details ======= We'll start with a picture. Consider a robot that starts at some latitude and longitude and with some heading. We assume in this tutorial that the heading comes from an IMU that reads 0 when facing east, and increases according to the ROS spec (i.e., counter-clockwise). The remainder of this tutorial will refer to Figure 1: .. image:: images/figure1.png :width: 800px :align: center :alt: Figure 1 `REP-105 `_ suggests four coordinate frames: *base_link*, *odom*, *map*, and *earth*. *base_link* is the coordinate frame that is rigidly attached to the vehicle. The *odom* and *map* frames are world-fixed frames and generally have their origins at the vehicle's start position and orientation. The *earth* frame is used as a common reference frame for multiple map frames, and is not yet supported by ``navsat_transform_node``. Note that in Figure 1, the robot has just started (``t = 0``), and so its *base_link*, *odom*, and *map* frames are aligned. We can also define a coordinate frame for the UTM grid, which we will call *utm*. For the purposes of this tutorial, we will refer to the UTM grid coordinate frame as *utm*. Therefore, what we want to do is create a *utm*->*map* transform. Referring to Figure 1, these ideas are (hopefully) made clear. The UTM origin is the :math:`(0_{UTM}, 0_{UTM})` point of the UTM zone that is associated with the robot's GPS location. The robot begins somewhere within the UTM zone at location :math:`(x_{UTM}, y_{UTM})`. The robot's initial orientation is some angle :math:`\theta` above the UTM grid's :math:`X`-axis. Our transform will therefore require that we know :math:`x_{UTM}, y_{UTM}` and :math:`\theta`. We now need to convert our latitude and longitude to UTM coordinates. The UTM grid assumes that the :math:`X`-axis faces east, the :math:`Y`-axis faces (true) north, and the :math:`Z`-axis points up out of the ground. This complies with the right-handed coordinate frame as dictated by `REP-105 `_. The REP also states that a yaw angle of :math:`0` means that we are facing straight down the :math:`X`-axis, and that the yaw increases counter-clockwise. ``navsat_transform_node`` assumes your heading data conforms to this standard. However, there are two factors that need to be considered: 1. The IMU driver may not allow the user to apply the magnetic declination correction factor 2. The IMU driver may incorrectly report :math:`0` when facing north, and not when facing east (even though its headings increase and decrease correctly). Fortunately, ``navsat_transform_node`` exposes two parameters to adddress these possible shortcomings in IMU data: ``magnetic_declination_radians`` and ``yaw_offset``. Referring to Figure 1, for an IMU that is currently measuring a yaw value of ``imu_yaw``, :math:`yaw_{imu} = -\omega - offset_{yaw} + \theta` :math:`\theta = yaw_{imu} + \omega + offset_{yaw}` We now have a translation :math:`(x_{UTM}, y_{UTM})` and rotation :math:`\theta`, which we can use to create the required *utm* -> *map* transform. We use the transform to convert all future GPS positions into the robot's local coordinate frame. ``navsat_transform_node`` will also broadcast this transform if the ``broadcast_utm_transform`` parameter is set to *true*. If you have any questions about this tutorial, please feel free to ask questions on `answers.ros.org `_. ================================================ FILE: src/robot_localization/doc/manifest.yaml ================================================ actions: [] authors: Tom Moore brief: '' bugtracker: '' depends: - catkin - eigen - diagnostic_updater - cmake_modules - tf2 - nav_msgs - roscpp - rostest - tf2_ros - message_generation - message_filters - tf2_geometry_msgs - sensor_msgs - message_runtime - std_msgs - roslint - rosunit - diagnostic_msgs - geographic_msgs - xmlrpcpp - python-catkin-pkg - geometry_msgs - rosbag description: The robot_localization package provides nonlinear state estimation through sensor fusion of an abritrary number of sensors. license: BSD maintainers: Tom Moore msgs: [] package_type: package repo_url: '' srvs: - SetPose - SetDatum url: http://ros.org/wiki/robot_localization ================================================ FILE: src/robot_localization/doc/migrating_from_robot_pose_ekf.rst ================================================ .. _migrating_from_robot_pose_ekf: Migrating from robot_pose_ekf ############################# Migration from ``robot_pose_ekf`` is fairly straightforward. This page is meant to highlight relevant differences between the packages to facilitate rapid transitions. Covariances in Source Messages ============================== For ``robot_pose_ekf``, a common means of getting the filter to ignore measurements is to give it a massively inflated covariance, often on the order of 10^3. However, the state estimation nodes in ``robot_localization`` allow users to specify *which* variables from the measurement should be fused with the current state. If your sensor reports zero for a given variable and you don't want to fuse that value with your filter, or if the sensor is known to produce poor data for that field, then simply set its ``xxxx_config`` parameter value to false for the variable in question (see the main page for a description of this parameter). However, users should take care: sometimes platform constraints create implicit :math:`0` measurements of variables. For example, a differential drive robot that cannot move instantaneously in the :math:`Y` direction can safely fuse a :math:`0` measurement for :math:`\dot{Y}` with a small covariance value. The ''differential'' Parameter ============================== By default, ``robot_pose_ekf`` will take a pose measurement at time :math:`t`, determine the difference between it and the measurement at time :math:`t-1`, transform that difference into the current frame, and then integrate that measurement. This cleverly aids in cases where two sensors are measuring the same pose variable: as time progresses, the values reported by each sensor will start to diverge. If the covariances on at least one of these measurements do not grow appopriately, the filter will eventually start to oscillate between the measured values. By carrying out differential integration, this situation is avoided and measurements are always consistent with the current state. This situation can be avoided using three different methods for the ``robot_localization`` state estimation nodes: 1. If fusing two different sources for the same pose data (e.g., two different sensors measuring :math:`Z` position), ensure that those sources accurately report their covariances. If the two sources begin to diverge, then their covariances should refect the growing error that must be occurring in at least one of them. 2. If available, fuse velocity data instead of pose data. If you have two separate data sources measuring the same variable, fuse the most accurate one as pose data and the other as velocity. 3. As an alternative to (2), if velocity data is unavailable for a given pose measurement, enable the ``_differential`` parameter for one of the sensors. This will cause it to be differentiated and fused as a velocity. ================================================ FILE: src/robot_localization/doc/navsat_transform_node.rst ================================================ navsat_transform_node ********************* ``navsat_transform_node`` takes as input a `nav_msgs/Odometry `_ message (usually the output of ``ekf_localization_node`` or ``ukf_localization_node``), a `sensor_msgs/Imu `_ containing an accurate estimate of your robot's heading, and a `sensor_msgs/NavSatFix `_ message containing GPS data. It produces an odometry message in coordinates that are consistent with your robot's world frame. This value can be directly fused into your state estimate. .. note:: If you fuse the output of this node with any of the state estimation nodes in ``robot_localization``, you should make sure that the ``odomN_differential`` setting is *false* for that input. Parameters ========== ~frequency ^^^^^^^^^^ The real-valued frequency, in Hz, at which ``navsat_transform_node`` checks for new `sensor_msgs/NavSatFix `_ messages, and publishes filtered `sensor_msgs/NavSatFix `_ when ``publish_filtered_gps`` is set to *true*. ~delay ^^^^^^ The time, in seconds, to wait before calculating the transform from GPS coordinates to your robot's world frame. ~magnetic_declination_radians ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Enter the magnetic declination for your location. If you don't know it, see `http://www.ngdc.noaa.gov/geomag-web `_ (make sure to convert the value to radians). This parameter is needed if your IMU prodives its orientation with respect to the magnetic north. ~yaw_offset ^^^^^^^^^^^ Your IMU should read 0 for yaw when facing east. If it doesn't, enter the offset here (desired_value = offset + sensor_raw_value). For example, if your IMU reports 0 when facing north, as most of them do, this parameter would be ``pi/2`` (~1.5707963). This parameter changed in version ``2.2.1``. Previously, ``navsat_transform_node`` assumed that IMUs read 0 when facing north, so yaw_offset was used acordingly. ~zero_altitude ^^^^^^^^^^^^^^ If this is *true*, the `nav_msgs/Odometry `_ message produced by this node has its pose Z value set to 0. ~publish_filtered_gps ^^^^^^^^^^^^^^^^^^^^^ If *true*, ``navsat_transform_node`` will also transform your robot's world frame (e.g., *map*) position back to GPS coordinates, and publish a `sensor_msgs/NavSatFix `_ message on the ``/gps/filtered`` topic. ~broadcast_utm_transform ^^^^^^^^^^^^^^^^^^^^^^^^ If this is *true*, ``navsat_transform_node`` will broadcast the transform between the UTM grid and the frame of the input odometry data. See Published Transforms below for more information. ~use_odometry_yaw ^^^^^^^^^^^^^^^^^ If *true*, ``navsat_transform_node`` will not get its heading from the IMU data, but from the input odometry message. Users should take care to only set this to true if your odometry message has orientation data specified in an earth-referenced frame, e.g., as produced by a magnetometer. Additionally, if the odometry source is one of the state estimation nodes in ``robot_localization``, the user should have at least one source of absolute orientation data being fed into the node, with the ``_differential`` and ``_relative`` parameters set to *false*. ~wait_for_datum ^^^^^^^^^^^^^^^ If *true*, ``navsat_transform_node`` will wait to get a datum from either: * The ``datum`` parameter * The ``set_datum`` service Subscribed Topics ================= * ``imu/data`` A `sensor_msgs/Imu `_ message with orientation data * ``odometry/filtered`` A `nav_msgs/Odometry `_ message of your robot's current position. This is needed in the event that your first GPS reading comes after your robot has attained some non-zero pose. * ``gps/fix`` A `sensor_msgs/NavSatFix `_ message containing your robot's GPS coordinates Published Topics ================ * ``odometry/gps`` A `nav_msgs/Odometry `_ message containing the GPS coordinates of your robot, transformed into its world coordinate frame. This message can be directly fused into ``robot_localization``'s state estimation nodes. * ``gps/filtered`` (optional) A `sensor_msgs/NavSatFix `_ message containing your robot's world frame position, transformed into GPS coordinates Published Transforms ==================== * ``world_frame->utm`` (optional) - If the ``broadcast_utm_transform`` parameter is set to *true*, ``navsat_transform_node`` calculates a transform from the *utm* frame to the ``frame_id`` of the input odometry data. By default, the *utm* frame is published as a child of the odometry frame by using the inverse transform. With use of the ``broadcast_utm_as_parent_frame`` parameter, the *utm* frame will be published as a parent of the odometry frame. This is useful if you have multiple robots within one TF tree. ================================================ FILE: src/robot_localization/doc/preparing_sensor_data.rst ================================================ Preparing Your Data for Use with robot_localization ################################################### Before getting started with the state estimation nodes in ``robot_localization``, it is important that users ensure that their sensor data well-formed. There are various considerations for each class of sensor data, and users are encouraged to read this tutorial in its entirety before attempting to use ``robot_localization``. For additional information, users are encouraged to watch this `presentation `_ from ROSCon 2015. Adherence to ROS Standards ************************** The two most important ROS REPs to consider are: * `REP-103 `_ (Standard Units of Measure and Coordinate Conventions) * `REP-105 `_ (Coordinate Frame Conventions). Users who are new to ROS or state estimation are encouraged to read over both REPs, as it will almost certainly aid you in preparing your sensor data. ``robot_localization`` attempts to adhere to these standards as much as possible. Also, it will likely benefit users to look over the specifications for each of the supported ROS message types: * `nav_msgs/Odometry `_ * `geometry_msgs/PoseWithCovarianceStamped `_ * `geometry_msgs/TwistWithCovarianceStamped `_ * `sensor_msgs/Imu `_ Coordinate Frames and Transforming Sensor Data ********************************************** `REP-105 `_ specifies four principal coordinate frames: *base_link*, *odom*, *map*, and *earth*. The *base_link* frame is rigidly affixed to the robot. The *map* and *odom* frames are world-fixed frames whose origins are typically aligned with the robot's start position. The *earth* frame is used to provide a common reference frame for multiple *map* frames (e.g., for robots distributed over a large area). The *earth* frame is not relevant to this tutorial. The state estimation nodes of ``robot_localization`` produce a state estimate whose pose is given in the *map* or *odom* frame and whose velocity is given in the *base_link* frame. All incoming data is transformed into one of these coordinate frames before being fused with the state. The data in each message type is transformed as follows: * `nav_msgs/Odometry `_ - All pose data (position and orientation) is transformed from the message header's ``frame_id`` into the coordinate frame specified by the ``world_frame`` parameter (typically *map* or *odom*). In the message itself, this specifically refers to everything contained within the ``pose`` property. All twist data (linear and angular velocity) is transformed from the ``child_frame_id`` of the message into the coordinate frame specified by the ``base_link_frame`` parameter (typically *base_link*). * `geometry_msgs/PoseWithCovarianceStamped `_ - Handled in the same fashion as the pose data in the Odometry message. * `geometry_msgs/TwistWithCovarianceStamped `_ - Handled in the same fashion as the twist data in the Odometry message. * `sensor_msgs/Imu `_ - The IMU message is currently subject to some ambiguity, though this is being addressed by the ROS community. Most IMUs natively report orientation data in a world-fixed frame whose :math:`X` and :math:`Z` axes are defined by the vectors pointing to magnetic north and the center of the earth, respectively, with the Y axis facing east (90 degrees offset from the magnetic north vector). This frame is often referred to as NED (North, East, Down). However, `REP-103 `_ specifies an ENU (East, North, Up) coordinate frame for outdoor navigation. As of this writing, ``robot_localization`` assumes an ENU frame for all IMU data, and does not work with NED frame data. This may change in the future, but for now, users should ensure that data is transformed to the ENU frame before using it with any node in ``robot_localization``. The IMU may also be oriented on the robot in a position other than its "neutral" position. For example, the user may mount the IMU on its side, or rotate it so that it faces a direction other than the front of the robot. This offset is typically specified by a static transform from the ``base_link_frame`` parameter to the IMU message's ``frame_id``. The state estimation nodes in ``robot_localization`` will automatically correct for the orientation of the sensor so that its data aligns with the frame specified by the ``base_link_frame`` parameter. Handling tf_prefix ****************** With the migration to `tf2 `_ as of ROS Indigo, ``robot_localization`` still allows for the use of the ``tf_prefix`` parameter, but, in accordance with `tf2 `_, all ``frame_id`` values will have any leading '/' stripped. Considerations for Each Sensor Message Type ******************************************* Odometry ======== Many robot platforms come equipped with wheel encoders that provide instantaneous translational and rotational velocity. Many also internally integrate these velocities to generate a position estimate. If you are responsible for this data, or can edit it, keep the following in mind: 1. **Velocities/Poses:** `robot_localization` can integrate velocities or absolute pose information. In general, the best practice is: * If the odometry provides both position and linear velocity, fuse the linear velocity. * If the odometry provides both orientation and angular velocity, fuse the orientation. .. note:: If you have two sources of orientation data, then you'll want to be careful. If both produce orientations with accurate covariance matrices, it's safe to fuse the orientations. If, however, one or both under-reports its covariance, then you should only fuse the orientation data from the more accurate sensor. For the other sensor, use the angular velocity (if it's provided), or continue to fuse the absolute orientation data, but turn `_differential` mode on for that sensor. 2. **frame_id:** See the section on coordinate frames and transforms above. 3. **Covariance:** Covariance values **matter** to ``robot_localization``. `robot_pose_ekf `_ attempts to fuse all pose variables in an odometry message. Some robots' drivers have been written to accommodate its requirements. This means that if a given sensor does not produce a certain variable (e.g., a robot that doesn't report :math:`Z` position), then the only way to get ``robot_pose_ekf`` to ignore it is to inflate its variance to a very large value (on the order of :math:`1e3`) so that the variable in question is effectively ignored. This practice is both unnecessary and even detrimental to the performance of ``robot_localization``. The exception is the case where you have a second input source measuring the variable in question, in which case inflated covariances will work. .. note:: See :ref:`configuring_robot_localization` and :ref:`migrating_from_robot_pose_ekf` for more information. 4. **Signs:** Adherence to `REP-103 `_ means that you need to ensure that the **signs** of your data are correct. For example, if you have a ground robot and turn it counter-clockwise, then its yaw angle should *increase*, and its yaw velocity should be *positive*. If you drive it *forward*, its X-position should *increase* and its X-velocity should be *positive*. 5. **Transforms:** Broadcast of the *odom*->*base_link* transform. When the ``world_frame`` parameter is set to the value of the ``odom_frame`` parameter in the configuration file, ``robot_localization``'s state estimation nodes output both a position estimate in a `nav_msgs/Odometry `_ message and a transform from the frame specified by its ``odom_frame`` parameter to its ``base_link_frame`` parameter. However, some robot drivers also broadcast this transform along with their odometry message. If users want ``robot_localization`` to be responsible for this transform, then they need to disable the broadcast of that transform by their robot's driver. This is often exposed as a parameter. IMU === In addition to the following, be sure to read the above section regarding coordinate frames and transforms for IMU data. 1. **Adherence to specifications:** As with odometry, be sure your data adheres to `REP-103 `_ and the `sensor_msgs/Imu `_ specification. Double-check the signs of your data, and make sure the ``frame_id`` values are correct. 2. **Covariance:** Echoing the advice for odometry, make sure your covariances make sense. Do not use large values to get the filter to ignore a given variable. Set the configuration for the variable you'd like to ignore to *false*. 3. **Acceleration:** Be careful with acceleration data. The state estimation nodes in ``robot_localization`` assume that an IMU that is placed in its neutral *right-side-up* position on a flat surface will: * Measure **+**:math:`9.81` meters per second squared for the :math:`Z` axis. * If the sensor is rolled **+**:math:`90` degrees (left side up), the acceleration should be **+**:math:`9.81` meters per second squared for the :math:`Y` axis. * If the sensor is pitched **+**:math:`90` degrees (front side down), it should read **-**:math:`9.81` meters per second squared for the :math:`X` axis. PoseWithCovarianceStamped ========================= See the section on odometry. TwistWithCovarianceStamped ========================== See the section on odometry. Common errors ************* * Input data doesn't adhere to `REP-103 `_. Make sure that all values (especially orientation angles) increase and decrease in the correct directions. * Incorrect ``frame_id`` values. Velocity data should be reported in the frame given by the ``base_link_frame`` parameter, or a transform should exist between the ``frame_id`` of the velocity data and the ``base_link_frame``. * Inflated covariances. The preferred method for ignoring variables in measurements is through the ``odomN_config`` parameter. * Missing covariances. If you have configured a given sensor to fuse a given variable into the state estimation node, then the variance for that value (i.e., the covariance matrix value at position :math:`(i, i)`, where :math:`i` is the index of that variable) should **not** be :math:`0`. If a :math:`0` variance value is encountered for a variable that is being fused, the state estimation nodes will add a small epsilon value (:math:`1e^{-6}`) to that value. A better solution is for users to set covariances appropriately. ================================================ FILE: src/robot_localization/doc/state_estimation_nodes.rst ================================================ State Estimation Nodes ###################### ekf_localization_node ********************* ``ekf_localization_node`` is an implementation of an `extended Kalman filter `_. It uses an omnidirectional motion model to project the state forward in time, and corrects that projected estimate using perceived sensor data. ukf_localization_node ********************* ``ukf_localization_node`` is an implementation of an `unscented Kalman filter `_. It uses a set of carefully selected sigma points to project the state through the same motion model that is used in the EKF, and then uses those projected sigma points to recover the state estimate and covariance. This eliminates the use of Jacobian matrices and makes the filter more stable. However, it is also more computationally taxing than ``ekf_localization_node``. Parameters ********** ``ekf_localization_node`` and ``ukf_localization_node`` share the vast majority of their parameters, as most of the parameters control how data is treated before being fused with the core filters. The relatively large number of parameters available to the state estimation nodes make launch and configuration files the preferred method for starting any of its nodes. The package contains template launch and configuration files to help get users started. Parameters Common to *ekf_localization_node* and *ukf_localization_node* ======================================================================== Standard Parameters ------------------- ~frequency ^^^^^^^^^^ The real-valued frequency, in Hz, at which the filter produces a state estimate. .. note:: The filter will not begin computation until it receives at least one message from one of the inputs. ~sensor_timeout ^^^^^^^^^^^^^^^ The real-valued period, in seconds, after which we consider any sensor to have timed out. In this event, we carry out a predict cycle on the EKF without correcting it. This parameter can be thought of as the inverse of the minimum frequency at which the filter will generate *new* output. ~two_d_mode ^^^^^^^^^^^ If your robot is operating in a planar environment and you're comfortable with ignoring the subtle variations in the ground (as reported by an IMU), then set this to true. It will fuse 0 values for all 3D variables (Z, roll, pitch, and their respective velocities and accelerations). This keeps the covariances for those values from exploding while ensuring that your robot's state estimate remains affixed to the X-Y plane. ~[frame] ^^^^^^^^^ Specific parameters: * ``~map_frame`` * ``~odom_frame`` * ``~base_link_frame`` * ``~world_frame`` These parameters define the operating "mode" for ``robot_localization``. `REP-105 `_ specifies three principal coordinate frames: *map*, *odom*, and *base_link*. *base_link* is the coordinate frame that is affixed to the robot. The robot's position in the *odom* frame will drift over time, but is accurate in the short term and should be continuous. The *map* frame, like the *odom* frame, is a world-fixed coordinate frame, and while it contains the most globally accurate position estimate for your robot, it is subject to discrete jumps, e.g., due to the fusion of GPS data. Here is how to use these parameters: 1. Set the ``map_frame``, ``odom_frame``, and ``base_link_frame`` parameters to the appropriate frame names for your system. .. note:: If your system does not have a ``map_frame``, just remove it, and make sure ``world_frame`` is set to the value of ``odom_frame``. 2. If you are only fusing continuous position data such as wheel encoder odometry, visual odometry, or IMU data, set ``world_frame`` to your ``odom_frame`` value. This is the default behavior for the state estimation nodes in ``robot_localization``, and the most common use for it. 3. If you are fusing global absolute position data that is subject to discrete jumps (e.g., GPS or position updates from landmark observations) then: i. Set your ``world_frame`` to your ``map_frame`` value ii. **Make sure** something else is generating the *odom->base_link* transform. This can even be another instance of a ``robot_localization`` state estimation node. However, that instance should *not* fuse the global data. The default values for ``map_frame``, ``odom_frame``, and ``base_link_frame`` are *map*, *odom,* and *base_link,* respectively. The ``world_frame`` parameter defaults to the value of ``odom_frame``. ~transform_time_offset ^^^^^^^^^^^^^^^^^^^^^^ Some packages require that your transforms are future-dated by a small time offset. The value of this parameter will be added to the timestamp of *map->odom* or *odom->base_link* transform being generated by the state estimation nodes in ``robot_localization``. ~transform_timeout ^^^^^^^^^^^^^^^^^^ The ``robot_localization`` package uses ``tf2``'s ``lookupTransform`` method to request transformations. This parameter specifies how long we would like to wait if a transformation is not available yet. Defaults to 0 if not set. The value 0 means we just get us the latest available (see ``tf2`` implementation) transform so we are not blocking the filter. Specifying a non-zero `transform_timeout` affects the filter's timing since it waits for a maximum of the `transform_timeout` for a transform to become available. This directly implies that mostly the specified desired output rate is not met since the filter has to wait for transforms when updating. ~[sensor] ^^^^^^^^^ For each sensor, users need to define this parameter based on the message type. For example, if we define one source of Imu messages and two sources of Odometry messages, the configuration would look like this: .. code-block:: xml The index for each parameter name is 0-based (e.g., ``odom0``, ``odom1``, etc.) and must be defined sequentially (e.g., do *not* use ``pose0`` and ``pose2`` if you have not defined ``pose1``). The values for each parameter are the topic name for that sensor. ~[sensor]_config ^^^^^^^^^^^^^^^^ Specific parameters: * ``~odomN_config`` * ``~twistN_config`` * ``~imuN_config`` * ``~poseN_config`` For each of the sensor messages defined above, users must specify what variables of those messages should be fused into the final state estimate. An example odometry configuration might look like this: .. code-block:: xml [true, true, false, false, false, true, true, false, false, false, false, true, false, false, false] The order of the boolean values are :math:`X, Y, Z, roll, pitch, yaw, \dot{X}, \dot{Y}, \dot{Z}, \dot{roll}, \dot{pitch}, \dot{yaw}, \ddot{X}, \ddot{Y}, \ddot{Z}`. In this example, we are fusing :math:`X` and :math:`Y` position, :math:`yaw`, :math:`\dot{X}`, and :math:`\dot{yaw}`. .. note:: The specification is done in the ``frame_id`` of the **sensor**, *not* in the ``world_frame`` or ``base_link_frame``. Please see the :doc:`coniguration tutorial ` for more information. ~[sensor]_queue_size ^^^^^^^^^^^^^^^^^^^^ Specific parameters: * ``~odomN_queue_size`` * ``~twistN_queue_size`` * ``~imuN_queue_size`` * ``~poseN_queue_size`` Users can use these parameters to adjust the callback queue sizes for each sensor. This is useful if your ``frequency`` parameter value is much lower than your sensor's frequency, as it allows the filter to incorporate all measurements that arrived in between update cycles. ~[sensor]_differential ^^^^^^^^^^^^^^^^^^^^^^ Specific parameters: * ``~odomN_differential`` * ``~imuN_differential`` * ``~poseN_differential`` For each of the sensor messages defined above *that contain pose information*, users can specify whether the pose variables should be integrated differentially. If a given value is set to *true*, then for a measurement at time :math:`t` from the sensor in question, we first subtract the measurement at time :math:`t-1`, and convert the resulting value to a velocity. This setting is especially useful if your robot has two sources of absolute pose information, e.g., yaw measurements from odometry and an IMU. In that case, if the variances on the input sources are not configured correctly, these measurements may get out of sync with one another and cause oscillations in the filter, but by integrating one or both of them differentially, we avoid this scenario. Users should take care when using this parameter for orientation data, as the conversion to velocity means that the covariance for orientation state variables will grow without bound (unless another source of absolute orientation data is being fused). If you simply want all of your pose variables to start at :math:`0`, then please use the ``_relative`` parameter. .. note:: If you are fusing GPS information via ``navsat_transform_node`` or ``utm_transform_node``, you should make sure that the ``_differential`` setting is *false.* ~[sensor]_relative ^^^^^^^^^^^^^^^^^^ Specific parameters: * ``~odomN_relative`` * ``~imuN_relative`` * ``~poseN_relative`` If this parameter is set to ``true``, then any measurements from this sensor will be fused relative to the first measurement received from that sensor. This is useful if, for example, you want your state estimate to always start at :math:`(0, 0, 0)` and with :math:`roll, pitch,` and :math:`yaw` values of :math:`(0, 0, 0)`. It is similar to the ``_differential`` parameter, but instead of removing the measurement at time :math:`t-1`, we always remove the measurement at time :math:`0`, and the measurement is not converted to a velocity. ~imuN_remove_gravitational_acceleration ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ If fusing accelerometer data from IMUs, this parameter determines whether or not acceleration due to gravity is removed from the acceleration measurement before fusing it. .. note:: This assumes that the IMU that is providing the acceleration data is also producing an absolute orientation. The orientation data is required to correctly remove gravitational acceleration. ~gravitational_acceleration ^^^^^^^^^^^^^^^^^^^^^^^^^^^ If ``imuN_remove_gravitational_acceleration`` is set to ``true``, then this parameter determines the acceleration in Z due to gravity that will be removed from the IMU's linear acceleration data. Default is 9.80665 (m/s^2). ~initial_state ^^^^^^^^^^^^^^ Starts the filter with the specified state. The state is given as a 15-D vector of doubles, in the same order as the sensor configurations. For example, to start your robot at a position of :math:`(5.0, 4.0, 3.0)`, a :math:`yaw` of :math:`1.57`, and a linear velocity of :math:`(0.1, 0.2, 0.3)`, you would use: .. code-block:: xml [5.0, 4.0, 3.0, 0.0, 0.0, 1.57, 0.1, 0.2, 0.3, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0] ~publish_tf ^^^^^^^^^^^ If *true*, the state estimation node will publish the transform from the frame specified by the ``world_frame`` parameter to the frame specified by the ``base_link_frame`` parameter. Defaults to *true*. ~publish_acceleration ^^^^^^^^^^^^^^^^^^^^^ If *true*, the state estimation node will publish the linear acceleration state. Defaults to *false*. ~print_diagnostics ^^^^^^^^^^^^^^^^^^ If true, the state estimation node will publish diagnostic messages to the ``/diagnostics`` topic. This is useful for debugging your configuration and sensor data. Advanced Parameters ------------------- ~use_control ^^^^^^^^^^^^ If *true*, the state estimation node will listen to the `cmd_vel` topic for a `geometry_msgs/Twist `_ message, and use that to generate an acceleration term. This term is then used in the robot's state prediction. This is especially useful in situations where even small amounts of lag in convergence for a given state variable cause problems in your application (e.g., LIDAR shifting during rotations). Defaults to *false*. .. note:: The presence and inclusion of linear acceleration data from an IMU will currently "override" the predicted linear acceleration value. ~stamped_control ^^^^^^^^^^^^^^^^ If *true* and ``use_control`` is also *true*, looks for a `geometry_msgs/TwistStamped `_ message instead of a `geometry_msgs/Twist `_ message. ~control_timeout ^^^^^^^^^^^^^^^^ If ``use_control`` is set to *true* and no control command is received in this amount of time, given in seconds, the control-based acceleration term ceases to be applied. ~control_config ^^^^^^^^^^^^^^^ Controls which variables in the ``cmd_vel`` message are used in state prediction. The order of the values is :math:`\dot{X}, \dot{Y}, \dot{Z}, \dot{roll}, \dot{pitch}, \dot{yaw}`. Only used if ``use_control`` is set to *true*. .. code-block:: xml [true, false, false, false, false, true] ~acceleration_limits ^^^^^^^^^^^^^^^^^^^^ How rapidly your robot can accelerate for each dimension. Matches the parameter order in ``control_config``. Only used if ``use_control`` is set to *true*. .. code-block:: xml [1.3, 0.0, 0.0, 0.0, 0.0, 3.2] ~deceleration_limits ^^^^^^^^^^^^^^^^^^^^ How rapidly your robot can decelerate for each dimension. Matches the parameter order in ``control_config``. Only used if ``use_control`` is set to *true*. ~acceleration_gains ^^^^^^^^^^^^^^^^^^^ If your robot cannot instantaneously reach its acceleration limit, the permitted change can be controlled with these gains. Only used if ``use_control`` is set to *true*. .. code-block:: xml [0.8, 0.0, 0.0, 0.0, 0.0, 0.9] ~deceleration_gains ^^^^^^^^^^^^^^^^^^^ If your robot cannot instantaneously reach its deceleration limit, the permitted change can be controlled with these gains. Only used if ``use_control`` is set to *true*. ~smooth_lagged_data ^^^^^^^^^^^^^^^^^^^ If any of your sensors produce data with timestamps that are older than the most recent filter update (more plainly, if you have a source of lagged sensor data), setting this parameter to *true* will enable the filter, upon reception of lagged data, to revert to the last state prior to the lagged measurement, then process all measurements until the current time. This is especially useful for measurements that come from nodes that require heavy CPU usage to generate pose estimates (e.g., laser scan matchers), as they are frequently lagged behind the current time. ~history_length ^^^^^^^^^^^^^^^ If ``smooth_lagged_data`` is set to *true*, this parameter specifies the number of seconds for which the filter will retain its state and measurement history. This value should be at least as large as the time delta between your lagged measurements and the current time. ~[sensor]_nodelay ^^^^^^^^^^^^^^^^^ Specific parameters: * ``~odomN_nodelay`` * ``~twistN_nodelay`` * ``~imuN_nodelay`` * ``~poseN_nodelay`` If *true*, sets the `tcpNoDelay` `transport hint `_. There is some evidence that Nagle's algorithm intereferes with the timely reception of large message types, such as the `nav_msgs/Odometry `_ message. Setting this to *true* for an input disables Nagle's algorithm for that subscriber. Defaults to *false*. ~[sensor]_threshold ^^^^^^^^^^^^^^^^^^^ Specific parameters: * ``~odomN_pose_rejection_threshold`` * ``odomN_twist_rejection_threshold`` * ``poseN_rejection_threshold`` * ``twistN_rejection_threshold`` * ``imuN_pose_rejection_threshold`` * ``imuN_angular_velocity_rejection_threshold`` * ``imuN_linear_acceleration_rejection_threshold`` If your data is subject to outliers, use these threshold settings, expressed as `Mahalanobis distances `_, to control how far away from the current vehicle state a sensor measurement is permitted to be. Each defaults to ``numeric_limits::max()`` if unspecified. ~debug ^^^^^^ Boolean flag that specifies whether or not to run in debug mode. WARNING: setting this to true will generate a massive amount of data. The data is written to the value of the ``debug_out_file`` parameter. Defaults to *false*. ~debug_out_file ^^^^^^^^^^^^^^^^ If ``debug`` is *true*, the file to which debug output is written. ~process_noise_covariance ^^^^^^^^^^^^^^^^^^^^^^^^^ The process noise covariance, commonly denoted *Q*, is used to model uncertainty in the prediction stage of the filtering algorithms. It can be difficult to tune, and has been exposed as a parameter for easier customization. This parameter can be left alone, but you will achieve superior results by tuning it. In general, the larger the value for *Q* relative to the variance for a given variable in an input message, the faster the filter will converge to the value in the measurement. ~dynamic_process_noise_covariance ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ If *true*, will dynamically scale the ``process_noise_covariance`` based on the robot's velocity. This is useful, e.g., when you want your robot's estimate error covariance to stop growing when the robot is stationary. Defaults to *false*. ~initial_estimate_covariance ^^^^^^^^^^^^^^^^^^^^^^^^^^^^ The estimate covariance, commonly denoted *P*, defines the error in the current state estimate. The parameter allows users to set the initial value for the matrix, which will affect how quickly the filter converges. For example, if users set the value at position :math:`[0, 0]` to a very small value, e.g., `1e-12`, and then attempt to fuse measurements of X position with a high variance value for :math:`X`, then the filter will be very slow to "trust" those measurements, and the time required for convergence will increase. Again, users should take care with this parameter. When only fusing velocity data (e.g., no absolute pose information), users will likely *not* want to set the initial covariance values for the absolute pose variables to large numbers. This is because those errors are going to grow without bound (owing to the lack of absolute pose measurements to reduce the error), and starting them with large values will not benefit the state estimate. ~reset_on_time_jump ^^^^^^^^^^^^^^^^^^^ If set to *true* and ``ros::Time::isSimTime()`` is *true*, the filter will reset to its uninitialized state when a jump back in time is detected on a topic. This is useful when working with bag data, in that the bag can be restarted without restarting the node. Node-specific Parameters ------------------------ The standard and advanced parameters are common to all state estimation nodes in ``robot_localization``. This section details parameters that are unique to their respective state estimation nodes. ukf_localization_node ^^^^^^^^^^^^^^^^^^^^^ The parameters for ``ukf_localization_node`` follow the nomenclature of the `original paper `_ and `wiki article `_. * **~alpha** - Controls the spread of sigma points. Unless you are familiar with unscented Kalman filters, it's probably best for this setting to remain at its default value (0.001). * **~kappa** - Also control the spread of sigma points. Unless you are familiar with unscented Kalman filters, it's probably best for this setting to remain at its default value (0). * **~beta** - Relates to the distribution of the state vector. The default value of 2 implies that the distribution is Gaussian. Like the other parameters, this should remain unchanged unless the user is familiar with unscented Kalman filters. Published Topics ================ * ``odometry/filtered`` (`nav_msgs/Odometry `_) * ``accel/filtered`` (`geometry_msgs/AccelWithCovarianceStamped `_) (if enabled) Published Transforms ==================== * If the user's ``world_frame`` parameter is set to the value of ``odom_frame``, a transform is published from the frame given by the ``odom_frame`` parameter to the frame given by the ``base_link_frame`` parameter. * If the user's ``world_frame`` parameter is set to the value of ``map_frame``, a transform is published from the frame given by the ``map_frame`` parameter to the frame given by the ``odom_frame`` parameter. .. note:: This mode assumes that another node is broadcasting the transform from the frame given by the ``odom_frame`` parameter to the frame given by the ``base_link_frame`` parameter. This can be another instance of a ``robot_localization`` state estimation node. Services ======== * ``set_pose`` - By issuing a `geometry_msgs/PoseWithCovarianceStamped `_ message to the ``set_pose`` topic, users can manually set the state of the filter. This is useful for resetting the filter during testing, and allows for interaction with ``rviz``. Alternatively, the state estimation nodes advertise a ``SetPose`` service, whose type is `robot_localization/SetPose `_.rejection ================================================ FILE: src/robot_localization/include/robot_localization/ekf.h ================================================ /* * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * 1. Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * 2. Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * 3. Neither the name of the copyright holder nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT 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 ROBOT_LOCALIZATION_EKF_H #define ROBOT_LOCALIZATION_EKF_H #include "robot_localization/filter_base.h" #include #include #include #include namespace RobotLocalization { //! @brief Extended Kalman filter class //! //! Implementation of an extended Kalman filter (EKF). This //! class derives from FilterBase and overrides the predict() //! and correct() methods in keeping with the discrete time //! EKF algorithm. //! class Ekf: public FilterBase { public: //! @brief Constructor for the Ekf class //! //! @param[in] args - Generic argument container (not used here, but //! needed so that the ROS filters can pass arbitrary arguments to //! templated filter types). //! explicit Ekf(std::vector args = std::vector()); //! @brief Destructor for the Ekf class //! ~Ekf(); //! @brief Carries out the correct step in the predict/update cycle. //! //! @param[in] measurement - The measurement to fuse with our estimate //! void correct(const Measurement &measurement); //! @brief Carries out the predict step in the predict/update cycle. //! //! Projects the state and error matrices forward using a model of //! the vehicle's motion. //! //! @param[in] referenceTime - The time at which the prediction is being made //! @param[in] delta - The time step over which to predict. //! void predict(const double referenceTime, const double delta); }; } // namespace RobotLocalization #endif // ROBOT_LOCALIZATION_EKF_H ================================================ FILE: src/robot_localization/include/robot_localization/filter_base.h ================================================ /* * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * 1. Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * 2. Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * 3. Neither the name of the copyright holder nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT 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 ROBOT_LOCALIZATION_FILTER_BASE_H #define ROBOT_LOCALIZATION_FILTER_BASE_H #include "robot_localization/filter_utilities.h" #include "robot_localization/filter_common.h" #include #include #include #include #include #include #include #include #include #include namespace RobotLocalization { //! @brief Structure used for storing and comparing measurements //! (for priority queues) //! //! Measurement units are assumed to be in meters and radians. //! Times are real-valued and measured in seconds. //! struct Measurement { // The topic name for this measurement. Needed // for capturing previous state values for new // measurements. std::string topicName_; // The measurement and its associated covariance Eigen::VectorXd measurement_; Eigen::MatrixXd covariance_; // This defines which variables within this measurement // actually get passed into the filter. std::vector // is generally frowned upon, so we use ints. std::vector updateVector_; // The real-valued time, in seconds, since some epoch // (presumably the start of execution, but any will do) double time_; // The Mahalanobis distance threshold in number of sigmas double mahalanobisThresh_; // The most recent control vector (needed for lagged data) Eigen::VectorXd latestControl_; // The time stamp of the most recent control term (needed for lagged data) double latestControlTime_; // We want earlier times to have greater priority bool operator()(const boost::shared_ptr &a, const boost::shared_ptr &b) { return (*this)(*(a.get()), *(b.get())); } bool operator()(const Measurement &a, const Measurement &b) { return a.time_ > b.time_; } Measurement() : topicName_(""), latestControl_(), latestControlTime_(0.0), time_(0.0), mahalanobisThresh_(std::numeric_limits::max()) { } }; typedef boost::shared_ptr MeasurementPtr; //! @brief Structure used for storing and comparing filter states //! //! This structure is useful when higher-level classes need to remember filter history. //! Measurement units are assumed to be in meters and radians. //! Times are real-valued and measured in seconds. //! struct FilterState { // The filter state vector Eigen::VectorXd state_; // The filter error covariance matrix Eigen::MatrixXd estimateErrorCovariance_; // The most recent control vector Eigen::VectorXd latestControl_; // The time stamp of the most recent measurement for the filter double lastMeasurementTime_; // The time stamp of the most recent control term double latestControlTime_; // We want the queue to be sorted from latest to earliest timestamps. bool operator()(const FilterState &a, const FilterState &b) { return a.lastMeasurementTime_ < b.lastMeasurementTime_; } FilterState() : state_(), estimateErrorCovariance_(), latestControl_(), lastMeasurementTime_(0.0), latestControlTime_(0.0) {} }; typedef boost::shared_ptr FilterStatePtr; class FilterBase { public: //! @brief Constructor for the FilterBase class //! FilterBase(); //! @brief Destructor for the FilterBase class //! virtual ~FilterBase(); //! @brief Resets filter to its unintialized state //! void reset(); //! @brief Computes a dynamic process noise covariance matrix using the parameterized state //! //! This allows us to, e.g., not increase the pose covariance values when the vehicle is not moving //! //! @param[in] state - The STATE_SIZE state vector that is used to generate the dynamic process noise covariance //! void computeDynamicProcessNoiseCovariance(const Eigen::VectorXd &state, const double delta); //! @brief Carries out the correct step in the predict/update cycle. This method //! must be implemented by subclasses. //! //! @param[in] measurement - The measurement to fuse with the state estimate //! virtual void correct(const Measurement &measurement) = 0; //! @brief Returns the control vector currently being used //! //! @return The control vector //! const Eigen::VectorXd& getControl(); //! @brief Returns the time at which the control term was issued //! //! @return The time the control vector was issued //! double getControlTime(); //! @brief Gets the value of the debug_ variable. //! //! @return True if in debug mode, false otherwise //! bool getDebug(); //! @brief Gets the estimate error covariance //! //! @return A copy of the estimate error covariance matrix //! const Eigen::MatrixXd& getEstimateErrorCovariance(); //! @brief Gets the filter's initialized status //! //! @return True if we've received our first measurement, false otherwise //! bool getInitializedStatus(); //! @brief Gets the most recent measurement time //! //! @return The time at which we last received a measurement //! double getLastMeasurementTime(); //! @brief Gets the filter's predicted state, i.e., the //! state estimate before correct() is called. //! //! @return A constant reference to the predicted state //! const Eigen::VectorXd& getPredictedState(); //! @brief Gets the filter's process noise covariance //! //! @return A constant reference to the process noise covariance //! const Eigen::MatrixXd& getProcessNoiseCovariance(); //! @brief Gets the sensor timeout value (in seconds) //! //! @return The sensor timeout value //! double getSensorTimeout(); //! @brief Gets the filter state //! //! @return A constant reference to the current state //! const Eigen::VectorXd& getState(); //! @brief Carries out the predict step in the predict/update cycle. //! Projects the state and error matrices forward using a model of //! the vehicle's motion. This method must be implemented by subclasses. //! //! @param[in] referenceTime - The time at which the prediction is being made //! @param[in] delta - The time step over which to predict. //! virtual void predict(const double referenceTime, const double delta) = 0; //! @brief Does some final preprocessing, carries out the predict/update cycle //! //! @param[in] measurement - The measurement object to fuse into the filter //! virtual void processMeasurement(const Measurement &measurement); //! @brief Sets the most recent control term //! //! @param[in] control - The control term to be applied //! @param[in] controlTime - The time at which the control in question was received //! void setControl(const Eigen::VectorXd &control, const double controlTime); //! @brief Sets the control update vector and acceleration limits //! //! @param[in] updateVector - The values the control term affects //! @param[in] controlTimeout - Timeout value, in seconds, after which a control is considered stale //! @param[in] accelerationLimits - The acceleration limits for the control variables //! @param[in] accelerationGains - Gains applied to the control term-derived acceleration //! @param[in] decelerationLimits - The deceleration limits for the control variables //! @param[in] decelerationGains - Gains applied to the control term-derived deceleration //! void setControlParams(const std::vector &updateVector, const double controlTimeout, const std::vector &accelerationLimits, const std::vector &accelerationGains, const std::vector &decelerationLimits, const std::vector &decelerationGains); //! @brief Sets the filter into debug mode //! //! NOTE: this will generates a lot of debug output to the provided stream. //! The value must be a pointer to a valid ostream object. //! //! @param[in] debug - Whether or not to place the filter in debug mode //! @param[in] outStream - If debug is true, then this must have a valid pointer. //! If the pointer is invalid, the filter will not enter debug mode. If debug is //! false, outStream is ignored. //! void setDebug(const bool debug, std::ostream *outStream = NULL); //! @brief Enables dynamic process noise covariance calculation //! //! @param[in] dynamicProcessNoiseCovariance - Whether or not to compute dynamic process noise covariance matrices //! void setUseDynamicProcessNoiseCovariance(const bool dynamicProcessNoiseCovariance); //! @brief Manually sets the filter's estimate error covariance //! //! @param[in] estimateErrorCovariance - The state to set as the filter's current state //! void setEstimateErrorCovariance(const Eigen::MatrixXd &estimateErrorCovariance); //! @brief Sets the filter's last measurement time. //! //! @param[in] lastMeasurementTime - The last measurement time of the filter //! void setLastMeasurementTime(const double lastMeasurementTime); //! @brief Sets the process noise covariance for the filter. //! //! This enables external initialization, which is important, as this //! matrix can be difficult to tune for a given implementation. //! //! @param[in] processNoiseCovariance - The STATE_SIZExSTATE_SIZE process noise covariance matrix //! to use for the filter //! void setProcessNoiseCovariance(const Eigen::MatrixXd &processNoiseCovariance); //! @brief Sets the sensor timeout //! //! @param[in] sensorTimeout - The time, in seconds, for a sensor to be //! considered having timed out //! void setSensorTimeout(const double sensorTimeout); //! @brief Manually sets the filter's state //! //! @param[in] state - The state to set as the filter's current state //! void setState(const Eigen::VectorXd &state); //! @brief Ensures a given time delta is valid (helps with bag file playback issues) //! //! @param[in] delta - The time delta, in seconds, to validate //! void validateDelta(double &delta); protected: //! @brief Method for settings bounds on acceleration values derived from controls //! @param[in] state - The current state variable (e.g., linear X velocity) //! @param[in] control - The current control commanded velocity corresponding to the state variable //! @param[in] accelerationLimit - Limit for acceleration (regardless of driving direction) //! @param[in] accelerationGain - Gain applied to acceleration control error //! @param[in] decelerationLimit - Limit for deceleration (moving towards zero, regardless of driving direction) //! @param[in] decelerationGain - Gain applied to deceleration control error //! @return a usable acceleration estimate for the control vector //! inline double computeControlAcceleration(const double state, const double control, const double accelerationLimit, const double accelerationGain, const double decelerationLimit, const double decelerationGain) { FB_DEBUG("---------- FilterBase::computeControlAcceleration ----------\n"); const double error = control - state; const bool sameSign = (::fabs(error) <= ::fabs(control) + 0.01); const double setPoint = (sameSign ? control : 0.0); const bool decelerating = ::fabs(setPoint) < ::fabs(state); double limit = accelerationLimit; double gain = accelerationGain; if (decelerating) { limit = decelerationLimit; gain = decelerationGain; } const double finalAccel = std::min(std::max(gain * error, -limit), limit); FB_DEBUG("Control value: " << control << "\n" << "State value: " << state << "\n" << "Error: " << error << "\n" << "Same sign: " << (sameSign ? "true" : "false") << "\n" << "Set point: " << setPoint << "\n" << "Decelerating: " << (decelerating ? "true" : "false") << "\n" << "Limit: " << limit << "\n" << "Gain: " << gain << "\n" << "Final is " << finalAccel << "\n"); return finalAccel; } //! @brief Keeps the state Euler angles in the range [-pi, pi] //! virtual void wrapStateAngles(); //! @brief Tests if innovation is within N-sigmas of covariance. Returns true if passed the test. //! @param[in] innovation - The difference between the measurement and the state //! @param[in] invCovariance - The innovation error //! @param[in] nsigmas - Number of standard deviations that are considered acceptable //! virtual bool checkMahalanobisThreshold(const Eigen::VectorXd &innovation, const Eigen::MatrixXd &invCovariance, const double nsigmas); //! @brief Converts the control term to an acceleration to be applied in the prediction step //! @param[in] referenceTime - The time of the update (measurement used in the prediction step) //! @param[in] predictionDelta - The amount of time over which we are carrying out our prediction //! void prepareControl(const double referenceTime, const double predictionDelta); //! @brief Gains applied to acceleration derived from control term //! std::vector accelerationGains_; //! @brief Caps the acceleration we apply from control input //! std::vector accelerationLimits_; //! @brief Variable that gets updated every time we process a measurement and we have a valid control //! Eigen::VectorXd controlAcceleration_; //! @brief Gains applied to deceleration derived from control term //! std::vector decelerationGains_; //! @brief Caps the deceleration we apply from control input //! std::vector decelerationLimits_; //! @brief Latest control term //! Eigen::VectorXd latestControl_; //! @brief Which control variables are being used (e.g., not every vehicle is controllable in Y or Z) //! std::vector controlUpdateVector_; //! @brief Timeout value, in seconds, after which a control is considered stale //! double controlTimeout_; //! @brief Covariance matrices can be incredibly unstable. We can //! add a small value to it at each iteration to help maintain its //! positive-definite property. //! Eigen::MatrixXd covarianceEpsilon_; //! @brief Used for outputting debug messages //! std::ostream *debugStream_; //! @brief Gets updated when useDynamicProcessNoise_ is true //! Eigen::MatrixXd dynamicProcessNoiseCovariance_; //! @brief This matrix stores the total error in our position //! estimate (the state_ variable). //! Eigen::MatrixXd estimateErrorCovariance_; //! @brief We need the identity for a few operations. Better to store it. //! Eigen::MatrixXd identity_; //! @brief Whether or not we've received any measurements //! bool initialized_; //! @brief Tracks the time the filter was last updated using a measurement. //! //! This value is used to monitor sensor readings with respect to the sensorTimeout_. //! We also use it to compute the time delta values for our prediction step. //! double lastMeasurementTime_; //! @brief The time of reception of the most recent control term //! double latestControlTime_; //! @brief Holds the last predicted state of the filter //! Eigen::VectorXd predictedState_; //! @brief As we move through the world, we follow a predict/update //! cycle. If one were to imagine a scenario where all we did was make //! predictions without correcting, the error in our position estimate //! would grow without bound. This error is stored in the //! stateEstimateCovariance_ matrix. However, this matrix doesn't answer //! the question of *how much* our error should grow for each time step. //! That's where the processNoiseCovariance matrix comes in. When we //! make a prediction using the transfer function, we add this matrix //! (times deltaT) to the state estimate covariance matrix. //! Eigen::MatrixXd processNoiseCovariance_; //! @brief The updates to the filter - both predict and correct - are driven //! by measurements. If we get a gap in measurements for some reason, we want //! the filter to continue estimating. When this gap occurs, as specified by //! this timeout, we will continue to call predict() at the filter's frequency. //! double sensorTimeout_; //! @brief This is the robot's state vector, which is what we are trying to //! filter. The values in this vector are what get reported by the node. //! Eigen::VectorXd state_; //! @brief The Kalman filter transfer function //! //! Kalman filters and extended Kalman filters project the current //! state forward in time. This is the "predict" part of the predict/correct //! cycle. A Kalman filter has a (typically constant) matrix A that defines //! how to turn the current state, x, into the predicted next state. For an //! EKF, this matrix becomes a function f(x). However, this function can still //! be expressed as a matrix to make the math a little cleaner, which is what //! we do here. Technically, each row in the matrix is actually a function. //! Some rows will contain many trigonometric functions, which are of course //! non-linear. In any case, you can think of this as the 'A' matrix in the //! Kalman filter formulation. //! Eigen::MatrixXd transferFunction_; //! @brief The Kalman filter transfer function Jacobian //! //! The transfer function is allowed to be non-linear in an EKF, but //! for propagating (predicting) the covariance matrix, we need to linearize //! it about the current mean (i.e., state). This is done via a Jacobian, //! which calculates partial derivatives of each row of the transfer function //! matrix with respect to each state variable. //! Eigen::MatrixXd transferFunctionJacobian_; //! @brief Whether or not we apply the control term //! bool useControl_; //! @brief If true, uses the robot's vehicle state and the static process noise covariance matrix to generate a //! dynamic process noise covariance matrix //! bool useDynamicProcessNoiseCovariance_; private: //! @brief Whether or not the filter is in debug mode //! bool debug_; }; } // namespace RobotLocalization #endif // ROBOT_LOCALIZATION_FILTER_BASE_H ================================================ FILE: src/robot_localization/include/robot_localization/filter_common.h ================================================ /* * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * 1. Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * 2. Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * 3. Neither the name of the copyright holder nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT 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 ROBOT_LOCALIZATION_FILTER_COMMON_H #define ROBOT_LOCALIZATION_FILTER_COMMON_H namespace RobotLocalization { //! @brief Enumeration that defines the state vector //! enum StateMembers { StateMemberX = 0, StateMemberY, StateMemberZ, StateMemberRoll, StateMemberPitch, StateMemberYaw, StateMemberVx, StateMemberVy, StateMemberVz, StateMemberVroll, StateMemberVpitch, StateMemberVyaw, StateMemberAx, StateMemberAy, StateMemberAz }; //! @brief Enumeration that defines the control vector //! enum ControlMembers { ControlMemberVx, ControlMemberVy, ControlMemberVz, ControlMemberVroll, ControlMemberVpitch, ControlMemberVyaw }; //! @brief Global constants that define our state //! vector size and offsets to groups of values //! within that state. const int STATE_SIZE = 15; const int POSITION_OFFSET = StateMemberX; const int ORIENTATION_OFFSET = StateMemberRoll; const int POSITION_V_OFFSET = StateMemberVx; const int ORIENTATION_V_OFFSET = StateMemberVroll; const int POSITION_A_OFFSET = StateMemberAx; //! @brief Pose and twist messages each //! contain six variables const int POSE_SIZE = 6; const int TWIST_SIZE = 6; const int POSITION_SIZE = 3; const int ORIENTATION_SIZE = 3; const int ACCELERATION_SIZE = 3; //! @brief Common variables const double PI = 3.141592653589793; const double TAU = 6.283185307179587; } // namespace RobotLocalization #endif // ROBOT_LOCALIZATION_FILTER_COMMON_H ================================================ FILE: src/robot_localization/include/robot_localization/filter_utilities.h ================================================ /* * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * 1. Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * 2. Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * 3. Neither the name of the copyright holder nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT 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 ROBOT_LOCALIZATION_FILTER_UTILITIES_H #define ROBOT_LOCALIZATION_FILTER_UTILITIES_H #include #include #include #include #include #define FB_DEBUG(msg) if (getDebug()) { *debugStream_ << msg; } // Handy methods for debug output std::ostream& operator<<(std::ostream& os, const Eigen::MatrixXd &mat); std::ostream& operator<<(std::ostream& os, const Eigen::VectorXd &vec); std::ostream& operator<<(std::ostream& os, const std::vector &vec); std::ostream& operator<<(std::ostream& os, const std::vector &vec); namespace RobotLocalization { namespace FilterUtilities { //! @brief Utility method keeping RPY angles in the range [-pi, pi] //! @param[in] rotation - The rotation to bind //! @return the bounded value //! double clampRotation(double rotation); //! @brief Utility method for appending tf2 prefixes cleanly //! @param[in] tfPrefix - the tf2 prefix to append //! @param[in, out] frameId - the resulting frame_id value //! void appendPrefix(std::string tfPrefix, std::string &frameId); } // namespace FilterUtilities } // namespace RobotLocalization #endif // ROBOT_LOCALIZATION_FILTER_UTILITIES_H ================================================ FILE: src/robot_localization/include/robot_localization/navsat_conversions.h ================================================ /* * Copyright (C) 2010 Austin Robot Technology, and others * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * 1. Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * 2. Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * 3. Neither the names of the University of Texas at Austin, nor * Austin Robot Technology, nor the names of other contributors may * be used to endorse or promote products derived from this * software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. * * This file contains code from multiple files in the original * source. The originals can be found here: * * https://github.com/austin-robot/utexas-art-ros-pkg/blob/afd147a1eb944fc3dbd138574c39699813f797bf/stacks/art_vehicle/art_common/include/art/UTM.h * https://github.com/austin-robot/utexas-art-ros-pkg/blob/afd147a1eb944fc3dbd138574c39699813f797bf/stacks/art_vehicle/art_common/include/art/conversions.h */ #ifndef ROBOT_LOCALIZATION_NAVSAT_CONVERSIONS_H #define ROBOT_LOCALIZATION_NAVSAT_CONVERSIONS_H /** @file @brief Universal Transverse Mercator transforms. Functions to convert (spherical) latitude and longitude to and from (Euclidean) UTM coordinates. @author Chuck Gantz- chuck.gantz@globalstar.com */ #include #include #include #include namespace RobotLocalization { namespace NavsatConversions { const double RADIANS_PER_DEGREE = M_PI/180.0; const double DEGREES_PER_RADIAN = 180.0/M_PI; // Grid granularity for rounding UTM coordinates to generate MapXY. const double grid_size = 100000.0; // 100 km grid // WGS84 Parameters #define WGS84_A 6378137.0 // major axis #define WGS84_B 6356752.31424518 // minor axis #define WGS84_F 0.0033528107 // ellipsoid flattening #define WGS84_E 0.0818191908 // first eccentricity #define WGS84_EP 0.0820944379 // second eccentricity // UTM Parameters #define UTM_K0 0.9996 // scale factor #define UTM_FE 500000.0 // false easting #define UTM_FN_N 0.0 // false northing, northern hemisphere #define UTM_FN_S 10000000.0 // false northing, southern hemisphere #define UTM_E2 (WGS84_E*WGS84_E) // e^2 #define UTM_E4 (UTM_E2*UTM_E2) // e^4 #define UTM_E6 (UTM_E4*UTM_E2) // e^6 #define UTM_EP2 (UTM_E2/(1-UTM_E2)) // e'^2 /** * Utility function to convert geodetic to UTM position * * Units in are floating point degrees (sign for east/west) * * Units out are meters * * @todo deprecate this interface in favor of LLtoUTM() */ static inline void UTM(double lat, double lon, double *x, double *y) { // constants static const double m0 = (1 - UTM_E2/4 - 3*UTM_E4/64 - 5*UTM_E6/256); static const double m1 = -(3*UTM_E2/8 + 3*UTM_E4/32 + 45*UTM_E6/1024); static const double m2 = (15*UTM_E4/256 + 45*UTM_E6/1024); static const double m3 = -(35*UTM_E6/3072); // compute the central meridian int cm = ((lon >= 0.0) ? (static_cast(lon) - (static_cast(lon)) % 6 + 3) : (static_cast(lon) - (static_cast(lon)) % 6 - 3)); // convert degrees into radians double rlat = lat * RADIANS_PER_DEGREE; double rlon = lon * RADIANS_PER_DEGREE; double rlon0 = cm * RADIANS_PER_DEGREE; // compute trigonometric functions double slat = sin(rlat); double clat = cos(rlat); double tlat = tan(rlat); // decide the false northing at origin double fn = (lat > 0) ? UTM_FN_N : UTM_FN_S; double T = tlat * tlat; double C = UTM_EP2 * clat * clat; double A = (rlon - rlon0) * clat; double M = WGS84_A * (m0*rlat + m1*sin(2*rlat) + m2*sin(4*rlat) + m3*sin(6*rlat)); double V = WGS84_A / sqrt(1 - UTM_E2*slat*slat); // compute the easting-northing coordinates *x = UTM_FE + UTM_K0 * V * (A + (1-T+C)*pow(A, 3)/6 + (5-18*T+T*T+72*C-58*UTM_EP2)*pow(A, 5)/120); *y = fn + UTM_K0 * (M + V * tlat * (A*A/2 + (5-T+9*C+4*C*C)*pow(A, 4)/24 + ((61-58*T+T*T+600*C-330*UTM_EP2) * pow(A, 6)/720))); return; } /** * Determine the correct UTM letter designator for the * given latitude * * @returns 'Z' if latitude is outside the UTM limits of 84N to 80S * * Written by Chuck Gantz- chuck.gantz@globalstar.com */ static inline char UTMLetterDesignator(double Lat) { char LetterDesignator; if ((84 >= Lat) && (Lat >= 72)) LetterDesignator = 'X'; else if ((72 > Lat) && (Lat >= 64)) LetterDesignator = 'W'; else if ((64 > Lat) && (Lat >= 56)) LetterDesignator = 'V'; else if ((56 > Lat) && (Lat >= 48)) LetterDesignator = 'U'; else if ((48 > Lat) && (Lat >= 40)) LetterDesignator = 'T'; else if ((40 > Lat) && (Lat >= 32)) LetterDesignator = 'S'; else if ((32 > Lat) && (Lat >= 24)) LetterDesignator = 'R'; else if ((24 > Lat) && (Lat >= 16)) LetterDesignator = 'Q'; else if ((16 > Lat) && (Lat >= 8)) LetterDesignator = 'P'; else if (( 8 > Lat) && (Lat >= 0)) LetterDesignator = 'N'; else if (( 0 > Lat) && (Lat >= -8)) LetterDesignator = 'M'; else if ((-8 > Lat) && (Lat >= -16)) LetterDesignator = 'L'; else if ((-16 > Lat) && (Lat >= -24)) LetterDesignator = 'K'; else if ((-24 > Lat) && (Lat >= -32)) LetterDesignator = 'J'; else if ((-32 > Lat) && (Lat >= -40)) LetterDesignator = 'H'; else if ((-40 > Lat) && (Lat >= -48)) LetterDesignator = 'G'; else if ((-48 > Lat) && (Lat >= -56)) LetterDesignator = 'F'; else if ((-56 > Lat) && (Lat >= -64)) LetterDesignator = 'E'; else if ((-64 > Lat) && (Lat >= -72)) LetterDesignator = 'D'; else if ((-72 > Lat) && (Lat >= -80)) LetterDesignator = 'C'; // 'Z' is an error flag, the Latitude is outside the UTM limits else LetterDesignator = 'Z'; return LetterDesignator; } /** * Convert lat/long to UTM coords. Equations from USGS Bulletin 1532 * * East Longitudes are positive, West longitudes are negative. * North latitudes are positive, South latitudes are negative * Lat and Long are in fractional degrees * * Written by Chuck Gantz- chuck.gantz@globalstar.com */ static inline void LLtoUTM(const double Lat, const double Long, double &UTMNorthing, double &UTMEasting, std::string &UTMZone) { double a = WGS84_A; double eccSquared = UTM_E2; double k0 = UTM_K0; double LongOrigin; double eccPrimeSquared; double N, T, C, A, M; // Make sure the longitude is between -180.00 .. 179.9 double LongTemp = (Long+180)-static_cast((Long+180)/360)*360-180; double LatRad = Lat*RADIANS_PER_DEGREE; double LongRad = LongTemp*RADIANS_PER_DEGREE; double LongOriginRad; int ZoneNumber; ZoneNumber = static_cast((LongTemp + 180)/6) + 1; if ( Lat >= 56.0 && Lat < 64.0 && LongTemp >= 3.0 && LongTemp < 12.0 ) ZoneNumber = 32; // Special zones for Svalbard if ( Lat >= 72.0 && Lat < 84.0 ) { if ( LongTemp >= 0.0 && LongTemp < 9.0 ) ZoneNumber = 31; else if ( LongTemp >= 9.0 && LongTemp < 21.0 ) ZoneNumber = 33; else if ( LongTemp >= 21.0 && LongTemp < 33.0 ) ZoneNumber = 35; else if ( LongTemp >= 33.0 && LongTemp < 42.0 ) ZoneNumber = 37; } // +3 puts origin in middle of zone LongOrigin = (ZoneNumber - 1)*6 - 180 + 3; LongOriginRad = LongOrigin * RADIANS_PER_DEGREE; // Compute the UTM Zone from the latitude and longitude char zone_buf[] = {0, 0, 0, 0}; snprintf(zone_buf, sizeof(zone_buf), "%d%c", ZoneNumber, UTMLetterDesignator(Lat)); UTMZone = std::string(zone_buf); eccPrimeSquared = (eccSquared)/(1-eccSquared); N = a/sqrt(1-eccSquared*sin(LatRad)*sin(LatRad)); T = tan(LatRad)*tan(LatRad); C = eccPrimeSquared*cos(LatRad)*cos(LatRad); A = cos(LatRad)*(LongRad-LongOriginRad); M = a*((1 - eccSquared/4 - 3*eccSquared*eccSquared/64 - 5*eccSquared*eccSquared*eccSquared/256) * LatRad - (3*eccSquared/8 + 3*eccSquared*eccSquared/32 + 45*eccSquared*eccSquared*eccSquared/1024)*sin(2*LatRad) + (15*eccSquared*eccSquared/256 + 45*eccSquared*eccSquared*eccSquared/1024)*sin(4*LatRad) - (35*eccSquared*eccSquared*eccSquared/3072)*sin(6*LatRad)); UTMEasting = static_cast (k0*N*(A+(1-T+C)*A*A*A/6 + (5-18*T+T*T+72*C-58*eccPrimeSquared)*A*A*A*A*A/120) + 500000.0); UTMNorthing = static_cast (k0*(M+N*tan(LatRad) *(A*A/2+(5-T+9*C+4*C*C)*A*A*A*A/24 + (61-58*T+T*T+600*C-330*eccPrimeSquared)*A*A*A*A*A*A/720))); if (Lat < 0) { // 10000000 meter offset for southern hemisphere UTMNorthing += 10000000.0; } } /** * Converts UTM coords to lat/long. Equations from USGS Bulletin 1532 * * East Longitudes are positive, West longitudes are negative. * North latitudes are positive, South latitudes are negative * Lat and Long are in fractional degrees. * * Written by Chuck Gantz- chuck.gantz@globalstar.com */ static inline void UTMtoLL(const double UTMNorthing, const double UTMEasting, const std::string &UTMZone, double& Lat, double& Long ) { double k0 = UTM_K0; double a = WGS84_A; double eccSquared = UTM_E2; double eccPrimeSquared; double e1 = (1-sqrt(1-eccSquared))/(1+sqrt(1-eccSquared)); double N1, T1, C1, R1, D, M; double LongOrigin; double mu, phi1Rad; double x, y; int ZoneNumber; char* ZoneLetter; x = UTMEasting - 500000.0; // remove 500,000 meter offset for longitude y = UTMNorthing; ZoneNumber = strtoul(UTMZone.c_str(), &ZoneLetter, 10); if ((*ZoneLetter - 'N') < 0) { // remove 10,000,000 meter offset used for southern hemisphere y -= 10000000.0; } // +3 puts origin in middle of zone LongOrigin = (ZoneNumber - 1)*6 - 180 + 3; eccPrimeSquared = (eccSquared)/(1-eccSquared); M = y / k0; mu = M/(a*(1-eccSquared/4-3*eccSquared*eccSquared/64 -5*eccSquared*eccSquared*eccSquared/256)); phi1Rad = mu + ((3*e1/2-27*e1*e1*e1/32)*sin(2*mu) + (21*e1*e1/16-55*e1*e1*e1*e1/32)*sin(4*mu) + (151*e1*e1*e1/96)*sin(6*mu)); N1 = a/sqrt(1-eccSquared*sin(phi1Rad)*sin(phi1Rad)); T1 = tan(phi1Rad)*tan(phi1Rad); C1 = eccPrimeSquared*cos(phi1Rad)*cos(phi1Rad); R1 = a*(1-eccSquared)/pow(1-eccSquared*sin(phi1Rad)*sin(phi1Rad), 1.5); D = x/(N1*k0); Lat = phi1Rad - ((N1*tan(phi1Rad)/R1) *(D*D/2 -(5+3*T1+10*C1-4*C1*C1-9*eccPrimeSquared)*D*D*D*D/24 +(61+90*T1+298*C1+45*T1*T1-252*eccPrimeSquared -3*C1*C1)*D*D*D*D*D*D/720)); Lat = Lat * DEGREES_PER_RADIAN; Long = ((D-(1+2*T1+C1)*D*D*D/6 +(5-2*C1+28*T1-3*C1*C1+8*eccPrimeSquared+24*T1*T1) *D*D*D*D*D/120) / cos(phi1Rad)); Long = LongOrigin + Long * DEGREES_PER_RADIAN; } } // namespace NavsatConversions } // namespace RobotLocalization #endif // ROBOT_LOCALIZATION_NAVSAT_CONVERSIONS_H ================================================ FILE: src/robot_localization/include/robot_localization/navsat_transform.h ================================================ /* * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * 1. Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * 2. Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * 3. Neither the name of the copyright holder nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT 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 ROBOT_LOCALIZATION_NAVSAT_TRANSFORM_H #define ROBOT_LOCALIZATION_NAVSAT_TRANSFORM_H #include #include #include #include #include #include #include #include #include #include #include namespace RobotLocalization { class NavSatTransform { public: //! @brief Constructor //! NavSatTransform(); //! @brief Destructor //! ~NavSatTransform(); //! @brief Main run loop //! void run(); private: //! @brief Computes the transform from the UTM frame to the odom frame //! void computeTransform(); //! @brief Callback for the datum service //! bool datumCallback(robot_localization::SetDatum::Request& request, robot_localization::SetDatum::Response&); //! @brief Given the pose of the navsat sensor in the UTM frame, removes the offset from the vehicle's centroid //! and returns the UTM-frame pose of said centroid. //! void getRobotOriginUtmPose(const tf2::Transform &gps_utm_pose, tf2::Transform &robot_utm_pose, const ros::Time &transform_time); //! @brief Given the pose of the navsat sensor in the world frame, removes the offset from the vehicle's centroid //! and returns the world-frame pose of said centroid. //! void getRobotOriginWorldPose(const tf2::Transform &gps_odom_pose, tf2::Transform &robot_odom_pose, const ros::Time &transform_time); //! @brief Callback for the GPS fix data //! @param[in] msg The NavSatFix message to process //! void gpsFixCallback(const sensor_msgs::NavSatFixConstPtr& msg); //! @brief Callback for the IMU data //! @param[in] msg The IMU message to process //! void imuCallback(const sensor_msgs::ImuConstPtr& msg); //! @brief Callback for the odom data //! @param[in] msg The odometry message to process //! void odomCallback(const nav_msgs::OdometryConstPtr& msg); //! @brief Converts the odometry data back to GPS and broadcasts it //! @param[out] filtered_gps The NavSatFix message to prepare //! bool prepareFilteredGps(sensor_msgs::NavSatFix &filtered_gps); //! @brief Prepares the GPS odometry message before sending //! @param[out] gps_odom The odometry message to prepare //! bool prepareGpsOdometry(nav_msgs::Odometry &gps_odom); //! @brief Used for setting the GPS data that will be used to compute the transform //! @param[in] msg The NavSatFix message to use in the transform //! void setTransformGps(const sensor_msgs::NavSatFixConstPtr& msg); //! @brief Used for setting the odometry data that will be used to compute the transform //! @param[in] msg The odometry message to use in the transform //! void setTransformOdometry(const nav_msgs::OdometryConstPtr& msg); //! @brief Frame ID of the robot's body frame //! //! This is needed for obtaining transforms from the robot's body frame to the frames of sensors (IMU and GPS) //! std::string base_link_frame_id_; //! @brief Whether or not we broadcast the UTM transform //! bool broadcast_utm_transform_; //! @brief Whether to broadcast the UTM transform as parent frame, default as child //! bool broadcast_utm_transform_as_parent_frame_; //! @brief The frame_id of the GPS message (specifies mounting location) //! std::string gps_frame_id_; //! @brief Timestamp of the latest good GPS message //! //! We assign this value to the timestamp of the odometry message that we output //! ros::Time gps_update_time_; //! @brief Whether or not we have new GPS data //! //! We only want to compute and broadcast our transformed GPS data if it's new. This variable keeps track of that. //! bool gps_updated_; //! @brief Whether or not the GPS fix is usable //! bool has_transform_gps_; //! @brief Signifies that we have received a usable IMU message //! bool has_transform_imu_; //! @brief Signifies that we have received a usable odometry message //! bool has_transform_odom_; //! @brief Covariance for most recent odometry data //! Eigen::MatrixXd latest_odom_covariance_; //! @brief Covariance for most recent GPS/UTM data //! Eigen::MatrixXd latest_utm_covariance_; //! @brief Latest GPS data, stored as UTM coords //! tf2::Transform latest_utm_pose_; //! @brief Latest odometry pose data //! tf2::Transform latest_world_pose_; //! @brief Parameter that specifies the magnetic declination for the robot's environment. //! double magnetic_declination_; //! @brief Timestamp of the latest good odometry message //! //! We assign this value to the timestamp of the odometry message that we output //! ros::Time odom_update_time_; //! @brief Whether or not we have new odometry data //! //! If we're creating filtered GPS messages, then we only want to broadcast them when new odometry data arrives. //! bool odom_updated_; //! @brief Whether or not we publish filtered GPS messages //! bool publish_gps_; //! @brief Transform buffer for managing coordinate transforms //! tf2_ros::Buffer tf_buffer_; //! @brief Transform listener for receiving transforms //! tf2_ros::TransformListener tf_listener_; //! @brief Whether or not we've computed a good heading //! bool transform_good_; //! @brief Latest IMU orientation //! tf2::Quaternion transform_orientation_; //! @brief Holds the UTM pose that is used to compute the transform //! tf2::Transform transform_utm_pose_; //! @brief Latest IMU orientation //! tf2::Transform transform_world_pose_; //! @brief Whether we get our datum from the first GPS message or from the set_datum //! service/parameter //! bool use_manual_datum_; //! @brief Whether we get the transform's yaw from the odometry or IMU source //! bool use_odometry_yaw_; //! @brief Used for publishing the static world_frame->utm transform //! tf2_ros::StaticTransformBroadcaster utm_broadcaster_; //! @brief Stores the yaw we need to compute the transform //! double utm_odom_tf_yaw_; //! @brief Holds the UTM->odom transform //! tf2::Transform utm_world_transform_; //! @brief Holds the odom->UTM transform for filtered GPS broadcast //! tf2::Transform utm_world_trans_inverse_; //! @brief UTM zone as determined after transforming GPS message //! std::string utm_zone_; //! @brief Frame ID of the GPS odometry output //! //! This will just match whatever your odometry message has //! std::string world_frame_id_; //! @brief IMU's yaw offset //! //! Your IMU should read 0 when facing *magnetic* north. If it doesn't, this (parameterized) value gives the offset //! (NOTE: if you have a magenetic declination, use the parameter setting for that). //! double yaw_offset_; //! @brief Parameter that specifies the how long we wait for a transform to become available. //! ros::Duration transform_timeout_; //! @brief Whether or not to report 0 altitude //! //! If this parameter is true, we always report 0 for the altitude of the converted GPS odometry message. //! bool zero_altitude_; }; } // namespace RobotLocalization #endif // ROBOT_LOCALIZATION_NAVSAT_TRANSFORM_H ================================================ FILE: src/robot_localization/include/robot_localization/robot_localization_estimator.h ================================================ /* * Copyright (c) 2016, TNO IVS Helmond. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * 1. Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * 2. Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * 3. Neither the name of the copyright holder nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT 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 ROBOT_LOCALIZATION_ROBOT_LOCALIZATION_ESTIMATOR_H #define ROBOT_LOCALIZATION_ROBOT_LOCALIZATION_ESTIMATOR_H #include #include #include #include #include "robot_localization/filter_base.h" #include "robot_localization/filter_utilities.h" #include "robot_localization/filter_common.h" namespace RobotLocalization { struct Twist { Eigen::Vector3d linear; Eigen::Vector3d angular; }; //! @brief Robot Localization Estimator State //! //! The Estimator State data structure bundles the state information of the estimator. //! struct EstimatorState { EstimatorState(): time_stamp(0.0), state(STATE_SIZE), covariance(STATE_SIZE, STATE_SIZE) { state.setZero(); covariance.setZero(); } //! @brief Time at which this state is/was achieved double time_stamp; //! @brief System state at time = time_stamp Eigen::VectorXd state; //! @brief System state covariance at time = time_stamp Eigen::MatrixXd covariance; friend std::ostream& operator<<(std::ostream &os, const EstimatorState& state) { return os << "state:\n - time_stamp: " << state.time_stamp << "\n - state: \n" << state.state << " - covariance: \n" << state.covariance; } }; namespace EstimatorResults { enum EstimatorResult { ExtrapolationIntoFuture = 0, Interpolation, ExtrapolationIntoPast, Exact, EmptyBuffer, Failed }; } // namespace EstimatorResults typedef EstimatorResults::EstimatorResult EstimatorResult; namespace FilterTypes { enum FilterType { EKF = 0, UKF, NotDefined }; } // namespace FilterTypes typedef FilterTypes::FilterType FilterType; //! @brief Robot Localization Listener class //! //! The Robot Localization Estimator class buffers states of and inputs to a system and can interpolate and extrapolate //! based on a given system model. //! class RobotLocalizationEstimator { public: //! @brief Constructor for the RobotLocalizationListener class //! //! @param[in] args - Generic argument container (not used here, but needed so that the ROS filters can pass arbitrary //! arguments to templated filter types). //! explicit RobotLocalizationEstimator(unsigned int buffer_capacity, FilterType filter_type, const Eigen::MatrixXd& process_noise_covariance, const std::vector& filter_args = std::vector()); //! @brief Destructor for the RobotLocalizationListener class //! virtual ~RobotLocalizationEstimator(); //! @brief Sets the current internal state of the listener. //! //! @param[in] state - The new state vector to set the internal state to //! void setState(const EstimatorState& state); //! @brief Returns the state at a given time //! //! Projects the current state and error matrices forward using a model of the robot's motion. //! //! @param[in] time - The time to which the prediction is being made //! @param[out] state - The returned state at the given time //! //! @return GetStateResult enum //! EstimatorResult getState(const double time, EstimatorState &state) const; //! @brief Clears the internal state buffer //! void clearBuffer(); //! @brief Sets the buffer capacity //! //! @param[in] capacity - The new buffer capacity //! void setBufferCapacity(const int capacity); //! @brief Returns the buffer capacity //! //! Returns the number of EstimatorState objects that can be pushed to the buffer before old ones are dropped. (The //! capacity of the buffer). //! //! @return buffer capacity //! unsigned int getBufferCapacity() const; //! @brief Returns the current buffer size //! //! Returns the number of EstimatorState objects currently in the buffer. //! //! @return current buffer size //! unsigned int getSize() const; private: friend std::ostream& operator<<(std::ostream &os, const RobotLocalizationEstimator& rle) { for ( boost::circular_buffer::const_iterator it = rle.state_buffer_.begin(); it != rle.state_buffer_.end(); ++it ) { os << *it << "\n"; } return os; } //! @brief Extrapolates the given state to a requested time stamp //! //! @param[in] boundary_state - state from which to extrapolate //! @param[in] requested_time - time stamp to extrapolate to //! @param[out] state_at_req_time - predicted state at requested time //! void extrapolate(const EstimatorState& boundary_state, const double requested_time, EstimatorState& state_at_req_time) const; //! @brief Interpolates the given state to a requested time stamp //! //! @param[in] given_state_1 - last state update before requested time //! @param[in] given_state_2 - next state update after requested time //! @param[in] requested_time - time stamp to extrapolate to //! @param[out] state_at_req_time - predicted state at requested time //! void interpolate(const EstimatorState& given_state_1, const EstimatorState& given_state_2, const double requested_time, EstimatorState& state_at_req_time) const; //! //! @brief The buffer holding the system states that have come in. Interpolation and extrapolation is done starting //! from these states. //! boost::circular_buffer state_buffer_; //! //! @brief A pointer to the filter instance that is used for extrapolation //! FilterBase* filter_; }; } // namespace RobotLocalization #endif // ROBOT_LOCALIZATION_ROBOT_LOCALIZATION_ESTIMATOR_H ================================================ FILE: src/robot_localization/include/robot_localization/ros_filter.h ================================================ /* * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * 1. Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * 2. Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * 3. Neither the name of the copyright holder nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT 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 ROBOT_LOCALIZATION_ROS_FILTER_H #define ROBOT_LOCALIZATION_ROS_FILTER_H #include "robot_localization/ros_filter_utilities.h" #include "robot_localization/filter_common.h" #include "robot_localization/filter_base.h" #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include namespace RobotLocalization { struct CallbackData { CallbackData(const std::string &topicName, const std::vector &updateVector, const int updateSum, const bool differential, const bool relative, const double rejectionThreshold) : topicName_(topicName), updateVector_(updateVector), updateSum_(updateSum), differential_(differential), relative_(relative), rejectionThreshold_(rejectionThreshold) { } std::string topicName_; std::vector updateVector_; int updateSum_; bool differential_; bool relative_; double rejectionThreshold_; }; typedef std::priority_queue, Measurement> MeasurementQueue; typedef std::deque MeasurementHistoryDeque; typedef std::deque FilterStateHistoryDeque; template class RosFilter { public: //! @brief Constructor //! //! The RosFilter constructor makes sure that anyone using //! this template is doing so with the correct object type //! explicit RosFilter(std::vector args = std::vector()); //! @brief Destructor //! //! Clears out the message filters and topic subscribers. //! ~RosFilter(); //! @brief Resets the filter to its initial state //! void reset(); //! @brief Callback method for receiving all acceleration (IMU) messages //! @param[in] msg - The ROS IMU message to take in. //! @param[in] callbackData - Relevant static callback data //! @param[in] targetFrame - The target frame_id into which to transform the data //! void accelerationCallback(const sensor_msgs::Imu::ConstPtr &msg, const CallbackData &callbackData, const std::string &targetFrame); //! @brief Callback method for receiving non-stamped control input //! @param[in] msg - The ROS twist message to take in //! void controlCallback(const geometry_msgs::Twist::ConstPtr &msg); //! @brief Callback method for receiving stamped control input //! @param[in] msg - The ROS stamped twist message to take in //! void controlCallback(const geometry_msgs::TwistStamped::ConstPtr &msg); //! @brief Adds a measurement to the queue of measurements to be processed //! //! @param[in] topicName - The name of the measurement source (only used for debugging) //! @param[in] measurement - The measurement to enqueue //! @param[in] measurementCovariance - The covariance of the measurement //! @param[in] updateVector - The boolean vector that specifies which variables to update from this measurement //! @param[in] mahalanobisThresh - Threshold, expressed as a Mahalanobis distance, for outlier rejection //! @param[in] time - The time of arrival (in seconds) //! void enqueueMeasurement(const std::string &topicName, const Eigen::VectorXd &measurement, const Eigen::MatrixXd &measurementCovariance, const std::vector &updateVector, const double mahalanobisThresh, const ros::Time &time); //! @brief Method for zeroing out 3D variables within measurements //! @param[out] measurement - The measurement whose 3D variables will be zeroed out //! @param[out] measurementCovariance - The covariance of the measurement //! @param[out] updateVector - The boolean update vector of the measurement //! //! If we're in 2D mode, then for every measurement from every sensor, we call this. //! It sets the 3D variables to 0, gives those variables tiny variances, and sets //! their updateVector values to 1. //! void forceTwoD(Eigen::VectorXd &measurement, Eigen::MatrixXd &measurementCovariance, std::vector &updateVector); //! @brief Retrieves the EKF's output for broadcasting //! @param[out] message - The standard ROS odometry message to be filled //! @return true if the filter is initialized, false otherwise //! bool getFilteredOdometryMessage(nav_msgs::Odometry &message); //! @brief Retrieves the EKF's acceleration output for broadcasting //! @param[out] message - The standard ROS acceleration message to be filled //! @return true if the filter is initialized, false otherwise //! bool getFilteredAccelMessage(geometry_msgs::AccelWithCovarianceStamped &message); //! @brief Callback method for receiving all IMU messages //! @param[in] msg - The ROS IMU message to take in. //! @param[in] topicName - The topic name for the IMU message (only used for debug output) //! @param[in] poseCallbackData - Relevant static callback data for orientation variables //! @param[in] twistCallbackData - Relevant static callback data for angular velocity variables //! @param[in] accelCallbackData - Relevant static callback data for linear acceleration variables //! //! This method separates out the orientation, angular velocity, and linear acceleration data and //! passed each on to its respective callback. //! void imuCallback(const sensor_msgs::Imu::ConstPtr &msg, const std::string &topicName, const CallbackData &poseCallbackData, const CallbackData &twistCallbackData, const CallbackData &accelCallbackData); //! @brief Processes all measurements in the measurement queue, in temporal order //! //! @param[in] currentTime - The time at which to carry out integration (the current time) //! void integrateMeasurements(const ros::Time ¤tTime); //! @brief Loads all parameters from file //! void loadParams(); //! @brief Callback method for receiving all odometry messages //! @param[in] msg - The ROS odometry message to take in. //! @param[in] topicName - The topic name for the odometry message (only used for debug output) //! @param[in] poseCallbackData - Relevant static callback data for pose variables //! @param[in] twistCallbackData - Relevant static callback data for twist variables //! //! This method simply separates out the pose and twist data into two new messages, and passes them into their //! respective callbacks //! void odometryCallback(const nav_msgs::Odometry::ConstPtr &msg, const std::string &topicName, const CallbackData &poseCallbackData, const CallbackData &twistCallbackData); //! @brief Callback method for receiving all pose messages //! @param[in] msg - The ROS stamped pose with covariance message to take in //! @param[in] callbackData - Relevant static callback data //! @param[in] targetFrame - The target frame_id into which to transform the data //! @param[in] imuData - Whether this data comes from an IMU //! void poseCallback(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &msg, const CallbackData &callbackData, const std::string &targetFrame, const bool imuData); //! @brief Main run method //! void run(); //! @brief Callback method for manually setting/resetting the internal pose estimate //! @param[in] msg - The ROS stamped pose with covariance message to take in //! void setPoseCallback(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &msg); //! @brief Service callback for manually setting/resetting the internal pose estimate //! //! @param[in] request - Custom service request with pose information //! @return true if successful, false if not bool setPoseSrvCallback(robot_localization::SetPose::Request& request, robot_localization::SetPose::Response&); //! @brief Service callback for manually enable the filter //! @param[in] request - N/A //! @param[out] response - N/A //! @return boolean true if successful, false if not bool enableFilterSrvCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&); //! @brief Callback method for receiving all twist messages //! @param[in] msg - The ROS stamped twist with covariance message to take in. //! @param[in] callbackData - Relevant static callback data //! @param[in] targetFrame - The target frame_id into which to transform the data //! void twistCallback(const geometry_msgs::TwistWithCovarianceStamped::ConstPtr &msg, const CallbackData &callbackData, const std::string &targetFrame); //! @brief Validates filter outputs for NaNs and Infinite values //! @param[out] message - The standard ROS odometry message to be validated //! @return true if the filter output is valid, false otherwise //! bool validateFilterOutput(const nav_msgs::Odometry &message); protected: //! @brief Finds the latest filter state before the given timestamp and makes it the current state again. //! //! This method also inserts all measurements between the older filter timestamp and now into the measurements //! queue. //! //! @param[in] time - The time to which the filter state should revert //! @return True if restoring the filter succeeded. False if not. //! bool revertTo(const double time); //! @brief Saves the current filter state in the queue of previous filter states //! //! These measurements will be used in backwards smoothing in the event that older measurements come in. //! @param[in] filter - The filter base object whose state we want to save //! void saveFilterState(FilterBase &filter); //! @brief Removes measurements and filter states older than the given cutoff time. //! @param[in] cutoffTime - Measurements and states older than this time will be dropped. //! void clearExpiredHistory(const double cutoffTime); //! @brief Adds a diagnostic message to the accumulating map and updates the error level //! @param[in] errLevel - The error level of the diagnostic //! @param[in] topicAndClass - The sensor topic (if relevant) and class of diagnostic //! @param[in] message - Details of the diagnostic //! @param[in] staticDiag - Whether or not this diagnostic information is static //! void addDiagnostic(const int errLevel, const std::string &topicAndClass, const std::string &message, const bool staticDiag); //! @brief Aggregates all diagnostics so they can be published //! @param[in] wrapper - The diagnostic status wrapper to update //! void aggregateDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &wrapper); //! @brief Utility method for copying covariances from ROS covariance arrays //! to Eigen matrices //! //! This method copies the covariances and also does some data validation, which is //! why it requires more parameters than just the covariance containers. //! @param[in] arr - The source array for the covariance data //! @param[in] covariance - The destination matrix for the covariance data //! @param[in] topicName - The name of the source data topic (for debug purposes) //! @param[in] updateVector - The update vector for the source topic //! @param[in] offset - The "starting" location within the array/update vector //! @param[in] dimension - The number of values to copy, starting at the offset //! void copyCovariance(const double *arr, Eigen::MatrixXd &covariance, const std::string &topicName, const std::vector &updateVector, const size_t offset, const size_t dimension); //! @brief Utility method for copying covariances from Eigen matrices to ROS //! covariance arrays //! //! @param[in] covariance - The source matrix for the covariance data //! @param[in] arr - The destination array //! @param[in] dimension - The number of values to copy //! void copyCovariance(const Eigen::MatrixXd &covariance, double *arr, const size_t dimension); //! @brief Loads fusion settings from the config file //! @param[in] topicName - The name of the topic for which to load settings //! @return The boolean vector of update settings for each variable for this topic //! std::vector loadUpdateConfig(const std::string &topicName); //! @brief Prepares an IMU message's linear acceleration for integration into the filter //! @param[in] msg - The IMU message to prepare //! @param[in] topicName - The name of the topic over which this message was received //! @param[in] targetFrame - The target tf frame //! @param[in] updateVector - The update vector for the data source //! @param[in] measurement - The twist data converted to a measurement //! @param[in] measurementCovariance - The covariance of the converted measurement //! bool prepareAcceleration(const sensor_msgs::Imu::ConstPtr &msg, const std::string &topicName, const std::string &targetFrame, std::vector &updateVector, Eigen::VectorXd &measurement, Eigen::MatrixXd &measurementCovariance); //! @brief Prepares a pose message for integration into the filter //! @param[in] msg - The pose message to prepare //! @param[in] topicName - The name of the topic over which this message was received //! @param[in] targetFrame - The target tf frame //! @param[in] differential - Whether we're carrying out differential integration //! @param[in] relative - Whether this measurement is processed relative to the first //! @param[in] imuData - Whether this measurement is from an IMU //! @param[in,out] updateVector - The update vector for the data source //! @param[out] measurement - The pose data converted to a measurement //! @param[out] measurementCovariance - The covariance of the converted measurement //! @return true indicates that the measurement was successfully prepared, false otherwise //! bool preparePose(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &msg, const std::string &topicName, const std::string &targetFrame, const bool differential, const bool relative, const bool imuData, std::vector &updateVector, Eigen::VectorXd &measurement, Eigen::MatrixXd &measurementCovariance); //! @brief Prepares a twist message for integration into the filter //! @param[in] msg - The twist message to prepare //! @param[in] topicName - The name of the topic over which this message was received //! @param[in] targetFrame - The target tf frame //! @param[in,out] updateVector - The update vector for the data source //! @param[out] measurement - The twist data converted to a measurement //! @param[out] measurementCovariance - The covariance of the converted measurement //! @return true indicates that the measurement was successfully prepared, false otherwise //! bool prepareTwist(const geometry_msgs::TwistWithCovarianceStamped::ConstPtr &msg, const std::string &topicName, const std::string &targetFrame, std::vector &updateVector, Eigen::VectorXd &measurement, Eigen::MatrixXd &measurementCovariance); //! @brief tf frame name for the robot's body frame //! std::string baseLinkFrameId_; //! @brief Subscribes to the control input topic //! ros::Subscriber controlSub_; //! @brief This object accumulates static diagnostics, e.g., diagnostics relating //! to the configuration parameters. //! //! The values are treated as static and always reported (i.e., this object is never cleared) //! std::map staticDiagnostics_; //! @brief This object accumulates dynamic diagnostics, e.g., diagnostics relating //! to sensor data. //! //! The values are considered transient and are cleared at every iteration. //! std::map dynamicDiagnostics_; //! @brief Used for outputting debug messages //! std::ofstream debugStream_; //! @brief The max (worst) dynamic diagnostic level. //! int dynamicDiagErrorLevel_; //! @brief Used for updating the diagnostics //! diagnostic_updater::Updater diagnosticUpdater_; //! @brief Our filter (EKF, UKF, etc.) //! T filter_; //! @brief The frequency of the run loop //! double frequency_; //! @brief The depth of the history we track for smoothing/delayed measurement processing //! //! This is the guaranteed minimum buffer size for which previous states and measurements are kept. //! double historyLength_; //! @brief Whether to reset the filters when backwards jump in time is detected //! //! This is usually the case when logs are being used and a jump in the logi //! is done or if a log files restarts from the beginning. //! bool resetOnTimeJump_; //! @brief The most recent control input //! Eigen::VectorXd latestControl_; //! @brief The time of the most recent control input //! ros::Time latestControlTime_; //! @brief Parameter that specifies the how long we wait for a transform to become available. //! ros::Duration tfTimeout_; //! @brief Vector to hold our subscribers until they go out of scope //! std::vector topicSubs_; //! @brief Stores the first measurement from each topic for relative measurements //! //! When a given sensor is being integrated in relative mode, its first measurement //! is effectively treated as an offset, and future measurements have this first //! measurement removed before they are fused. This variable stores the initial //! measurements. Note that this is different from using differential mode, as in //! differential mode, pose data is converted to twist data, resulting in boundless //! error growth for the variables being fused. With relative measurements, the //! vehicle will start with a 0 heading and position, but the measurements are still //! fused absolutely. std::map initialMeasurements_; //! @brief Store the last time a message from each topic was received //! //! If we're getting messages rapidly, we may accidentally get //! an older message arriving after a newer one. This variable keeps //! track of the most recent message time for each subscribed message //! topic. We also use it when listening to odometry messages to //! determine if we should be using messages from that topic. //! std::map lastMessageTimes_; //! @brief Store the last time set pose message was received //! //! If we receive a setPose message to reset the filter, we can get in //! strange situations wherein we process the pose reset, but then even //! after another spin cycle or two, we can get a new message with a time //! stamp that is *older* than the setPose message's time stamp. This means //! we have to check the message's time stamp against the lastSetPoseTime_. ros::Time lastSetPoseTime_; //! @brief tf frame name for the robot's map (world-fixed) frame //! std::string mapFrameId_; //! @brief We process measurements by queueing them up in //! callbacks and processing them all at once within each //! iteration //! MeasurementQueue measurementQueue_; //! @brief Node handle //! ros::NodeHandle nh_; //! @brief Local node handle (for params) //! ros::NodeHandle nhLocal_; //! @brief tf frame name for the robot's odometry (world-fixed) frame //! std::string odomFrameId_; //! @brief Stores the last measurement from a given topic for differential integration //! //! To carry out differential integration, we have to (1) transform //! that into the target frame (probably the frame specified by //! @p odomFrameId_), (2) "subtract" the previous measurement from //! the current measurement, and then (3) transform it again by the previous //! state estimate. This holds the measurements used for step (2). //! std::map previousMeasurements_; //! @brief We also need the previous covariance matrix for differential data //! std::map previousMeasurementCovariances_; //! @brief By default, the filter predicts and corrects up to the time of the latest measurement. If this is set //! to true, the filter does the same, but then also predicts up to the current time step. //! bool predictToCurrentTime_; //! @brief Whether or not we print diagnostic messages to the /diagnostics topic //! bool printDiagnostics_; //! @brief If including acceleration for each IMU input, whether or not we remove acceleration due to gravity //! std::map removeGravitationalAcc_; //! @brief What is the acceleration in Z due to gravity (m/s^2)? Default is +9.80665. //! double gravitationalAcc_; //! @brief Subscribes to the set_pose topic (usually published from rviz). Message //! type is geometry_msgs/PoseWithCovarianceStamped. //! ros::Subscriber setPoseSub_; //! @brief Service that allows another node to change the current state and recieve a confirmation. Uses //! a custom SetPose service. //! ros::ServiceServer setPoseSrv_; //! @brief Whether or not we use smoothing //! bool smoothLaggedData_; //! @brief Service that allows another node to enable the filter. Uses a standard Empty service. //! ros::ServiceServer enableFilterSrv_; //! @brief Contains the state vector variable names in string format //! std::vector stateVariableNames_; //! @brief The max (worst) static diagnostic level. //! int staticDiagErrorLevel_; //! @brief Transform buffer for managing coordinate transforms //! tf2_ros::Buffer tfBuffer_; //! @brief Transform listener for receiving transforms //! tf2_ros::TransformListener tfListener_; //! @brief For future (or past) dating the world_frame->base_link_frame transform //! ros::Duration tfTimeOffset_; //! @brief Whether or not we're in 2D mode //! //! If this is true, the filter binds all 3D variables (Z, //! roll, pitch, and their respective velocities) to 0 for //! every measurement. //! bool twoDMode_; //! @brief Whether or not we use a control term //! bool useControl_; //! @brief Start the Filter disabled at startup //! //! If this is true, the filter reads parameters and prepares publishers and subscribes //! but does not integrate new messages into the state vector. //! The filter can be enabled later using a service. bool disabledAtStartup_; //! @brief Whether the filter is enabled or not. See disabledAtStartup_. bool enabled_; //! @brief Message that contains our latest transform (i.e., state) //! //! We use the vehicle's latest state in a number of places, and often //! use it as a transform, so this is the most convenient variable to //! use as our global "current state" object //! geometry_msgs::TransformStamped worldBaseLinkTransMsg_; //! @brief tf frame name that is the parent frame of the transform that this node will calculate and broadcast. //! std::string worldFrameId_; //! @brief Whether we publish the transform from the world_frame to the base_link_frame //! bool publishTransform_; //! @brief Whether we publish the acceleration //! bool publishAcceleration_; //! @brief An implicitly time ordered queue of past filter states used for smoothing. // // front() refers to the filter state with the earliest timestamp. // back() refers to the filter state with the latest timestamp. FilterStateHistoryDeque filterStateHistory_; //! @brief A deque of previous measurements which is implicitly ordered from earliest to latest measurement. // when popped from the measurement priority queue. // front() refers to the measurement with the earliest timestamp. // back() refers to the measurement with the latest timestamp. MeasurementHistoryDeque measurementHistory_; }; } // namespace RobotLocalization #endif // ROBOT_LOCALIZATION_ROS_FILTER_H ================================================ FILE: src/robot_localization/include/robot_localization/ros_filter_types.h ================================================ /* * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * 1. Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * 2. Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * 3. Neither the name of the copyright holder nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT 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 ROBOT_LOCALIZATION_ROS_FILTER_TYPES_H #define ROBOT_LOCALIZATION_ROS_FILTER_TYPES_H #include "robot_localization/ros_filter.h" #include "robot_localization/ekf.h" #include "robot_localization/ukf.h" namespace RobotLocalization { typedef RosFilter RosEkf; typedef RosFilter RosUkf; } #endif // ROBOT_LOCALIZATION_ROS_FILTER_TYPES_H ================================================ FILE: src/robot_localization/include/robot_localization/ros_filter_utilities.h ================================================ /* * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * 1. Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * 2. Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * 3. Neither the name of the copyright holder nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT 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 ROBOT_LOCALIZATION_ROS_FILTER_UTILITIES_H #define ROBOT_LOCALIZATION_ROS_FILTER_UTILITIES_H #include #include #include #include #include #include #include #include #define RF_DEBUG(msg) if (filter_.getDebug()) { debugStream_ << msg; } // Handy methods for debug output std::ostream& operator<<(std::ostream& os, const tf2::Vector3 &vec); std::ostream& operator<<(std::ostream& os, const tf2::Quaternion &quat); std::ostream& operator<<(std::ostream& os, const tf2::Transform &trans); std::ostream& operator<<(std::ostream& os, const std::vector &vec); namespace RobotLocalization { namespace RosFilterUtilities { double getYaw(const tf2::Quaternion quat); //! @brief Method for safely obtaining transforms. //! @param[in] buffer - tf buffer object to use for looking up the transform //! @param[in] targetFrame - The target frame of the desired transform //! @param[in] sourceFrame - The source frame of the desired transform //! @param[in] time - The time at which we want the transform //! @param[in] timeout - How long to block before falling back to last transform //! @param[out] targetFrameTrans - The resulting transform object //! @param[in] silent - Whether or not to print transform warnings //! @return Sets the value of @p targetFrameTrans and returns true if successful, //! false otherwise. //! //! This method attempts to obtain a transform from the @p sourceFrame to the @p //! targetFrame at the specific @p time. If no transform is available at that time, //! it attempts to simply obtain the latest transform. If that still fails, then the //! method checks to see if the transform is going from a given frame_id to itself. //! If any of these checks succeed, the method sets the value of @p targetFrameTrans //! and returns true, otherwise it returns false. //! bool lookupTransformSafe(const tf2_ros::Buffer &buffer, const std::string &targetFrame, const std::string &sourceFrame, const ros::Time &time, const ros::Duration &timeout, tf2::Transform &targetFrameTrans, const bool silent = false); //! @brief Method for safely obtaining transforms. //! @param[in] buffer - tf buffer object to use for looking up the transform //! @param[in] targetFrame - The target frame of the desired transform //! @param[in] sourceFrame - The source frame of the desired transform //! @param[in] time - The time at which we want the transform //! @param[out] targetFrameTrans - The resulting transform object //! @param[in] silent - Whether or not to print transform warnings //! @return Sets the value of @p targetFrameTrans and returns true if successful, //! false otherwise. //! //! This method attempts to obtain a transform from the @p sourceFrame to the @p //! targetFrame at the specific @p time. If no transform is available at that time, //! it attempts to simply obtain the latest transform. If that still fails, then the //! method checks to see if the transform is going from a given frame_id to itself. //! If any of these checks succeed, the method sets the value of @p targetFrameTrans //! and returns true, otherwise it returns false. //! bool lookupTransformSafe(const tf2_ros::Buffer &buffer, const std::string &targetFrame, const std::string &sourceFrame, const ros::Time &time, tf2::Transform &targetFrameTrans, const bool silent = false); //! @brief Utility method for converting quaternion to RPY //! @param[in] quat - The quaternion to convert //! @param[out] roll - The converted roll //! @param[out] pitch - The converted pitch //! @param[out] yaw - The converted yaw //! void quatToRPY(const tf2::Quaternion &quat, double &roll, double &pitch, double &yaw); //! @brief Converts our Eigen state vector into a TF transform/pose //! @param[in] state - The state to convert //! @param[out] stateTF - The converted state //! void stateToTF(const Eigen::VectorXd &state, tf2::Transform &stateTF); //! @brief Converts a TF transform/pose into our Eigen state vector //! @param[in] stateTF - The state to convert //! @param[out] state - The converted state //! void TFtoState(const tf2::Transform &stateTF, Eigen::VectorXd &state); } // namespace RosFilterUtilities } // namespace RobotLocalization #endif // ROBOT_LOCALIZATION_ROS_FILTER_UTILITIES_H ================================================ FILE: src/robot_localization/include/robot_localization/ros_robot_localization_listener.h ================================================ /* * Copyright (c) 2016, TNO IVS Helmond. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * 1. Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * 2. Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * 3. Neither the name of the copyright holder nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT 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 ROBOT_LOCALIZATION_ROS_ROBOT_LOCALIZATION_LISTENER_H #define ROBOT_LOCALIZATION_ROS_ROBOT_LOCALIZATION_LISTENER_H #include "robot_localization/robot_localization_estimator.h" #include #include #include #include #include #include #include namespace RobotLocalization { //! @brief RosRobotLocalizationListener class //! //! This class wraps the RobotLocalizationEstimator. It listens to topics over which the (filtered) robot state is //! published (odom and accel) and pushes them into its instance of the RobotLocalizationEstimator. It exposes a //! getState method to offer the user the estimated state at a requested time. This class offers the option to run this //! listener without the need to run a separate node. If you do wish to run this functionality in a separate node, //! consider the robot localization listener node. //! class RosRobotLocalizationListener { public: //! @brief Constructor //! //! The RosRobotLocalizationListener constructor initializes nodehandles, subscribers, a filter for synchronized //! listening to the topics it subscribes to, and an instance of the RobotLocalizationEstimator. //! explicit RosRobotLocalizationListener(); //! @brief Destructor //! //! Empty destructor //! ~RosRobotLocalizationListener(); //! @brief Get a state from the localization estimator //! //! Requests the predicted state and covariance at a given time from the Robot Localization Estimator. //! //! @param[in] time - time of the requested state //! @param[in] frame_id - frame id of which the state is requested. //! @param[out] state - state at the requested time //! @param[out] covariance - covariance at the requested time //! //! @return false if buffer is empty, true otherwise //! bool getState(const double time, const std::string& frame_id, Eigen::VectorXd& state, Eigen::MatrixXd& covariance, std::string world_frame_id = "") const; //! @brief Get a state from the localization estimator //! //! Overload of getState method for using ros::Time. //! //! @param[in] ros_time - ros time of the requested state //! @param[in] frame_id - frame id of which the state is requested. //! @param[out] state - state at the requested time //! @param[out] covariance - covariance at the requested time //! //! @return false if buffer is empty, true otherwise //! bool getState(const ros::Time& ros_time, const std::string& frame_id, Eigen::VectorXd& state, Eigen::MatrixXd& covariance, const std::string& world_frame_id = "") const; //! //! \brief getBaseFrameId Returns the base frame id of the localization listener //! \return The base frame id //! const std::string& getBaseFrameId() const; //! //! \brief getWorldFrameId Returns the world frame id of the localization listener //! \return The world frame id //! const std::string& getWorldFrameId() const; private: //! @brief Callback for odom and accel //! //! Puts the information from the odom and accel messages in a Robot Localization Estimator state and sets the most //! recent state of the estimator. //! //! @param[in] odometry message //! @param[in] accel message //! void odomAndAccelCallback(const nav_msgs::Odometry& odom, const geometry_msgs::AccelWithCovarianceStamped& accel); //! @brief The core state estimator that facilitates inter- and //! extrapolation between buffered states. //! RobotLocalizationEstimator* estimator_; //! @brief A public handle to the ROS node //! ros::NodeHandle nh_; //! @brief A private handle to the ROS node //! ros::NodeHandle nh_p_; //! @brief Subscriber to the odometry state topic (output of a filter node) //! message_filters::Subscriber odom_sub_; //! @brief Subscriber to the acceleration state topic (output of a filter node) //! message_filters::Subscriber accel_sub_; //! @brief Waits for both an Odometry and an Accel message before calling a single callback function //! message_filters::TimeSynchronizer sync_; //! @brief Child frame id received from the Odometry message //! std::string base_frame_id_; //! @brief Frame id received from the odometry message //! std::string world_frame_id_; //! @brief Tf buffer for looking up transforms //! tf2_ros::Buffer tf_buffer_; //! @brief Transform listener to fill the tf_buffer //! tf2_ros::TransformListener tf_listener_; }; } // namespace RobotLocalization #endif // ROBOT_LOCALIZATION_ROS_ROBOT_LOCALIZATION_LISTENER_H ================================================ FILE: src/robot_localization/include/robot_localization/ukf.h ================================================ /* * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * 1. Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * 2. Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * 3. Neither the name of the copyright holder nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT 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 ROBOT_LOCALIZATION_UKF_H #define ROBOT_LOCALIZATION_UKF_H #include "robot_localization/filter_base.h" #include #include #include #include namespace RobotLocalization { //! @brief Unscented Kalman filter class //! //! Implementation of an unscenter Kalman filter (UKF). This //! class derives from FilterBase and overrides the predict() //! and correct() methods in keeping with the discrete time //! UKF algorithm. The algorithm was derived from the UKF //! Wikipedia article at //! (http://en.wikipedia.org/wiki/Kalman_filter#Unscented_Kalman_filter) //! ...and this paper: //! J. J. LaViola, Jr., “A comparison of unscented and extended Kalman //! filtering for estimating quaternion motion,” in Proc. American Control //! Conf., Denver, CO, June 4–6, 2003, pp. 2435–2440 //! Obtained here: http://www.cs.ucf.edu/~jjl/pubs/laviola_acc2003.pdf //! class Ukf: public FilterBase { public: //! @brief Constructor for the Ukf class //! //! @param[in] args - Generic argument container. It is assumed //! that args[0] constains the alpha parameter, args[1] contains //! the kappa parameter, and args[2] contains the beta parameter. //! explicit Ukf(std::vector args); //! @brief Destructor for the Ukf class //! ~Ukf(); //! @brief Carries out the correct step in the predict/update cycle. //! //! @param[in] measurement - The measurement to fuse with our estimate //! void correct(const Measurement &measurement); //! @brief Carries out the predict step in the predict/update cycle. //! //! Projects the state and error matrices forward using a model of //! the vehicle's motion. //! //! @param[in] referenceTime - The time at which the prediction is being made //! @param[in] delta - The time step over which to predict. //! void predict(const double referenceTime, const double delta); protected: //! @brief The UKF sigma points //! //! Used to sample possible next states during prediction. //! std::vector sigmaPoints_; //! @brief This matrix is used to generate the sigmaPoints_ //! Eigen::MatrixXd weightedCovarSqrt_; //! @brief The weights associated with each sigma point when generating //! a new state //! std::vector stateWeights_; //! @brief The weights associated with each sigma point when calculating //! a predicted estimateErrorCovariance_ //! std::vector covarWeights_; //! @brief Used in weight generation for the sigma points //! double lambda_; //! @brief Used to determine if we need to re-compute the sigma //! points when carrying out multiple corrections //! bool uncorrected_; }; } // namespace RobotLocalization #endif // ROBOT_LOCALIZATION_UKF_H ================================================ FILE: src/robot_localization/launch/dual_ekf_navsat_example.launch ================================================ ================================================ FILE: src/robot_localization/launch/ekf_template.launch ================================================ ================================================ FILE: src/robot_localization/launch/navsat_transform_template.launch ================================================ ================================================ FILE: src/robot_localization/launch/ukf_template.launch ================================================ ================================================ FILE: src/robot_localization/package.xml ================================================ robot_localization 2.4.3 Provides nonlinear state estimation through sensor fusion of an abritrary number of sensors. Tom Moore BSD http://ros.org/wiki/robot_localization Tom Moore catkin cmake_modules diagnostic_msgs diagnostic_updater eigen eigen_conversions geographic_msgs geometry_msgs message_filters nav_msgs roscpp sensor_msgs std_msgs std_srvs tf2 tf2_geometry_msgs tf2_ros xmlrpcpp yaml-cpp message_generation python-catkin-pkg roslint message_runtime rosbag rostest rosunit ================================================ FILE: src/robot_localization/params/dual_ekf_navsat_example.yaml ================================================ # For parameter descriptions, please refer to the template parameter files for each node. ekf_se_odom: frequency: 30 sensor_timeout: 0.1 two_d_mode: false transform_time_offset: 0.0 transform_timeout: 0.0 print_diagnostics: true debug: false map_frame: map odom_frame: odom base_link_frame: base_link world_frame: odom odom0: odometry/wheel odom0_config: [false, false, false, false, false, false, true, true, true, false, false, true, false, false, false] odom0_queue_size: 10 odom0_nodelay: true odom0_differential: false odom0_relative: false imu0: imu/data imu0_config: [false, false, false, true, true, false, false, false, false, true, true, true, true, true, true] imu0_nodelay: false imu0_differential: false imu0_relative: false imu0_queue_size: 10 imu0_remove_gravitational_acceleration: true use_control: false process_noise_covariance: [1e-3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.3] initial_estimate_covariance: [1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0] ekf_se_map: frequency: 30 sensor_timeout: 0.1 two_d_mode: false transform_time_offset: 0.0 transform_timeout: 0.0 print_diagnostics: true debug: false map_frame: map odom_frame: odom base_link_frame: base_link world_frame: map odom0: odometry/wheel odom0_config: [false, false, false, false, false, false, true, true, true, false, false, true, false, false, false] odom0_queue_size: 10 odom0_nodelay: true odom0_differential: false odom0_relative: false odom1: odometry/gps odom1_config: [true, true, false, false, false, false, false, false, false, false, false, false, false, false, false] odom1_queue_size: 10 odom1_nodelay: true odom1_differential: false odom1_relative: false imu0: imu/data imu0_config: [false, false, false, true, true, false, false, false, false, true, true, true, true, true, true] imu0_nodelay: true imu0_differential: false imu0_relative: false imu0_queue_size: 10 imu0_remove_gravitational_acceleration: true use_control: false process_noise_covariance: [1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.3] initial_estimate_covariance: [1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0] navsat_transform: frequency: 30 delay: 3.0 magnetic_declination_radians: 0.0429351 # For lat/long 55.944831, -3.186998 yaw_offset: 1.570796327 # IMU reads 0 facing magnetic north, not east zero_altitude: false broadcast_utm_transform: true publish_filtered_gps: true use_odometry_yaw: false wait_for_datum: false ================================================ FILE: src/robot_localization/params/ekf_template.yaml ================================================ # The frequency, in Hz, at which the filter will output a position estimate. Note that the filter will not begin # computation until it receives at least one message from one of the inputs. It will then run continuously at the # frequency specified here, regardless of whether it receives more measurements. Defaults to 30 if unspecified. frequency: 30 # The period, in seconds, after which we consider a sensor to have timed out. In this event, we carry out a predict # cycle on the EKF without correcting it. This parameter can be thought of as the minimum frequency with which the # filter will generate new output. Defaults to 1 / frequency if not specified. sensor_timeout: 0.1 # ekf_localization_node and ukf_localization_node both use a 3D omnidirectional motion model. If this parameter is # set to true, no 3D information will be used in your state estimate. Use this if you are operating in a planar # environment and want to ignore the effect of small variations in the ground plane that might otherwise be detected # by, for example, an IMU. Defaults to false if unspecified. two_d_mode: false # Use this parameter to provide an offset to the transform generated by ekf_localization_node. This can be used for # future dating the transform, which is required for interaction with some other packages. Defaults to 0.0 if # unspecified. transform_time_offset: 0.0 # Use this parameter to provide specify how long the tf listener should wait for a transform to become available. # Defaults to 0.0 if unspecified. transform_timeout: 0.0 # If you're having trouble, try setting this to true, and then echo the /diagnostics_agg topic to see if the node is # unhappy with any settings or data. print_diagnostics: true # Debug settings. Not for the faint of heart. Outputs a ludicrous amount of information to the file specified by # debug_out_file. I hope you like matrices! Please note that setting this to true will have strongly deleterious # effects on the performance of the node. Defaults to false if unspecified. debug: false # Defaults to "robot_localization_debug.txt" if unspecified. Please specify the full path. debug_out_file: /path/to/debug/file.txt # Whether to broadcast the transformation over the /tf topic. Defaults to true if unspecified. publish_tf: true # Whether to publish the acceleration state. Defaults to false if unspecified. publish_acceleration: false # REP-105 (http://www.ros.org/reps/rep-0105.html) specifies four principal coordinate frames: base_link, odom, map, and # earth. base_link is the coordinate frame that is affixed to the robot. Both odom and map are world-fixed frames. # The robot's position in the odom frame will drift over time, but is accurate in the short term and should be # continuous. The odom frame is therefore the best frame for executing local motion plans. The map frame, like the odom # frame, is a world-fixed coordinate frame, and while it contains the most globally accurate position estimate for your # robot, it is subject to discrete jumps, e.g., due to the fusion of GPS data or a correction from a map-based # localization node. The earth frame is used to relate multiple map frames by giving them a common reference frame. # ekf_localization_node and ukf_localization_node are not concerned with the earth frame. # Here is how to use the following settings: # 1. Set the map_frame, odom_frame, and base_link frames to the appropriate frame names for your system. # 1a. If your system does not have a map_frame, just remove it, and make sure "world_frame" is set to the value of # odom_frame. # 2. If you are fusing continuous position data such as wheel encoder odometry, visual odometry, or IMU data, set # "world_frame" to your odom_frame value. This is the default behavior for robot_localization's state estimation nodes. # 3. If you are fusing global absolute position data that is subject to discrete jumps (e.g., GPS or position updates # from landmark observations) then: # 3a. Set your "world_frame" to your map_frame value # 3b. MAKE SURE something else is generating the odom->base_link transform. Note that this can even be another state # estimation node from robot_localization! However, that instance should *not* fuse the global data. map_frame: map # Defaults to "map" if unspecified odom_frame: odom # Defaults to "odom" if unspecified base_link_frame: base_link # Defaults to "base_link" if unspecified world_frame: odom # Defaults to the value of odom_frame if unspecified # The filter accepts an arbitrary number of inputs from each input message type (nav_msgs/Odometry, # geometry_msgs/PoseWithCovarianceStamped, geometry_msgs/TwistWithCovarianceStamped, # sensor_msgs/Imu). To add an input, simply append the next number in the sequence to its "base" name, e.g., odom0, # odom1, twist0, twist1, imu0, imu1, imu2, etc. The value should be the topic name. These parameters obviously have no # default values, and must be specified. odom0: example/odom # Each sensor reading updates some or all of the filter's state. These options give you greater control over which # values from each measurement are fed to the filter. For example, if you have an odometry message as input, but only # want to use its Z position value, then set the entire vector to false, except for the third entry. The order of the # values is x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. Note that not some message types # do not provide some of the state variables estimated by the filter. For example, a TwistWithCovarianceStamped message # has no pose information, so the first six values would be meaningless in that case. Each vector defaults to all false # if unspecified, effectively making this parameter required for each sensor. odom0_config: [true, true, false, false, false, false, false, false, false, false, false, true, false, false, false] # If you have high-frequency data or are running with a low frequency parameter value, then you may want to increase # the size of the subscription queue so that more measurements are fused. odom0_queue_size: 2 # [ADVANCED] Large messages in ROS can exhibit strange behavior when they arrive at a high frequency. This is a result # of Nagle's algorithm. This option tells the ROS subscriber to use the tcpNoDelay option, which disables Nagle's # algorithm. odom0_nodelay: false # [ADVANCED] When measuring one pose variable with two sensors, a situation can arise in which both sensors under- # report their covariances. This can lead to the filter rapidly jumping back and forth between each measurement as they # arrive. In these cases, it often makes sense to (a) correct the measurement covariances, or (b) if velocity is also # measured by one of the sensors, let one sensor measure pose, and the other velocity. However, doing (a) or (b) isn't # always feasible, and so we expose the differential parameter. When differential mode is enabled, all absolute pose # data is converted to velocity data by differentiating the absolute pose measurements. These velocities are then # integrated as usual. NOTE: this only applies to sensors that provide pose measurements; setting differential to true # for twist measurements has no effect. odom0_differential: false # [ADVANCED] When the node starts, if this parameter is true, then the first measurement is treated as a "zero point" # for all future measurements. While you can achieve the same effect with the differential paremeter, the key # difference is that the relative parameter doesn't cause the measurement to be converted to a velocity before # integrating it. If you simply want your measurements to start at 0 for a given sensor, set this to true. odom0_relative: false # [ADVANCED] If your data is subject to outliers, use these threshold settings, expressed as Mahalanobis distances, to # control how far away from the current vehicle state a sensor measurement is permitted to be. Each defaults to # numeric_limits::max() if unspecified. It is strongly recommended that these parameters be removed if not # required. Data is specified at the level of pose and twist variables, rather than for each variable in isolation. # For messages that have both pose and twist data, the parameter specifies to which part of the message we are applying # the thresholds. odom0_pose_rejection_threshold: 5 odom0_twist_rejection_threshold: 1 # Further input parameter examples odom1: example/another_odom odom1_config: [false, false, true, false, false, false, false, false, false, false, false, true, false, false, false] odom1_differential: false odom1_relative: true odom1_queue_size: 2 odom1_pose_rejection_threshold: 2 odom1_twist_rejection_threshold: 0.2 odom1_nodelay: false pose0: example/pose pose0_config: [true, true, false, false, false, false, false, false, false, false, false, false, false, false, false] pose0_differential: true pose0_relative: false pose0_queue_size: 5 pose0_rejection_threshold: 2 # Note the difference in parameter name pose0_nodelay: false twist0: example/twist twist0_config: [false, false, false, false, false, false, true, true, true, false, false, false, false, false, false] twist0_queue_size: 3 twist0_rejection_threshold: 2 twist0_nodelay: false imu0: example/imu imu0_config: [false, false, false, true, true, true, false, false, false, true, true, true, true, true, true] imu0_nodelay: false imu0_differential: false imu0_relative: true imu0_queue_size: 5 imu0_pose_rejection_threshold: 0.8 # Note the difference in parameter names imu0_twist_rejection_threshold: 0.8 # imu0_linear_acceleration_rejection_threshold: 0.8 # # [ADVANCED] Some IMUs automatically remove acceleration due to gravity, and others don't. If yours doesn't, please set # this to true, and *make sure* your data conforms to REP-103, specifically, that the data is in ENU frame. imu0_remove_gravitational_acceleration: true # [ADVANCED] The EKF and UKF models follow a standard predict/correct cycle. During prediction, if there is no # acceleration reference, the velocity at time t+1 is simply predicted to be the same as the velocity at time t. During # correction, this predicted value is fused with the measured value to produce the new velocity estimate. This can be # problematic, as the final velocity will effectively be a weighted average of the old velocity and the new one. When # this velocity is the integrated into a new pose, the result can be sluggish covergence. This effect is especially # noticeable with LIDAR data during rotations. To get around it, users can try inflating the process_noise_covariance # for the velocity variable in question, or decrease the variance of the variable in question in the measurement # itself. In addition, users can also take advantage of the control command being issued to the robot at the time we # make the prediction. If control is used, it will get converted into an acceleration term, which will be used during # predicition. Note that if an acceleration measurement for the variable in question is available from one of the # inputs, the control term will be ignored. # Whether or not we use the control input during predicition. Defaults to false. use_control: true # Whether the input (assumed to be cmd_vel) is a geometry_msgs/Twist or geometry_msgs/TwistStamped message. Defaults to # false. stamped_control: false # The last issued control command will be used in prediction for this period. Defaults to 0.2. control_timeout: 0.2 # Which velocities are being controlled. Order is vx, vy, vz, vroll, vpitch, vyaw. control_config: [true, false, false, false, false, true] # Places limits on how large the acceleration term will be. Should match your robot's kinematics. acceleration_limits: [1.3, 0.0, 0.0, 0.0, 0.0, 3.4] # Acceleration and deceleration limits are not always the same for robots. deceleration_limits: [1.3, 0.0, 0.0, 0.0, 0.0, 4.5] # If your robot cannot instantaneously reach its acceleration limit, the permitted change can be controlled with these # gains acceleration_gains: [0.8, 0.0, 0.0, 0.0, 0.0, 0.9] # If your robot cannot instantaneously reach its deceleration limit, the permitted change can be controlled with these # gains deceleration_gains: [1.0, 0.0, 0.0, 0.0, 0.0, 1.0] # [ADVANCED] The process noise covariance matrix can be difficult to tune, and can vary for each application, so it is # exposed as a configuration parameter. This matrix represents the noise we add to the total error after each # prediction step. The better the omnidirectional motion model matches your system, the smaller these values can be. # However, if users find that a given variable is slow to converge, one approach is to increase the # process_noise_covariance diagonal value for the variable in question, which will cause the filter's predicted error # to be larger, which will cause the filter to trust the incoming measurement more during correction. The values are # ordered as x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. Defaults to the matrix below if # unspecified. process_noise_covariance: [0.05, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.05, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.06, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.06, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.025, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.025, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.04, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.02, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.015] # [ADVANCED] This represents the initial value for the state estimate error covariance matrix. Setting a diagonal # value (variance) to a large value will result in rapid convergence for initial measurements of the variable in # question. Users should take care not to use large values for variables that will not be measured directly. The values # are ordered as x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. Defaults to the matrix below #if unspecified. initial_estimate_covariance: [1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9] ================================================ FILE: src/robot_localization/params/navsat_transform_template.yaml ================================================ # Frequency of the main run loop frequency: 30 # Delay time, in seconds, before we calculate the transform from the UTM frame to your world frame. This is especially # important if you have use_odometry_yaw set to true. Defaults to 0. delay: 3.0 # PLEASE READ: Like all nodes in robot_localization, this node assumes that your IMU data is reported in the ENU frame. # Many IMUs report data in the NED frame, so you'll want to verify that your data is in the correct frame before using # it. # If your IMU does not account for magnetic declination, enter the value for your location here. If you don't know it, # see http://www.ngdc.noaa.gov/geomag-web/ (make sure to convert the value to radians). This parameter is mandatory. magnetic_declination_radians: 0 # Your IMU's yaw, once the magentic_declination_radians value is added to it, should report 0 when facing east. If it # doesn't, enter the offset here. Defaults to 0. yaw_offset: 0.0 # If this is true, the altitude is set to 0 in the output odometry message. Defaults to false. zero_altitude: false # If this is true, the transform world_frame->utm transform is broadcast for use by other nodes. Defaults to false. broadcast_utm_transform: false # If this is true, the utm->world_frame transform will be published instead of the world_frame->utm transform. # Note that broadcast_utm_transform still has to be enabled. Defaults to false. broadcast_utm_transform_as_parent_frame: false # If this is true, all received odometry data is converted back to a lat/lon and published as a NavSatFix message as # /gps/filtered. Defaults to false. publish_filtered_gps: false # If this is true, the node ignores the IMU data and gets its heading from the odometry source (typically the # /odometry/filtered topic coming from one of robot_localization's state estimation nodes). BE CAREFUL when using this! # The yaw value in your odometry source *must* be world-referenced, e.g., you cannot use your odometry source for yaw # if your yaw data is based purely on integrated velocities. Defaults to false. use_odometry_yaw: false # If true, will retrieve the datum from the 'datum' parameter below, if available. If no 'datum' parameter exists, # navsat_transform_node will wait until the user calls the 'datum' service with the SetDatum service message. wait_for_datum: false # Instead of using the first GPS location and IMU-based heading for the local-frame origin, users can specify the # origin (datum) using this parameter. The fields in the parameter represent latitude and longitude in decimal degrees, # and heading in radians. As navsat_transform_node assumes an ENU standard, a 0 heading corresponds to east. datum: [55.944904, -3.186693, 0.0] ================================================ FILE: src/robot_localization/params/ukf_template.yaml ================================================ # The frequency, in Hz, at which the filter will output a position estimate. Note that the filter will not begin # computation until it receives at least one message from one of the inputs. It will then run continuously at the # frequency specified here, regardless of whether it receives more measurements. Defaults to 30 if unspecified. frequency: 30 # The period, in seconds, after which we consider a sensor to have timed out. In this event, we carry out a predict # cycle on the EKF without correcting it. This parameter can be thought of as the minimum frequency with which the # filter will generate new output. Defaults to 1 / frequency if not specified. sensor_timeout: 0.1 # ekf_localization_node and ukf_localization_node both use a 3D omnidirectional motion model. If this parameter is # set to true, no 3D information will be used in your state estimate. Use this if you are operating in a planar # environment and want to ignore the effect of small variations in the ground plane that might otherwise be detected # by, for example, an IMU. Defaults to false if unspecified. two_d_mode: false # Use this parameter to provide an offset to the transform generated by ekf_localization_node. This can be used for # future dating the transform, which is required for interaction with some other packages. Defaults to 0.0 if # unspecified. transform_time_offset: 0.0 # Use this parameter to provide specify how long the tf listener should wait for a transform to become available. # Defaults to 0.0 if unspecified. transform_timeout: 0.0 # If you're having trouble, try setting this to true, and then echo the /diagnostics_agg topic to see if the node is # unhappy with any settings or data. print_diagnostics: true # Debug settings. Not for the faint of heart. Outputs a ludicrous amount of information to the file specified by # debug_out_file. I hope you like matrices! Please note that setting this to true will have strongly deleterious # effects on the performance of the node. Defaults to false if unspecified. debug: false # Defaults to "robot_localization_debug.txt" if unspecified. Please specify the full path. debug_out_file: /path/to/debug/file.txt # REP-105 (http://www.ros.org/reps/rep-0105.html) specifies four principal coordinate frames: base_link, odom, map, and # earth. base_link is the coordinate frame that is affixed to the robot. Both odom and map are world-fixed frames. # The robot's position in the odom frame will drift over time, but is accurate in the short term and should be # continuous. The odom frame is therefore the best frame for executing local motion plans. The map frame, like the odom # frame, is a world-fixed coordinate frame, and while it contains the most globally accurate position estimate for your # robot, it is subject to discrete jumps, e.g., due to the fusion of GPS data or a correction from a map-based # localization node. The earth frame is used to relate multiple map frames by giving them a common reference frame. # ekf_localization_node and ukf_localization_node are not concerned with the earth frame. # Here is how to use the following settings: # 1. Set the map_frame, odom_frame, and base_link frames to the appropriate frame names for your system. # 1a. If your system does not have a map_frame, just remove it, and make sure "world_frame" is set to the value of # odom_frame. # 2. If you are fusing continuous position data such as wheel encoder odometry, visual odometry, or IMU data, set # "world_frame" to your odom_frame value. This is the default behavior for robot_localization's state estimation nodes. # 3. If you are fusing global absolute position data that is subject to discrete jumps (e.g., GPS or position updates # from landmark observations) then: # 3a. Set your "world_frame" to your map_frame value # 3b. MAKE SURE something else is generating the odom->base_link transform. Note that this can even be another state # estimation node from robot_localization! However, that instance should *not* fuse the global data. map_frame: map # Defaults to "map" if unspecified odom_frame: odom # Defaults to "odom" if unspecified base_link_frame: base_link # Defaults to "base_link" if unspecified world_frame: odom # Defaults to the value of odom_frame if unspecified # The filter accepts an arbitrary number of inputs from each input message type (nav_msgs/Odometry, # geometry_msgs/PoseWithCovarianceStamped, geometry_msgs/TwistWithCovarianceStamped, # sensor_msgs/Imu). To add an input, simply append the next number in the sequence to its "base" name, e.g., odom0, # odom1, twist0, twist1, imu0, imu1, imu2, etc. The value should be the topic name. These parameters obviously have no # default values, and must be specified. odom0: example/odom # Each sensor reading updates some or all of the filter's state. These options give you greater control over which # values from each measurement are fed to the filter. For example, if you have an odometry message as input, but only # want to use its Z position value, then set the entire vector to false, except for the third entry. The order of the # values is x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. Note that not some message types # do not provide some of the state variables estimated by the filter. For example, a TwistWithCovarianceStamped message # has no pose information, so the first six values would be meaningless in that case. Each vector defaults to all false # if unspecified, effectively making this parameter required for each sensor. odom0_config: [true, true, false, false, false, false, false, false, false, false, false, true, false, false, false] # If you have high-frequency data or are running with a low frequency parameter value, then you may want to increase # the size of the subscription queue so that more measurements are fused. odom0_queue_size: 2 # [ADVANCED] Large messages in ROS can exhibit strange behavior when they arrive at a high frequency. This is a result # of Nagle's algorithm. This option tells the ROS subscriber to use the tcpNoDelay option, which disables Nagle's # algorithm. odom0_nodelay: false # [ADVANCED] When measuring one pose variable with two sensors, a situation can arise in which both sensors under- # report their covariances. This can lead to the filter rapidly jumping back and forth between each measurement as they # arrive. In these cases, it often makes sense to (a) correct the measurement covariances, or (b) if velocity is also # measured by one of the sensors, let one sensor measure pose, and the other velocity. However, doing (a) or (b) isn't # always feasible, and so we expose the differential parameter. When differential mode is enabled, all absolute pose # data is converted to velocity data by differentiating the absolute pose measurements. These velocities are then # integrated as usual. NOTE: this only applies to sensors that provide pose measurements; setting differential to true # for twist measurements has no effect. odom0_differential: false # [ADVANCED] When the node starts, if this parameter is true, then the first measurement is treated as a "zero point" # for all future measurements. While you can achieve the same effect with the differential paremeter, the key # difference is that the relative parameter doesn't cause the measurement to be converted to a velocity before # integrating it. If you simply want your measurements to start at 0 for a given sensor, set this to true. odom0_relative: false # [ADVANCED] If your data is subject to outliers, use these threshold settings, expressed as Mahalanobis distances, to # control how far away from the current vehicle state a sensor measurement is permitted to be. Each defaults to # numeric_limits::max() if unspecified. It is strongly recommended that these parameters be removed if not # required. Data is specified at the level of pose and twist variables, rather than for each variable in isolation. # For messages that have both pose and twist data, the parameter specifies to which part of the message we are applying # the thresholds. odom0_pose_rejection_threshold: 5 odom0_twist_rejection_threshold: 1 # Further input parameter examples odom1: example/another_odom odom1_config: [false, false, true, false, false, false, false, false, false, false, false, true, false, false, false] odom1_differential: false odom1_relative: true odom1_queue_size: 2 odom1_pose_rejection_threshold: 2 odom1_twist_rejection_threshold: 0.2 odom1_nodelay: false pose0: example/pose pose0_config: [true, true, false, false, false, false, false, false, false, false, false, false, false, false, false] pose0_differential: true pose0_relative: false pose0_queue_size: 5 pose0_rejection_threshold: 2 # Note the difference in parameter name pose0_nodelay: false twist0: example/twist twist0_config: [false, false, false, false, false, false, true, true, true, false, false, false, false, false, false] twist0_queue_size: 3 twist0_rejection_threshold: 2 twist0_nodelay: false imu0: example/imu imu0_config: [false, false, false, true, true, true, false, false, false, true, true, true, true, true, true] imu0_nodelay: false imu0_differential: false imu0_relative: true imu0_queue_size: 5 imu0_pose_rejection_threshold: 0.8 # Note the difference in parameter names imu0_twist_rejection_threshold: 0.8 # imu0_linear_acceleration_rejection_threshold: 0.8 # # [ADVANCED] Some IMUs automatically remove acceleration due to gravity, and others don't. If yours doesn't, please set # this to true, and *make sure* your data conforms to REP-103, specifically, that the data is in ENU frame. imu0_remove_gravitational_acceleration: true # [ADVANCED] The EKF and UKF models follow a standard predict/correct cycle. During prediction, if there is no # acceleration reference, the velocity at time t+1 is simply predicted to be the same as the velocity at time t. During # correction, this predicted value is fused with the measured value to produce the new velocity estimate. This can be # problematic, as the final velocity will effectively be a weighted average of the old velocity and the new one. When # this velocity is the integrated into a new pose, the result can be sluggish covergence. This effect is especially # noticeable with LIDAR data during rotations. To get around it, users can try inflating the process_noise_covariance # for the velocity variable in question, or decrease the variance of the variable in question in the measurement # itself. In addition, users can also take advantage of the control command being issued to the robot at the time we # make the prediction. If control is used, it will get converted into an acceleration term, which will be used during # predicition. Note that if an acceleration measurement for the variable in question is available from one of the # inputs, the control term will be ignored. # Whether or not we use the control input during predicition. Defaults to false. use_control: true # Whether the input (assumed to be cmd_vel) is a geometry_msgs/Twist or geometry_msgs/TwistStamped message. Defaults to # false. stamped_control: false # The last issued control command will be used in prediction for this period. Defaults to 0.2. control_timeout: 0.2 # Which velocities are being controlled. Order is vx, vy, vz, vroll, vpitch, vyaw. control_config: [true, false, false, false, false, true] # Places limits on how large the acceleration term will be. Should match your robot's kinematics. acceleration_limits: [1.3, 0.0, 0.0, 0.0, 0.0, 3.4] # Acceleration and deceleration limits are not always the same for robots. deceleration_limits: [1.3, 0.0, 0.0, 0.0, 0.0, 4.5] # If your robot cannot instantaneously reach its acceleration limit, the permitted change can be controlled with these # gains acceleration_gains: [0.8, 0.0, 0.0, 0.0, 0.0, 0.9] # If your robot cannot instantaneously reach its deceleration limit, the permitted change can be controlled with these # gains deceleration_gains: [1.0, 0.0, 0.0, 0.0, 0.0, 1.0] # [ADVANCED] The process noise covariance matrix can be difficult to tune, and can vary for each application, so it is # exposed as a configuration parameter. This matrix represents the noise we add to the total error after each # prediction step. The better the omnidirectional motion model matches your system, the smaller these values can be. # However, if users find that a given variable is slow to converge, one approach is to increase the # process_noise_covariance diagonal value for the variable in question, which will cause the filter's predicted error # to be larger, which will cause the filter to trust the incoming measurement more during correction. The values are # ordered as x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. Defaults to the matrix below if # unspecified. process_noise_covariance: [0.05, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.05, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.06, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.06, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.025, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.025, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.04, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.02, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.015] # [ADVANCED] This represents the initial value for the state estimate error covariance matrix. Setting a diagonal # value (variance) to a large value will result in rapid convergence for initial measurements of the variable in # question. Users should take care not to use large values for variables that will not be measured directly. The values # are ordered as x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. Defaults to the matrix below #if unspecified. initial_estimate_covariance: [1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9] # [ADVANCED, UKF ONLY] The alpha and kappa variables control the spread of the sigma points. Unless you are familiar # with UKFs, it's probably a good idea to leave these alone. # Defaults to 0.001 if unspecified. alpha: 0.001 # Defaults to 0 if unspecified. kappa: 0 # [ADVANCED, UKF ONLY] The beta variable relates to the distribution of the state vector. Again, it's probably best to # leave this alone if you're uncertain. Defaults to 2 if unspecified. beta: 2 ================================================ FILE: src/robot_localization/rosdoc.yaml ================================================ - builder: sphinx sphinx_root_dir: doc - builder: doxygen output_dir: api file_patterns: '*.cpp *.h *.dox *.md' exclude_patterns: '*/test/*' ================================================ FILE: src/robot_localization/src/ekf.cpp ================================================ /* * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * 1. Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * 2. Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * 3. Neither the name of the copyright holder nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #include "robot_localization/ekf.h" #include "robot_localization/filter_common.h" #include #include #include #include #include namespace RobotLocalization { Ekf::Ekf(std::vector) : FilterBase() // Must initialize filter base! { } Ekf::~Ekf() { } void Ekf::correct(const Measurement &measurement) { FB_DEBUG("---------------------- Ekf::correct ----------------------\n" << "State is:\n" << state_ << "\n" "Topic is:\n" << measurement.topicName_ << "\n" "Measurement is:\n" << measurement.measurement_ << "\n" "Measurement topic name is:\n" << measurement.topicName_ << "\n\n" "Measurement covariance is:\n" << measurement.covariance_ << "\n"); // We don't want to update everything, so we need to build matrices that only update // the measured parts of our state vector. Throughout prediction and correction, we // attempt to maximize efficiency in Eigen. // First, determine how many state vector values we're updating std::vector updateIndices; for (size_t i = 0; i < measurement.updateVector_.size(); ++i) { if (measurement.updateVector_[i]) { // Handle nan and inf values in measurements if (std::isnan(measurement.measurement_(i))) { FB_DEBUG("Value at index " << i << " was nan. Excluding from update.\n"); } else if (std::isinf(measurement.measurement_(i))) { FB_DEBUG("Value at index " << i << " was inf. Excluding from update.\n"); } else { updateIndices.push_back(i); } } } FB_DEBUG("Update indices are:\n" << updateIndices << "\n"); size_t updateSize = updateIndices.size(); // Now set up the relevant matrices Eigen::VectorXd stateSubset(updateSize); // x (in most literature) Eigen::VectorXd measurementSubset(updateSize); // z Eigen::MatrixXd measurementCovarianceSubset(updateSize, updateSize); // R Eigen::MatrixXd stateToMeasurementSubset(updateSize, state_.rows()); // H Eigen::MatrixXd kalmanGainSubset(state_.rows(), updateSize); // K Eigen::VectorXd innovationSubset(updateSize); // z - Hx stateSubset.setZero(); measurementSubset.setZero(); measurementCovarianceSubset.setZero(); stateToMeasurementSubset.setZero(); kalmanGainSubset.setZero(); innovationSubset.setZero(); // Now build the sub-matrices from the full-sized matrices for (size_t i = 0; i < updateSize; ++i) { measurementSubset(i) = measurement.measurement_(updateIndices[i]); stateSubset(i) = state_(updateIndices[i]); for (size_t j = 0; j < updateSize; ++j) { measurementCovarianceSubset(i, j) = measurement.covariance_(updateIndices[i], updateIndices[j]); } // Handle negative (read: bad) covariances in the measurement. Rather // than exclude the measurement or make up a covariance, just take // the absolute value. if (measurementCovarianceSubset(i, i) < 0) { FB_DEBUG("WARNING: Negative covariance for index " << i << " of measurement (value is" << measurementCovarianceSubset(i, i) << "). Using absolute value...\n"); measurementCovarianceSubset(i, i) = ::fabs(measurementCovarianceSubset(i, i)); } // If the measurement variance for a given variable is very // near 0 (as in e-50 or so) and the variance for that // variable in the covariance matrix is also near zero, then // the Kalman gain computation will blow up. Really, no // measurement can be completely without error, so add a small // amount in that case. if (measurementCovarianceSubset(i, i) < 1e-9) { FB_DEBUG("WARNING: measurement had very small error covariance for index " << updateIndices[i] << ". Adding some noise to maintain filter stability.\n"); measurementCovarianceSubset(i, i) = 1e-9; } } // The state-to-measurement function, h, will now be a measurement_size x full_state_size // matrix, with ones in the (i, i) locations of the values to be updated for (size_t i = 0; i < updateSize; ++i) { stateToMeasurementSubset(i, updateIndices[i]) = 1; } FB_DEBUG("Current state subset is:\n" << stateSubset << "\nMeasurement subset is:\n" << measurementSubset << "\nMeasurement covariance subset is:\n" << measurementCovarianceSubset << "\nState-to-measurement subset is:\n" << stateToMeasurementSubset << "\n"); // (1) Compute the Kalman gain: K = (PH') / (HPH' + R) Eigen::MatrixXd pht = estimateErrorCovariance_ * stateToMeasurementSubset.transpose(); Eigen::MatrixXd hphrInv = (stateToMeasurementSubset * pht + measurementCovarianceSubset).inverse(); kalmanGainSubset.noalias() = pht * hphrInv; innovationSubset = (measurementSubset - stateSubset); // Wrap angles in the innovation for (size_t i = 0; i < updateSize; ++i) { if (updateIndices[i] == StateMemberRoll || updateIndices[i] == StateMemberPitch || updateIndices[i] == StateMemberYaw) { while (innovationSubset(i) < -PI) { innovationSubset(i) += TAU; } while (innovationSubset(i) > PI) { innovationSubset(i) -= TAU; } } } // (2) Check Mahalanobis distance between mapped measurement and state. if (checkMahalanobisThreshold(innovationSubset, hphrInv, measurement.mahalanobisThresh_)) { // (3) Apply the gain to the difference between the state and measurement: x = x + K(z - Hx) state_.noalias() += kalmanGainSubset * innovationSubset; // (4) Update the estimate error covariance using the Joseph form: (I - KH)P(I - KH)' + KRK' Eigen::MatrixXd gainResidual = identity_; gainResidual.noalias() -= kalmanGainSubset * stateToMeasurementSubset; estimateErrorCovariance_ = gainResidual * estimateErrorCovariance_ * gainResidual.transpose(); estimateErrorCovariance_.noalias() += kalmanGainSubset * measurementCovarianceSubset * kalmanGainSubset.transpose(); // Handle wrapping of angles wrapStateAngles(); FB_DEBUG("Kalman gain subset is:\n" << kalmanGainSubset << "\nInnovation is:\n" << innovationSubset << "\nCorrected full state is:\n" << state_ << "\nCorrected full estimate error covariance is:\n" << estimateErrorCovariance_ << "\n\n---------------------- /Ekf::correct ----------------------\n"); } } void Ekf::predict(const double referenceTime, const double delta) { FB_DEBUG("---------------------- Ekf::predict ----------------------\n" << "delta is " << delta << "\n" << "state is " << state_ << "\n"); double roll = state_(StateMemberRoll); double pitch = state_(StateMemberPitch); double yaw = state_(StateMemberYaw); double xVel = state_(StateMemberVx); double yVel = state_(StateMemberVy); double zVel = state_(StateMemberVz); double rollVel = state_(StateMemberVroll); double pitchVel = state_(StateMemberVpitch); double yawVel = state_(StateMemberVyaw); double xAcc = state_(StateMemberAx); double yAcc = state_(StateMemberAy); double zAcc = state_(StateMemberAz); // We'll need these trig calculations a lot. double sp = ::sin(pitch); double cp = ::cos(pitch); double sr = ::sin(roll); double cr = ::cos(roll); double sy = ::sin(yaw); double cy = ::cos(yaw); prepareControl(referenceTime, delta); // Prepare the transfer function transferFunction_(StateMemberX, StateMemberVx) = cy * cp * delta; transferFunction_(StateMemberX, StateMemberVy) = (cy * sp * sr - sy * cr) * delta; transferFunction_(StateMemberX, StateMemberVz) = (cy * sp * cr + sy * sr) * delta; transferFunction_(StateMemberX, StateMemberAx) = 0.5 * transferFunction_(StateMemberX, StateMemberVx) * delta; transferFunction_(StateMemberX, StateMemberAy) = 0.5 * transferFunction_(StateMemberX, StateMemberVy) * delta; transferFunction_(StateMemberX, StateMemberAz) = 0.5 * transferFunction_(StateMemberX, StateMemberVz) * delta; transferFunction_(StateMemberY, StateMemberVx) = sy * cp * delta; transferFunction_(StateMemberY, StateMemberVy) = (sy * sp * sr + cy * cr) * delta; transferFunction_(StateMemberY, StateMemberVz) = (sy * sp * cr - cy * sr) * delta; transferFunction_(StateMemberY, StateMemberAx) = 0.5 * transferFunction_(StateMemberY, StateMemberVx) * delta; transferFunction_(StateMemberY, StateMemberAy) = 0.5 * transferFunction_(StateMemberY, StateMemberVy) * delta; transferFunction_(StateMemberY, StateMemberAz) = 0.5 * transferFunction_(StateMemberY, StateMemberVz) * delta; transferFunction_(StateMemberZ, StateMemberVx) = -sp * delta; transferFunction_(StateMemberZ, StateMemberVy) = cp * sr * delta; transferFunction_(StateMemberZ, StateMemberVz) = cp * cr * delta; transferFunction_(StateMemberZ, StateMemberAx) = 0.5 * transferFunction_(StateMemberZ, StateMemberVx) * delta; transferFunction_(StateMemberZ, StateMemberAy) = 0.5 * transferFunction_(StateMemberZ, StateMemberVy) * delta; transferFunction_(StateMemberZ, StateMemberAz) = 0.5 * transferFunction_(StateMemberZ, StateMemberVz) * delta; transferFunction_(StateMemberRoll, StateMemberVroll) = transferFunction_(StateMemberX, StateMemberVx); transferFunction_(StateMemberRoll, StateMemberVpitch) = transferFunction_(StateMemberX, StateMemberVy); transferFunction_(StateMemberRoll, StateMemberVyaw) = transferFunction_(StateMemberX, StateMemberVz); transferFunction_(StateMemberPitch, StateMemberVroll) = transferFunction_(StateMemberY, StateMemberVx); transferFunction_(StateMemberPitch, StateMemberVpitch) = transferFunction_(StateMemberY, StateMemberVy); transferFunction_(StateMemberPitch, StateMemberVyaw) = transferFunction_(StateMemberY, StateMemberVz); transferFunction_(StateMemberYaw, StateMemberVroll) = transferFunction_(StateMemberZ, StateMemberVx); transferFunction_(StateMemberYaw, StateMemberVpitch) = transferFunction_(StateMemberZ, StateMemberVy); transferFunction_(StateMemberYaw, StateMemberVyaw) = transferFunction_(StateMemberZ, StateMemberVz); transferFunction_(StateMemberVx, StateMemberAx) = delta; transferFunction_(StateMemberVy, StateMemberAy) = delta; transferFunction_(StateMemberVz, StateMemberAz) = delta; // Prepare the transfer function Jacobian. This function is analytically derived from the // transfer function. double xCoeff = 0.0; double yCoeff = 0.0; double zCoeff = 0.0; double oneHalfATSquared = 0.5 * delta * delta; yCoeff = cy * sp * cr + sy * sr; zCoeff = -cy * sp * sr + sy * cr; double dFx_dR = (yCoeff * yVel + zCoeff * zVel) * delta + (yCoeff * yAcc + zCoeff * zAcc) * oneHalfATSquared; double dFR_dR = 1 + (yCoeff * pitchVel + zCoeff * yawVel) * delta; xCoeff = -cy * sp; yCoeff = cy * cp * sr; zCoeff = cy * cp * cr; double dFx_dP = (xCoeff * xVel + yCoeff * yVel + zCoeff * zVel) * delta + (xCoeff * xAcc + yCoeff * yAcc + zCoeff * zAcc) * oneHalfATSquared; double dFR_dP = (xCoeff * rollVel + yCoeff * pitchVel + zCoeff * yawVel) * delta; xCoeff = -sy * cp; yCoeff = -sy * sp * sr - cy * cr; zCoeff = -sy * sp * cr + cy * sr; double dFx_dY = (xCoeff * xVel + yCoeff * yVel + zCoeff * zVel) * delta + (xCoeff * xAcc + yCoeff * yAcc + zCoeff * zAcc) * oneHalfATSquared; double dFR_dY = (xCoeff * rollVel + yCoeff * pitchVel + zCoeff * yawVel) * delta; yCoeff = sy * sp * cr - cy * sr; zCoeff = -sy * sp * sr - cy * cr; double dFy_dR = (yCoeff * yVel + zCoeff * zVel) * delta + (yCoeff * yAcc + zCoeff * zAcc) * oneHalfATSquared; double dFP_dR = (yCoeff * pitchVel + zCoeff * yawVel) * delta; xCoeff = -sy * sp; yCoeff = sy * cp * sr; zCoeff = sy * cp * cr; double dFy_dP = (xCoeff * xVel + yCoeff * yVel + zCoeff * zVel) * delta + (xCoeff * xAcc + yCoeff * yAcc + zCoeff * zAcc) * oneHalfATSquared; double dFP_dP = 1 + (xCoeff * rollVel + yCoeff * pitchVel + zCoeff * yawVel) * delta; xCoeff = cy * cp; yCoeff = cy * sp * sr - sy * cr; zCoeff = cy * sp * cr + sy * sr; double dFy_dY = (xCoeff * xVel + yCoeff * yVel + zCoeff * zVel) * delta + (xCoeff * xAcc + yCoeff * yAcc + zCoeff * zAcc) * oneHalfATSquared; double dFP_dY = (xCoeff * rollVel + yCoeff * pitchVel + zCoeff * yawVel) * delta; yCoeff = cp * cr; zCoeff = -cp * sr; double dFz_dR = (yCoeff * yVel + zCoeff * zVel) * delta + (yCoeff * yAcc + zCoeff * zAcc) * oneHalfATSquared; double dFY_dR = (yCoeff * pitchVel + zCoeff * yawVel) * delta; xCoeff = -cp; yCoeff = -sp * sr; zCoeff = -sp * cr; double dFz_dP = (xCoeff * xVel + yCoeff * yVel + zCoeff * zVel) * delta + (xCoeff * xAcc + yCoeff * yAcc + zCoeff * zAcc) * oneHalfATSquared; double dFY_dP = (xCoeff * rollVel + yCoeff * pitchVel + zCoeff * yawVel) * delta; // Much of the transfer function Jacobian is identical to the transfer function transferFunctionJacobian_ = transferFunction_; transferFunctionJacobian_(StateMemberX, StateMemberRoll) = dFx_dR; transferFunctionJacobian_(StateMemberX, StateMemberPitch) = dFx_dP; transferFunctionJacobian_(StateMemberX, StateMemberYaw) = dFx_dY; transferFunctionJacobian_(StateMemberY, StateMemberRoll) = dFy_dR; transferFunctionJacobian_(StateMemberY, StateMemberPitch) = dFy_dP; transferFunctionJacobian_(StateMemberY, StateMemberYaw) = dFy_dY; transferFunctionJacobian_(StateMemberZ, StateMemberRoll) = dFz_dR; transferFunctionJacobian_(StateMemberZ, StateMemberPitch) = dFz_dP; transferFunctionJacobian_(StateMemberRoll, StateMemberRoll) = dFR_dR; transferFunctionJacobian_(StateMemberRoll, StateMemberPitch) = dFR_dP; transferFunctionJacobian_(StateMemberRoll, StateMemberYaw) = dFR_dY; transferFunctionJacobian_(StateMemberPitch, StateMemberRoll) = dFP_dR; transferFunctionJacobian_(StateMemberPitch, StateMemberPitch) = dFP_dP; transferFunctionJacobian_(StateMemberPitch, StateMemberYaw) = dFP_dY; transferFunctionJacobian_(StateMemberYaw, StateMemberRoll) = dFY_dR; transferFunctionJacobian_(StateMemberYaw, StateMemberPitch) = dFY_dP; FB_DEBUG("Transfer function is:\n" << transferFunction_ << "\nTransfer function Jacobian is:\n" << transferFunctionJacobian_ << "\nProcess noise covariance is:\n" << processNoiseCovariance_ << "\nCurrent state is:\n" << state_ << "\n"); Eigen::MatrixXd *processNoiseCovariance = &processNoiseCovariance_; if (useDynamicProcessNoiseCovariance_) { computeDynamicProcessNoiseCovariance(state_, delta); processNoiseCovariance = &dynamicProcessNoiseCovariance_; } // (1) Apply control terms, which are actually accelerations state_(StateMemberVroll) += controlAcceleration_(ControlMemberVroll) * delta; state_(StateMemberVpitch) += controlAcceleration_(ControlMemberVpitch) * delta; state_(StateMemberVyaw) += controlAcceleration_(ControlMemberVyaw) * delta; state_(StateMemberAx) = (controlUpdateVector_[ControlMemberVx] ? controlAcceleration_(ControlMemberVx) : state_(StateMemberAx)); state_(StateMemberAy) = (controlUpdateVector_[ControlMemberVy] ? controlAcceleration_(ControlMemberVy) : state_(StateMemberAy)); state_(StateMemberAz) = (controlUpdateVector_[ControlMemberVz] ? controlAcceleration_(ControlMemberVz) : state_(StateMemberAz)); // (2) Project the state forward: x = Ax + Bu (really, x = f(x, u)) state_ = transferFunction_ * state_; // Handle wrapping wrapStateAngles(); FB_DEBUG("Predicted state is:\n" << state_ << "\nCurrent estimate error covariance is:\n" << estimateErrorCovariance_ << "\n"); // (3) Project the error forward: P = J * P * J' + Q estimateErrorCovariance_ = (transferFunctionJacobian_ * estimateErrorCovariance_ * transferFunctionJacobian_.transpose()); estimateErrorCovariance_.noalias() += delta * (*processNoiseCovariance); FB_DEBUG("Predicted estimate error covariance is:\n" << estimateErrorCovariance_ << "\n\n--------------------- /Ekf::predict ----------------------\n"); } } // namespace RobotLocalization ================================================ FILE: src/robot_localization/src/ekf_localization_node.cpp ================================================ /* * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * 1. Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * 2. Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * 3. Neither the name of the copyright holder nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #include "robot_localization/ros_filter_types.h" #include int main(int argc, char **argv) { ros::init(argc, argv, "ekf_navigation_node"); RobotLocalization::RosEkf ekf; ekf.run(); return EXIT_SUCCESS; } ================================================ FILE: src/robot_localization/src/filter_base.cpp ================================================ /* * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * 1. Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * 2. Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * 3. Neither the name of the copyright holder nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #include "robot_localization/filter_base.h" #include "robot_localization/filter_common.h" #include #include #include #include #include namespace RobotLocalization { FilterBase::FilterBase() : accelerationGains_(TWIST_SIZE, 0.0), accelerationLimits_(TWIST_SIZE, 0.0), decelerationGains_(TWIST_SIZE, 0.0), decelerationLimits_(TWIST_SIZE, 0.0), controlAcceleration_(TWIST_SIZE), controlTimeout_(0.0), controlUpdateVector_(TWIST_SIZE, 0), dynamicProcessNoiseCovariance_(STATE_SIZE, STATE_SIZE), latestControlTime_(0.0), state_(STATE_SIZE), predictedState_(STATE_SIZE), transferFunction_(STATE_SIZE, STATE_SIZE), transferFunctionJacobian_(STATE_SIZE, STATE_SIZE), estimateErrorCovariance_(STATE_SIZE, STATE_SIZE), covarianceEpsilon_(STATE_SIZE, STATE_SIZE), processNoiseCovariance_(STATE_SIZE, STATE_SIZE), identity_(STATE_SIZE, STATE_SIZE), debug_(false), debugStream_(NULL), useControl_(false), useDynamicProcessNoiseCovariance_(false) { reset(); } FilterBase::~FilterBase() { } void FilterBase::reset() { initialized_ = false; // Clear the state and predicted state state_.setZero(); predictedState_.setZero(); controlAcceleration_.setZero(); // Prepare the invariant parts of the transfer // function transferFunction_.setIdentity(); // Clear the Jacobian transferFunctionJacobian_.setZero(); // Set the estimate error covariance. We want our measurements // to be accepted rapidly when the filter starts, so we should // initialize the state's covariance with large values. estimateErrorCovariance_.setIdentity(); estimateErrorCovariance_ *= 1e-9; // We need the identity for the update equations identity_.setIdentity(); // Set the epsilon matrix to be a matrix with small values on the diagonal // It is used to maintain the positive-definite property of the covariance covarianceEpsilon_.setIdentity(); covarianceEpsilon_ *= 0.001; // Assume 30Hz from sensor data (configurable) sensorTimeout_ = 0.033333333; // Initialize our measurement time lastMeasurementTime_ = 0; // These can be overridden via the launch parameters, // but we need default values. processNoiseCovariance_.setZero(); processNoiseCovariance_(StateMemberX, StateMemberX) = 0.05; processNoiseCovariance_(StateMemberY, StateMemberY) = 0.05; processNoiseCovariance_(StateMemberZ, StateMemberZ) = 0.06; processNoiseCovariance_(StateMemberRoll, StateMemberRoll) = 0.03; processNoiseCovariance_(StateMemberPitch, StateMemberPitch) = 0.03; processNoiseCovariance_(StateMemberYaw, StateMemberYaw) = 0.06; processNoiseCovariance_(StateMemberVx, StateMemberVx) = 0.025; processNoiseCovariance_(StateMemberVy, StateMemberVy) = 0.025; processNoiseCovariance_(StateMemberVz, StateMemberVz) = 0.04; processNoiseCovariance_(StateMemberVroll, StateMemberVroll) = 0.01; processNoiseCovariance_(StateMemberVpitch, StateMemberVpitch) = 0.01; processNoiseCovariance_(StateMemberVyaw, StateMemberVyaw) = 0.02; processNoiseCovariance_(StateMemberAx, StateMemberAx) = 0.01; processNoiseCovariance_(StateMemberAy, StateMemberAy) = 0.01; processNoiseCovariance_(StateMemberAz, StateMemberAz) = 0.015; dynamicProcessNoiseCovariance_ = processNoiseCovariance_; } void FilterBase::computeDynamicProcessNoiseCovariance(const Eigen::VectorXd &state, const double delta) { // A more principled approach would be to get the current velocity from the state, make a diagonal matrix from it, // and then rotate it to be in the world frame (i.e., the same frame as the pose data). We could then use this // rotated velocity matrix to scale the process noise covariance for the pose variables as // rotatedVelocityMatrix * poseCovariance * rotatedVelocityMatrix' // However, this presents trouble for robots that may incur rotational error as a result of linear motion (and // vice-versa). Instead, we create a diagonal matrix whose diagonal values are the vector norm of the state's // velocity. We use that to scale the process noise covariance. Eigen::MatrixXd velocityMatrix(TWIST_SIZE, TWIST_SIZE); velocityMatrix.setIdentity(); velocityMatrix.diagonal() *= state.segment(POSITION_V_OFFSET, TWIST_SIZE).norm(); dynamicProcessNoiseCovariance_.block(POSITION_OFFSET, POSITION_OFFSET) = velocityMatrix * processNoiseCovariance_.block(POSITION_OFFSET, POSITION_OFFSET) * velocityMatrix.transpose(); } const Eigen::VectorXd& FilterBase::getControl() { return latestControl_; } double FilterBase::getControlTime() { return latestControlTime_; } bool FilterBase::getDebug() { return debug_; } const Eigen::MatrixXd& FilterBase::getEstimateErrorCovariance() { return estimateErrorCovariance_; } bool FilterBase::getInitializedStatus() { return initialized_; } double FilterBase::getLastMeasurementTime() { return lastMeasurementTime_; } const Eigen::VectorXd& FilterBase::getPredictedState() { return predictedState_; } const Eigen::MatrixXd& FilterBase::getProcessNoiseCovariance() { return processNoiseCovariance_; } double FilterBase::getSensorTimeout() { return sensorTimeout_; } const Eigen::VectorXd& FilterBase::getState() { return state_; } void FilterBase::processMeasurement(const Measurement &measurement) { FB_DEBUG("------ FilterBase::processMeasurement (" << measurement.topicName_ << ") ------\n"); double delta = 0.0; // If we've had a previous reading, then go through the predict/update // cycle. Otherwise, set our state and covariance to whatever we get // from this measurement. if (initialized_) { // Determine how much time has passed since our last measurement delta = measurement.time_ - lastMeasurementTime_; FB_DEBUG("Filter is already initialized. Carrying out predict/correct loop...\n" "Measurement time is " << std::setprecision(20) << measurement.time_ << ", last measurement time is " << lastMeasurementTime_ << ", delta is " << delta << "\n"); // Only want to carry out a prediction if it's // forward in time. Otherwise, just correct. if (delta > 0) { validateDelta(delta); predict(measurement.time_, delta); // Return this to the user predictedState_ = state_; } correct(measurement); } else { FB_DEBUG("First measurement. Initializing filter.\n"); // Initialize the filter, but only with the values we're using size_t measurementLength = measurement.updateVector_.size(); for (size_t i = 0; i < measurementLength; ++i) { state_[i] = (measurement.updateVector_[i] ? measurement.measurement_[i] : state_[i]); } // Same for covariance for (size_t i = 0; i < measurementLength; ++i) { for (size_t j = 0; j < measurementLength; ++j) { estimateErrorCovariance_(i, j) = (measurement.updateVector_[i] && measurement.updateVector_[j] ? measurement.covariance_(i, j) : estimateErrorCovariance_(i, j)); } } initialized_ = true; } if (delta >= 0.0) { lastMeasurementTime_ = measurement.time_; } FB_DEBUG("------ /FilterBase::processMeasurement (" << measurement.topicName_ << ") ------\n"); } void FilterBase::setControl(const Eigen::VectorXd &control, const double controlTime) { latestControl_ = control; latestControlTime_ = controlTime; } void FilterBase::setControlParams(const std::vector &updateVector, const double controlTimeout, const std::vector &accelerationLimits, const std::vector &accelerationGains, const std::vector &decelerationLimits, const std::vector &decelerationGains) { useControl_ = true; controlUpdateVector_ = updateVector; controlTimeout_ = controlTimeout; accelerationLimits_ = accelerationLimits; accelerationGains_ = accelerationGains; decelerationLimits_ = decelerationLimits; decelerationGains_ = decelerationGains; } void FilterBase::setDebug(const bool debug, std::ostream *outStream) { if (debug) { if (outStream != NULL) { debugStream_ = outStream; debug_ = true; } else { debug_ = false; } } else { debug_ = false; } } void FilterBase::setUseDynamicProcessNoiseCovariance(const bool useDynamicProcessNoiseCovariance) { useDynamicProcessNoiseCovariance_ = useDynamicProcessNoiseCovariance; } void FilterBase::setEstimateErrorCovariance(const Eigen::MatrixXd &estimateErrorCovariance) { estimateErrorCovariance_ = estimateErrorCovariance; } void FilterBase::setLastMeasurementTime(const double lastMeasurementTime) { lastMeasurementTime_ = lastMeasurementTime; } void FilterBase::setProcessNoiseCovariance(const Eigen::MatrixXd &processNoiseCovariance) { processNoiseCovariance_ = processNoiseCovariance; dynamicProcessNoiseCovariance_ = processNoiseCovariance_; } void FilterBase::setSensorTimeout(const double sensorTimeout) { sensorTimeout_ = sensorTimeout; } void FilterBase::setState(const Eigen::VectorXd &state) { state_ = state; } void FilterBase::validateDelta(double &delta) { // This handles issues with ROS time when use_sim_time is on and we're playing from bags. if (delta > 100000.0) { FB_DEBUG("Delta was very large. Suspect playing from bag file. Setting to 0.01\n"); delta = 0.01; } } void FilterBase::prepareControl(const double referenceTime, const double predictionDelta) { controlAcceleration_.setZero(); if (useControl_) { bool timedOut = ::fabs(referenceTime - latestControlTime_) >= controlTimeout_; if (timedOut) { FB_DEBUG("Control timed out. Reference time was " << referenceTime << ", latest control time was " << latestControlTime_ << ", control timeout was " << controlTimeout_ << "\n"); } for (size_t controlInd = 0; controlInd < TWIST_SIZE; ++controlInd) { if (controlUpdateVector_[controlInd]) { controlAcceleration_(controlInd) = computeControlAcceleration(state_(controlInd + POSITION_V_OFFSET), (timedOut ? 0.0 : latestControl_(controlInd)), accelerationLimits_[controlInd], accelerationGains_[controlInd], decelerationLimits_[controlInd], decelerationGains_[controlInd]); } } } } void FilterBase::wrapStateAngles() { state_(StateMemberRoll) = FilterUtilities::clampRotation(state_(StateMemberRoll)); state_(StateMemberPitch) = FilterUtilities::clampRotation(state_(StateMemberPitch)); state_(StateMemberYaw) = FilterUtilities::clampRotation(state_(StateMemberYaw)); } bool FilterBase::checkMahalanobisThreshold(const Eigen::VectorXd &innovation, const Eigen::MatrixXd &invCovariance, const double nsigmas) { double sqMahalanobis = innovation.dot(invCovariance * innovation); double threshold = nsigmas * nsigmas; if (sqMahalanobis >= threshold) { FB_DEBUG("Innovation mahalanobis distance test failed. Squared Mahalanobis is: " << sqMahalanobis << "\n" << "Threshold is: " << threshold << "\n" << "Innovation is: " << innovation << "\n" << "Innovation covariance is:\n" << invCovariance << "\n"); return false; } return true; } } // namespace RobotLocalization ================================================ FILE: src/robot_localization/src/filter_utilities.cpp ================================================ /* * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * 1. Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * 2. Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * 3. Neither the name of the copyright holder nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #include "robot_localization/filter_utilities.h" #include "robot_localization/filter_common.h" #include #include std::ostream& operator<<(std::ostream& os, const Eigen::MatrixXd &mat) { os << "["; int rowCount = static_cast(mat.rows()); for (int row = 0; row < rowCount; ++row) { if (row > 0) { os << " "; } for (int col = 0; col < mat.cols(); ++col) { os << std::setiosflags(std::ios::left) << std::setw(12) << std::setprecision(5) << mat(row, col); } if (row < rowCount - 1) { os << "\n"; } } os << "]\n"; return os; } std::ostream& operator<<(std::ostream& os, const Eigen::VectorXd &vec) { os << "["; for (int dim = 0; dim < vec.rows(); ++dim) { os << std::setiosflags(std::ios::left) << std::setw(12) << std::setprecision(5) << vec(dim); } os << "]\n"; return os; } std::ostream& operator<<(std::ostream& os, const std::vector &vec) { os << "["; for (size_t dim = 0; dim < vec.size(); ++dim) { os << std::setiosflags(std::ios::left) << std::setw(12) << std::setprecision(5) << vec[dim]; } os << "]\n"; return os; } std::ostream& operator<<(std::ostream& os, const std::vector &vec) { os << "["; for (size_t dim = 0; dim < vec.size(); ++dim) { os << std::setiosflags(std::ios::left) << std::setw(3) << (vec[dim] ? "t" : "f"); } os << "]\n"; return os; } namespace RobotLocalization { namespace FilterUtilities { void appendPrefix(std::string tfPrefix, std::string &frameId) { // Strip all leading slashes for tf2 compliance if (!frameId.empty() && frameId.at(0) == '/') { frameId = frameId.substr(1); } if (!tfPrefix.empty() && tfPrefix.at(0) == '/') { tfPrefix = tfPrefix.substr(1); } // If we do have a tf prefix, then put a slash in between if (!tfPrefix.empty()) { frameId = tfPrefix + "/" + frameId; } } double clampRotation(double rotation) { while (rotation > PI) { rotation -= TAU; } while (rotation < -PI) { rotation += TAU; } return rotation; } } // namespace FilterUtilities } // namespace RobotLocalization ================================================ FILE: src/robot_localization/src/navsat_transform.cpp ================================================ /* * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * 1. Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * 2. Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * 3. Neither the name of the copyright holder nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #include "robot_localization/navsat_transform.h" #include "robot_localization/filter_common.h" #include "robot_localization/filter_utilities.h" #include "robot_localization/navsat_conversions.h" #include "robot_localization/ros_filter_utilities.h" #include #include #include namespace RobotLocalization { NavSatTransform::NavSatTransform() : magnetic_declination_(0.0), utm_odom_tf_yaw_(0.0), yaw_offset_(0.0), transform_timeout_(ros::Duration(0)), broadcast_utm_transform_(false), broadcast_utm_transform_as_parent_frame_(false), has_transform_odom_(false), has_transform_gps_(false), has_transform_imu_(false), transform_good_(false), gps_frame_id_(""), gps_updated_(false), odom_updated_(false), publish_gps_(false), use_odometry_yaw_(false), use_manual_datum_(false), zero_altitude_(false), world_frame_id_("odom"), base_link_frame_id_("base_link"), utm_zone_(""), tf_listener_(tf_buffer_) { latest_utm_covariance_.resize(POSE_SIZE, POSE_SIZE); latest_odom_covariance_.resize(POSE_SIZE, POSE_SIZE); } NavSatTransform::~NavSatTransform() { } void NavSatTransform::run() { ros::Time::init(); double frequency = 10.0; double delay = 0.0; double transform_timeout = 0.0; ros::NodeHandle nh; ros::NodeHandle nh_priv("~"); // Load the parameters we need nh_priv.getParam("magnetic_declination_radians", magnetic_declination_); nh_priv.param("yaw_offset", yaw_offset_, 0.0); nh_priv.param("broadcast_utm_transform", broadcast_utm_transform_, false); nh_priv.param("broadcast_utm_transform_as_parent_frame", broadcast_utm_transform_as_parent_frame_, false); nh_priv.param("zero_altitude", zero_altitude_, false); nh_priv.param("publish_filtered_gps", publish_gps_, false); nh_priv.param("use_odometry_yaw", use_odometry_yaw_, false); nh_priv.param("wait_for_datum", use_manual_datum_, false); nh_priv.param("frequency", frequency, 10.0); nh_priv.param("delay", delay, 0.0); nh_priv.param("transform_timeout", transform_timeout, 0.0); transform_timeout_.fromSec(transform_timeout); // Subscribe to the messages and services we need ros::ServiceServer datum_srv = nh.advertiseService("datum", &NavSatTransform::datumCallback, this); if (use_manual_datum_ && nh_priv.hasParam("datum")) { XmlRpc::XmlRpcValue datum_config; try { double datum_lat; double datum_lon; double datum_yaw; nh_priv.getParam("datum", datum_config); // Handle datum specification. Users should always specify a baseLinkFrameId_ in the // datum config, but we had a release where it wasn't used, so we'll maintain compatibility. ROS_ASSERT(datum_config.getType() == XmlRpc::XmlRpcValue::TypeArray); ROS_ASSERT(datum_config.size() >= 3); if (datum_config.size() > 3) { ROS_WARN_STREAM("Deprecated datum parameter configuration detected. Only the first three parameters " "(latitude, longitude, yaw) will be used. frame_ids will be derived from odometry and navsat inputs."); } std::ostringstream ostr; ostr << std::setprecision(20) << datum_config[0] << " " << datum_config[1] << " " << datum_config[2]; std::istringstream istr(ostr.str()); istr >> datum_lat >> datum_lon >> datum_yaw; // Try to resolve tf_prefix std::string tf_prefix = ""; std::string tf_prefix_path = ""; if (nh_priv.searchParam("tf_prefix", tf_prefix_path)) { nh_priv.getParam(tf_prefix_path, tf_prefix); } // Append the tf prefix in a tf2-friendly manner FilterUtilities::appendPrefix(tf_prefix, world_frame_id_); FilterUtilities::appendPrefix(tf_prefix, base_link_frame_id_); robot_localization::SetDatum::Request request; request.geo_pose.position.latitude = datum_lat; request.geo_pose.position.longitude = datum_lon; request.geo_pose.position.altitude = 0.0; tf2::Quaternion quat; quat.setRPY(0.0, 0.0, datum_yaw); request.geo_pose.orientation = tf2::toMsg(quat); robot_localization::SetDatum::Response response; datumCallback(request, response); } catch (XmlRpc::XmlRpcException &e) { ROS_ERROR_STREAM("ERROR reading sensor config: " << e.getMessage() << " for process_noise_covariance (type: " << datum_config.getType() << ")"); } } ros::Subscriber odom_sub = nh.subscribe("odometry/filtered", 1, &NavSatTransform::odomCallback, this); ros::Subscriber gps_sub = nh.subscribe("gps/fix", 1, &NavSatTransform::gpsFixCallback, this); ros::Subscriber imu_sub; if (!use_odometry_yaw_ && !use_manual_datum_) { imu_sub = nh.subscribe("imu/data", 1, &NavSatTransform::imuCallback, this); } ros::Publisher gps_odom_pub = nh.advertise("odometry/gps", 10); ros::Publisher filtered_gps_pub; if (publish_gps_) { filtered_gps_pub = nh.advertise("gps/filtered", 10); } // Sleep for the parameterized amount of time, to give // other nodes time to start up (not always necessary) ros::Duration start_delay(delay); start_delay.sleep(); ros::Rate rate(frequency); while (ros::ok()) { ros::spinOnce(); if (!transform_good_) { computeTransform(); if (transform_good_ && !use_odometry_yaw_ && !use_manual_datum_) { // Once we have the transform, we don't need the IMU imu_sub.shutdown(); } } else { nav_msgs::Odometry gps_odom; if (prepareGpsOdometry(gps_odom)) { gps_odom_pub.publish(gps_odom); } if (publish_gps_) { sensor_msgs::NavSatFix odom_gps; if (prepareFilteredGps(odom_gps)) { filtered_gps_pub.publish(odom_gps); } } } rate.sleep(); } } void NavSatTransform::computeTransform() { // Only do this if: // 1. We haven't computed the odom_frame->utm_frame transform before // 2. We've received the data we need if (!transform_good_ && has_transform_odom_ && has_transform_gps_ && has_transform_imu_) { // The UTM pose we have is given at the location of the GPS sensor on the robot. We need to get the UTM pose of // the robot's origin. tf2::Transform transform_utm_pose_corrected; if (!use_manual_datum_) { getRobotOriginUtmPose(transform_utm_pose_, transform_utm_pose_corrected, ros::Time(0)); } else { transform_utm_pose_corrected = transform_utm_pose_; } // Get the IMU's current RPY values. Need the raw values (for yaw, anyway). tf2::Matrix3x3 mat(transform_orientation_); // Convert to RPY double imu_roll; double imu_pitch; double imu_yaw; mat.getRPY(imu_roll, imu_pitch, imu_yaw); /* The IMU's heading was likely originally reported w.r.t. magnetic north. * However, all the nodes in robot_localization assume that orientation data, * including that reported by IMUs, is reported in an ENU frame, with a 0 yaw * value being reported when facing east and increasing counter-clockwise (i.e., * towards north). Conveniently, this aligns with the UTM grid, where X is east * and Y is north. However, we have two additional considerations: * 1. The IMU may have its non-ENU frame data transformed to ENU, but there's * a possibility that its data has not been corrected for magnetic * declination. We need to account for this. A positive magnetic * declination is counter-clockwise in an ENU frame. Therefore, if * we have a magnetic declination of N radians, then when the sensor * is facing a heading of N, it reports 0. Therefore, we need to add * the declination angle. * 2. To account for any other offsets that may not be accounted for by the * IMU driver or any interim processing node, we expose a yaw offset that * lets users work with navsat_transform_node. */ imu_yaw += (magnetic_declination_ + yaw_offset_); ROS_INFO_STREAM("Corrected for magnetic declination of " << std::fixed << magnetic_declination_ << " and user-specified offset of " << yaw_offset_ << "." << " Transform heading factor is now " << imu_yaw); // Convert to tf-friendly structures tf2::Quaternion imu_quat; imu_quat.setRPY(0.0, 0.0, imu_yaw); // The transform order will be orig_odom_pos * orig_utm_pos_inverse * cur_utm_pos. // Doing it this way will allow us to cope with having non-zero odometry position // when we get our first GPS message. tf2::Transform utm_pose_with_orientation; utm_pose_with_orientation.setOrigin(transform_utm_pose_corrected.getOrigin()); utm_pose_with_orientation.setRotation(imu_quat); utm_world_transform_.mult(transform_world_pose_, utm_pose_with_orientation.inverse()); utm_world_trans_inverse_ = utm_world_transform_.inverse(); ROS_INFO_STREAM("Transform world frame pose is: " << transform_world_pose_); ROS_INFO_STREAM("World frame->utm transform is " << utm_world_transform_); transform_good_ = true; // Send out the (static) UTM transform in case anyone else would like to use it. if (broadcast_utm_transform_) { geometry_msgs::TransformStamped utm_transform_stamped; utm_transform_stamped.header.stamp = ros::Time::now(); utm_transform_stamped.header.frame_id = (broadcast_utm_transform_as_parent_frame_ ? "utm" : world_frame_id_); utm_transform_stamped.child_frame_id = (broadcast_utm_transform_as_parent_frame_ ? world_frame_id_ : "utm"); utm_transform_stamped.transform = (broadcast_utm_transform_as_parent_frame_ ? tf2::toMsg(utm_world_trans_inverse_) : tf2::toMsg(utm_world_transform_)); utm_transform_stamped.transform.translation.z = (zero_altitude_ ? 0.0 : utm_transform_stamped.transform.translation.z); utm_broadcaster_.sendTransform(utm_transform_stamped); } } } bool NavSatTransform::datumCallback(robot_localization::SetDatum::Request& request, robot_localization::SetDatum::Response&) { // If we get a service call with a manual datum, even if we already computed the transform using the robot's // initial pose, then we want to assume that we are using a datum from now on, and we want other methods to // not attempt to transform the values we are specifying here. use_manual_datum_ = true; transform_good_ = false; sensor_msgs::NavSatFix *fix = new sensor_msgs::NavSatFix(); fix->latitude = request.geo_pose.position.latitude; fix->longitude = request.geo_pose.position.longitude; fix->altitude = request.geo_pose.position.altitude; fix->header.stamp = ros::Time::now(); fix->position_covariance[0] = 0.1; fix->position_covariance[4] = 0.1; fix->position_covariance[8] = 0.1; fix->position_covariance_type = sensor_msgs::NavSatStatus::STATUS_FIX; sensor_msgs::NavSatFixConstPtr fix_ptr(fix); setTransformGps(fix_ptr); nav_msgs::Odometry *odom = new nav_msgs::Odometry(); odom->pose.pose.orientation.x = 0; odom->pose.pose.orientation.y = 0; odom->pose.pose.orientation.z = 0; odom->pose.pose.orientation.w = 1; odom->pose.pose.position.x = 0; odom->pose.pose.position.y = 0; odom->pose.pose.position.z = 0; odom->header.frame_id = world_frame_id_; odom->child_frame_id = base_link_frame_id_; nav_msgs::OdometryConstPtr odom_ptr(odom); setTransformOdometry(odom_ptr); sensor_msgs::Imu *imu = new sensor_msgs::Imu(); imu->orientation = request.geo_pose.orientation; imu->header.frame_id = base_link_frame_id_; sensor_msgs::ImuConstPtr imu_ptr(imu); imuCallback(imu_ptr); return true; } void NavSatTransform::getRobotOriginUtmPose(const tf2::Transform &gps_utm_pose, tf2::Transform &robot_utm_pose, const ros::Time &transform_time) { robot_utm_pose.setIdentity(); // Get linear offset from origin for the GPS tf2::Transform offset; bool can_transform = RosFilterUtilities::lookupTransformSafe(tf_buffer_, base_link_frame_id_, gps_frame_id_, transform_time, ros::Duration(transform_timeout_), offset); if (can_transform) { // Get the orientation we'll use for our UTM->world transform tf2::Quaternion utm_orientation = transform_orientation_; tf2::Matrix3x3 mat(utm_orientation); // Add the offsets double roll; double pitch; double yaw; mat.getRPY(roll, pitch, yaw); yaw += (magnetic_declination_ + yaw_offset_); utm_orientation.setRPY(roll, pitch, yaw); // Rotate the GPS linear offset by the orientation // Zero out the orientation, because the GPS orientation is meaningless, and if it's non-zero, it will make the // the computation of robot_utm_pose erroneous. offset.setOrigin(tf2::quatRotate(utm_orientation, offset.getOrigin())); offset.setRotation(tf2::Quaternion::getIdentity()); // Update the initial pose robot_utm_pose = offset.inverse() * gps_utm_pose; } else { if (gps_frame_id_ != "") { ROS_WARN_STREAM_ONCE("Unable to obtain " << base_link_frame_id_ << "->" << gps_frame_id_ << " transform. Will assume navsat device is mounted at robot's origin"); } robot_utm_pose = gps_utm_pose; } } void NavSatTransform::getRobotOriginWorldPose(const tf2::Transform &gps_odom_pose, tf2::Transform &robot_odom_pose, const ros::Time &transform_time) { robot_odom_pose.setIdentity(); // Remove the offset from base_link tf2::Transform gps_offset_rotated; bool can_transform = RosFilterUtilities::lookupTransformSafe(tf_buffer_, base_link_frame_id_, gps_frame_id_, transform_time, transform_timeout_, gps_offset_rotated); if (can_transform) { tf2::Transform robot_orientation; can_transform = RosFilterUtilities::lookupTransformSafe(tf_buffer_, world_frame_id_, base_link_frame_id_, transform_time, transform_timeout_, robot_orientation); if (can_transform) { // Zero out rotation because we don't care about the orientation of the // GPS receiver relative to base_link gps_offset_rotated.setOrigin(tf2::quatRotate(robot_orientation.getRotation(), gps_offset_rotated.getOrigin())); gps_offset_rotated.setRotation(tf2::Quaternion::getIdentity()); robot_odom_pose = gps_offset_rotated.inverse() * gps_odom_pose; } else { ROS_WARN_STREAM_THROTTLE(5.0, "Could not obtain " << world_frame_id_ << "->" << base_link_frame_id_ << " transform. Will not remove offset of navsat device from robot's origin."); } } else { ROS_WARN_STREAM_THROTTLE(5.0, "Could not obtain " << base_link_frame_id_ << "->" << gps_frame_id_ << " transform. Will not remove offset of navsat device from robot's origin."); } } void NavSatTransform::gpsFixCallback(const sensor_msgs::NavSatFixConstPtr& msg) { gps_frame_id_ = msg->header.frame_id; if (gps_frame_id_.empty()) { ROS_WARN_STREAM_ONCE("NavSatFix message has empty frame_id. Will assume navsat device is mounted at robot's " "origin."); } // Make sure the GPS data is usable bool good_gps = (msg->status.status != sensor_msgs::NavSatStatus::STATUS_NO_FIX && !std::isnan(msg->altitude) && !std::isnan(msg->latitude) && !std::isnan(msg->longitude)); if (good_gps) { // If we haven't computed the transform yet, then // store this message as the initial GPS data to use if (!transform_good_ && !use_manual_datum_) { setTransformGps(msg); } double utmX = 0; double utmY = 0; std::string utm_zone_tmp; NavsatConversions::LLtoUTM(msg->latitude, msg->longitude, utmY, utmX, utm_zone_tmp); latest_utm_pose_.setOrigin(tf2::Vector3(utmX, utmY, msg->altitude)); latest_utm_covariance_.setZero(); // Copy the measurement's covariance matrix so that we can rotate it later for (size_t i = 0; i < POSITION_SIZE; i++) { for (size_t j = 0; j < POSITION_SIZE; j++) { latest_utm_covariance_(i, j) = msg->position_covariance[POSITION_SIZE * i + j]; } } gps_update_time_ = msg->header.stamp; gps_updated_ = true; } } void NavSatTransform::imuCallback(const sensor_msgs::ImuConstPtr& msg) { // We need the baseLinkFrameId_ from the odometry message, so // we need to wait until we receive it. if (has_transform_odom_) { /* This method only gets called if we don't yet have the * IMU data (the subscriber gets shut down once we compute * the transform), so we can assumed that every IMU message * that comes here is meant to be used for that purpose. */ tf2::fromMsg(msg->orientation, transform_orientation_); // Correct for the IMU's orientation w.r.t. base_link tf2::Transform target_frame_trans; bool can_transform = RosFilterUtilities::lookupTransformSafe(tf_buffer_, base_link_frame_id_, msg->header.frame_id, msg->header.stamp, transform_timeout_, target_frame_trans); if (can_transform) { double roll_offset = 0; double pitch_offset = 0; double yaw_offset = 0; double roll = 0; double pitch = 0; double yaw = 0; RosFilterUtilities::quatToRPY(target_frame_trans.getRotation(), roll_offset, pitch_offset, yaw_offset); RosFilterUtilities::quatToRPY(transform_orientation_, roll, pitch, yaw); ROS_DEBUG_STREAM("Initial orientation is " << transform_orientation_); // Apply the offset (making sure to bound them), and throw them in a vector tf2::Vector3 rpy_angles(FilterUtilities::clampRotation(roll - roll_offset), FilterUtilities::clampRotation(pitch - pitch_offset), FilterUtilities::clampRotation(yaw - yaw_offset)); // Now we need to rotate the roll and pitch by the yaw offset value. // Imagine a case where an IMU is mounted facing sideways. In that case // pitch for the IMU's world frame is roll for the robot. tf2::Matrix3x3 mat; mat.setRPY(0.0, 0.0, yaw_offset); rpy_angles = mat * rpy_angles; transform_orientation_.setRPY(rpy_angles.getX(), rpy_angles.getY(), rpy_angles.getZ()); ROS_DEBUG_STREAM("Initial corrected orientation roll, pitch, yaw is (" << rpy_angles.getX() << ", " << rpy_angles.getY() << ", " << rpy_angles.getZ() << ")"); has_transform_imu_ = true; } } } void NavSatTransform::odomCallback(const nav_msgs::OdometryConstPtr& msg) { world_frame_id_ = msg->header.frame_id; base_link_frame_id_ = msg->child_frame_id; if (!transform_good_ && !use_manual_datum_) { setTransformOdometry(msg); } tf2::fromMsg(msg->pose.pose, latest_world_pose_); latest_odom_covariance_.setZero(); for (size_t row = 0; row < POSE_SIZE; ++row) { for (size_t col = 0; col < POSE_SIZE; ++col) { latest_odom_covariance_(row, col) = msg->pose.covariance[row * POSE_SIZE + col]; } } odom_update_time_ = msg->header.stamp; odom_updated_ = true; } bool NavSatTransform::prepareFilteredGps(sensor_msgs::NavSatFix &filtered_gps) { bool new_data = false; if (transform_good_ && odom_updated_) { tf2::Transform odom_as_utm; odom_as_utm.mult(utm_world_trans_inverse_, latest_world_pose_); odom_as_utm.setRotation(tf2::Quaternion::getIdentity()); // Rotate the covariance as well tf2::Matrix3x3 rot(utm_world_trans_inverse_.getRotation()); Eigen::MatrixXd rot_6d(POSE_SIZE, POSE_SIZE); rot_6d.setIdentity(); for (size_t rInd = 0; rInd < POSITION_SIZE; ++rInd) { rot_6d(rInd, 0) = rot.getRow(rInd).getX(); rot_6d(rInd, 1) = rot.getRow(rInd).getY(); rot_6d(rInd, 2) = rot.getRow(rInd).getZ(); rot_6d(rInd+POSITION_SIZE, 3) = rot.getRow(rInd).getX(); rot_6d(rInd+POSITION_SIZE, 4) = rot.getRow(rInd).getY(); rot_6d(rInd+POSITION_SIZE, 5) = rot.getRow(rInd).getZ(); } // Rotate the covariance latest_odom_covariance_ = rot_6d * latest_odom_covariance_.eval() * rot_6d.transpose(); // Now convert the data back to lat/long and place into the message NavsatConversions::UTMtoLL(odom_as_utm.getOrigin().getY(), odom_as_utm.getOrigin().getX(), utm_zone_, filtered_gps.latitude, filtered_gps.longitude); filtered_gps.altitude = odom_as_utm.getOrigin().getZ(); // Copy the measurement's covariance matrix back for (size_t i = 0; i < POSITION_SIZE; i++) { for (size_t j = 0; j < POSITION_SIZE; j++) { filtered_gps.position_covariance[POSITION_SIZE * i + j] = latest_odom_covariance_(i, j); } } filtered_gps.position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_KNOWN; filtered_gps.status.status = sensor_msgs::NavSatStatus::STATUS_GBAS_FIX; filtered_gps.header.frame_id = "gps"; filtered_gps.header.stamp = odom_update_time_; // Mark this GPS as used odom_updated_ = false; new_data = true; } return new_data; } bool NavSatTransform::prepareGpsOdometry(nav_msgs::Odometry &gps_odom) { bool new_data = false; if (transform_good_ && gps_updated_ && odom_updated_) { tf2::Transform transformed_utm_gps; transformed_utm_gps.mult(utm_world_transform_, latest_utm_pose_); transformed_utm_gps.setRotation(tf2::Quaternion::getIdentity()); // Set header information stamp because we would like to know the robot's position at that timestamp gps_odom.header.frame_id = world_frame_id_; gps_odom.header.stamp = gps_update_time_; // Want the pose of the vehicle origin, not the GPS tf2::Transform transformed_utm_robot; getRobotOriginWorldPose(transformed_utm_gps, transformed_utm_robot, gps_odom.header.stamp); // Rotate the covariance as well tf2::Matrix3x3 rot(utm_world_transform_.getRotation()); Eigen::MatrixXd rot_6d(POSE_SIZE, POSE_SIZE); rot_6d.setIdentity(); for (size_t rInd = 0; rInd < POSITION_SIZE; ++rInd) { rot_6d(rInd, 0) = rot.getRow(rInd).getX(); rot_6d(rInd, 1) = rot.getRow(rInd).getY(); rot_6d(rInd, 2) = rot.getRow(rInd).getZ(); rot_6d(rInd+POSITION_SIZE, 3) = rot.getRow(rInd).getX(); rot_6d(rInd+POSITION_SIZE, 4) = rot.getRow(rInd).getY(); rot_6d(rInd+POSITION_SIZE, 5) = rot.getRow(rInd).getZ(); } // Rotate the covariance latest_utm_covariance_ = rot_6d * latest_utm_covariance_.eval() * rot_6d.transpose(); // Now fill out the message. Set the orientation to the identity. tf2::toMsg(transformed_utm_robot, gps_odom.pose.pose); gps_odom.pose.pose.position.z = (zero_altitude_ ? 0.0 : gps_odom.pose.pose.position.z); // Copy the measurement's covariance matrix so that we can rotate it later for (size_t i = 0; i < POSE_SIZE; i++) { for (size_t j = 0; j < POSE_SIZE; j++) { gps_odom.pose.covariance[POSE_SIZE * i + j] = latest_utm_covariance_(i, j); } } // Mark this GPS as used gps_updated_ = false; new_data = true; } return new_data; } void NavSatTransform::setTransformGps(const sensor_msgs::NavSatFixConstPtr& msg) { double utm_x = 0; double utm_y = 0; NavsatConversions::LLtoUTM(msg->latitude, msg->longitude, utm_y, utm_x, utm_zone_); ROS_INFO_STREAM("Datum (latitude, longitude, altitude) is (" << std::fixed << msg->latitude << ", " << msg->longitude << ", " << msg->altitude << ")"); ROS_INFO_STREAM("Datum UTM coordinate is (" << std::fixed << utm_x << ", " << utm_y << ")"); transform_utm_pose_.setOrigin(tf2::Vector3(utm_x, utm_y, msg->altitude)); transform_utm_pose_.setRotation(tf2::Quaternion::getIdentity()); has_transform_gps_ = true; } void NavSatTransform::setTransformOdometry(const nav_msgs::OdometryConstPtr& msg) { tf2::fromMsg(msg->pose.pose, transform_world_pose_); has_transform_odom_ = true; ROS_INFO_STREAM("Initial odometry pose is " << transform_world_pose_); // Users can optionally use the (potentially fused) heading from // the odometry source, which may have multiple fused sources of // heading data, and so would act as a better heading for the // UTM->world_frame transform. if (!transform_good_ && use_odometry_yaw_ && !use_manual_datum_) { sensor_msgs::Imu *imu = new sensor_msgs::Imu(); imu->orientation = msg->pose.pose.orientation; imu->header.frame_id = msg->child_frame_id; imu->header.stamp = msg->header.stamp; sensor_msgs::ImuConstPtr imuPtr(imu); imuCallback(imuPtr); } } } // namespace RobotLocalization ================================================ FILE: src/robot_localization/src/navsat_transform_node.cpp ================================================ /* * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * 1. Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * 2. Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * 3. Neither the name of the copyright holder nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #include "robot_localization/navsat_transform.h" #include int main(int argc, char **argv) { ros::init(argc, argv, "navsat_transform_node"); RobotLocalization::NavSatTransform trans; trans.run(); return EXIT_SUCCESS; } ================================================ FILE: src/robot_localization/src/robot_localization_estimator.cpp ================================================ /* * Copyright (c) 2016, TNO IVS Helmond. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * 1. Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * 2. Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * 3. Neither the name of the copyright holder nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #include "robot_localization/robot_localization_estimator.h" #include "robot_localization/ekf.h" #include "robot_localization/ukf.h" #include namespace RobotLocalization { RobotLocalizationEstimator::RobotLocalizationEstimator(unsigned int buffer_capacity, FilterType filter_type, const Eigen::MatrixXd& process_noise_covariance, const std::vector& filter_args) { state_buffer_.set_capacity(buffer_capacity); // Set up the filter that is used for predictions if ( filter_type == FilterTypes::EKF ) { filter_ = new Ekf; } else if ( filter_type == FilterTypes::UKF ) { filter_ = new Ukf(filter_args); } filter_->setProcessNoiseCovariance(process_noise_covariance); } RobotLocalizationEstimator::~RobotLocalizationEstimator() { delete filter_; } void RobotLocalizationEstimator::setState(const EstimatorState& state) { // If newly received state is newer than any in the buffer, push back if ( state_buffer_.empty() || state.time_stamp > state_buffer_.back().time_stamp ) { state_buffer_.push_back(state); } // If it is older, put it in the right position else { for ( boost::circular_buffer::iterator it = state_buffer_.begin(); it != state_buffer_.end(); ++it ) { if ( state.time_stamp < it->time_stamp ) { state_buffer_.insert(it, state); return; } } } } EstimatorResult RobotLocalizationEstimator::getState(const double time, EstimatorState& state) const { // If there's nothing in the buffer, there's nothing to give. if ( state_buffer_.size() == 0 ) { return EstimatorResults::EmptyBuffer; } // Set state to the most recent one for now state = state_buffer_.back(); // Go through buffer from new to old EstimatorState last_state_before_time = state_buffer_.front(); EstimatorState next_state_after_time = state_buffer_.back(); bool previous_state_found = false; bool next_state_found = false; for (boost::circular_buffer::const_reverse_iterator it = state_buffer_.rbegin(); it != state_buffer_.rend(); ++it) { /* If the time stamp of the current state from the buffer is * older than the requested time, store it as the last state * before the requested time. If it is younger, save it as the * next one after, and go on to find the last one before. */ if ( it->time_stamp == time ) { state = *it; return EstimatorResults::Exact; } else if ( it->time_stamp <= time ) { last_state_before_time = *it; previous_state_found = true; break; } else { next_state_after_time = *it; next_state_found = true; } } // If we found a previous state and a next state, we can do interpolation if ( previous_state_found && next_state_found ) { interpolate(last_state_before_time, next_state_after_time, time, state); return EstimatorResults::Interpolation; } // If only a previous state is found, we can do extrapolation into the future else if ( previous_state_found ) { extrapolate(last_state_before_time, time, state); return EstimatorResults::ExtrapolationIntoFuture; } // If only a next state is found, we'll have to extrapolate into the past. else if ( next_state_found ) { extrapolate(next_state_after_time, time, state); return EstimatorResults::ExtrapolationIntoPast; } else { return EstimatorResults::Failed; } } void RobotLocalizationEstimator::setBufferCapacity(const int capacity) { state_buffer_.set_capacity(capacity); } void RobotLocalizationEstimator::clearBuffer() { state_buffer_.clear(); } unsigned int RobotLocalizationEstimator::getBufferCapacity() const { return state_buffer_.capacity(); } unsigned int RobotLocalizationEstimator::getSize() const { return state_buffer_.size(); } void RobotLocalizationEstimator::extrapolate(const EstimatorState& boundary_state, const double requested_time, EstimatorState& state_at_req_time) const { // Set up the filter with the boundary state filter_->setState(boundary_state.state); filter_->setEstimateErrorCovariance(boundary_state.covariance); // Calculate how much time we need to extrapolate into the future double delta = requested_time - boundary_state.time_stamp; // Use the filter to predict filter_->predict(boundary_state.time_stamp, delta); state_at_req_time.time_stamp = requested_time; state_at_req_time.state = filter_->getState(); state_at_req_time.covariance = filter_->getEstimateErrorCovariance(); return; } void RobotLocalizationEstimator::interpolate(const EstimatorState& given_state_1, const EstimatorState& given_state_2, const double requested_time, EstimatorState& state_at_req_time) const { /* * TODO: Right now, we only extrapolate from the last known state before the requested time. But as the state after * the requested time is also known, we may want to perform interpolation between states. */ extrapolate(given_state_1, requested_time, state_at_req_time); return; } } // namespace RobotLocalization ================================================ FILE: src/robot_localization/src/robot_localization_listener_node.cpp ================================================ /* * Copyright (c) 2016, TNO IVS Helmond. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * 1. Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * 2. Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * 3. Neither the name of the copyright holder nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #include "robot_localization/ros_robot_localization_listener.h" #include "robot_localization/GetState.h" #include namespace RobotLocalization { class RobotLocalizationListenerNode { public: RobotLocalizationListenerNode() { service_ = n_.advertiseService("get_state", &RobotLocalizationListenerNode::getStateCallback, this); } std::string getService() { return service_.getService(); } private: RosRobotLocalizationListener rll_; ros::NodeHandle n_; ros::ServiceServer service_; bool getStateCallback(robot_localization::GetState::Request &req, robot_localization::GetState::Response &res) { Eigen::VectorXd state(STATE_SIZE); Eigen::MatrixXd covariance(STATE_SIZE, STATE_SIZE); if ( !rll_.getState(req.time_stamp, req.frame_id, state, covariance) ) { ROS_ERROR("Robot Localization Listener Node: Listener instance returned false at getState call."); return false; } for (size_t i = 0; i < STATE_SIZE; i++) { res.state[i] = (*(state.data() + i)); } for (size_t i = 0; i < STATE_SIZE * STATE_SIZE; i++) { res.covariance[i] = (*(covariance.data() + i)); } ROS_DEBUG("Robot Localization Listener Node: Listener responded with state and covariance at the requested time."); return true; } }; } // namespace RobotLocalization int main(int argc, char **argv) { ros::init(argc, argv, "robot_localization_listener_node"); RobotLocalization::RobotLocalizationListenerNode rlln; ROS_INFO_STREAM("Robot Localization Listener Node: Ready to handle GetState requests at " << rlln.getService()); ros::spin(); return 0; } ================================================ FILE: src/robot_localization/src/ros_filter.cpp ================================================ /* * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * 1. Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * 2. Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * 3. Neither the name of the copyright holder nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #include "robot_localization/ros_filter.h" #include "robot_localization/filter_utilities.h" #include "robot_localization/ekf.h" #include "robot_localization/ukf.h" #include #include #include #include #include #include #include namespace RobotLocalization { template RosFilter::RosFilter(std::vector args) : staticDiagErrorLevel_(diagnostic_msgs::DiagnosticStatus::OK), tfListener_(tfBuffer_), dynamicDiagErrorLevel_(diagnostic_msgs::DiagnosticStatus::OK), filter_(args), frequency_(30.0), historyLength_(0), lastSetPoseTime_(0), latestControl_(), latestControlTime_(0), tfTimeout_(ros::Duration(0)), nhLocal_("~"), predictToCurrentTime_(false), printDiagnostics_(true), gravitationalAcc_(9.80665), publishTransform_(true), publishAcceleration_(false), twoDMode_(false), useControl_(false), smoothLaggedData_(false), disabledAtStartup_(false), enabled_(false) { stateVariableNames_.push_back("X"); stateVariableNames_.push_back("Y"); stateVariableNames_.push_back("Z"); stateVariableNames_.push_back("ROLL"); stateVariableNames_.push_back("PITCH"); stateVariableNames_.push_back("YAW"); stateVariableNames_.push_back("X_VELOCITY"); stateVariableNames_.push_back("Y_VELOCITY"); stateVariableNames_.push_back("Z_VELOCITY"); stateVariableNames_.push_back("ROLL_VELOCITY"); stateVariableNames_.push_back("PITCH_VELOCITY"); stateVariableNames_.push_back("YAW_VELOCITY"); stateVariableNames_.push_back("X_ACCELERATION"); stateVariableNames_.push_back("Y_ACCELERATION"); stateVariableNames_.push_back("Z_ACCELERATION"); diagnosticUpdater_.setHardwareID("none"); } template RosFilter::~RosFilter() { topicSubs_.clear(); } template void RosFilter::reset() { // Get rid of any initial poses (pretend we've never had a measurement) initialMeasurements_.clear(); previousMeasurements_.clear(); previousMeasurementCovariances_.clear(); // Clear the measurement queue. // This prevents us from immediately undoing our reset. while (!measurementQueue_.empty() && ros::ok()) { measurementQueue_.pop(); } filterStateHistory_.clear(); measurementHistory_.clear(); // Also set the last set pose time, so we ignore all messages // that occur before it lastSetPoseTime_ = ros::Time(0); // clear tf buffer to avoid TF_OLD_DATA errors tfBuffer_.clear(); // clear last message timestamp, so older messages will be accepted lastMessageTimes_.clear(); // reset filter to uninitialized state filter_.reset(); // clear all waiting callbacks ros::getGlobalCallbackQueue()->clear(); } // @todo: Replace with AccelWithCovarianceStamped template void RosFilter::accelerationCallback(const sensor_msgs::Imu::ConstPtr &msg, const CallbackData &callbackData, const std::string &targetFrame) { // If we've just reset the filter, then we want to ignore any messages // that arrive with an older timestamp if (msg->header.stamp <= lastSetPoseTime_) { return; } const std::string &topicName = callbackData.topicName_; RF_DEBUG("------ RosFilter::accelerationCallback (" << topicName << ") ------\n" "Twist message:\n" << *msg); if (lastMessageTimes_.count(topicName) == 0) { lastMessageTimes_.insert(std::pair(topicName, msg->header.stamp)); } // Make sure this message is newer than the last one if (msg->header.stamp >= lastMessageTimes_[topicName]) { RF_DEBUG("Update vector for " << topicName << " is:\n" << topicName); Eigen::VectorXd measurement(STATE_SIZE); Eigen::MatrixXd measurementCovariance(STATE_SIZE, STATE_SIZE); measurement.setZero(); measurementCovariance.setZero(); // Make sure we're actually updating at least one of these variables std::vector updateVectorCorrected = callbackData.updateVector_; // Prepare the twist data for inclusion in the filter if (prepareAcceleration(msg, topicName, targetFrame, updateVectorCorrected, measurement, measurementCovariance)) { // Store the measurement. Add an "acceleration" suffix so we know what kind of measurement // we're dealing with when we debug the core filter logic. enqueueMeasurement(topicName, measurement, measurementCovariance, updateVectorCorrected, callbackData.rejectionThreshold_, msg->header.stamp); RF_DEBUG("Enqueued new measurement for " << topicName << "_acceleration\n"); } else { RF_DEBUG("Did *not* enqueue measurement for " << topicName << "_acceleration\n"); } lastMessageTimes_[topicName] = msg->header.stamp; RF_DEBUG("Last message time for " << topicName << " is now " << lastMessageTimes_[topicName] << "\n"); } else if (resetOnTimeJump_ && ros::Time::isSimTime()) { reset(); } else { std::stringstream stream; stream << "The " << topicName << " message has a timestamp before that of the previous message received," << " this message will be ignored. This may indicate a bad timestamp. (message time: " << msg->header.stamp.toSec() << ")"; addDiagnostic(diagnostic_msgs::DiagnosticStatus::WARN, topicName + "_timestamp", stream.str(), false); RF_DEBUG("Message is too old. Last message time for " << topicName << " is " << lastMessageTimes_[topicName] << ", current message time is " << msg->header.stamp << ".\n"); } RF_DEBUG("\n----- /RosFilter::accelerationCallback (" << topicName << ") ------\n"); } template void RosFilter::controlCallback(const geometry_msgs::Twist::ConstPtr &msg) { geometry_msgs::TwistStampedPtr twistStampedPtr = geometry_msgs::TwistStampedPtr(new geometry_msgs::TwistStamped()); twistStampedPtr->twist = *msg; twistStampedPtr->header.frame_id = baseLinkFrameId_; twistStampedPtr->header.stamp = ros::Time::now(); controlCallback(twistStampedPtr); } template void RosFilter::controlCallback(const geometry_msgs::TwistStamped::ConstPtr &msg) { if (msg->header.frame_id == baseLinkFrameId_ || msg->header.frame_id == "") { latestControl_(ControlMemberVx) = msg->twist.linear.x; latestControl_(ControlMemberVy) = msg->twist.linear.y; latestControl_(ControlMemberVz) = msg->twist.linear.z; latestControl_(ControlMemberVroll) = msg->twist.angular.x; latestControl_(ControlMemberVpitch) = msg->twist.angular.y; latestControl_(ControlMemberVyaw) = msg->twist.angular.z; latestControlTime_ = msg->header.stamp; // Update the filter with this control term filter_.setControl(latestControl_, msg->header.stamp.toSec()); } else { ROS_WARN_STREAM_THROTTLE(5.0, "Commanded velocities must be given in the robot's body frame (" << baseLinkFrameId_ << "). Message frame was " << msg->header.frame_id); } } template void RosFilter::enqueueMeasurement(const std::string &topicName, const Eigen::VectorXd &measurement, const Eigen::MatrixXd &measurementCovariance, const std::vector &updateVector, const double mahalanobisThresh, const ros::Time &time) { MeasurementPtr meas = MeasurementPtr(new Measurement()); meas->topicName_ = topicName; meas->measurement_ = measurement; meas->covariance_ = measurementCovariance; meas->updateVector_ = updateVector; meas->time_ = time.toSec(); meas->mahalanobisThresh_ = mahalanobisThresh; meas->latestControl_ = latestControl_; meas->latestControlTime_ = latestControlTime_.toSec(); measurementQueue_.push(meas); } template void RosFilter::forceTwoD(Eigen::VectorXd &measurement, Eigen::MatrixXd &measurementCovariance, std::vector &updateVector) { measurement(StateMemberZ) = 0.0; measurement(StateMemberRoll) = 0.0; measurement(StateMemberPitch) = 0.0; measurement(StateMemberVz) = 0.0; measurement(StateMemberVroll) = 0.0; measurement(StateMemberVpitch) = 0.0; measurement(StateMemberAz) = 0.0; measurementCovariance(StateMemberZ, StateMemberZ) = 1e-6; measurementCovariance(StateMemberRoll, StateMemberRoll) = 1e-6; measurementCovariance(StateMemberPitch, StateMemberPitch) = 1e-6; measurementCovariance(StateMemberVz, StateMemberVz) = 1e-6; measurementCovariance(StateMemberVroll, StateMemberVroll) = 1e-6; measurementCovariance(StateMemberVpitch, StateMemberVpitch) = 1e-6; measurementCovariance(StateMemberAz, StateMemberAz) = 1e-6; updateVector[StateMemberZ] = 1; updateVector[StateMemberRoll] = 1; updateVector[StateMemberPitch] = 1; updateVector[StateMemberVz] = 1; updateVector[StateMemberVroll] = 1; updateVector[StateMemberVpitch] = 1; updateVector[StateMemberAz] = 1; } template bool RosFilter::getFilteredOdometryMessage(nav_msgs::Odometry &message) { // If the filter has received a measurement at some point... if (filter_.getInitializedStatus()) { // Grab our current state and covariance estimates const Eigen::VectorXd &state = filter_.getState(); const Eigen::MatrixXd &estimateErrorCovariance = filter_.getEstimateErrorCovariance(); // Convert from roll, pitch, and yaw back to quaternion for // orientation values tf2::Quaternion quat; quat.setRPY(state(StateMemberRoll), state(StateMemberPitch), state(StateMemberYaw)); // Fill out the message message.pose.pose.position.x = state(StateMemberX); message.pose.pose.position.y = state(StateMemberY); message.pose.pose.position.z = state(StateMemberZ); message.pose.pose.orientation.x = quat.x(); message.pose.pose.orientation.y = quat.y(); message.pose.pose.orientation.z = quat.z(); message.pose.pose.orientation.w = quat.w(); message.twist.twist.linear.x = state(StateMemberVx); message.twist.twist.linear.y = state(StateMemberVy); message.twist.twist.linear.z = state(StateMemberVz); message.twist.twist.angular.x = state(StateMemberVroll); message.twist.twist.angular.y = state(StateMemberVpitch); message.twist.twist.angular.z = state(StateMemberVyaw); // Our covariance matrix layout doesn't quite match for (size_t i = 0; i < POSE_SIZE; i++) { for (size_t j = 0; j < POSE_SIZE; j++) { message.pose.covariance[POSE_SIZE * i + j] = estimateErrorCovariance(i, j); } } // POSE_SIZE and TWIST_SIZE are currently the same size, but we can spare a few // cycles to be meticulous and not index a twist covariance array on the size of // a pose covariance array for (size_t i = 0; i < TWIST_SIZE; i++) { for (size_t j = 0; j < TWIST_SIZE; j++) { message.twist.covariance[TWIST_SIZE * i + j] = estimateErrorCovariance(i + POSITION_V_OFFSET, j + POSITION_V_OFFSET); } } message.header.stamp = ros::Time(filter_.getLastMeasurementTime()); message.header.frame_id = worldFrameId_; message.child_frame_id = baseLinkFrameId_; } return filter_.getInitializedStatus(); } template bool RosFilter::getFilteredAccelMessage(geometry_msgs::AccelWithCovarianceStamped &message) { // If the filter has received a measurement at some point... if (filter_.getInitializedStatus()) { // Grab our current state and covariance estimates const Eigen::VectorXd &state = filter_.getState(); const Eigen::MatrixXd &estimateErrorCovariance = filter_.getEstimateErrorCovariance(); //! Fill out the accel_msg message.accel.accel.linear.x = state(StateMemberAx); message.accel.accel.linear.y = state(StateMemberAy); message.accel.accel.linear.z = state(StateMemberAz); // Fill the covariance (only the left-upper matrix since we are not estimating // the rotational accelerations arround the axes for (size_t i = 0; i < ACCELERATION_SIZE; i++) { for (size_t j = 0; j < ACCELERATION_SIZE; j++) { // We use the POSE_SIZE since the accel cov matrix of ROS is 6x6 message.accel.covariance[POSE_SIZE * i + j] = estimateErrorCovariance(i + POSITION_A_OFFSET, j + POSITION_A_OFFSET); } } // Fill header information message.header.stamp = ros::Time(filter_.getLastMeasurementTime()); message.header.frame_id = baseLinkFrameId_; } return filter_.getInitializedStatus(); } template void RosFilter::imuCallback(const sensor_msgs::Imu::ConstPtr &msg, const std::string &topicName, const CallbackData &poseCallbackData, const CallbackData &twistCallbackData, const CallbackData &accelCallbackData) { RF_DEBUG("------ RosFilter::imuCallback (" << topicName << ") ------\n" << "IMU message:\n" << *msg); // If we've just reset the filter, then we want to ignore any messages // that arrive with an older timestamp if (msg->header.stamp <= lastSetPoseTime_) { std::stringstream stream; stream << "The " << topicName << " message has a timestamp equal to or before the last filter reset, " << "this message will be ignored. This may indicate an empty or bad timestamp. (message time: " << msg->header.stamp.toSec() << ")"; addDiagnostic(diagnostic_msgs::DiagnosticStatus::WARN, topicName + "_timestamp", stream.str(), false); RF_DEBUG("Received message that preceded the most recent pose reset. Ignoring..."); return; } // As with the odometry message, we can separate out the pose- and twist-related variables // in the IMU message and pass them to the pose and twist callbacks (filters) if (poseCallbackData.updateSum_ > 0) { // Per the IMU message specification, if the IMU does not provide orientation, // then its first covariance value should be set to -1, and we should ignore // that portion of the message. robot_localization allows users to explicitly // ignore data using its parameters, but we should also be compliant with // message specs. if (::fabs(msg->orientation_covariance[0] + 1) < 1e-9) { RF_DEBUG("Received IMU message with -1 as its first covariance value for orientation. " "Ignoring orientation..."); } else { // Extract the pose (orientation) data, pass it to its filter geometry_msgs::PoseWithCovarianceStamped *posPtr = new geometry_msgs::PoseWithCovarianceStamped(); posPtr->header = msg->header; posPtr->pose.pose.orientation = msg->orientation; // Copy the covariance for roll, pitch, and yaw for (size_t i = 0; i < ORIENTATION_SIZE; i++) { for (size_t j = 0; j < ORIENTATION_SIZE; j++) { posPtr->pose.covariance[POSE_SIZE * (i + ORIENTATION_SIZE) + (j + ORIENTATION_SIZE)] = msg->orientation_covariance[ORIENTATION_SIZE * i + j]; } } // IMU data gets handled a bit differently, since the message is ambiguous and has only a single frame_id, // even though the data in it is reported in two different frames. As we assume users will specify a base_link // to imu transform, we make the target frame baseLinkFrameId_ and tell the poseCallback that it is working // with IMU data. This will cause it to apply different logic to the data. geometry_msgs::PoseWithCovarianceStampedConstPtr pptr(posPtr); poseCallback(pptr, poseCallbackData, baseLinkFrameId_, true); } } if (twistCallbackData.updateSum_ > 0) { // Ignore rotational velocity if the first covariance value is -1 if (::fabs(msg->angular_velocity_covariance[0] + 1) < 1e-9) { RF_DEBUG("Received IMU message with -1 as its first covariance value for angular " "velocity. Ignoring angular velocity..."); } else { // Repeat for velocity geometry_msgs::TwistWithCovarianceStamped *twistPtr = new geometry_msgs::TwistWithCovarianceStamped(); twistPtr->header = msg->header; twistPtr->twist.twist.angular = msg->angular_velocity; // Copy the covariance for (size_t i = 0; i < ORIENTATION_SIZE; i++) { for (size_t j = 0; j < ORIENTATION_SIZE; j++) { twistPtr->twist.covariance[TWIST_SIZE * (i + ORIENTATION_SIZE) + (j + ORIENTATION_SIZE)] = msg->angular_velocity_covariance[ORIENTATION_SIZE * i + j]; } } geometry_msgs::TwistWithCovarianceStampedConstPtr tptr(twistPtr); twistCallback(tptr, twistCallbackData, baseLinkFrameId_); } } if (accelCallbackData.updateSum_ > 0) { // Ignore linear acceleration if the first covariance value is -1 if (::fabs(msg->linear_acceleration_covariance[0] + 1) < 1e-9) { RF_DEBUG("Received IMU message with -1 as its first covariance value for linear " "acceleration. Ignoring linear acceleration..."); } else { // Pass the message on accelerationCallback(msg, accelCallbackData, baseLinkFrameId_); } } RF_DEBUG("\n----- /RosFilter::imuCallback (" << topicName << ") ------\n"); } template void RosFilter::integrateMeasurements(const ros::Time ¤tTime) { const double currentTimeSec = currentTime.toSec(); RF_DEBUG("------ RosFilter::integrateMeasurements ------\n\n" "Integration time is " << std::setprecision(20) << currentTimeSec << "\n" << measurementQueue_.size() << " measurements in queue.\n"); bool predictToCurrentTime = predictToCurrentTime_; // If we have any measurements in the queue, process them if (!measurementQueue_.empty()) { // Check if the first measurement we're going to process is older than the filter's last measurement. // This means we have received an out-of-sequence message (one with an old timestamp), and we need to // revert both the filter state and measurement queue to the first state that preceded the time stamp // of our first measurement. const MeasurementPtr& firstMeasurement = measurementQueue_.top(); int restoredMeasurementCount = 0; if (smoothLaggedData_ && firstMeasurement->time_ < filter_.getLastMeasurementTime()) { RF_DEBUG("Received a measurement that was " << filter_.getLastMeasurementTime() - firstMeasurement->time_ << " seconds in the past. Reverting filter state and measurement queue..."); int originalCount = static_cast(measurementQueue_.size()); const double firstMeasurementTime = firstMeasurement->time_; const std::string firstMeasurementTopic = firstMeasurement->topicName_; if (!revertTo(firstMeasurement->time_ - 1e-9)) // revertTo may invalidate firstMeasurement { RF_DEBUG("ERROR: history interval is too small to revert to time " << firstMeasurementTime << "\n"); ROS_WARN_STREAM_DELAYED_THROTTLE(historyLength_, "Received old measurement for topic " << firstMeasurementTopic << ", but history interval is insufficiently sized to revert state and " "measurement queue."); restoredMeasurementCount = 0; } restoredMeasurementCount = static_cast(measurementQueue_.size()) - originalCount; } while (!measurementQueue_.empty() && ros::ok()) { MeasurementPtr measurement = measurementQueue_.top(); // If we've reached a measurement that has a time later than now, it should wait until a future iteration. // Since measurements are stored in a priority queue, all remaining measurements will be in the future. if (measurement->time_ > currentTime.toSec()) { break; } measurementQueue_.pop(); // When we receive control messages, we call this directly in the control callback. However, we also associate // a control with each sensor message so that we can support lagged smoothing. As we cannot guarantee that the // new control callback will fire before a new measurement, we should only perform this operation if we are // processing messages from the history. Otherwise, we may get a new measurement, store the "old" latest // control, then receive a control, call setControl, and then overwrite that value with this one (i.e., with // the "old" control we associated with the measurement). if (useControl_ && restoredMeasurementCount > 0) { filter_.setControl(measurement->latestControl_, measurement->latestControlTime_); restoredMeasurementCount--; } // This will call predict and, if necessary, correct filter_.processMeasurement(*(measurement.get())); // Store old states and measurements if we're smoothing if (smoothLaggedData_) { // Invariant still holds: measurementHistoryDeque_.back().time_ < measurementQueue_.top().time_ measurementHistory_.push_back(measurement); // We should only save the filter state once per unique timstamp if (measurementQueue_.empty() || ::fabs(measurementQueue_.top()->time_ - filter_.getLastMeasurementTime()) > 1e-9) { saveFilterState(filter_); } } } } else if (filter_.getInitializedStatus()) { // In the event that we don't get any measurements for a long time, // we still need to continue to estimate our state. Therefore, we // should project the state forward here. double lastUpdateDelta = currentTimeSec - filter_.getLastMeasurementTime(); // If we get a large delta, then continuously predict until if (lastUpdateDelta >= filter_.getSensorTimeout()) { predictToCurrentTime = true; RF_DEBUG("Sensor timeout! Last measurement time was " << filter_.getLastMeasurementTime() << ", current time is " << currentTimeSec << ", delta is " << lastUpdateDelta << "\n"); } } else { RF_DEBUG("Filter not yet initialized.\n"); } if (filter_.getInitializedStatus() && predictToCurrentTime) { double lastUpdateDelta = currentTimeSec - filter_.getLastMeasurementTime(); filter_.validateDelta(lastUpdateDelta); filter_.predict(currentTimeSec, lastUpdateDelta); // Update the last measurement time and last update time filter_.setLastMeasurementTime(filter_.getLastMeasurementTime() + lastUpdateDelta); } RF_DEBUG("\n----- /RosFilter::integrateMeasurements ------\n"); } template void RosFilter::loadParams() { /* For diagnostic purposes, collect information about how many different * sources are measuring each absolute pose variable and do not have * differential integration enabled. */ std::map absPoseVarCounts; absPoseVarCounts[StateMemberX] = 0; absPoseVarCounts[StateMemberY] = 0; absPoseVarCounts[StateMemberZ] = 0; absPoseVarCounts[StateMemberRoll] = 0; absPoseVarCounts[StateMemberPitch] = 0; absPoseVarCounts[StateMemberYaw] = 0; // Same for twist variables std::map twistVarCounts; twistVarCounts[StateMemberVx] = 0; twistVarCounts[StateMemberVy] = 0; twistVarCounts[StateMemberVz] = 0; twistVarCounts[StateMemberVroll] = 0; twistVarCounts[StateMemberVpitch] = 0; twistVarCounts[StateMemberVyaw] = 0; // Determine if we'll be printing diagnostic information nhLocal_.param("print_diagnostics", printDiagnostics_, true); // Check for custom gravitational acceleration value nhLocal_.param("gravitational_acceleration", gravitationalAcc_, 9.80665); // Grab the debug param. If true, the node will produce a LOT of output. bool debug; nhLocal_.param("debug", debug, false); if (debug) { std::string debugOutFile; try { nhLocal_.param("debug_out_file", debugOutFile, std::string("robot_localization_debug.txt")); debugStream_.open(debugOutFile.c_str()); // Make sure we succeeded if (debugStream_.is_open()) { filter_.setDebug(debug, &debugStream_); } else { ROS_WARN_STREAM("RosFilter::loadParams() - unable to create debug output file " << debugOutFile); } } catch(const std::exception &e) { ROS_WARN_STREAM("RosFilter::loadParams() - unable to create debug output file" << debugOutFile << ". Error was " << e.what() << "\n"); } } // These params specify the name of the robot's body frame (typically // base_link) and odometry frame (typically odom) nhLocal_.param("map_frame", mapFrameId_, std::string("map")); nhLocal_.param("odom_frame", odomFrameId_, std::string("odom")); nhLocal_.param("base_link_frame", baseLinkFrameId_, std::string("base_link")); /* * These parameters are designed to enforce compliance with REP-105: * http://www.ros.org/reps/rep-0105.html * When fusing absolute position data from sensors such as GPS, the state * estimate can undergo discrete jumps. According to REP-105, we want three * coordinate frames: map, odom, and base_link. The map frame can have * discontinuities, but is the frame with the most accurate position estimate * for the robot and should not suffer from drift. The odom frame drifts over * time, but is guaranteed to be continuous and is accurate enough for local * planning and navigation. The base_link frame is affixed to the robot. The * intention is that some odometry source broadcasts the odom->base_link * transform. The localization software should broadcast map->base_link. * However, tf does not allow multiple parents for a coordinate frame, so * we must *compute* map->base_link, but then use the existing odom->base_link * transform to compute *and broadcast* map->odom. * * The state estimation nodes in robot_localization therefore have two "modes." * If your world_frame parameter value matches the odom_frame parameter value, * then robot_localization will assume someone else is broadcasting a transform * from odom_frame->base_link_frame, and it will compute the * map_frame->odom_frame transform. Otherwise, it will simply compute the * odom_frame->base_link_frame transform. * * The default is the latter behavior (broadcast of odom->base_link). */ nhLocal_.param("world_frame", worldFrameId_, odomFrameId_); ROS_FATAL_COND(mapFrameId_ == odomFrameId_ || odomFrameId_ == baseLinkFrameId_ || mapFrameId_ == baseLinkFrameId_, "Invalid frame configuration! The values for map_frame, odom_frame, " "and base_link_frame must be unique"); // Try to resolve tf_prefix std::string tfPrefix = ""; std::string tfPrefixPath = ""; if (nhLocal_.searchParam("tf_prefix", tfPrefixPath)) { nhLocal_.getParam(tfPrefixPath, tfPrefix); } // Append the tf prefix in a tf2-friendly manner FilterUtilities::appendPrefix(tfPrefix, mapFrameId_); FilterUtilities::appendPrefix(tfPrefix, odomFrameId_); FilterUtilities::appendPrefix(tfPrefix, baseLinkFrameId_); FilterUtilities::appendPrefix(tfPrefix, worldFrameId_); // Whether we're publshing the world_frame->base_link_frame transform nhLocal_.param("publish_tf", publishTransform_, true); // Whether we're publishing the acceleration state transform nhLocal_.param("publish_acceleration", publishAcceleration_, false); // Transform future dating double offsetTmp; nhLocal_.param("transform_time_offset", offsetTmp, 0.0); tfTimeOffset_.fromSec(offsetTmp); // Transform timeout double timeoutTmp; nhLocal_.param("transform_timeout", timeoutTmp, 0.0); tfTimeout_.fromSec(timeoutTmp); // Update frequency and sensor timeout double sensorTimeout; nhLocal_.param("frequency", frequency_, 30.0); nhLocal_.param("sensor_timeout", sensorTimeout, 1.0 / frequency_); filter_.setSensorTimeout(sensorTimeout); // Determine if we're in 2D mode nhLocal_.param("two_d_mode", twoDMode_, false); // Smoothing window size nhLocal_.param("smooth_lagged_data", smoothLaggedData_, false); nhLocal_.param("history_length", historyLength_, 0.0); // Wether we reset filter on jump back in time nhLocal_.param("reset_on_time_jump", resetOnTimeJump_, false); if (!smoothLaggedData_ && ::fabs(historyLength_) > 1e-9) { ROS_WARN_STREAM("Filter history interval of " << historyLength_ << " specified, but smooth_lagged_data is set to false. Lagged data will not be smoothed."); } if (smoothLaggedData_ && historyLength_ < -1e9) { ROS_WARN_STREAM("Negative history interval of " << historyLength_ << " specified. Absolute value will be assumed."); } historyLength_ = ::fabs(historyLength_); nhLocal_.param("predict_to_current_time", predictToCurrentTime_, false); // Determine if we're using a control term bool stampedControl = false; double controlTimeout = sensorTimeout; std::vector controlUpdateVector(TWIST_SIZE, 0); std::vector accelerationLimits(TWIST_SIZE, 1.0); std::vector accelerationGains(TWIST_SIZE, 1.0); std::vector decelerationLimits(TWIST_SIZE, 1.0); std::vector decelerationGains(TWIST_SIZE, 1.0); nhLocal_.param("use_control", useControl_, false); nhLocal_.param("stamped_control", stampedControl, false); nhLocal_.param("control_timeout", controlTimeout, sensorTimeout); if (useControl_) { if (nhLocal_.getParam("control_config", controlUpdateVector)) { if (controlUpdateVector.size() != TWIST_SIZE) { ROS_ERROR_STREAM("Control configuration must be of size " << TWIST_SIZE << ". Provided config was of " "size " << controlUpdateVector.size() << ". No control term will be used."); useControl_ = false; } } else { ROS_ERROR_STREAM("use_control is set to true, but control_config is missing. No control term will be used."); useControl_ = false; } if (nhLocal_.getParam("acceleration_limits", accelerationLimits)) { if (accelerationLimits.size() != TWIST_SIZE) { ROS_ERROR_STREAM("Acceleration configuration must be of size " << TWIST_SIZE << ". Provided config was of " "size " << accelerationLimits.size() << ". No control term will be used."); useControl_ = false; } } else { ROS_WARN_STREAM("use_control is set to true, but acceleration_limits is missing. Will use default values."); } if (nhLocal_.getParam("acceleration_gains", accelerationGains)) { const int size = accelerationGains.size(); if (size != TWIST_SIZE) { ROS_ERROR_STREAM("Acceleration gain configuration must be of size " << TWIST_SIZE << ". Provided config was of size " << size << ". All gains will be assumed to be 1."); std::fill_n(accelerationGains.begin(), std::min(size, TWIST_SIZE), 1.0); accelerationGains.resize(TWIST_SIZE, 1.0); } } if (nhLocal_.getParam("deceleration_limits", decelerationLimits)) { if (decelerationLimits.size() != TWIST_SIZE) { ROS_ERROR_STREAM("Deceleration configuration must be of size " << TWIST_SIZE << ". Provided config was of size " << decelerationLimits.size() << ". No control term will be used."); useControl_ = false; } } else { ROS_INFO_STREAM("use_control is set to true, but no deceleration_limits specified. Will use acceleration " "limits."); decelerationLimits = accelerationLimits; } if (nhLocal_.getParam("deceleration_gains", decelerationGains)) { const int size = decelerationGains.size(); if (size != TWIST_SIZE) { ROS_ERROR_STREAM("Deceleration gain configuration must be of size " << TWIST_SIZE << ". Provided config was of size " << size << ". All gains will be assumed to be 1."); std::fill_n(decelerationGains.begin(), std::min(size, TWIST_SIZE), 1.0); decelerationGains.resize(TWIST_SIZE, 1.0); } } else { ROS_INFO_STREAM("use_control is set to true, but no deceleration_gains specified. Will use acceleration " "gains."); decelerationGains = accelerationGains; } } bool dynamicProcessNoiseCovariance = false; nhLocal_.param("dynamic_process_noise_covariance", dynamicProcessNoiseCovariance, false); filter_.setUseDynamicProcessNoiseCovariance(dynamicProcessNoiseCovariance); std::vector initialState(STATE_SIZE, 0.0); if (nhLocal_.getParam("initial_state", initialState)) { if (initialState.size() != STATE_SIZE) { ROS_ERROR_STREAM("Initial state must be of size " << STATE_SIZE << ". Provided config was of size " << initialState.size() << ". The initial state will be ignored."); } else { Eigen::Map eigenState(initialState.data(), initialState.size()); filter_.setState(eigenState); } } // Check if the filter should start or not nhLocal_.param("disabled_at_startup", disabledAtStartup_, false); enabled_ = !disabledAtStartup_; // Debugging writes to file RF_DEBUG("tf_prefix is " << tfPrefix << "\nmap_frame is " << mapFrameId_ << "\nodom_frame is " << odomFrameId_ << "\nbase_link_frame is " << baseLinkFrameId_ << "\nworld_frame is " << worldFrameId_ << "\ntransform_time_offset is " << tfTimeOffset_.toSec() << "\ntransform_timeout is " << tfTimeout_.toSec() << "\nfrequency is " << frequency_ << "\nsensor_timeout is " << filter_.getSensorTimeout() << "\ntwo_d_mode is " << (twoDMode_ ? "true" : "false") << "\nsmooth_lagged_data is " << (smoothLaggedData_ ? "true" : "false") << "\nhistory_length is " << historyLength_ << "\nuse_control is " << (useControl_ ? "true" : "false") << "\nstamped_control is " << (stampedControl ? "true" : "false") << "\ncontrol_config is " << controlUpdateVector << "\ncontrol_timeout is " << controlTimeout << "\nacceleration_limits are " << accelerationLimits << "\nacceleration_gains are " << accelerationGains << "\ndeceleration_limits are " << decelerationLimits << "\ndeceleration_gains are " << decelerationGains << "\ninitial state is " << filter_.getState() << "\ndynamic_process_noise_covariance is " << (dynamicProcessNoiseCovariance ? "true" : "false") << "\nprint_diagnostics is " << (printDiagnostics_ ? "true" : "false") << "\n"); // Create a subscriber for manually setting/resetting pose setPoseSub_ = nh_.subscribe("set_pose", 1, &RosFilter::setPoseCallback, this, ros::TransportHints().tcpNoDelay(false)); // Create a service for manually setting/resetting pose setPoseSrv_ = nh_.advertiseService("set_pose", &RosFilter::setPoseSrvCallback, this); // Create a service for manually enabling the filter enableFilterSrv_ = nhLocal_.advertiseService("enable", &RosFilter::enableFilterSrvCallback, this); // Init the last last measurement time so we don't get a huge initial delta filter_.setLastMeasurementTime(ros::Time::now().toSec()); // Now pull in each topic to which we want to subscribe. // Start with odom. size_t topicInd = 0; bool moreParams = false; do { // Build the string in the form of "odomX", where X is the odom topic number, // then check if we have any parameters with that value. Users need to make // sure they don't have gaps in their configs (e.g., odom0 and then odom2) std::stringstream ss; ss << "odom" << topicInd++; std::string odomTopicName = ss.str(); moreParams = nhLocal_.hasParam(odomTopicName); if (moreParams) { // Determine if we want to integrate this sensor differentially bool differential; nhLocal_.param(odomTopicName + std::string("_differential"), differential, false); // Determine if we want to integrate this sensor relatively bool relative; nhLocal_.param(odomTopicName + std::string("_relative"), relative, false); if (relative && differential) { ROS_WARN_STREAM("Both " << odomTopicName << "_differential" << " and " << odomTopicName << "_relative were set to true. Using differential mode."); relative = false; } std::string odomTopic; nhLocal_.getParam(odomTopicName, odomTopic); // Check for pose rejection threshold double poseMahalanobisThresh; nhLocal_.param(odomTopicName + std::string("_pose_rejection_threshold"), poseMahalanobisThresh, std::numeric_limits::max()); // Check for twist rejection threshold double twistMahalanobisThresh; nhLocal_.param(odomTopicName + std::string("_twist_rejection_threshold"), twistMahalanobisThresh, std::numeric_limits::max()); // Now pull in its boolean update vector configuration. Create separate vectors for pose // and twist data, and then zero out the opposite values in each vector (no pose data in // the twist update vector and vice-versa). std::vector updateVec = loadUpdateConfig(odomTopicName); std::vector poseUpdateVec = updateVec; std::fill(poseUpdateVec.begin() + POSITION_V_OFFSET, poseUpdateVec.begin() + POSITION_V_OFFSET + TWIST_SIZE, 0); std::vector twistUpdateVec = updateVec; std::fill(twistUpdateVec.begin() + POSITION_OFFSET, twistUpdateVec.begin() + POSITION_OFFSET + POSE_SIZE, 0); int poseUpdateSum = std::accumulate(poseUpdateVec.begin(), poseUpdateVec.end(), 0); int twistUpdateSum = std::accumulate(twistUpdateVec.begin(), twistUpdateVec.end(), 0); int odomQueueSize = 1; nhLocal_.param(odomTopicName + "_queue_size", odomQueueSize, 1); const CallbackData poseCallbackData(odomTopicName + "_pose", poseUpdateVec, poseUpdateSum, differential, relative, poseMahalanobisThresh); const CallbackData twistCallbackData(odomTopicName + "_twist", twistUpdateVec, twistUpdateSum, false, false, twistMahalanobisThresh); bool nodelayOdom = false; nhLocal_.param(odomTopicName + "_nodelay", nodelayOdom, false); // Store the odometry topic subscribers so they don't go out of scope. if (poseUpdateSum + twistUpdateSum > 0) { topicSubs_.push_back( nh_.subscribe(odomTopic, odomQueueSize, boost::bind(&RosFilter::odometryCallback, this, _1, odomTopicName, poseCallbackData, twistCallbackData), ros::VoidPtr(), ros::TransportHints().tcpNoDelay(nodelayOdom))); } else { std::stringstream stream; stream << odomTopic << " is listed as an input topic, but all update variables are false"; addDiagnostic(diagnostic_msgs::DiagnosticStatus::WARN, odomTopic + "_configuration", stream.str(), true); } if (poseUpdateSum > 0) { if (differential) { twistVarCounts[StateMemberVx] += poseUpdateVec[StateMemberX]; twistVarCounts[StateMemberVy] += poseUpdateVec[StateMemberY]; twistVarCounts[StateMemberVz] += poseUpdateVec[StateMemberZ]; twistVarCounts[StateMemberVroll] += poseUpdateVec[StateMemberRoll]; twistVarCounts[StateMemberVpitch] += poseUpdateVec[StateMemberPitch]; twistVarCounts[StateMemberVyaw] += poseUpdateVec[StateMemberYaw]; } else { absPoseVarCounts[StateMemberX] += poseUpdateVec[StateMemberX]; absPoseVarCounts[StateMemberY] += poseUpdateVec[StateMemberY]; absPoseVarCounts[StateMemberZ] += poseUpdateVec[StateMemberZ]; absPoseVarCounts[StateMemberRoll] += poseUpdateVec[StateMemberRoll]; absPoseVarCounts[StateMemberPitch] += poseUpdateVec[StateMemberPitch]; absPoseVarCounts[StateMemberYaw] += poseUpdateVec[StateMemberYaw]; } } if (twistUpdateSum > 0) { twistVarCounts[StateMemberVx] += twistUpdateVec[StateMemberVx]; twistVarCounts[StateMemberVy] += twistUpdateVec[StateMemberVx]; twistVarCounts[StateMemberVz] += twistUpdateVec[StateMemberVz]; twistVarCounts[StateMemberVroll] += twistUpdateVec[StateMemberVroll]; twistVarCounts[StateMemberVpitch] += twistUpdateVec[StateMemberVpitch]; twistVarCounts[StateMemberVyaw] += twistUpdateVec[StateMemberVyaw]; } RF_DEBUG("Subscribed to " << odomTopic << " (" << odomTopicName << ")\n\t" << odomTopicName << "_differential is " << (differential ? "true" : "false") << "\n\t" << odomTopicName << "_pose_rejection_threshold is " << poseMahalanobisThresh << "\n\t" << odomTopicName << "_twist_rejection_threshold is " << twistMahalanobisThresh << "\n\t" << odomTopicName << "_queue_size is " << odomQueueSize << "\n\t" << odomTopicName << " pose update vector is " << poseUpdateVec << "\t"<< odomTopicName << " twist update vector is " << twistUpdateVec); } } while (moreParams); // Repeat for pose topicInd = 0; moreParams = false; do { std::stringstream ss; ss << "pose" << topicInd++; std::string poseTopicName = ss.str(); moreParams = nhLocal_.hasParam(poseTopicName); if (moreParams) { bool differential; nhLocal_.param(poseTopicName + std::string("_differential"), differential, false); // Determine if we want to integrate this sensor relatively bool relative; nhLocal_.param(poseTopicName + std::string("_relative"), relative, false); if (relative && differential) { ROS_WARN_STREAM("Both " << poseTopicName << "_differential" << " and " << poseTopicName << "_relative were set to true. Using differential mode."); relative = false; } std::string poseTopic; nhLocal_.getParam(poseTopicName, poseTopic); // Check for pose rejection threshold double poseMahalanobisThresh; nhLocal_.param(poseTopicName + std::string("_rejection_threshold"), poseMahalanobisThresh, std::numeric_limits::max()); int poseQueueSize = 1; nhLocal_.param(poseTopicName + "_queue_size", poseQueueSize, 1); bool nodelayPose = false; nhLocal_.param(poseTopicName + "_nodelay", nodelayPose, false); // Pull in the sensor's config, zero out values that are invalid for the pose type std::vector poseUpdateVec = loadUpdateConfig(poseTopicName); std::fill(poseUpdateVec.begin() + POSITION_V_OFFSET, poseUpdateVec.begin() + POSITION_V_OFFSET + TWIST_SIZE, 0); std::fill(poseUpdateVec.begin() + POSITION_A_OFFSET, poseUpdateVec.begin() + POSITION_A_OFFSET + ACCELERATION_SIZE, 0); int poseUpdateSum = std::accumulate(poseUpdateVec.begin(), poseUpdateVec.end(), 0); if (poseUpdateSum > 0) { const CallbackData callbackData(poseTopicName, poseUpdateVec, poseUpdateSum, differential, relative, poseMahalanobisThresh); topicSubs_.push_back( nh_.subscribe(poseTopic, poseQueueSize, boost::bind(&RosFilter::poseCallback, this, _1, callbackData, worldFrameId_, false), ros::VoidPtr(), ros::TransportHints().tcpNoDelay(nodelayPose))); if (differential) { twistVarCounts[StateMemberVx] += poseUpdateVec[StateMemberX]; twistVarCounts[StateMemberVy] += poseUpdateVec[StateMemberY]; twistVarCounts[StateMemberVz] += poseUpdateVec[StateMemberZ]; twistVarCounts[StateMemberVroll] += poseUpdateVec[StateMemberRoll]; twistVarCounts[StateMemberVpitch] += poseUpdateVec[StateMemberPitch]; twistVarCounts[StateMemberVyaw] += poseUpdateVec[StateMemberYaw]; } else { absPoseVarCounts[StateMemberX] += poseUpdateVec[StateMemberX]; absPoseVarCounts[StateMemberY] += poseUpdateVec[StateMemberY]; absPoseVarCounts[StateMemberZ] += poseUpdateVec[StateMemberZ]; absPoseVarCounts[StateMemberRoll] += poseUpdateVec[StateMemberRoll]; absPoseVarCounts[StateMemberPitch] += poseUpdateVec[StateMemberPitch]; absPoseVarCounts[StateMemberYaw] += poseUpdateVec[StateMemberYaw]; } } else { ROS_WARN_STREAM("Warning: " << poseTopic << " is listed as an input topic, " "but all pose update variables are false"); } RF_DEBUG("Subscribed to " << poseTopic << " (" << poseTopicName << ")\n\t" << poseTopicName << "_differential is " << (differential ? "true" : "false") << "\n\t" << poseTopicName << "_rejection_threshold is " << poseMahalanobisThresh << "\n\t" << poseTopicName << "_queue_size is " << poseQueueSize << "\n\t" << poseTopicName << " update vector is " << poseUpdateVec); } } while (moreParams); // Repeat for twist topicInd = 0; moreParams = false; do { std::stringstream ss; ss << "twist" << topicInd++; std::string twistTopicName = ss.str(); moreParams = nhLocal_.hasParam(twistTopicName); if (moreParams) { std::string twistTopic; nhLocal_.getParam(twistTopicName, twistTopic); // Check for twist rejection threshold double twistMahalanobisThresh; nhLocal_.param(twistTopicName + std::string("_rejection_threshold"), twistMahalanobisThresh, std::numeric_limits::max()); int twistQueueSize = 1; nhLocal_.param(twistTopicName + "_queue_size", twistQueueSize, 1); bool nodelayTwist = false; nhLocal_.param(twistTopicName + "_nodelay", nodelayTwist, false); // Pull in the sensor's config, zero out values that are invalid for the twist type std::vector twistUpdateVec = loadUpdateConfig(twistTopicName); std::fill(twistUpdateVec.begin() + POSITION_OFFSET, twistUpdateVec.begin() + POSITION_OFFSET + POSE_SIZE, 0); int twistUpdateSum = std::accumulate(twistUpdateVec.begin(), twistUpdateVec.end(), 0); if (twistUpdateSum > 0) { const CallbackData callbackData(twistTopicName, twistUpdateVec, twistUpdateSum, false, false, twistMahalanobisThresh); topicSubs_.push_back( nh_.subscribe(twistTopic, twistQueueSize, boost::bind(&RosFilter::twistCallback, this, _1, callbackData, baseLinkFrameId_), ros::VoidPtr(), ros::TransportHints().tcpNoDelay(nodelayTwist))); twistVarCounts[StateMemberVx] += twistUpdateVec[StateMemberVx]; twistVarCounts[StateMemberVy] += twistUpdateVec[StateMemberVy]; twistVarCounts[StateMemberVz] += twistUpdateVec[StateMemberVz]; twistVarCounts[StateMemberVroll] += twistUpdateVec[StateMemberVroll]; twistVarCounts[StateMemberVpitch] += twistUpdateVec[StateMemberVpitch]; twistVarCounts[StateMemberVyaw] += twistUpdateVec[StateMemberVyaw]; } else { ROS_WARN_STREAM("Warning: " << twistTopic << " is listed as an input topic, " "but all twist update variables are false"); } RF_DEBUG("Subscribed to " << twistTopic << " (" << twistTopicName << ")\n\t" << twistTopicName << "_rejection_threshold is " << twistMahalanobisThresh << "\n\t" << twistTopicName << "_queue_size is " << twistQueueSize << "\n\t" << twistTopicName << " update vector is " << twistUpdateVec); } } while (moreParams); // Repeat for IMU topicInd = 0; moreParams = false; do { std::stringstream ss; ss << "imu" << topicInd++; std::string imuTopicName = ss.str(); moreParams = nhLocal_.hasParam(imuTopicName); if (moreParams) { bool differential; nhLocal_.param(imuTopicName + std::string("_differential"), differential, false); // Determine if we want to integrate this sensor relatively bool relative; nhLocal_.param(imuTopicName + std::string("_relative"), relative, false); if (relative && differential) { ROS_WARN_STREAM("Both " << imuTopicName << "_differential" << " and " << imuTopicName << "_relative were set to true. Using differential mode."); relative = false; } std::string imuTopic; nhLocal_.getParam(imuTopicName, imuTopic); // Check for pose rejection threshold double poseMahalanobisThresh; nhLocal_.param(imuTopicName + std::string("_pose_rejection_threshold"), poseMahalanobisThresh, std::numeric_limits::max()); // Check for angular velocity rejection threshold double twistMahalanobisThresh; std::string imuTwistRejectionName = imuTopicName + std::string("_twist_rejection_threshold"); nhLocal_.param(imuTwistRejectionName, twistMahalanobisThresh, std::numeric_limits::max()); // Check for acceleration rejection threshold double accelMahalanobisThresh; nhLocal_.param(imuTopicName + std::string("_linear_acceleration_rejection_threshold"), accelMahalanobisThresh, std::numeric_limits::max()); bool removeGravAcc = false; nhLocal_.param(imuTopicName + "_remove_gravitational_acceleration", removeGravAcc, false); removeGravitationalAcc_[imuTopicName + "_acceleration"] = removeGravAcc; // Now pull in its boolean update vector configuration and differential // update configuration (as this contains pose information) std::vector updateVec = loadUpdateConfig(imuTopicName); std::vector poseUpdateVec = updateVec; std::fill(poseUpdateVec.begin() + POSITION_V_OFFSET, poseUpdateVec.begin() + POSITION_V_OFFSET + TWIST_SIZE, 0); std::fill(poseUpdateVec.begin() + POSITION_A_OFFSET, poseUpdateVec.begin() + POSITION_A_OFFSET + ACCELERATION_SIZE, 0); std::vector twistUpdateVec = updateVec; std::fill(twistUpdateVec.begin() + POSITION_OFFSET, twistUpdateVec.begin() + POSITION_OFFSET + POSE_SIZE, 0); std::fill(twistUpdateVec.begin() + POSITION_A_OFFSET, twistUpdateVec.begin() + POSITION_A_OFFSET + ACCELERATION_SIZE, 0); std::vector accelUpdateVec = updateVec; std::fill(accelUpdateVec.begin() + POSITION_OFFSET, accelUpdateVec.begin() + POSITION_OFFSET + POSE_SIZE, 0); std::fill(accelUpdateVec.begin() + POSITION_V_OFFSET, accelUpdateVec.begin() + POSITION_V_OFFSET + TWIST_SIZE, 0); int poseUpdateSum = std::accumulate(poseUpdateVec.begin(), poseUpdateVec.end(), 0); int twistUpdateSum = std::accumulate(twistUpdateVec.begin(), twistUpdateVec.end(), 0); int accelUpdateSum = std::accumulate(accelUpdateVec.begin(), accelUpdateVec.end(), 0); // Check if we're using control input for any of the acceleration variables; turn off if so if (static_cast(controlUpdateVector[ControlMemberVx]) && static_cast(accelUpdateVec[StateMemberAx])) { ROS_WARN_STREAM("X acceleration is being measured from IMU; X velocity control input is disabled"); controlUpdateVector[ControlMemberVx] = 0; } if (static_cast(controlUpdateVector[ControlMemberVy]) && static_cast(accelUpdateVec[StateMemberAy])) { ROS_WARN_STREAM("Y acceleration is being measured from IMU; Y velocity control input is disabled"); controlUpdateVector[ControlMemberVy] = 0; } if (static_cast(controlUpdateVector[ControlMemberVz]) && static_cast(accelUpdateVec[StateMemberAz])) { ROS_WARN_STREAM("Z acceleration is being measured from IMU; Z velocity control input is disabled"); controlUpdateVector[ControlMemberVz] = 0; } int imuQueueSize = 1; nhLocal_.param(imuTopicName + "_queue_size", imuQueueSize, 1); bool nodelayImu = false; nhLocal_.param(imuTopicName + "_nodelay", nodelayImu, false); if (poseUpdateSum + twistUpdateSum + accelUpdateSum > 0) { const CallbackData poseCallbackData(imuTopicName + "_pose", poseUpdateVec, poseUpdateSum, differential, relative, poseMahalanobisThresh); const CallbackData twistCallbackData(imuTopicName + "_twist", twistUpdateVec, twistUpdateSum, differential, relative, twistMahalanobisThresh); const CallbackData accelCallbackData(imuTopicName + "_acceleration", accelUpdateVec, accelUpdateSum, differential, relative, accelMahalanobisThresh); topicSubs_.push_back( nh_.subscribe(imuTopic, imuQueueSize, boost::bind(&RosFilter::imuCallback, this, _1, imuTopicName, poseCallbackData, twistCallbackData, accelCallbackData), ros::VoidPtr(), ros::TransportHints().tcpNoDelay(nodelayImu))); } else { ROS_WARN_STREAM("Warning: " << imuTopic << " is listed as an input topic, " "but all its update variables are false"); } if (poseUpdateSum > 0) { if (differential) { twistVarCounts[StateMemberVroll] += poseUpdateVec[StateMemberRoll]; twistVarCounts[StateMemberVpitch] += poseUpdateVec[StateMemberPitch]; twistVarCounts[StateMemberVyaw] += poseUpdateVec[StateMemberYaw]; } else { absPoseVarCounts[StateMemberRoll] += poseUpdateVec[StateMemberRoll]; absPoseVarCounts[StateMemberPitch] += poseUpdateVec[StateMemberPitch]; absPoseVarCounts[StateMemberYaw] += poseUpdateVec[StateMemberYaw]; } } if (twistUpdateSum > 0) { twistVarCounts[StateMemberVroll] += twistUpdateVec[StateMemberVroll]; twistVarCounts[StateMemberVpitch] += twistUpdateVec[StateMemberVpitch]; twistVarCounts[StateMemberVyaw] += twistUpdateVec[StateMemberVyaw]; } RF_DEBUG("Subscribed to " << imuTopic << " (" << imuTopicName << ")\n\t" << imuTopicName << "_differential is " << (differential ? "true" : "false") << "\n\t" << imuTopicName << "_pose_rejection_threshold is " << poseMahalanobisThresh << "\n\t" << imuTopicName << "_twist_rejection_threshold is " << twistMahalanobisThresh << "\n\t" << imuTopicName << "_linear_acceleration_rejection_threshold is " << accelMahalanobisThresh << "\n\t" << imuTopicName << "_remove_gravitational_acceleration is " << (removeGravAcc ? "true" : "false") << "\n\t" << imuTopicName << "_queue_size is " << imuQueueSize << "\n\t" << imuTopicName << " pose update vector is " << poseUpdateVec << "\t"<< imuTopicName << " twist update vector is " << twistUpdateVec << "\t" << imuTopicName << " acceleration update vector is " << accelUpdateVec); } } while (moreParams); // Now that we've checked if IMU linear acceleration is being used, we can determine our final control parameters if (useControl_ && std::accumulate(controlUpdateVector.begin(), controlUpdateVector.end(), 0) == 0) { ROS_ERROR_STREAM("use_control is set to true, but control_config has only false values. No control term " "will be used."); useControl_ = false; } // If we're using control, set the parameters and create the necessary subscribers if (useControl_) { latestControl_.resize(TWIST_SIZE); latestControl_.setZero(); filter_.setControlParams(controlUpdateVector, controlTimeout, accelerationLimits, accelerationGains, decelerationLimits, decelerationGains); if (stampedControl) { controlSub_ = nh_.subscribe("cmd_vel", 1, &RosFilter::controlCallback, this); } else { controlSub_ = nh_.subscribe("cmd_vel", 1, &RosFilter::controlCallback, this); } } /* Warn users about: * 1. Multiple non-differential input sources * 2. No absolute *or* velocity measurements for pose variables */ if (printDiagnostics_) { for (int stateVar = StateMemberX; stateVar <= StateMemberYaw; ++stateVar) { if (absPoseVarCounts[static_cast(stateVar)] > 1) { std::stringstream stream; stream << absPoseVarCounts[static_cast(stateVar - POSITION_OFFSET)] << " absolute pose inputs detected for " << stateVariableNames_[stateVar] << ". This may result in oscillations. Please ensure that your variances for each " "measured variable are set appropriately."; addDiagnostic(diagnostic_msgs::DiagnosticStatus::WARN, stateVariableNames_[stateVar] + "_configuration", stream.str(), true); } else if (absPoseVarCounts[static_cast(stateVar)] == 0) { if ((static_cast(stateVar) == StateMemberX && twistVarCounts[static_cast(StateMemberVx)] == 0) || (static_cast(stateVar) == StateMemberY && twistVarCounts[static_cast(StateMemberVy)] == 0) || (static_cast(stateVar) == StateMemberZ && twistVarCounts[static_cast(StateMemberVz)] == 0 && twoDMode_ == false) || (static_cast(stateVar) == StateMemberRoll && twistVarCounts[static_cast(StateMemberVroll)] == 0 && twoDMode_ == false) || (static_cast(stateVar) == StateMemberPitch && twistVarCounts[static_cast(StateMemberVpitch)] == 0 && twoDMode_ == false) || (static_cast(stateVar) == StateMemberYaw && twistVarCounts[static_cast(StateMemberVyaw)] == 0)) { std::stringstream stream; stream << "Neither " << stateVariableNames_[stateVar] << " nor its " "velocity is being measured. This will result in unbounded " "error growth and erratic filter behavior."; addDiagnostic(diagnostic_msgs::DiagnosticStatus::ERROR, stateVariableNames_[stateVar] + "_configuration", stream.str(), true); } } } } // Load up the process noise covariance (from the launch file/parameter server) Eigen::MatrixXd processNoiseCovariance(STATE_SIZE, STATE_SIZE); processNoiseCovariance.setZero(); XmlRpc::XmlRpcValue processNoiseCovarConfig; if (nhLocal_.hasParam("process_noise_covariance")) { try { nhLocal_.getParam("process_noise_covariance", processNoiseCovarConfig); ROS_ASSERT(processNoiseCovarConfig.getType() == XmlRpc::XmlRpcValue::TypeArray); int matSize = processNoiseCovariance.rows(); for (int i = 0; i < matSize; i++) { for (int j = 0; j < matSize; j++) { try { // These matrices can cause problems if all the types // aren't specified with decimal points. Handle that // using string streams. std::ostringstream ostr; ostr << processNoiseCovarConfig[matSize * i + j]; std::istringstream istr(ostr.str()); istr >> processNoiseCovariance(i, j); } catch(XmlRpc::XmlRpcException &e) { throw e; } catch(...) { throw; } } } RF_DEBUG("Process noise covariance is:\n" << processNoiseCovariance << "\n"); } catch (XmlRpc::XmlRpcException &e) { ROS_ERROR_STREAM("ERROR reading sensor config: " << e.getMessage() << " for process_noise_covariance (type: " << processNoiseCovarConfig.getType() << ")"); } filter_.setProcessNoiseCovariance(processNoiseCovariance); } // Load up the process noise covariance (from the launch file/parameter server) Eigen::MatrixXd initialEstimateErrorCovariance(STATE_SIZE, STATE_SIZE); initialEstimateErrorCovariance.setZero(); XmlRpc::XmlRpcValue estimateErrorCovarConfig; if (nhLocal_.hasParam("initial_estimate_covariance")) { try { nhLocal_.getParam("initial_estimate_covariance", estimateErrorCovarConfig); ROS_ASSERT(estimateErrorCovarConfig.getType() == XmlRpc::XmlRpcValue::TypeArray); int matSize = initialEstimateErrorCovariance.rows(); for (int i = 0; i < matSize; i++) { for (int j = 0; j < matSize; j++) { try { // These matrices can cause problems if all the types // aren't specified with decimal points. Handle that // using string streams. std::ostringstream ostr; ostr << estimateErrorCovarConfig[matSize * i + j]; std::istringstream istr(ostr.str()); istr >> initialEstimateErrorCovariance(i, j); } catch(XmlRpc::XmlRpcException &e) { throw e; } catch(...) { throw; } } } RF_DEBUG("Initial estimate error covariance is:\n" << initialEstimateErrorCovariance << "\n"); } catch (XmlRpc::XmlRpcException &e) { ROS_ERROR_STREAM("ERROR reading initial_estimate_covariance (type: " << estimateErrorCovarConfig.getType() << "): " << e.getMessage()); } catch(...) { ROS_ERROR_STREAM( "ERROR reading initial_estimate_covariance (type: " << estimateErrorCovarConfig.getType() << ")"); } filter_.setEstimateErrorCovariance(initialEstimateErrorCovariance); } } template void RosFilter::odometryCallback(const nav_msgs::Odometry::ConstPtr &msg, const std::string &topicName, const CallbackData &poseCallbackData, const CallbackData &twistCallbackData) { // If we've just reset the filter, then we want to ignore any messages // that arrive with an older timestamp if (msg->header.stamp <= lastSetPoseTime_) { std::stringstream stream; stream << "The " << topicName << " message has a timestamp equal to or before the last filter reset, " << "this message will be ignored. This may indicate an empty or bad timestamp. (message time: " << msg->header.stamp.toSec() << ")"; addDiagnostic(diagnostic_msgs::DiagnosticStatus::WARN, topicName + "_timestamp", stream.str(), false); RF_DEBUG("Received message that preceded the most recent pose reset. Ignoring..."); return; } RF_DEBUG("------ RosFilter::odometryCallback (" << topicName << ") ------\n" << "Odometry message:\n" << *msg); if (poseCallbackData.updateSum_ > 0) { // Grab the pose portion of the message and pass it to the poseCallback geometry_msgs::PoseWithCovarianceStamped *posPtr = new geometry_msgs::PoseWithCovarianceStamped(); posPtr->header = msg->header; posPtr->pose = msg->pose; // Entire pose object, also copies covariance geometry_msgs::PoseWithCovarianceStampedConstPtr pptr(posPtr); poseCallback(pptr, poseCallbackData, worldFrameId_, false); } if (twistCallbackData.updateSum_ > 0) { // Grab the twist portion of the message and pass it to the twistCallback geometry_msgs::TwistWithCovarianceStamped *twistPtr = new geometry_msgs::TwistWithCovarianceStamped(); twistPtr->header = msg->header; twistPtr->header.frame_id = msg->child_frame_id; twistPtr->twist = msg->twist; // Entire twist object, also copies covariance geometry_msgs::TwistWithCovarianceStampedConstPtr tptr(twistPtr); twistCallback(tptr, twistCallbackData, baseLinkFrameId_); } RF_DEBUG("\n----- /RosFilter::odometryCallback (" << topicName << ") ------\n"); } template void RosFilter::poseCallback(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &msg, const CallbackData &callbackData, const std::string &targetFrame, const bool imuData) { const std::string &topicName = callbackData.topicName_; // If we've just reset the filter, then we want to ignore any messages // that arrive with an older timestamp if (msg->header.stamp <= lastSetPoseTime_) { std::stringstream stream; stream << "The " << topicName << " message has a timestamp equal to or before the last filter reset, " << "this message will be ignored. This may indicate an empty or bad timestamp. (message time: " << msg->header.stamp.toSec() << ")"; addDiagnostic(diagnostic_msgs::DiagnosticStatus::WARN, topicName + "_timestamp", stream.str(), false); return; } RF_DEBUG("------ RosFilter::poseCallback (" << topicName << ") ------\n" << "Pose message:\n" << *msg); // Put the initial value in the lastMessagTimes_ for this variable if it's empty if (lastMessageTimes_.count(topicName) == 0) { lastMessageTimes_.insert(std::pair(topicName, msg->header.stamp)); } // Make sure this message is newer than the last one if (msg->header.stamp >= lastMessageTimes_[topicName]) { RF_DEBUG("Update vector for " << topicName << " is:\n" << callbackData.updateVector_); Eigen::VectorXd measurement(STATE_SIZE); Eigen::MatrixXd measurementCovariance(STATE_SIZE, STATE_SIZE); measurement.setZero(); measurementCovariance.setZero(); // Make sure we're actually updating at least one of these variables std::vector updateVectorCorrected = callbackData.updateVector_; // Prepare the pose data for inclusion in the filter if (preparePose(msg, topicName, targetFrame, callbackData.differential_, callbackData.relative_, imuData, updateVectorCorrected, measurement, measurementCovariance)) { // Store the measurement. Add a "pose" suffix so we know what kind of measurement // we're dealing with when we debug the core filter logic. enqueueMeasurement(topicName, measurement, measurementCovariance, updateVectorCorrected, callbackData.rejectionThreshold_, msg->header.stamp); RF_DEBUG("Enqueued new measurement for " << topicName << "\n"); } else { RF_DEBUG("Did *not* enqueue measurement for " << topicName << "\n"); } lastMessageTimes_[topicName] = msg->header.stamp; RF_DEBUG("Last message time for " << topicName << " is now " << lastMessageTimes_[topicName] << "\n"); } else if (resetOnTimeJump_ && ros::Time::isSimTime()) { reset(); } else { std::stringstream stream; stream << "The " << topicName << " message has a timestamp before that of the previous message received," << " this message will be ignored. This may indicate a bad timestamp. (message time: " << msg->header.stamp.toSec() << ")"; addDiagnostic(diagnostic_msgs::DiagnosticStatus::WARN, topicName + "_timestamp", stream.str(), false); RF_DEBUG("Message is too old. Last message time for " << topicName << " is " << lastMessageTimes_[topicName] << ", current message time is " << msg->header.stamp << ".\n"); } RF_DEBUG("\n----- /RosFilter::poseCallback (" << topicName << ") ------\n"); } template void RosFilter::run() { ROS_INFO("Waiting for valid clock time..."); ros::Time::waitForValid(); ROS_INFO("Valid clock time received. Starting node."); loadParams(); if (printDiagnostics_) { diagnosticUpdater_.add("Filter diagnostic updater", this, &RosFilter::aggregateDiagnostics); } // Set up the frequency diagnostic double minFrequency = frequency_ - 2; double maxFrequency = frequency_ + 2; diagnostic_updater::HeaderlessTopicDiagnostic freqDiag("odometry/filtered", diagnosticUpdater_, diagnostic_updater::FrequencyStatusParam(&minFrequency, &maxFrequency, 0.1, 10)); // We may need to broadcast a different transform than // the one we've already calculated. tf2::Transform mapOdomTrans; tf2::Transform odomBaseLinkTrans; geometry_msgs::TransformStamped mapOdomTransMsg; ros::Time curTime; ros::Time lastDiagTime = ros::Time::now(); // Clear out the transforms worldBaseLinkTransMsg_.transform = tf2::toMsg(tf2::Transform::getIdentity()); mapOdomTransMsg.transform = tf2::toMsg(tf2::Transform::getIdentity()); // Publisher ros::Publisher positionPub = nh_.advertise("odometry/filtered", 20); tf2_ros::TransformBroadcaster worldTransformBroadcaster; // Optional acceleration publisher ros::Publisher accelPub; if (publishAcceleration_) { accelPub = nh_.advertise("accel/filtered", 20); } const ros::Duration loop_cycle_time(1.0 / frequency_); ros::Time loop_end_time = ros::Time::now(); // Wait for the filter to be enabled while (!enabled_ && ros::ok()) { ROS_WARN_STREAM_ONCE("[" << ros::this_node::getName() << ":] This filter is disabled. To enable it call the service " << ros::this_node::getName() << "/enable"); ros::spinOnce(); if (enabled_) { break; } } while (ros::ok()) { // The spin will call all the available callbacks and enqueue // their received measurements ros::spinOnce(); curTime = ros::Time::now(); // Now we'll integrate any measurements we've received integrateMeasurements(curTime); // Get latest state and publish it nav_msgs::Odometry filteredPosition; if (getFilteredOdometryMessage(filteredPosition)) { worldBaseLinkTransMsg_.header.stamp = filteredPosition.header.stamp + tfTimeOffset_; worldBaseLinkTransMsg_.header.frame_id = filteredPosition.header.frame_id; worldBaseLinkTransMsg_.child_frame_id = filteredPosition.child_frame_id; worldBaseLinkTransMsg_.transform.translation.x = filteredPosition.pose.pose.position.x; worldBaseLinkTransMsg_.transform.translation.y = filteredPosition.pose.pose.position.y; worldBaseLinkTransMsg_.transform.translation.z = filteredPosition.pose.pose.position.z; worldBaseLinkTransMsg_.transform.rotation = filteredPosition.pose.pose.orientation; // the filteredPosition is the message containing the state and covariances: nav_msgs Odometry if (!validateFilterOutput(filteredPosition)) { ROS_ERROR_STREAM("Critical Error, NaNs were detected in the output state of the filter." << " This was likely due to poorly coniditioned process, noise, or sensor covariances."); } // If the worldFrameId_ is the odomFrameId_ frame, then we can just send the transform. If the // worldFrameId_ is the mapFrameId_ frame, we'll have some work to do. if (publishTransform_) { if (filteredPosition.header.frame_id == odomFrameId_) { worldTransformBroadcaster.sendTransform(worldBaseLinkTransMsg_); } else if (filteredPosition.header.frame_id == mapFrameId_) { try { tf2::Transform worldBaseLinkTrans; tf2::fromMsg(worldBaseLinkTransMsg_.transform, worldBaseLinkTrans); if (!RosFilterUtilities::lookupTransformSafe( tfBuffer_, baseLinkFrameId_, odomFrameId_, ros::Time(filter_.getLastMeasurementTime()), odomBaseLinkTrans, true)) { ROS_ERROR_STREAM_DELAYED_THROTTLE(1.0, "Unable to retrieve " << odomFrameId_ << "->" << baseLinkFrameId_ << " transform. Skipping iteration..."); continue; } /* * First, see these two references: * http://wiki.ros.org/tf/Overview/Using%20Published%20Transforms#lookupTransform * http://wiki.ros.org/geometry/CoordinateFrameConventions#Transform_Direction * We have a transform from mapFrameId_->baseLinkFrameId_, but it would actually transform * a given pose from baseLinkFrameId_->mapFrameId_. We then used lookupTransform, whose * first two arguments are target frame and source frame, to get a transform from * baseLinkFrameId_->odomFrameId_. However, this transform would actually transform data * from odomFrameId_->baseLinkFrameId_. Now imagine that we have a position in the * mapFrameId_ frame. First, we multiply it by the inverse of the * mapFrameId_->baseLinkFrameId, which will transform that data from mapFrameId_ to * baseLinkFrameId_. Now we want to go from baseLinkFrameId_->odomFrameId_, but the * transform we have takes data from odomFrameId_->baseLinkFrameId_, so we need its * inverse as well. We have now transformed our data from mapFrameId_ to odomFrameId_. * However, if we want other users to be able to do the same, we need to broadcast * the inverse of that entire transform. */ mapOdomTrans.mult(worldBaseLinkTrans, odomBaseLinkTrans); mapOdomTransMsg.transform = tf2::toMsg(mapOdomTrans); mapOdomTransMsg.header.stamp = filteredPosition.header.stamp + tfTimeOffset_; mapOdomTransMsg.header.frame_id = mapFrameId_; mapOdomTransMsg.child_frame_id = odomFrameId_; worldTransformBroadcaster.sendTransform(mapOdomTransMsg); } catch(...) { ROS_ERROR_STREAM_DELAYED_THROTTLE(5.0, "Could not obtain transform from " << odomFrameId_ << "->" << baseLinkFrameId_); } } else { ROS_ERROR_STREAM("Odometry message frame_id was " << filteredPosition.header.frame_id << ", expected " << mapFrameId_ << " or " << odomFrameId_); } } // Fire off the position and the transform positionPub.publish(filteredPosition); if (printDiagnostics_) { freqDiag.tick(); } } // Publish the acceleration if desired and filter is initialized geometry_msgs::AccelWithCovarianceStamped filteredAcceleration; if (publishAcceleration_ && getFilteredAccelMessage(filteredAcceleration)) { accelPub.publish(filteredAcceleration); } /* Diagnostics can behave strangely when playing back from bag * files and using simulated time, so we have to check for * time suddenly moving backwards as well as the standard * timeout criterion before publishing. */ double diagDuration = (curTime - lastDiagTime).toSec(); if (printDiagnostics_ && (diagDuration >= diagnosticUpdater_.getPeriod() || diagDuration < 0.0)) { diagnosticUpdater_.force_update(); lastDiagTime = curTime; } // Clear out expired history data if (smoothLaggedData_) { clearExpiredHistory(filter_.getLastMeasurementTime() - historyLength_); } ros::Duration loop_elapsed_time = ros::Time::now() - loop_end_time; if (loop_elapsed_time > loop_cycle_time) { ROS_WARN_STREAM_DELAYED_THROTTLE(1.0, "Failed to meet update rate! Took " << std::setprecision(20) << loop_elapsed_time.toSec() << " seconds. Try decreasing the rate, limiting sensor output frequency, or " "limiting the number of sensors."); } else { ros::Duration sleep_time = loop_cycle_time - loop_elapsed_time; sleep_time.sleep(); } loop_end_time = ros::Time::now(); } } template void RosFilter::setPoseCallback(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &msg) { RF_DEBUG("------ RosFilter::setPoseCallback ------\nPose message:\n" << *msg); std::string topicName("setPose"); // Get rid of any initial poses (pretend we've never had a measurement) initialMeasurements_.clear(); previousMeasurements_.clear(); previousMeasurementCovariances_.clear(); // Clear out the measurement queue so that we don't immediately undo our // reset. while (!measurementQueue_.empty() && ros::ok()) { measurementQueue_.pop(); } filterStateHistory_.clear(); measurementHistory_.clear(); // Also set the last set pose time, so we ignore all messages // that occur before it lastSetPoseTime_ = msg->header.stamp; // Set the state vector to the reported pose Eigen::VectorXd measurement(STATE_SIZE); Eigen::MatrixXd measurementCovariance(STATE_SIZE, STATE_SIZE); std::vector updateVector(STATE_SIZE, true); // We only measure pose variables, so initialize the vector to 0 measurement.setZero(); // Set this to the identity and let the message reset it measurementCovariance.setIdentity(); measurementCovariance *= 1e-6; // Prepare the pose data (really just using this to transform it into the target frame). // Twist data is going to get zeroed out. preparePose(msg, topicName, worldFrameId_, false, false, false, updateVector, measurement, measurementCovariance); // For the state filter_.setState(measurement); filter_.setEstimateErrorCovariance(measurementCovariance); filter_.setLastMeasurementTime(ros::Time::now().toSec()); // This method can apparently cancel all callbacks, and may stop the executing of the very callback that we're // currently in. Therefore, nothing of consequence should come after it. ros::getGlobalCallbackQueue()->clear(); RF_DEBUG("\n------ /RosFilter::setPoseCallback ------\n"); } template bool RosFilter::setPoseSrvCallback(robot_localization::SetPose::Request& request, robot_localization::SetPose::Response&) { geometry_msgs::PoseWithCovarianceStamped::Ptr msg; msg = boost::make_shared(request.pose); setPoseCallback(msg); return true; } template bool RosFilter::enableFilterSrvCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&) { RF_DEBUG("\n[" << ros::this_node::getName() << ":]" << " ------ /RosFilter::enableFilterSrvCallback ------\n"); if (enabled_) { ROS_WARN_STREAM("[" << ros::this_node::getName() << ":] Asking for enabling filter service, but the filter was already enabled! Use param disabled_at_startup."); } else { ROS_INFO_STREAM("[" << ros::this_node::getName() << ":] Enabling filter..."); enabled_ = true; } return true; } template void RosFilter::twistCallback(const geometry_msgs::TwistWithCovarianceStamped::ConstPtr &msg, const CallbackData &callbackData, const std::string &targetFrame) { const std::string &topicName = callbackData.topicName_; // If we've just reset the filter, then we want to ignore any messages // that arrive with an older timestamp if (msg->header.stamp <= lastSetPoseTime_) { std::stringstream stream; stream << "The " << topicName << " message has a timestamp equal to or before the last filter reset, " << "this message will be ignored. This may indicate an empty or bad timestamp. (message time: " << msg->header.stamp.toSec() << ")"; addDiagnostic(diagnostic_msgs::DiagnosticStatus::WARN, topicName + "_timestamp", stream.str(), false); return; } RF_DEBUG("------ RosFilter::twistCallback (" << topicName << ") ------\n" "Twist message:\n" << *msg); if (lastMessageTimes_.count(topicName) == 0) { lastMessageTimes_.insert(std::pair(topicName, msg->header.stamp)); } // Make sure this message is newer than the last one if (msg->header.stamp >= lastMessageTimes_[topicName]) { RF_DEBUG("Update vector for " << topicName << " is:\n" << callbackData.updateVector_); Eigen::VectorXd measurement(STATE_SIZE); Eigen::MatrixXd measurementCovariance(STATE_SIZE, STATE_SIZE); measurement.setZero(); measurementCovariance.setZero(); // Make sure we're actually updating at least one of these variables std::vector updateVectorCorrected = callbackData.updateVector_; // Prepare the twist data for inclusion in the filter if (prepareTwist(msg, topicName, targetFrame, updateVectorCorrected, measurement, measurementCovariance)) { // Store the measurement. Add a "twist" suffix so we know what kind of measurement // we're dealing with when we debug the core filter logic. enqueueMeasurement(topicName, measurement, measurementCovariance, updateVectorCorrected, callbackData.rejectionThreshold_, msg->header.stamp); RF_DEBUG("Enqueued new measurement for " << topicName << "_twist\n"); } else { RF_DEBUG("Did *not* enqueue measurement for " << topicName << "_twist\n"); } lastMessageTimes_[topicName] = msg->header.stamp; RF_DEBUG("Last message time for " << topicName << " is now " << lastMessageTimes_[topicName] << "\n"); } else if (resetOnTimeJump_ && ros::Time::isSimTime()) { reset(); } else { std::stringstream stream; stream << "The " << topicName << " message has a timestamp before that of the previous message received," << " this message will be ignored. This may indicate a bad timestamp. (message time: " << msg->header.stamp.toSec() << ")"; addDiagnostic(diagnostic_msgs::DiagnosticStatus::WARN, topicName + "_timestamp", stream.str(), false); RF_DEBUG("Message is too old. Last message time for " << topicName << " is " << lastMessageTimes_[topicName] << ", current message time is " << msg->header.stamp << ".\n"); } RF_DEBUG("\n----- /RosFilter::twistCallback (" << topicName << ") ------\n"); } template void RosFilter::addDiagnostic(const int errLevel, const std::string &topicAndClass, const std::string &message, const bool staticDiag) { if (staticDiag) { staticDiagnostics_[topicAndClass] = message; staticDiagErrorLevel_ = std::max(staticDiagErrorLevel_, errLevel); } else { dynamicDiagnostics_[topicAndClass] = message; dynamicDiagErrorLevel_ = std::max(dynamicDiagErrorLevel_, errLevel); } } template void RosFilter::aggregateDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &wrapper) { wrapper.clear(); wrapper.clearSummary(); int maxErrLevel = std::max(staticDiagErrorLevel_, dynamicDiagErrorLevel_); // Report the overall status switch (maxErrLevel) { case diagnostic_msgs::DiagnosticStatus::ERROR: wrapper.summary(maxErrLevel, "Erroneous data or settings detected for a robot_localization state estimation node."); break; case diagnostic_msgs::DiagnosticStatus::WARN: wrapper.summary(maxErrLevel, "Potentially erroneous data or settings detected for " "a robot_localization state estimation node."); break; case diagnostic_msgs::DiagnosticStatus::STALE: wrapper.summary(maxErrLevel, "The state of the robot_localization state estimation node is stale."); break; case diagnostic_msgs::DiagnosticStatus::OK: wrapper.summary(maxErrLevel, "The robot_localization state estimation node appears to be functioning properly."); break; default: break; } // Aggregate all the static messages for (std::map::iterator diagIt = staticDiagnostics_.begin(); diagIt != staticDiagnostics_.end(); ++diagIt) { wrapper.add(diagIt->first, diagIt->second); } // Aggregate all the dynamic messages, then clear them for (std::map::iterator diagIt = dynamicDiagnostics_.begin(); diagIt != dynamicDiagnostics_.end(); ++diagIt) { wrapper.add(diagIt->first, diagIt->second); } dynamicDiagnostics_.clear(); // Reset the warning level for the dynamic diagnostic messages dynamicDiagErrorLevel_ = diagnostic_msgs::DiagnosticStatus::OK; } template void RosFilter::copyCovariance(const double *arr, Eigen::MatrixXd &covariance, const std::string &topicName, const std::vector &updateVector, const size_t offset, const size_t dimension) { for (size_t i = 0; i < dimension; i++) { for (size_t j = 0; j < dimension; j++) { covariance(i, j) = arr[dimension * i + j]; if (printDiagnostics_) { std::string iVar = stateVariableNames_[offset + i]; if (covariance(i, j) > 1e3 && (updateVector[offset + i] || updateVector[offset + j])) { std::string jVar = stateVariableNames_[offset + j]; std::stringstream stream; stream << "The covariance at position (" << dimension * i + j << "), which corresponds to " << (i == j ? iVar + " variance" : iVar + " and " + jVar + " covariance") << ", the value is extremely large (" << covariance(i, j) << "), but the update vector for " << (i == j ? iVar : iVar + " and/or " + jVar) << " is set to true. This may produce undesirable results."; addDiagnostic(diagnostic_msgs::DiagnosticStatus::WARN, topicName + "_covariance", stream.str(), false); } else if (updateVector[i] && i == j && covariance(i, j) == 0) { std::stringstream stream; stream << "The covariance at position (" << dimension * i + j << "), which corresponds to " << iVar << " variance, was zero. This will be replaced with a small value to maintain filter " "stability, but should be corrected at the message origin node."; addDiagnostic(diagnostic_msgs::DiagnosticStatus::WARN, topicName + "_covariance", stream.str(), false); } else if (updateVector[i] && i == j && covariance(i, j) < 0) { std::stringstream stream; stream << "The covariance at position (" << dimension * i + j << "), which corresponds to " << iVar << " variance, was negative. This will be replaced with a " "small positive value to maintain filter stability, but should be corrected at the message " "origin node."; addDiagnostic(diagnostic_msgs::DiagnosticStatus::WARN, topicName + "_covariance", stream.str(), false); } } } } } template void RosFilter::copyCovariance(const Eigen::MatrixXd &covariance, double *arr, const size_t dimension) { for (size_t i = 0; i < dimension; i++) { for (size_t j = 0; j < dimension; j++) { arr[dimension * i + j] = covariance(i, j); } } } template std::vector RosFilter::loadUpdateConfig(const std::string &topicName) { XmlRpc::XmlRpcValue topicConfig; std::vector updateVector(STATE_SIZE, 0); std::string topicConfigName = topicName + "_config"; try { nhLocal_.getParam(topicConfigName, topicConfig); ROS_ASSERT(topicConfig.getType() == XmlRpc::XmlRpcValue::TypeArray); if (topicConfig.size() != STATE_SIZE) { ROS_WARN_STREAM("Configuration vector for " << topicConfigName << " should have 15 entries."); } for (int i = 0; i < topicConfig.size(); i++) { // The double cast looks strange, but we'll get exceptions if we // remove the cast to bool. vector is discouraged, so updateVector // uses integers. updateVector[i] = static_cast(static_cast(topicConfig[i])); } } catch (XmlRpc::XmlRpcException &e) { ROS_FATAL_STREAM("Could not read sensor update configuration for topic " << topicName << " (type: " << topicConfig.getType() << ", expected: " << XmlRpc::XmlRpcValue::TypeArray << "). Error was " << e.getMessage() << "\n"); } return updateVector; } template bool RosFilter::prepareAcceleration(const sensor_msgs::Imu::ConstPtr &msg, const std::string &topicName, const std::string &targetFrame, std::vector &updateVector, Eigen::VectorXd &measurement, Eigen::MatrixXd &measurementCovariance) { RF_DEBUG("------ RosFilter::prepareAcceleration (" << topicName << ") ------\n"); // 1. Get the measurement into a vector tf2::Vector3 accTmp(msg->linear_acceleration.x, msg->linear_acceleration.y, msg->linear_acceleration.z); // Set relevant header info std::string msgFrame = (msg->header.frame_id == "" ? baseLinkFrameId_ : msg->header.frame_id); // 2. robot_localization lets users configure which variables from the sensor should be // fused with the filter. This is specified at the sensor level. However, the data // may go through transforms before being fused with the state estimate. In that case, // we need to know which of the transformed variables came from the pre-transformed // "approved" variables (i.e., the ones that had "true" in their xxx_config parameter). // To do this, we create a pose from the original upate vector, which contains only // zeros and ones. This pose goes through the same transforms as the measurement. The // non-zero values that result will be used to modify the updateVector. tf2::Matrix3x3 maskAcc(updateVector[StateMemberAx], 0, 0, 0, updateVector[StateMemberAy], 0, 0, 0, updateVector[StateMemberAz]); // 3. We'll need to rotate the covariance as well Eigen::MatrixXd covarianceRotated(ACCELERATION_SIZE, ACCELERATION_SIZE); covarianceRotated.setZero(); this->copyCovariance(&(msg->linear_acceleration_covariance[0]), covarianceRotated, topicName, updateVector, POSITION_A_OFFSET, ACCELERATION_SIZE); RF_DEBUG("Original measurement as tf object: " << accTmp << "\nOriginal update vector:\n" << updateVector << "\nOriginal covariance matrix:\n" << covarianceRotated << "\n"); // 4. We need to transform this into the target frame (probably base_link) // It's unlikely that we'll get a velocity measurement in another frame, but // we have to handle the situation. tf2::Transform targetFrameTrans; bool canTransform = RosFilterUtilities::lookupTransformSafe(tfBuffer_, targetFrame, msgFrame, msg->header.stamp, tfTimeout_, targetFrameTrans); if (canTransform) { // We don't know if the user has already handled the removal // of normal forces, so we use a parameter if (removeGravitationalAcc_[topicName]) { tf2::Vector3 normAcc(0, 0, gravitationalAcc_); tf2::Quaternion curAttitude; tf2::Transform trans; if (::fabs(msg->orientation_covariance[0] + 1) < 1e-9) { // Imu message contains no orientation, so we should use orientation // from filter state to transform and remove acceleration const Eigen::VectorXd &state = filter_.getState(); tf2::Vector3 stateTmp(state(StateMemberRoll), state(StateMemberPitch), state(StateMemberYaw)); // transform state orientation to IMU frame tf2::Transform imuFrameTrans; RosFilterUtilities::lookupTransformSafe(tfBuffer_, msgFrame, targetFrame, msg->header.stamp, tfTimeout_, imuFrameTrans); stateTmp = imuFrameTrans.getBasis() * stateTmp; curAttitude.setRPY(stateTmp.getX(), stateTmp.getY(), stateTmp.getZ()); } else { tf2::fromMsg(msg->orientation, curAttitude); if (fabs(curAttitude.length() - 1.0) > 0.01) { ROS_WARN_ONCE("An input was not normalized, this should NOT happen, but will normalize."); curAttitude.normalize(); } } trans.setRotation(curAttitude); tf2::Vector3 rotNorm = trans.getBasis().inverse() * normAcc; accTmp.setX(accTmp.getX() - rotNorm.getX()); accTmp.setY(accTmp.getY() - rotNorm.getY()); accTmp.setZ(accTmp.getZ() - rotNorm.getZ()); RF_DEBUG("Orientation is " << curAttitude << "Acceleration due to gravity is " << rotNorm << "After removing acceleration due to gravity, acceleration is " << accTmp << "\n"); } // Transform to correct frame // @todo: This needs to take into account offsets from the origin. Right now, // it assumes that if the sensor is placed at some non-zero offset from the // vehicle's center, that the vehicle turns with constant velocity. This needs // to be something like // accTmp = targetFrameTrans.getBasis() * accTmp - targetFrameTrans.getOrigin().cross(rotation_acceleration); // We can get rotational acceleration by differentiating the rotational velocity // (if it's available) accTmp = targetFrameTrans.getBasis() * accTmp; maskAcc = targetFrameTrans.getBasis() * maskAcc; // Now use the mask values to determine which update vector values should be true updateVector[StateMemberAx] = static_cast( maskAcc.getRow(StateMemberAx - POSITION_A_OFFSET).length() >= 1e-6); updateVector[StateMemberAy] = static_cast( maskAcc.getRow(StateMemberAy - POSITION_A_OFFSET).length() >= 1e-6); updateVector[StateMemberAz] = static_cast( maskAcc.getRow(StateMemberAz - POSITION_A_OFFSET).length() >= 1e-6); RF_DEBUG(msg->header.frame_id << "->" << targetFrame << " transform:\n" << targetFrameTrans << "\nAfter applying transform to " << targetFrame << ", update vector is:\n" << updateVector << "\nAfter applying transform to " << targetFrame << ", measurement is:\n" << accTmp << "\n"); // 5. Now rotate the covariance: create an augmented // matrix that contains a 3D rotation matrix in the // upper-left and lower-right quadrants, and zeros // elsewhere tf2::Matrix3x3 rot(targetFrameTrans.getRotation()); Eigen::MatrixXd rot3d(ACCELERATION_SIZE, ACCELERATION_SIZE); rot3d.setIdentity(); for (size_t rInd = 0; rInd < ACCELERATION_SIZE; ++rInd) { rot3d(rInd, 0) = rot.getRow(rInd).getX(); rot3d(rInd, 1) = rot.getRow(rInd).getY(); rot3d(rInd, 2) = rot.getRow(rInd).getZ(); } // Carry out the rotation covarianceRotated = rot3d * covarianceRotated.eval() * rot3d.transpose(); RF_DEBUG("Transformed covariance is \n" << covarianceRotated << "\n"); // 6. Store our corrected measurement and covariance measurement(StateMemberAx) = accTmp.getX(); measurement(StateMemberAy) = accTmp.getY(); measurement(StateMemberAz) = accTmp.getZ(); // Copy the covariances measurementCovariance.block(POSITION_A_OFFSET, POSITION_A_OFFSET, ACCELERATION_SIZE, ACCELERATION_SIZE) = covarianceRotated.block(0, 0, ACCELERATION_SIZE, ACCELERATION_SIZE); // 7. Handle 2D mode if (twoDMode_) { forceTwoD(measurement, measurementCovariance, updateVector); } } else { RF_DEBUG("Could not transform measurement into " << targetFrame << ". Ignoring...\n"); } RF_DEBUG("\n----- /RosFilter::prepareAcceleration(" << topicName << ") ------\n"); return canTransform; } template bool RosFilter::preparePose(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &msg, const std::string &topicName, const std::string &targetFrame, const bool differential, const bool relative, const bool imuData, std::vector &updateVector, Eigen::VectorXd &measurement, Eigen::MatrixXd &measurementCovariance) { bool retVal = false; RF_DEBUG("------ RosFilter::preparePose (" << topicName << ") ------\n"); // 1. Get the measurement into a tf-friendly transform (pose) object tf2::Stamped poseTmp; // We'll need this later for storing this measurement for differential integration tf2::Transform curMeasurement; // Handle issues where frame_id data is not filled out properly // @todo: verify that this is necessary still. New IMU handling may // have rendered this obsolete. std::string finalTargetFrame; if (targetFrame == "" && msg->header.frame_id == "") { // Blank target and message frames mean we can just // use our world_frame finalTargetFrame = worldFrameId_; poseTmp.frame_id_ = finalTargetFrame; } else if (targetFrame == "") { // A blank target frame means we shouldn't bother // transforming the data finalTargetFrame = msg->header.frame_id; poseTmp.frame_id_ = finalTargetFrame; } else { // Otherwise, we should use our target frame finalTargetFrame = targetFrame; poseTmp.frame_id_ = (differential ? finalTargetFrame : msg->header.frame_id); } RF_DEBUG("Final target frame for " << topicName << " is " << finalTargetFrame << "\n"); poseTmp.stamp_ = msg->header.stamp; // Fill out the position data poseTmp.setOrigin(tf2::Vector3(msg->pose.pose.position.x, msg->pose.pose.position.y, msg->pose.pose.position.z)); tf2::Quaternion orientation; // Handle bad (empty) quaternions if (msg->pose.pose.orientation.x == 0 && msg->pose.pose.orientation.y == 0 && msg->pose.pose.orientation.z == 0 && msg->pose.pose.orientation.w == 0) { orientation.setValue(0.0, 0.0, 0.0, 1.0); if (updateVector[StateMemberRoll] || updateVector[StateMemberPitch] || updateVector[StateMemberYaw]) { std::stringstream stream; stream << "The " << topicName << " message contains an invalid orientation quaternion, " << "but its configuration is such that orientation data is being used. Correcting..."; addDiagnostic(diagnostic_msgs::DiagnosticStatus::WARN, topicName + "_orientation", stream.str(), false); } } else { tf2::fromMsg(msg->pose.pose.orientation, orientation); if (fabs(orientation.length() - 1.0) > 0.01) { ROS_WARN_ONCE("An input was not normalized, this should NOT happen, but will normalize."); orientation.normalize(); } } // Fill out the orientation data poseTmp.setRotation(orientation); // 2. Get the target frame transformation tf2::Transform targetFrameTrans; bool canTransform = RosFilterUtilities::lookupTransformSafe(tfBuffer_, finalTargetFrame, poseTmp.frame_id_, poseTmp.stamp_, tfTimeout_, targetFrameTrans); // 3. Make sure we can work with this data before carrying on if (canTransform) { /* 4. robot_localization lets users configure which variables from the sensor should be * fused with the filter. This is specified at the sensor level. However, the data * may go through transforms before being fused with the state estimate. In that case, * we need to know which of the transformed variables came from the pre-transformed * "approved" variables (i.e., the ones that had "true" in their xxx_config parameter). * To do this, we construct matrices using the update vector values on the diagonals, * pass this matrix through the rotation, and use the length of each row to determine * the transformed update vector. The process is slightly different for IMUs, as the * coordinate frame transform is really the base_link->imu_frame transform, and not * a transform from some other world-fixed frame (even though the IMU data itself *is* * reported in a world fixed frame). */ tf2::Matrix3x3 maskPosition(updateVector[StateMemberX], 0, 0, 0, updateVector[StateMemberY], 0, 0, 0, updateVector[StateMemberZ]); tf2::Matrix3x3 maskOrientation(updateVector[StateMemberRoll], 0, 0, 0, updateVector[StateMemberPitch], 0, 0, 0, updateVector[StateMemberYaw]); if (imuData) { /* We have to treat IMU orientation data differently. Even though we are dealing with pose * data when we work with orientations, for IMUs, the frame_id is the frame in which the * sensor is mounted, and not the coordinate frame of the IMU. Imagine an IMU that is mounted * facing sideways. The pitch in the IMU frame becomes roll for the vehicle. This means that * we need to rotate roll and pitch angles by the IMU's mounting yaw offset, and we must apply * similar treatment to its update mask and covariance. */ double dummy, yaw; targetFrameTrans.getBasis().getRPY(dummy, dummy, yaw); tf2::Matrix3x3 transTmp; transTmp.setRPY(0.0, 0.0, yaw); maskPosition = transTmp * maskPosition; maskOrientation = transTmp * maskOrientation; } else { maskPosition = targetFrameTrans.getBasis() * maskPosition; maskOrientation = targetFrameTrans.getBasis() * maskOrientation; } // Now copy the mask values back into the update vector: any row with a significant vector length // indicates that we want to set that variable to true in the update vector. updateVector[StateMemberX] = static_cast( maskPosition.getRow(StateMemberX - POSITION_OFFSET).length() >= 1e-6); updateVector[StateMemberY] = static_cast( maskPosition.getRow(StateMemberY - POSITION_OFFSET).length() >= 1e-6); updateVector[StateMemberZ] = static_cast( maskPosition.getRow(StateMemberZ - POSITION_OFFSET).length() >= 1e-6); updateVector[StateMemberRoll] = static_cast( maskOrientation.getRow(StateMemberRoll - ORIENTATION_OFFSET).length() >= 1e-6); updateVector[StateMemberPitch] = static_cast( maskOrientation.getRow(StateMemberPitch - ORIENTATION_OFFSET).length() >= 1e-6); updateVector[StateMemberYaw] = static_cast( maskOrientation.getRow(StateMemberYaw - ORIENTATION_OFFSET).length() >= 1e-6); // 5a. We'll need to rotate the covariance as well. Create a container and copy over the // covariance data Eigen::MatrixXd covariance(POSE_SIZE, POSE_SIZE); covariance.setZero(); copyCovariance(&(msg->pose.covariance[0]), covariance, topicName, updateVector, POSITION_OFFSET, POSE_SIZE); // 5b. Now rotate the covariance: create an augmented matrix that // contains a 3D rotation matrix in the upper-left and lower-right // quadrants, with zeros elsewhere. tf2::Matrix3x3 rot; Eigen::MatrixXd rot6d(POSE_SIZE, POSE_SIZE); rot6d.setIdentity(); Eigen::MatrixXd covarianceRotated; if (imuData) { // Apply the same special logic to the IMU covariance rotation double dummy, yaw; targetFrameTrans.getBasis().getRPY(dummy, dummy, yaw); rot.setRPY(0.0, 0.0, yaw); } else { rot.setRotation(targetFrameTrans.getRotation()); } for (size_t rInd = 0; rInd < POSITION_SIZE; ++rInd) { rot6d(rInd, 0) = rot.getRow(rInd).getX(); rot6d(rInd, 1) = rot.getRow(rInd).getY(); rot6d(rInd, 2) = rot.getRow(rInd).getZ(); rot6d(rInd+POSITION_SIZE, 3) = rot.getRow(rInd).getX(); rot6d(rInd+POSITION_SIZE, 4) = rot.getRow(rInd).getY(); rot6d(rInd+POSITION_SIZE, 5) = rot.getRow(rInd).getZ(); } // Now carry out the rotation covarianceRotated = rot6d * covariance * rot6d.transpose(); RF_DEBUG("After rotating into the " << finalTargetFrame << " frame, covariance is \n" << covarianceRotated << "\n"); /* 6a. For IMU data, the transform that we get is the transform from the body * frame of the robot (e.g., base_link) to the mounting frame of the robot. It * is *not* the coordinate frame in which the IMU orientation data is reported. * If the IMU is mounted in a non-neutral orientation, we need to remove those * offsets, and then we need to potentially "swap" roll and pitch. * Note that this transform does NOT handle NED->ENU conversions. Data is assumed * to be in the ENU frame when it is received. * */ if (imuData) { // First, convert the transform and measurement rotation to RPY // @todo: There must be a way to handle this with quaternions. Need to look into it. double rollOffset = 0; double pitchOffset = 0; double yawOffset = 0; double roll = 0; double pitch = 0; double yaw = 0; RosFilterUtilities::quatToRPY(targetFrameTrans.getRotation(), rollOffset, pitchOffset, yawOffset); RosFilterUtilities::quatToRPY(poseTmp.getRotation(), roll, pitch, yaw); // 6b. Apply the offset (making sure to bound them), and throw them in a vector tf2::Vector3 rpyAngles(FilterUtilities::clampRotation(roll - rollOffset), FilterUtilities::clampRotation(pitch - pitchOffset), FilterUtilities::clampRotation(yaw - yawOffset)); // 6c. Now we need to rotate the roll and pitch by the yaw offset value. // Imagine a case where an IMU is mounted facing sideways. In that case // pitch for the IMU's world frame is roll for the robot. tf2::Matrix3x3 mat; mat.setRPY(0.0, 0.0, yawOffset); rpyAngles = mat * rpyAngles; poseTmp.getBasis().setRPY(rpyAngles.getX(), rpyAngles.getY(), rpyAngles.getZ()); // We will use this target transformation later on, but // we've already transformed this data as if the IMU // were mounted neutrall on the robot, so we can just // make the transform the identity. targetFrameTrans.setIdentity(); } // 7. Two cases: if we're in differential mode, we need to generate a twist // message. Otherwise, we just transform it to the target frame. if (differential) { bool success = false; // We're going to be playing with poseTmp, so store it, // as we'll need to save its current value for the next // measurement. curMeasurement = poseTmp; // Make sure we have previous measurements to work with if (previousMeasurements_.count(topicName) > 0 && previousMeasurementCovariances_.count(topicName) > 0) { // 7a. If we are carrying out differential integration and // we have a previous measurement for this sensor,then we // need to apply the inverse of that measurement to this new // measurement to produce a "delta" measurement between the two. // Even if we're not using all of the variables from this sensor, // we need to use the whole measurement to determine the delta // to the new measurement tf2::Transform prevMeasurement = previousMeasurements_[topicName]; poseTmp.setData(prevMeasurement.inverseTimes(poseTmp)); RF_DEBUG("Previous measurement:\n" << previousMeasurements_[topicName] << "\nAfter removing previous measurement, measurement delta is:\n" << poseTmp << "\n"); // 7b. Now we we have a measurement delta in the frame_id of the // message, but we want that delta to be in the target frame, so // we need to apply the rotation of the target frame transform. targetFrameTrans.setOrigin(tf2::Vector3(0.0, 0.0, 0.0)); poseTmp.mult(targetFrameTrans, poseTmp); RF_DEBUG("After rotating to the target frame, measurement delta is:\n" << poseTmp << "\n"); // 7c. Now use the time difference from the last message to compute // translational and rotational velocities double dt = msg->header.stamp.toSec() - lastMessageTimes_[topicName].toSec(); double xVel = poseTmp.getOrigin().getX() / dt; double yVel = poseTmp.getOrigin().getY() / dt; double zVel = poseTmp.getOrigin().getZ() / dt; double rollVel = 0; double pitchVel = 0; double yawVel = 0; RosFilterUtilities::quatToRPY(poseTmp.getRotation(), rollVel, pitchVel, yawVel); rollVel /= dt; pitchVel /= dt; yawVel /= dt; RF_DEBUG("Previous message time was " << lastMessageTimes_[topicName].toSec() << ", current message time is " << msg->header.stamp.toSec() << ", delta is " << dt << ", velocity is (vX, vY, vZ): (" << xVel << ", " << yVel << ", " << zVel << ")\n" << "(vRoll, vPitch, vYaw): (" << rollVel << ", " << pitchVel << ", " << yawVel << ")\n"); // 7d. Fill out the velocity data in the message geometry_msgs::TwistWithCovarianceStamped *twistPtr = new geometry_msgs::TwistWithCovarianceStamped(); twistPtr->header = msg->header; twistPtr->header.frame_id = baseLinkFrameId_; twistPtr->twist.twist.linear.x = xVel; twistPtr->twist.twist.linear.y = yVel; twistPtr->twist.twist.linear.z = zVel; twistPtr->twist.twist.angular.x = rollVel; twistPtr->twist.twist.angular.y = pitchVel; twistPtr->twist.twist.angular.z = yawVel; std::vector twistUpdateVec(STATE_SIZE, false); std::copy(updateVector.begin() + POSITION_OFFSET, updateVector.begin() + POSE_SIZE, twistUpdateVec.begin() + POSITION_V_OFFSET); std::copy(twistUpdateVec.begin(), twistUpdateVec.end(), updateVector.begin()); geometry_msgs::TwistWithCovarianceStampedConstPtr ptr(twistPtr); // 7e. Now rotate the previous covariance for this measurement to get it // into the target frame, and add the current measurement's rotated covariance // to the previous measurement's rotated covariance, and multiply by the time delta. Eigen::MatrixXd prevCovarRotated = rot6d * previousMeasurementCovariances_[topicName] * rot6d.transpose(); covarianceRotated = (covarianceRotated.eval() + prevCovarRotated) * dt; copyCovariance(covarianceRotated, &(twistPtr->twist.covariance[0]), POSE_SIZE); RF_DEBUG("Previous measurement covariance:\n" << previousMeasurementCovariances_[topicName] << "\nPrevious measurement covariance rotated:\n" << prevCovarRotated << "\nFinal twist covariance:\n" << covarianceRotated << "\n"); // Now pass this on to prepareTwist, which will convert it to the required frame success = prepareTwist(ptr, topicName + "_twist", twistPtr->header.frame_id, updateVector, measurement, measurementCovariance); } // 7f. Update the previous measurement and measurement covariance previousMeasurements_[topicName] = curMeasurement; previousMeasurementCovariances_[topicName] = covariance; retVal = success; } else { // 7g. If we're in relative mode, remove the initial measurement if (relative) { if (initialMeasurements_.count(topicName) == 0) { initialMeasurements_.insert(std::pair(topicName, poseTmp)); } tf2::Transform initialMeasurement = initialMeasurements_[topicName]; poseTmp.setData(initialMeasurement.inverseTimes(poseTmp)); } // 7h. Apply the target frame transformation to the pose object. poseTmp.mult(targetFrameTrans, poseTmp); poseTmp.frame_id_ = finalTargetFrame; // 7i. Finally, copy everything into our measurement and covariance objects measurement(StateMemberX) = poseTmp.getOrigin().x(); measurement(StateMemberY) = poseTmp.getOrigin().y(); measurement(StateMemberZ) = poseTmp.getOrigin().z(); // The filter needs roll, pitch, and yaw values instead of quaternions double roll, pitch, yaw; RosFilterUtilities::quatToRPY(poseTmp.getRotation(), roll, pitch, yaw); measurement(StateMemberRoll) = roll; measurement(StateMemberPitch) = pitch; measurement(StateMemberYaw) = yaw; measurementCovariance.block(0, 0, POSE_SIZE, POSE_SIZE) = covarianceRotated.block(0, 0, POSE_SIZE, POSE_SIZE); // 8. Handle 2D mode if (twoDMode_) { forceTwoD(measurement, measurementCovariance, updateVector); } retVal = true; } } else { retVal = false; RF_DEBUG("Could not transform measurement into " << finalTargetFrame << ". Ignoring..."); } RF_DEBUG("\n----- /RosFilter::preparePose (" << topicName << ") ------\n"); return retVal; } template bool RosFilter::prepareTwist(const geometry_msgs::TwistWithCovarianceStamped::ConstPtr &msg, const std::string &topicName, const std::string &targetFrame, std::vector &updateVector, Eigen::VectorXd &measurement, Eigen::MatrixXd &measurementCovariance) { RF_DEBUG("------ RosFilter::prepareTwist (" << topicName << ") ------\n"); // 1. Get the measurement into two separate vector objects. tf2::Vector3 twistLin(msg->twist.twist.linear.x, msg->twist.twist.linear.y, msg->twist.twist.linear.z); tf2::Vector3 measTwistRot(msg->twist.twist.angular.x, msg->twist.twist.angular.y, msg->twist.twist.angular.z); // 1a. This sensor may or may not measure rotational velocity. Regardless, // if it measures linear velocity, then later on, we'll need to remove "false" // linear velocity resulting from angular velocity and the translational offset // of the sensor from the vehicle origin. const Eigen::VectorXd &state = filter_.getState(); tf2::Vector3 stateTwistRot(state(StateMemberVroll), state(StateMemberVpitch), state(StateMemberVyaw)); // Determine the frame_id of the data std::string msgFrame = (msg->header.frame_id == "" ? targetFrame : msg->header.frame_id); // 2. robot_localization lets users configure which variables from the sensor should be // fused with the filter. This is specified at the sensor level. However, the data // may go through transforms before being fused with the state estimate. In that case, // we need to know which of the transformed variables came from the pre-transformed // "approved" variables (i.e., the ones that had "true" in their xxx_config parameter). // To do this, we construct matrices using the update vector values on the diagonals, // pass this matrix through the rotation, and use the length of each row to determine // the transformed update vector. tf2::Matrix3x3 maskLin(updateVector[StateMemberVx], 0, 0, 0, updateVector[StateMemberVy], 0, 0, 0, updateVector[StateMemberVz]); tf2::Matrix3x3 maskRot(updateVector[StateMemberVroll], 0, 0, 0, updateVector[StateMemberVpitch], 0, 0, 0, updateVector[StateMemberVyaw]); // 3. We'll need to rotate the covariance as well Eigen::MatrixXd covarianceRotated(TWIST_SIZE, TWIST_SIZE); covarianceRotated.setZero(); copyCovariance(&(msg->twist.covariance[0]), covarianceRotated, topicName, updateVector, POSITION_V_OFFSET, TWIST_SIZE); RF_DEBUG("Original measurement as tf object:\nLinear: " << twistLin << "Rotational: " << measTwistRot << "\nOriginal update vector:\n" << updateVector << "\nOriginal covariance matrix:\n" << covarianceRotated << "\n"); // 4. We need to transform this into the target frame (probably base_link) tf2::Transform targetFrameTrans; bool canTransform = RosFilterUtilities::lookupTransformSafe(tfBuffer_, targetFrame, msgFrame, msg->header.stamp, tfTimeout_, targetFrameTrans); if (canTransform) { // Transform to correct frame. Note that we can get linear velocity // as a result of the sensor offset and rotational velocity measTwistRot = targetFrameTrans.getBasis() * measTwistRot; twistLin = targetFrameTrans.getBasis() * twistLin + targetFrameTrans.getOrigin().cross(stateTwistRot); maskLin = targetFrameTrans.getBasis() * maskLin; maskRot = targetFrameTrans.getBasis() * maskRot; // Now copy the mask values back into the update vector updateVector[StateMemberVx] = static_cast( maskLin.getRow(StateMemberVx - POSITION_V_OFFSET).length() >= 1e-6); updateVector[StateMemberVy] = static_cast( maskLin.getRow(StateMemberVy - POSITION_V_OFFSET).length() >= 1e-6); updateVector[StateMemberVz] = static_cast( maskLin.getRow(StateMemberVz - POSITION_V_OFFSET).length() >= 1e-6); updateVector[StateMemberVroll] = static_cast( maskRot.getRow(StateMemberVroll - ORIENTATION_V_OFFSET).length() >= 1e-6); updateVector[StateMemberVpitch] = static_cast( maskRot.getRow(StateMemberVpitch - ORIENTATION_V_OFFSET).length() >= 1e-6); updateVector[StateMemberVyaw] = static_cast( maskRot.getRow(StateMemberVyaw - ORIENTATION_V_OFFSET).length() >= 1e-6); RF_DEBUG(msg->header.frame_id << "->" << targetFrame << " transform:\n" << targetFrameTrans << "\nAfter applying transform to " << targetFrame << ", update vector is:\n" << updateVector << "\nAfter applying transform to " << targetFrame << ", measurement is:\n" << "Linear: " << twistLin << "Rotational: " << measTwistRot << "\n"); // 5. Now rotate the covariance: create an augmented // matrix that contains a 3D rotation matrix in the // upper-left and lower-right quadrants, and zeros // elsewhere tf2::Matrix3x3 rot(targetFrameTrans.getRotation()); Eigen::MatrixXd rot6d(TWIST_SIZE, TWIST_SIZE); rot6d.setIdentity(); for (size_t rInd = 0; rInd < POSITION_SIZE; ++rInd) { rot6d(rInd, 0) = rot.getRow(rInd).getX(); rot6d(rInd, 1) = rot.getRow(rInd).getY(); rot6d(rInd, 2) = rot.getRow(rInd).getZ(); rot6d(rInd+POSITION_SIZE, 3) = rot.getRow(rInd).getX(); rot6d(rInd+POSITION_SIZE, 4) = rot.getRow(rInd).getY(); rot6d(rInd+POSITION_SIZE, 5) = rot.getRow(rInd).getZ(); } // Carry out the rotation covarianceRotated = rot6d * covarianceRotated.eval() * rot6d.transpose(); RF_DEBUG("Transformed covariance is \n" << covarianceRotated << "\n"); // 6. Store our corrected measurement and covariance measurement(StateMemberVx) = twistLin.getX(); measurement(StateMemberVy) = twistLin.getY(); measurement(StateMemberVz) = twistLin.getZ(); measurement(StateMemberVroll) = measTwistRot.getX(); measurement(StateMemberVpitch) = measTwistRot.getY(); measurement(StateMemberVyaw) = measTwistRot.getZ(); // Copy the covariances measurementCovariance.block(POSITION_V_OFFSET, POSITION_V_OFFSET, TWIST_SIZE, TWIST_SIZE) = covarianceRotated.block(0, 0, TWIST_SIZE, TWIST_SIZE); // 7. Handle 2D mode if (twoDMode_) { forceTwoD(measurement, measurementCovariance, updateVector); } } else { RF_DEBUG("Could not transform measurement into " << targetFrame << ". Ignoring..."); } RF_DEBUG("\n----- /RosFilter::prepareTwist (" << topicName << ") ------\n"); return canTransform; } template void RosFilter::saveFilterState(FilterBase& filter) { FilterStatePtr state = FilterStatePtr(new FilterState()); state->state_ = Eigen::VectorXd(filter.getState()); state->estimateErrorCovariance_ = Eigen::MatrixXd(filter.getEstimateErrorCovariance()); state->lastMeasurementTime_ = filter.getLastMeasurementTime(); state->latestControl_ = Eigen::VectorXd(filter.getControl()); state->latestControlTime_ = filter.getControlTime(); filterStateHistory_.push_back(state); RF_DEBUG("Saved state with timestamp " << std::setprecision(20) << state->lastMeasurementTime_ << " to history. " << filterStateHistory_.size() << " measurements are in the queue.\n"); } template bool RosFilter::revertTo(const double time) { RF_DEBUG("\n----- RosFilter::revertTo -----\n"); RF_DEBUG("\nRequested time was " << std::setprecision(20) << time << "\n") // Walk back through the queue until we reach a filter state whose time stamp is less than or equal to the // requested time. Since every saved state after that time will be overwritten/corrected, we can pop from // the queue. If the history is insufficiently short, we just take the oldest state we have. FilterStatePtr lastHistoryState; while (!filterStateHistory_.empty() && filterStateHistory_.back()->lastMeasurementTime_ > time) { lastHistoryState = filterStateHistory_.back(); filterStateHistory_.pop_back(); } // If the state history is not empty at this point, it means that our history was large enough, and we // should revert to the state at the back of the history deque. bool retVal = false; if (!filterStateHistory_.empty()) { retVal = true; lastHistoryState = filterStateHistory_.back(); } else { RF_DEBUG("Insufficient history to revert to time " << time << "\n"); if (lastHistoryState.get() != NULL) { RF_DEBUG("Will revert to oldest state at " << lastHistoryState->latestControlTime_ << ".\n"); } } // If we have a valid reversion state, revert if (lastHistoryState.get() != NULL) { // Reset filter to the latest state from the queue. const FilterStatePtr &state = lastHistoryState; filter_.setState(state->state_); filter_.setEstimateErrorCovariance(state->estimateErrorCovariance_); filter_.setLastMeasurementTime(state->lastMeasurementTime_); RF_DEBUG("Reverted to state with time " << std::setprecision(20) << state->lastMeasurementTime_ << "\n"); } // Repeat for measurements, but push every measurement onto the measurement queue as we go int restored_measurements = 0; while (!measurementHistory_.empty() && measurementHistory_.back()->time_ > time) { measurementQueue_.push(measurementHistory_.back()); measurementHistory_.pop_back(); restored_measurements++; } RF_DEBUG("Restored " << restored_measurements << " to measurement queue.\n"); RF_DEBUG("\n----- /RosFilter::revertTo\n"); return retVal; } template bool RosFilter::validateFilterOutput(const nav_msgs::Odometry &message) { return !std::isnan(message.pose.pose.position.x) && !std::isinf(message.pose.pose.position.x) && !std::isnan(message.pose.pose.position.y) && !std::isinf(message.pose.pose.position.y) && !std::isnan(message.pose.pose.position.z) && !std::isinf(message.pose.pose.position.z) && !std::isnan(message.pose.pose.orientation.x) && !std::isinf(message.pose.pose.orientation.x) && !std::isnan(message.pose.pose.orientation.y) && !std::isinf(message.pose.pose.orientation.y) && !std::isnan(message.pose.pose.orientation.z) && !std::isinf(message.pose.pose.orientation.z) && !std::isnan(message.pose.pose.orientation.w) && !std::isinf(message.pose.pose.orientation.w) && !std::isnan(message.twist.twist.linear.x) && !std::isinf(message.twist.twist.linear.x) && !std::isnan(message.twist.twist.linear.y) && !std::isinf(message.twist.twist.linear.y) && !std::isnan(message.twist.twist.linear.z) && !std::isinf(message.twist.twist.linear.z) && !std::isnan(message.twist.twist.angular.x) && !std::isinf(message.twist.twist.angular.x) && !std::isnan(message.twist.twist.angular.y) && !std::isinf(message.twist.twist.angular.y) && !std::isnan(message.twist.twist.angular.z) && !std::isinf(message.twist.twist.angular.z); } template void RosFilter::clearExpiredHistory(const double cutOffTime) { RF_DEBUG("\n----- RosFilter::clearExpiredHistory -----" << "\nCutoff time is " << cutOffTime << "\n"); int poppedMeasurements = 0; int poppedStates = 0; while (!measurementHistory_.empty() && measurementHistory_.front()->time_ < cutOffTime) { measurementHistory_.pop_front(); poppedMeasurements++; } while (!filterStateHistory_.empty() && filterStateHistory_.front()->lastMeasurementTime_ < cutOffTime) { filterStateHistory_.pop_front(); poppedStates++; } RF_DEBUG("\nPopped " << poppedMeasurements << " measurements and " << poppedStates << " states from their respective queues." << "\n---- /RosFilter::clearExpiredHistory ----\n"); } } // namespace RobotLocalization // Instantiations of classes is required when template class code // is placed in a .cpp file. template class RobotLocalization::RosFilter; template class RobotLocalization::RosFilter; ================================================ FILE: src/robot_localization/src/ros_filter_utilities.cpp ================================================ /* * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * 1. Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * 2. Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * 3. Neither the name of the copyright holder nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #include "robot_localization/ros_filter_utilities.h" #include "robot_localization/filter_common.h" #include #include #include #include std::ostream& operator<<(std::ostream& os, const tf2::Vector3 &vec) { os << "(" << std::setprecision(20) << vec.getX() << " " << vec.getY() << " " << vec.getZ() << ")\n"; return os; } std::ostream& operator<<(std::ostream& os, const tf2::Quaternion &quat) { double roll, pitch, yaw; tf2::Matrix3x3 orTmp(quat); orTmp.getRPY(roll, pitch, yaw); os << "(" << std::setprecision(20) << roll << ", " << pitch << ", " << yaw << ")\n"; return os; } std::ostream& operator<<(std::ostream& os, const tf2::Transform &trans) { os << "Origin: " << trans.getOrigin() << "Rotation (RPY): " << trans.getRotation(); return os; } std::ostream& operator<<(std::ostream& os, const std::vector &vec) { os << "(" << std::setprecision(20); for (size_t i = 0; i < vec.size(); ++i) { os << vec[i] << " "; } os << ")\n"; return os; } namespace RobotLocalization { namespace RosFilterUtilities { double getYaw(const tf2::Quaternion quat) { tf2::Matrix3x3 mat(quat); double dummy; double yaw; mat.getRPY(dummy, dummy, yaw); return yaw; } bool lookupTransformSafe(const tf2_ros::Buffer &buffer, const std::string &targetFrame, const std::string &sourceFrame, const ros::Time &time, const ros::Duration &timeout, tf2::Transform &targetFrameTrans, const bool silent) { bool retVal = true; // First try to transform the data at the requested time try { tf2::fromMsg(buffer.lookupTransform(targetFrame, sourceFrame, time, timeout).transform, targetFrameTrans); } catch (tf2::TransformException &ex) { // The issue might be that the transforms that are available are not close // enough temporally to be used. In that case, just use the latest available // transform and warn the user. try { tf2::fromMsg(buffer.lookupTransform(targetFrame, sourceFrame, ros::Time(0)).transform, targetFrameTrans); if (!silent) { ROS_WARN_STREAM_THROTTLE(2.0, "Transform from " << sourceFrame << " to " << targetFrame << " was unavailable for the time requested. Using latest instead.\n"); } } catch(tf2::TransformException &ex) { if (!silent) { ROS_WARN_STREAM_THROTTLE(2.0, "Could not obtain transform from " << sourceFrame << " to " << targetFrame << ". Error was " << ex.what() << "\n"); } retVal = false; } } // Transforming from a frame id to itself can fail when the tf tree isn't // being broadcast (e.g., for some bag files). This is the only failure that // would throw an exception, so check for this situation before giving up. if (!retVal) { if (targetFrame == sourceFrame) { targetFrameTrans.setIdentity(); retVal = true; } } return retVal; } bool lookupTransformSafe(const tf2_ros::Buffer &buffer, const std::string &targetFrame, const std::string &sourceFrame, const ros::Time &time, tf2::Transform &targetFrameTrans, const bool silent) { return lookupTransformSafe(buffer, targetFrame, sourceFrame, time, ros::Duration(0), targetFrameTrans, silent); } void quatToRPY(const tf2::Quaternion &quat, double &roll, double &pitch, double &yaw) { tf2::Matrix3x3 orTmp(quat); orTmp.getRPY(roll, pitch, yaw); } void stateToTF(const Eigen::VectorXd &state, tf2::Transform &stateTF) { stateTF.setOrigin(tf2::Vector3(state(StateMemberX), state(StateMemberY), state(StateMemberZ))); tf2::Quaternion quat; quat.setRPY(state(StateMemberRoll), state(StateMemberPitch), state(StateMemberYaw)); stateTF.setRotation(quat); } void TFtoState(const tf2::Transform &stateTF, Eigen::VectorXd &state) { state(StateMemberX) = stateTF.getOrigin().getX(); state(StateMemberY) = stateTF.getOrigin().getY(); state(StateMemberZ) = stateTF.getOrigin().getZ(); quatToRPY(stateTF.getRotation(), state(StateMemberRoll), state(StateMemberPitch), state(StateMemberYaw)); } } // namespace RosFilterUtilities } // namespace RobotLocalization ================================================ FILE: src/robot_localization/src/ros_robot_localization_listener.cpp ================================================ /* * Copyright (c) 2016, TNO IVS Helmond. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * 1. Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * 2. Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * 3. Neither the name of the copyright holder nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #include "robot_localization/ros_robot_localization_listener.h" #include "robot_localization/ros_filter_utilities.h" #include #include #include #include #include #include #include #include #include namespace RobotLocalization { FilterType filterTypeFromString(const std::string& filter_type_str) { if ( filter_type_str == "ekf" ) { return FilterTypes::EKF; } else if ( filter_type_str == "ukf" ) { return FilterTypes::UKF; } else { return FilterTypes::NotDefined; } } RosRobotLocalizationListener::RosRobotLocalizationListener(): nh_p_("robot_localization"), odom_sub_(nh_, "odometry/filtered", 1), accel_sub_(nh_, "accel/filtered", 1), sync_(odom_sub_, accel_sub_, 10), tf_listener_(tf_buffer_), base_frame_id_(""), world_frame_id_("") { int buffer_size; nh_p_.param("buffer_size", buffer_size, 10); std::string param_ns; nh_p_.param("parameter_namespace", param_ns, nh_p_.getNamespace()); ros::NodeHandle nh_param(param_ns); std::string filter_type_str; nh_param.param("filter_type", filter_type_str, std::string("ekf")); FilterType filter_type = filterTypeFromString(filter_type_str); if ( filter_type == FilterTypes::NotDefined ) { ROS_ERROR("RosRobotLocalizationListener: Parameter filter_type invalid"); return; } // Load up the process noise covariance (from the launch file/parameter server) // todo: this code is copied from ros_filter. In a refactor, this could be moved to a function in ros_filter_utilities Eigen::MatrixXd process_noise_covariance(STATE_SIZE, STATE_SIZE); process_noise_covariance.setZero(); XmlRpc::XmlRpcValue process_noise_covar_config; if (!nh_param.hasParam("process_noise_covariance")) { ROS_FATAL_STREAM("Process noise covariance not found in the robot localization listener config (namespace " << nh_param.getNamespace() << ")! Use the ~parameter_namespace to specify the parameter namespace."); } else { try { nh_param.getParam("process_noise_covariance", process_noise_covar_config); ROS_ASSERT(process_noise_covar_config.getType() == XmlRpc::XmlRpcValue::TypeArray); int mat_size = process_noise_covariance.rows(); for (int i = 0; i < mat_size; i++) { for (int j = 0; j < mat_size; j++) { try { // These matrices can cause problems if all the types // aren't specified with decimal points. Handle that // using string streams. std::ostringstream ostr; process_noise_covar_config[mat_size * i + j].write(ostr); std::istringstream istr(ostr.str()); istr >> process_noise_covariance(i, j); } catch(XmlRpc::XmlRpcException &e) { throw e; } catch(...) { throw; } } } ROS_DEBUG_STREAM("Process noise covariance is:\n" << process_noise_covariance << "\n"); } catch (XmlRpc::XmlRpcException &e) { ROS_ERROR_STREAM("ERROR reading robot localization listener config: " << e.getMessage() << " for process_noise_covariance (type: " << process_noise_covar_config.getType() << ")"); } } std::vector filter_args; nh_param.param("filter_args", filter_args, std::vector()); estimator_ = new RobotLocalizationEstimator(buffer_size, filter_type, process_noise_covariance, filter_args); sync_.registerCallback(&RosRobotLocalizationListener::odomAndAccelCallback, this); ROS_INFO_STREAM("Ros Robot Localization Listener: Listening to topics " << odom_sub_.getTopic() << " and " << accel_sub_.getTopic()); // Wait until the base and world frames are set by the incoming messages while (ros::ok() && base_frame_id_.empty()) { ros::spinOnce(); ROS_INFO_STREAM_THROTTLE(1.0, "Ros Robot Localization Listener: Waiting for incoming messages on topics " << odom_sub_.getTopic() << " and " << accel_sub_.getTopic()); ros::Duration(0.1).sleep(); } } RosRobotLocalizationListener::~RosRobotLocalizationListener() { delete estimator_; } void RosRobotLocalizationListener::odomAndAccelCallback(const nav_msgs::Odometry& odom, const geometry_msgs::AccelWithCovarianceStamped& accel) { // Instantiate a state that can be added to the robot localization estimator EstimatorState state; // Set its time stamp and the state received from the messages state.time_stamp = odom.header.stamp.toSec(); // Get the base frame id from the odom message if ( base_frame_id_.empty() ) base_frame_id_ = odom.child_frame_id; // Get the world frame id from the odom message if ( world_frame_id_.empty() ) world_frame_id_ = odom.header.frame_id; // Pose: Position state.state(StateMemberX) = odom.pose.pose.position.x; state.state(StateMemberY) = odom.pose.pose.position.y; state.state(StateMemberZ) = odom.pose.pose.position.z; // Pose: Orientation tf2::Quaternion orientation_quat; tf2::fromMsg(odom.pose.pose.orientation, orientation_quat); double roll, pitch, yaw; RosFilterUtilities::quatToRPY(orientation_quat, roll, pitch, yaw); state.state(StateMemberRoll) = roll; state.state(StateMemberPitch) = pitch; state.state(StateMemberYaw) = yaw; // Pose: Covariance for ( unsigned int i = 0; i < POSE_SIZE; i++ ) { for ( unsigned int j = 0; j < POSE_SIZE; j++ ) { state.covariance(POSITION_OFFSET + i, POSITION_OFFSET + j) = odom.pose.covariance[i*POSE_SIZE + j]; } } // Velocity: Linear state.state(StateMemberVx) = odom.twist.twist.linear.x; state.state(StateMemberVy) = odom.twist.twist.linear.y; state.state(StateMemberVz) = odom.twist.twist.linear.z; // Velocity: Angular state.state(StateMemberVroll) = odom.twist.twist.angular.x; state.state(StateMemberVpitch) = odom.twist.twist.angular.y; state.state(StateMemberVyaw) = odom.twist.twist.angular.z; // Velocity: Covariance for ( unsigned int i = 0; i < TWIST_SIZE; i++ ) { for ( unsigned int j = 0; j < TWIST_SIZE; j++ ) { state.covariance(POSITION_V_OFFSET + i, POSITION_V_OFFSET + j) = odom.twist.covariance[i*TWIST_SIZE + j]; } } // Acceleration: Linear state.state(StateMemberAx) = accel.accel.accel.linear.x; state.state(StateMemberAy) = accel.accel.accel.linear.y; state.state(StateMemberAz) = accel.accel.accel.linear.z; // Acceleration: Angular is not available in state // Acceleration: Covariance for ( unsigned int i = 0; i < ACCELERATION_SIZE; i++ ) { for ( unsigned int j = 0; j < ACCELERATION_SIZE; j++ ) { state.covariance(POSITION_A_OFFSET + i, POSITION_A_OFFSET + j) = accel.accel.covariance[i*TWIST_SIZE + j]; } } // Add the state to the buffer, so that we can later interpolate between this and earlier states estimator_->setState(state); return; } bool findAncestorRecursiveYAML(YAML::Node& tree, const std::string& source_frame, const std::string& target_frame) { if ( source_frame == target_frame ) { return true; } std::string parent_frame = tree[source_frame]["parent"].Scalar(); if ( parent_frame.empty() ) { return false; } return findAncestorRecursiveYAML(tree, parent_frame, target_frame); } // Cache, assumption that the tree parent child order does not change over time static std::map > ancestor_map; static std::map > descendant_map; bool findAncestor(const tf2_ros::Buffer& buffer, const std::string& source_frame, const std::string& target_frame) { // Check cache const std::vector& ancestors = ancestor_map[source_frame]; if (std::find(ancestors.begin(), ancestors.end(), target_frame) != ancestors.end()) { return true; } const std::vector& descendants = descendant_map[source_frame]; if (std::find(descendants.begin(), descendants.end(), target_frame) != descendants.end()) { return false; } std::stringstream frames_stream(buffer.allFramesAsYAML()); YAML::Node frames_yaml = YAML::Load(frames_stream); bool target_frame_is_ancestor = findAncestorRecursiveYAML(frames_yaml, source_frame, target_frame); bool target_frame_is_descendant = findAncestorRecursiveYAML(frames_yaml, target_frame, source_frame); // Caching if (target_frame_is_ancestor) { ancestor_map[source_frame].push_back(target_frame); } if (target_frame_is_descendant) { descendant_map[source_frame].push_back(target_frame); } return target_frame_is_ancestor; } bool RosRobotLocalizationListener::getState(const double time, const std::string& frame_id, Eigen::VectorXd& state, Eigen::MatrixXd& covariance, std::string world_frame_id) const { EstimatorState estimator_state; state.resize(STATE_SIZE); state.setZero(); covariance.resize(STATE_SIZE, STATE_SIZE); covariance.setZero(); if ( base_frame_id_.empty() || world_frame_id_.empty() ) { if ( estimator_->getSize() == 0 ) { ROS_WARN("Ros Robot Localization Listener: The base or world frame id is not set. " "No odom/accel messages have come in."); } else { ROS_ERROR("Ros Robot Localization Listener: The base or world frame id is not set. " "Are the child_frame_id and the header.frame_id in the odom messages set?"); } return false; } if ( estimator_->getState(time, estimator_state) == EstimatorResults::ExtrapolationIntoPast ) { ROS_WARN("Ros Robot Localization Listener: A state is requested at a time stamp older than the oldest in the " "estimator buffer. The result is an extrapolation into the past. Maybe you should increase the buffer " "size?"); } // If no world_frame_id is specified, we will default to the world frame_id of the received odometry message if (world_frame_id.empty()) { world_frame_id = world_frame_id_; } if ( frame_id == base_frame_id_ && world_frame_id == world_frame_id_ ) { // If the state of the base frame is requested and the world frame equals the world frame of the robot_localization // estimator, we can simply return the state we got from the state estimator state = estimator_state.state; covariance = estimator_state.covariance; return true; } // - - - - - - - - - - - - - - - - - - // Get the transformation between the requested world frame and the world_frame of the estimator // - - - - - - - - - - - - - - - - - - Eigen::Affine3d world_pose_requested_frame; // If the requested frame is the same as the tracker, set to identity if (world_frame_id == world_frame_id_) { world_pose_requested_frame.setIdentity(); } else { geometry_msgs::TransformStamped world_requested_to_world_transform; try { world_requested_to_world_transform = tf_buffer_.lookupTransform(world_frame_id, world_frame_id_, ros::Time(time), ros::Duration(0.1)); // TODO: magic number if ( findAncestor(tf_buffer_, world_frame_id, base_frame_id_) ) { ROS_ERROR_STREAM("You are trying to get the state with respect to world frame " << world_frame_id << ", but this frame is a child of robot base frame " << base_frame_id_ << ", so this doesn't make sense."); return false; } } catch ( tf2::TransformException e ) { ROS_WARN_STREAM("Ros Robot Localization Listener: Could not look up transform: " << e.what()); return false; } // Convert to pose tf::transformMsgToEigen(world_requested_to_world_transform.transform, world_pose_requested_frame); } // - - - - - - - - - - - - - - - - - - // Calculate the state of the requested frame from the state of the base frame. // - - - - - - - - - - - - - - - - - - // First get the transform from base to target geometry_msgs::TransformStamped base_to_target_transform; try { base_to_target_transform = tf_buffer_.lookupTransform(base_frame_id_, frame_id, ros::Time(time), ros::Duration(0.1)); // TODO: magic number // Check that frame_id is a child of the base frame. If it is not, it does not make sense to request its state. // Do this after tf lookup, so we know that there is a connection. if ( ! findAncestor(tf_buffer_, frame_id, base_frame_id_) ) { ROS_ERROR_STREAM("You are trying to get the state of " << frame_id << ", but this frame is not a child of the " "base frame: " << base_frame_id_ << "."); return false; } } catch ( tf2::TransformException e ) { ROS_WARN_STREAM("Ros Robot Localization Listener: Could not look up transform: " << e.what()); return false; } // And convert it to an eigen Affine transformation Eigen::Affine3d target_pose_base; tf::transformMsgToEigen(base_to_target_transform.transform, target_pose_base); // Then convert the base pose to an Eigen Affine transformation Eigen::Vector3d base_position(estimator_state.state(StateMemberX), estimator_state.state(StateMemberY), estimator_state.state(StateMemberZ)); Eigen::AngleAxisd roll_angle(estimator_state.state(StateMemberRoll), Eigen::Vector3d::UnitX()); Eigen::AngleAxisd pitch_angle(estimator_state.state(StateMemberPitch), Eigen::Vector3d::UnitY()); Eigen::AngleAxisd yaw_angle(estimator_state.state(StateMemberYaw), Eigen::Vector3d::UnitZ()); Eigen::Quaterniond base_orientation(yaw_angle * pitch_angle * roll_angle); Eigen::Affine3d base_pose(Eigen::Translation3d(base_position) * base_orientation); // Now we can calculate the transform from odom to the requested frame (target)... Eigen::Affine3d target_pose_odom = world_pose_requested_frame * base_pose * target_pose_base; // ... and put it in the output state state(StateMemberX) = target_pose_odom.translation().x(); state(StateMemberY) = target_pose_odom.translation().y(); state(StateMemberZ) = target_pose_odom.translation().z(); Eigen::Vector3d ypr = target_pose_odom.rotation().eulerAngles(2, 1, 0); state(StateMemberRoll) = ypr[2]; state(StateMemberPitch) = ypr[1]; state(StateMemberYaw) = ypr[0]; // Now let's calculate the twist of the target frame // First get the base's twist Twist base_velocity; Twist target_velocity_base; base_velocity.linear = Eigen::Vector3d(estimator_state.state(StateMemberVx), estimator_state.state(StateMemberVy), estimator_state.state(StateMemberVz)); base_velocity.angular = Eigen::Vector3d(estimator_state.state(StateMemberVroll), estimator_state.state(StateMemberVpitch), estimator_state.state(StateMemberVyaw)); // Then calculate the target frame's twist as a result of the base's twist. /* * We first calculate the coordinates of the velocity vectors (linear and angular) in the base frame. We have to keep * in mind that a rotation of the base frame, together with the translational offset of the target frame from the base * frame, induces a translational velocity of the target frame. */ target_velocity_base.linear = base_velocity.linear + base_velocity.angular.cross(target_pose_base.translation()); target_velocity_base.angular = base_velocity.angular; // Now we can transform that to the target frame Twist target_velocity; target_velocity.linear = target_pose_base.rotation().transpose() * target_velocity_base.linear; target_velocity.angular = target_pose_base.rotation().transpose() * target_velocity_base.angular; state(StateMemberVx) = target_velocity.linear(0); state(StateMemberVy) = target_velocity.linear(1); state(StateMemberVz) = target_velocity.linear(2); state(StateMemberVroll) = target_velocity.angular(0); state(StateMemberVpitch) = target_velocity.angular(1); state(StateMemberVyaw) = target_velocity.angular(2); // Rotate the covariance as well Eigen::MatrixXd rot_6d(POSE_SIZE, POSE_SIZE); rot_6d.setIdentity(); rot_6d.block(POSITION_OFFSET, POSITION_OFFSET) = target_pose_base.rotation(); rot_6d.block(ORIENTATION_OFFSET, ORIENTATION_OFFSET) = target_pose_base.rotation(); // Rotate the covariance covariance.block(POSITION_OFFSET, POSITION_OFFSET) = rot_6d * estimator_state.covariance.eval() * rot_6d.transpose(); return true; } bool RosRobotLocalizationListener::getState(const ros::Time& ros_time, const std::string& frame_id, Eigen::VectorXd& state, Eigen::MatrixXd& covariance, const std::string& world_frame_id) const { double time; if ( ros_time.isZero() ) { ROS_INFO("Ros Robot Localization Listener: State requested at time = zero, returning state at current time"); time = ros::Time::now().toSec(); } else { time = ros_time.toSec(); } return getState(time, frame_id, state, covariance, world_frame_id); } const std::string& RosRobotLocalizationListener::getBaseFrameId() const { return base_frame_id_; } const std::string& RosRobotLocalizationListener::getWorldFrameId() const { return world_frame_id_; } } // namespace RobotLocalization ================================================ FILE: src/robot_localization/src/ukf.cpp ================================================ /* * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * 1. Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * 2. Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * 3. Neither the name of the copyright holder nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #include "robot_localization/ukf.h" #include "robot_localization/filter_common.h" #include #include #include #include #include #include #include #include namespace RobotLocalization { Ukf::Ukf(std::vector args) : FilterBase(), // Must initialize filter base! uncorrected_(true) { assert(args.size() == 3); double alpha = args[0]; double kappa = args[1]; double beta = args[2]; size_t sigmaCount = (STATE_SIZE << 1) + 1; sigmaPoints_.resize(sigmaCount, Eigen::VectorXd(STATE_SIZE)); // Prepare constants lambda_ = alpha * alpha * (STATE_SIZE + kappa) - STATE_SIZE; stateWeights_.resize(sigmaCount); covarWeights_.resize(sigmaCount); stateWeights_[0] = lambda_ / (STATE_SIZE + lambda_); covarWeights_[0] = stateWeights_[0] + (1 - (alpha * alpha) + beta); sigmaPoints_[0].setZero(); for (size_t i = 1; i < sigmaCount; ++i) { sigmaPoints_[i].setZero(); stateWeights_[i] = 1 / (2 * (STATE_SIZE + lambda_)); covarWeights_[i] = stateWeights_[i]; } } Ukf::~Ukf() { } void Ukf::correct(const Measurement &measurement) { FB_DEBUG("---------------------- Ukf::correct ----------------------\n" << "State is:\n" << state_ << "\nMeasurement is:\n" << measurement.measurement_ << "\nMeasurement covariance is:\n" << measurement.covariance_ << "\n"); // In our implementation, it may be that after we call predict once, we call correct // several times in succession (multiple measurements with different time stamps). In // that event, the sigma points need to be updated to reflect the current state. // Throughout prediction and correction, we attempt to maximize efficiency in Eigen. if (!uncorrected_) { // Take the square root of a small fraction of the estimateErrorCovariance_ using LL' decomposition weightedCovarSqrt_ = ((STATE_SIZE + lambda_) * estimateErrorCovariance_).llt().matrixL(); // Compute sigma points // First sigma point is the current state sigmaPoints_[0] = state_; // Next STATE_SIZE sigma points are state + weightedCovarSqrt_[ith column] // STATE_SIZE sigma points after that are state - weightedCovarSqrt_[ith column] for (size_t sigmaInd = 0; sigmaInd < STATE_SIZE; ++sigmaInd) { sigmaPoints_[sigmaInd + 1] = state_ + weightedCovarSqrt_.col(sigmaInd); sigmaPoints_[sigmaInd + 1 + STATE_SIZE] = state_ - weightedCovarSqrt_.col(sigmaInd); } } // We don't want to update everything, so we need to build matrices that only update // the measured parts of our state vector // First, determine how many state vector values we're updating std::vector updateIndices; for (size_t i = 0; i < measurement.updateVector_.size(); ++i) { if (measurement.updateVector_[i]) { // Handle nan and inf values in measurements if (std::isnan(measurement.measurement_(i))) { FB_DEBUG("Value at index " << i << " was nan. Excluding from update.\n"); } else if (std::isinf(measurement.measurement_(i))) { FB_DEBUG("Value at index " << i << " was inf. Excluding from update.\n"); } else { updateIndices.push_back(i); } } } FB_DEBUG("Update indices are:\n" << updateIndices << "\n"); size_t updateSize = updateIndices.size(); // Now set up the relevant matrices Eigen::VectorXd stateSubset(updateSize); // x (in most literature) Eigen::VectorXd measurementSubset(updateSize); // z Eigen::MatrixXd measurementCovarianceSubset(updateSize, updateSize); // R Eigen::MatrixXd stateToMeasurementSubset(updateSize, STATE_SIZE); // H Eigen::MatrixXd kalmanGainSubset(STATE_SIZE, updateSize); // K Eigen::VectorXd innovationSubset(updateSize); // z - Hx Eigen::VectorXd predictedMeasurement(updateSize); Eigen::VectorXd sigmaDiff(updateSize); Eigen::MatrixXd predictedMeasCovar(updateSize, updateSize); Eigen::MatrixXd crossCovar(STATE_SIZE, updateSize); std::vector sigmaPointMeasurements(sigmaPoints_.size(), Eigen::VectorXd(updateSize)); stateSubset.setZero(); measurementSubset.setZero(); measurementCovarianceSubset.setZero(); stateToMeasurementSubset.setZero(); kalmanGainSubset.setZero(); innovationSubset.setZero(); predictedMeasurement.setZero(); predictedMeasCovar.setZero(); crossCovar.setZero(); // Now build the sub-matrices from the full-sized matrices for (size_t i = 0; i < updateSize; ++i) { measurementSubset(i) = measurement.measurement_(updateIndices[i]); stateSubset(i) = state_(updateIndices[i]); for (size_t j = 0; j < updateSize; ++j) { measurementCovarianceSubset(i, j) = measurement.covariance_(updateIndices[i], updateIndices[j]); } // Handle negative (read: bad) covariances in the measurement. Rather // than exclude the measurement or make up a covariance, just take // the absolute value. if (measurementCovarianceSubset(i, i) < 0) { FB_DEBUG("WARNING: Negative covariance for index " << i << " of measurement (value is" << measurementCovarianceSubset(i, i) << "). Using absolute value...\n"); measurementCovarianceSubset(i, i) = ::fabs(measurementCovarianceSubset(i, i)); } // If the measurement variance for a given variable is very // near 0 (as in e-50 or so) and the variance for that // variable in the covariance matrix is also near zero, then // the Kalman gain computation will blow up. Really, no // measurement can be completely without error, so add a small // amount in that case. if (measurementCovarianceSubset(i, i) < 1e-9) { measurementCovarianceSubset(i, i) = 1e-9; FB_DEBUG("WARNING: measurement had very small error covariance for index " << updateIndices[i] << ". Adding some noise to maintain filter stability.\n"); } } // The state-to-measurement function, h, will now be a measurement_size x full_state_size // matrix, with ones in the (i, i) locations of the values to be updated for (size_t i = 0; i < updateSize; ++i) { stateToMeasurementSubset(i, updateIndices[i]) = 1; } FB_DEBUG("Current state subset is:\n" << stateSubset << "\nMeasurement subset is:\n" << measurementSubset << "\nMeasurement covariance subset is:\n" << measurementCovarianceSubset << "\nState-to-measurement subset is:\n" << stateToMeasurementSubset << "\n"); // (1) Generate sigma points, use them to generate a predicted measurement for (size_t sigmaInd = 0; sigmaInd < sigmaPoints_.size(); ++sigmaInd) { sigmaPointMeasurements[sigmaInd] = stateToMeasurementSubset * sigmaPoints_[sigmaInd]; predictedMeasurement.noalias() += stateWeights_[sigmaInd] * sigmaPointMeasurements[sigmaInd]; } // (2) Use the sigma point measurements and predicted measurement to compute a predicted // measurement covariance matrix P_zz and a state/measurement cross-covariance matrix P_xz. for (size_t sigmaInd = 0; sigmaInd < sigmaPoints_.size(); ++sigmaInd) { sigmaDiff = sigmaPointMeasurements[sigmaInd] - predictedMeasurement; predictedMeasCovar.noalias() += covarWeights_[sigmaInd] * (sigmaDiff * sigmaDiff.transpose()); crossCovar.noalias() += covarWeights_[sigmaInd] * ((sigmaPoints_[sigmaInd] - state_) * sigmaDiff.transpose()); } // (3) Compute the Kalman gain, making sure to use the actual measurement covariance: K = P_xz * (P_zz + R)^-1 Eigen::MatrixXd invInnovCov = (predictedMeasCovar + measurementCovarianceSubset).inverse(); kalmanGainSubset = crossCovar * invInnovCov; // (4) Apply the gain to the difference between the actual and predicted measurements: x = x + K(z - z_hat) innovationSubset = (measurementSubset - predictedMeasurement); // Wrap angles in the innovation for (size_t i = 0; i < updateSize; ++i) { if (updateIndices[i] == StateMemberRoll || updateIndices[i] == StateMemberPitch || updateIndices[i] == StateMemberYaw) { while (innovationSubset(i) < -PI) { innovationSubset(i) += TAU; } while (innovationSubset(i) > PI) { innovationSubset(i) -= TAU; } } } // (5) Check Mahalanobis distance of innovation if (checkMahalanobisThreshold(innovationSubset, invInnovCov, measurement.mahalanobisThresh_)) { state_.noalias() += kalmanGainSubset * innovationSubset; // (6) Compute the new estimate error covariance P = P - (K * P_zz * K') estimateErrorCovariance_.noalias() -= (kalmanGainSubset * predictedMeasCovar * kalmanGainSubset.transpose()); wrapStateAngles(); // Mark that we need to re-compute sigma points for successive corrections uncorrected_ = false; FB_DEBUG("Predicated measurement covariance is:\n" << predictedMeasCovar << "\nCross covariance is:\n" << crossCovar << "\nKalman gain subset is:\n" << kalmanGainSubset << "\nInnovation:\n" << innovationSubset << "\nCorrected full state is:\n" << state_ << "\nCorrected full estimate error covariance is:\n" << estimateErrorCovariance_ << "\n\n---------------------- /Ukf::correct ----------------------\n"); } } void Ukf::predict(const double referenceTime, const double delta) { FB_DEBUG("---------------------- Ukf::predict ----------------------\n" << "delta is " << delta << "\nstate is " << state_ << "\n"); double roll = state_(StateMemberRoll); double pitch = state_(StateMemberPitch); double yaw = state_(StateMemberYaw); // We'll need these trig calculations a lot. double sp = ::sin(pitch); double cp = ::cos(pitch); double sr = ::sin(roll); double cr = ::cos(roll); double sy = ::sin(yaw); double cy = ::cos(yaw); prepareControl(referenceTime, delta); // Prepare the transfer function transferFunction_(StateMemberX, StateMemberVx) = cy * cp * delta; transferFunction_(StateMemberX, StateMemberVy) = (cy * sp * sr - sy * cr) * delta; transferFunction_(StateMemberX, StateMemberVz) = (cy * sp * cr + sy * sr) * delta; transferFunction_(StateMemberX, StateMemberAx) = 0.5 * transferFunction_(StateMemberX, StateMemberVx) * delta; transferFunction_(StateMemberX, StateMemberAy) = 0.5 * transferFunction_(StateMemberX, StateMemberVy) * delta; transferFunction_(StateMemberX, StateMemberAz) = 0.5 * transferFunction_(StateMemberX, StateMemberVz) * delta; transferFunction_(StateMemberY, StateMemberVx) = sy * cp * delta; transferFunction_(StateMemberY, StateMemberVy) = (sy * sp * sr + cy * cr) * delta; transferFunction_(StateMemberY, StateMemberVz) = (sy * sp * cr - cy * sr) * delta; transferFunction_(StateMemberY, StateMemberAx) = 0.5 * transferFunction_(StateMemberY, StateMemberVx) * delta; transferFunction_(StateMemberY, StateMemberAy) = 0.5 * transferFunction_(StateMemberY, StateMemberVy) * delta; transferFunction_(StateMemberY, StateMemberAz) = 0.5 * transferFunction_(StateMemberY, StateMemberVz) * delta; transferFunction_(StateMemberZ, StateMemberVx) = -sp * delta; transferFunction_(StateMemberZ, StateMemberVy) = cp * sr * delta; transferFunction_(StateMemberZ, StateMemberVz) = cp * cr * delta; transferFunction_(StateMemberZ, StateMemberAx) = 0.5 * transferFunction_(StateMemberZ, StateMemberVx) * delta; transferFunction_(StateMemberZ, StateMemberAy) = 0.5 * transferFunction_(StateMemberZ, StateMemberVy) * delta; transferFunction_(StateMemberZ, StateMemberAz) = 0.5 * transferFunction_(StateMemberZ, StateMemberVz) * delta; transferFunction_(StateMemberRoll, StateMemberVroll) = transferFunction_(StateMemberX, StateMemberVx); transferFunction_(StateMemberRoll, StateMemberVpitch) = transferFunction_(StateMemberX, StateMemberVy); transferFunction_(StateMemberRoll, StateMemberVyaw) = transferFunction_(StateMemberX, StateMemberVz); transferFunction_(StateMemberPitch, StateMemberVroll) = transferFunction_(StateMemberY, StateMemberVx); transferFunction_(StateMemberPitch, StateMemberVpitch) = transferFunction_(StateMemberY, StateMemberVy); transferFunction_(StateMemberPitch, StateMemberVyaw) = transferFunction_(StateMemberY, StateMemberVz); transferFunction_(StateMemberYaw, StateMemberVroll) = transferFunction_(StateMemberZ, StateMemberVx); transferFunction_(StateMemberYaw, StateMemberVpitch) = transferFunction_(StateMemberZ, StateMemberVy); transferFunction_(StateMemberYaw, StateMemberVyaw) = transferFunction_(StateMemberZ, StateMemberVz); transferFunction_(StateMemberVx, StateMemberAx) = delta; transferFunction_(StateMemberVy, StateMemberAy) = delta; transferFunction_(StateMemberVz, StateMemberAz) = delta; // (1) Take the square root of a small fraction of the estimateErrorCovariance_ using LL' decomposition weightedCovarSqrt_ = ((STATE_SIZE + lambda_) * estimateErrorCovariance_).llt().matrixL(); // (2) Compute sigma points *and* pass them through the transfer function to save // the extra loop // First sigma point is the current state sigmaPoints_[0] = transferFunction_ * state_; // Next STATE_SIZE sigma points are state + weightedCovarSqrt_[ith column] // STATE_SIZE sigma points after that are state - weightedCovarSqrt_[ith column] for (size_t sigmaInd = 0; sigmaInd < STATE_SIZE; ++sigmaInd) { sigmaPoints_[sigmaInd + 1] = transferFunction_ * (state_ + weightedCovarSqrt_.col(sigmaInd)); sigmaPoints_[sigmaInd + 1 + STATE_SIZE] = transferFunction_ * (state_ - weightedCovarSqrt_.col(sigmaInd)); } // (3) Sum the weighted sigma points to generate a new state prediction state_.setZero(); for (size_t sigmaInd = 0; sigmaInd < sigmaPoints_.size(); ++sigmaInd) { state_.noalias() += stateWeights_[sigmaInd] * sigmaPoints_[sigmaInd]; } // (4) Now us the sigma points and the predicted state to compute a predicted covariance estimateErrorCovariance_.setZero(); Eigen::VectorXd sigmaDiff(STATE_SIZE); for (size_t sigmaInd = 0; sigmaInd < sigmaPoints_.size(); ++sigmaInd) { sigmaDiff = (sigmaPoints_[sigmaInd] - state_); estimateErrorCovariance_.noalias() += covarWeights_[sigmaInd] * (sigmaDiff * sigmaDiff.transpose()); } // (5) Not strictly in the theoretical UKF formulation, but necessary here // to ensure that we actually incorporate the processNoiseCovariance_ Eigen::MatrixXd *processNoiseCovariance = &processNoiseCovariance_; if (useDynamicProcessNoiseCovariance_) { computeDynamicProcessNoiseCovariance(state_, delta); processNoiseCovariance = &dynamicProcessNoiseCovariance_; } estimateErrorCovariance_.noalias() += delta * (*processNoiseCovariance); // Keep the angles bounded wrapStateAngles(); // Mark that we can keep these sigma points uncorrected_ = true; FB_DEBUG("Predicted state is:\n" << state_ << "\nPredicted estimate error covariance is:\n" << estimateErrorCovariance_ << "\n\n--------------------- /Ukf::predict ----------------------\n"); } } // namespace RobotLocalization ================================================ FILE: src/robot_localization/src/ukf_localization_node.cpp ================================================ /* * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * 1. Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * 2. Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * 3. Neither the name of the copyright holder nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #include "robot_localization/ros_filter_types.h" #include #include int main(int argc, char **argv) { ros::init(argc, argv, "ukf_navigation_node"); ros::NodeHandle nhLocal("~"); std::vector args(3, 0); nhLocal.param("alpha", args[0], 0.001); nhLocal.param("kappa", args[1], 0.0); nhLocal.param("beta", args[2], 2.0); RobotLocalization::RosUkf ukf(args); ukf.run(); return EXIT_SUCCESS; } ================================================ FILE: src/robot_localization/srv/GetState.srv ================================================ time time_stamp string frame_id --- # State vector: x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az float64[15] state # Covariance matrix in row-major order float64[225] covariance ================================================ FILE: src/robot_localization/srv/SetDatum.srv ================================================ geographic_msgs/GeoPose geo_pose --- ================================================ FILE: src/robot_localization/srv/SetPose.srv ================================================ geometry_msgs/PoseWithCovarianceStamped pose --- ================================================ FILE: src/robot_localization/test/record_all_stats.sh ================================================ #!/bin/bash ./stat_recorder.sh test_ekf_localization_node_bag1.test $1/ekf1.txt ./stat_recorder.sh test_ekf_localization_node_bag2.test $1/ekf2.txt ./stat_recorder.sh test_ekf_localization_node_bag3.test $1/ekf3.txt ./stat_recorder.sh test_ukf_localization_node_bag1.test $1/ukf1.txt ./stat_recorder.sh test_ukf_localization_node_bag2.test $1/ukf2.txt ./stat_recorder.sh test_ukf_localization_node_bag3.test $1/ukf3.txt ================================================ FILE: src/robot_localization/test/stat_recorder.sh ================================================ #!/bin/bash rm $2 echo "x = [" > $2 i="0" while [ $i -lt 30 ] do rostest robot_localization $1 output_final_position:=true output_location:=$2 i=$[$i+1] sleep 3 done echo "]" >> $2 echo "mean(x)" >> $2 echo "sqrt(sum((4 * std(x)).^2))" >> $2 ================================================ FILE: src/robot_localization/test/test3.bag ================================================ [File too large to display: 24.5 MB] ================================================ FILE: src/robot_localization/test/test_ekf.cpp ================================================ /* * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * 1. Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * 2. Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * 3. Neither the name of the copyright holder nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #include "robot_localization/ros_filter_types.h" #include #include #include using RobotLocalization::Ekf; using RobotLocalization::RosEkf; using RobotLocalization::STATE_SIZE; class RosEkfPassThrough : public RosEkf { public: RosEkfPassThrough() { } Ekf &getFilter() { return filter_; } }; TEST(EkfTest, Measurements) { RosEkfPassThrough ekf; Eigen::MatrixXd initialCovar(15, 15); initialCovar.setIdentity(); initialCovar *= 0.5; ekf.getFilter().setEstimateErrorCovariance(initialCovar); Eigen::VectorXd measurement(STATE_SIZE); measurement.setIdentity(); for (size_t i = 0; i < STATE_SIZE; ++i) { measurement[i] = i * 0.01 * STATE_SIZE; } Eigen::MatrixXd measurementCovariance(STATE_SIZE, STATE_SIZE); measurementCovariance.setIdentity(); for (size_t i = 0; i < STATE_SIZE; ++i) { measurementCovariance(i, i) = 1e-9; } std::vector updateVector(STATE_SIZE, true); // Ensure that measurements are being placed in the queue correctly ros::Time time; time.fromSec(1000); ekf.enqueueMeasurement("odom0", measurement, measurementCovariance, updateVector, std::numeric_limits::max(), time); ekf.integrateMeasurements(ros::Time(1001)); EXPECT_EQ(ekf.getFilter().getState(), measurement); EXPECT_EQ(ekf.getFilter().getEstimateErrorCovariance(), measurementCovariance); ekf.getFilter().setEstimateErrorCovariance(initialCovar); // Now fuse another measurement and check the output. // We know what the filter's state should be when // this is complete, so we'll check the difference and // make sure it's suitably small. Eigen::VectorXd measurement2 = measurement; measurement2 *= 2.0; for (size_t i = 0; i < STATE_SIZE; ++i) { measurementCovariance(i, i) = 1e-9; } time.fromSec(1002); ekf.enqueueMeasurement("odom0", measurement2, measurementCovariance, updateVector, std::numeric_limits::max(), time); ekf.integrateMeasurements(ros::Time(1003)); measurement = measurement2.eval() - ekf.getFilter().getState(); for (size_t i = 0; i < STATE_SIZE; ++i) { EXPECT_LT(::fabs(measurement[i]), 0.001); } } int main(int argc, char **argv) { ros::init(argc, argv, "ekf"); testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); } ================================================ FILE: src/robot_localization/test/test_ekf.test ================================================ ================================================ FILE: src/robot_localization/test/test_ekf_localization_node_bag1.test ================================================ [false, false, false, false, false, false, true, true, true, false, false, false, false, false, false] [false, false, false, true, true, true, false, false, false, true, true, false, true, true, true] [0.05, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.05, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.06, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.06, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.025, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.025, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.04, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.02, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.015] [1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9] ================================================ FILE: src/robot_localization/test/test_ekf_localization_node_bag2.test ================================================ [false, false, false, false, false, false, true, true, true, false, false, true, false, false, false] [false, false, false, true, true, true, false, false, false, true, true, true, true, true, true] [0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.06, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.025, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.025, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.05, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.002, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.002, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.004, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01] [1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9] ================================================ FILE: src/robot_localization/test/test_ekf_localization_node_bag3.test ================================================ [false, false, true, false, false, false, true, true, false, false, false, true, false, false, false] [false, false, false, true, true, true, false, false, false, true, true, true, false, false, false] [0.03, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.4, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.025, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.025, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01] ================================================ FILE: src/robot_localization/test/test_ekf_localization_node_interfaces.cpp ================================================ /* * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * 1. Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * 2. Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * 3. Neither the name of the copyright holder nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #include "robot_localization/SetPose.h" #include #include #include #include #include #include #include #include #include nav_msgs::Odometry filtered_; bool stateUpdated_; void resetFilter() { ros::NodeHandle nh; ros::ServiceClient client = nh.serviceClient("/set_pose"); robot_localization::SetPose setPose; setPose.request.pose.pose.pose.orientation.w = 1; setPose.request.pose.header.frame_id = "odom"; for (size_t ind = 0; ind < 36; ind+=7) { setPose.request.pose.pose.covariance[ind] = 1e-6; } setPose.request.pose.header.stamp = ros::Time::now(); client.call(setPose); setPose.request.pose.header.seq++; ros::spinOnce(); ros::Duration(0.01).sleep(); stateUpdated_ = false; double deltaX = 0.0; double deltaY = 0.0; double deltaZ = 0.0; while (!stateUpdated_ || ::sqrt(deltaX * deltaX + deltaY * deltaY + deltaZ * deltaZ) > 0.1) { ros::spinOnce(); ros::Duration(0.01).sleep(); deltaX = filtered_.pose.pose.position.x - setPose.request.pose.pose.pose.position.x; deltaY = filtered_.pose.pose.position.y - setPose.request.pose.pose.pose.position.y; deltaZ = filtered_.pose.pose.position.z - setPose.request.pose.pose.pose.position.z; } EXPECT_LT(::sqrt(deltaX * deltaX + deltaY * deltaY + deltaZ * deltaZ), 0.1); } void filterCallback(const nav_msgs::OdometryConstPtr &msg) { filtered_ = *msg; stateUpdated_ = true; } TEST(InterfacesTest, OdomPoseBasicIO) { stateUpdated_ = false; ros::NodeHandle nh; ros::Publisher odomPub = nh.advertise("/odom_input0", 5); ros::Subscriber filteredSub = nh.subscribe("/odometry/filtered", 1, &filterCallback); nav_msgs::Odometry odom; odom.pose.pose.position.x = 20.0; odom.pose.pose.position.y = 10.0; odom.pose.pose.position.z = -40.0; odom.pose.covariance[0] = 2.0; odom.pose.covariance[7] = 2.0; odom.pose.covariance[14] = 2.0; odom.header.frame_id = "odom"; odom.child_frame_id = "base_link"; ros::Rate loopRate(50); for (size_t i = 0; i < 50; ++i) { odom.header.stamp = ros::Time::now(); odomPub.publish(odom); ros::spinOnce(); loopRate.sleep(); odom.header.seq++; } // Now check the values from the callback EXPECT_LT(::fabs(filtered_.pose.pose.position.x - odom.pose.pose.position.x), 0.01); EXPECT_LT(::fabs(filtered_.pose.pose.position.y), 0.01); // Configuration for this variable for this sensor is false EXPECT_LT(::fabs(filtered_.pose.pose.position.z - odom.pose.pose.position.z), 0.01); EXPECT_LT(filtered_.pose.covariance[0], 0.5); EXPECT_LT(filtered_.pose.covariance[7], 0.25); // Configuration for this variable for this sensor is false EXPECT_LT(filtered_.pose.covariance[14], 0.5); resetFilter(); } TEST(InterfacesTest, OdomTwistBasicIO) { ros::NodeHandle nh; ros::Publisher odomPub = nh.advertise("/odom_input2", 5); ros::Subscriber filteredSub = nh.subscribe("/odometry/filtered", 1, &filterCallback); nav_msgs::Odometry odom; odom.twist.twist.linear.x = 5.0; odom.twist.twist.linear.y = 0.0; odom.twist.twist.linear.z = 0.0; odom.twist.twist.angular.x = 0.0; odom.twist.twist.angular.y = 0.0; odom.twist.twist.angular.z = 0.0; for (size_t ind = 0; ind < 36; ind+=7) { odom.twist.covariance[ind] = 1e-6; } odom.header.frame_id = "odom"; odom.child_frame_id = "base_link"; ros::Rate loopRate(20); for (size_t i = 0; i < 400; ++i) { odom.header.stamp = ros::Time::now(); odomPub.publish(odom); ros::spinOnce(); loopRate.sleep(); odom.header.seq++; } ros::spinOnce(); EXPECT_LT(::fabs(filtered_.twist.twist.linear.x - odom.twist.twist.linear.x), 0.1); EXPECT_LT(::fabs(filtered_.pose.pose.position.x - 100.0), 2.0); resetFilter(); odom.twist.twist.linear.x = 0.0; odom.twist.twist.linear.y = 5.0; loopRate = ros::Rate(20); for (size_t i = 0; i < 200; ++i) { odom.header.stamp = ros::Time::now(); odomPub.publish(odom); ros::spinOnce(); loopRate.sleep(); odom.header.seq++; } ros::spinOnce(); EXPECT_LT(::fabs(filtered_.twist.twist.linear.y - odom.twist.twist.linear.y), 0.1); EXPECT_LT(::fabs(filtered_.pose.pose.position.y - 50.0), 1.0); resetFilter(); odom.twist.twist.linear.y = 0.0; odom.twist.twist.linear.z = 5.0; loopRate = ros::Rate(20); for (size_t i = 0; i < 100; ++i) { odom.header.stamp = ros::Time::now(); odomPub.publish(odom); ros::spinOnce(); loopRate.sleep(); odom.header.seq++; } ros::spinOnce(); EXPECT_LT(::fabs(filtered_.twist.twist.linear.z - odom.twist.twist.linear.z), 0.1); EXPECT_LT(::fabs(filtered_.pose.pose.position.z - 25.0), 1.0); resetFilter(); odom.twist.twist.linear.z = 0.0; odom.twist.twist.linear.x = 1.0; odom.twist.twist.angular.z = (M_PI/2) / (100.0 * 0.05); loopRate = ros::Rate(20); for (size_t i = 0; i < 100; ++i) { odom.header.stamp = ros::Time::now(); odomPub.publish(odom); ros::spinOnce(); loopRate.sleep(); odom.header.seq++; } ros::spinOnce(); EXPECT_LT(::fabs(filtered_.twist.twist.linear.x - odom.twist.twist.linear.x), 0.1); EXPECT_LT(::fabs(filtered_.twist.twist.angular.z - odom.twist.twist.angular.z), 0.1); EXPECT_LT(::fabs(filtered_.pose.pose.position.x - filtered_.pose.pose.position.y), 0.5); resetFilter(); odom.twist.twist.linear.x = 0.0; odom.twist.twist.angular.z = 0.0; odom.twist.twist.angular.x = -(M_PI/2) / (100.0 * 0.05); // First, roll the vehicle on its side loopRate = ros::Rate(20); for (size_t i = 0; i < 100; ++i) { odom.header.stamp = ros::Time::now(); odomPub.publish(odom); ros::spinOnce(); loopRate.sleep(); odom.header.seq++; } ros::spinOnce(); odom.twist.twist.angular.x = 0.0; odom.twist.twist.angular.y = (M_PI/2) / (100.0 * 0.05); // Now, pitch it down (positive pitch velocity in vehicle frame) loopRate = ros::Rate(20); for (size_t i = 0; i < 100; ++i) { odom.header.stamp = ros::Time::now(); odomPub.publish(odom); ros::spinOnce(); loopRate.sleep(); odom.header.seq++; } ros::spinOnce(); odom.twist.twist.angular.y = 0.0; odom.twist.twist.linear.x = 3.0; // We should now be on our side and facing -Y. Move forward in // the vehicle frame X direction, and make sure Y decreases in // the world frame. loopRate = ros::Rate(20); for (size_t i = 0; i < 100; ++i) { odom.header.stamp = ros::Time::now(); odomPub.publish(odom); ros::spinOnce(); loopRate.sleep(); odom.header.seq++; } ros::spinOnce(); EXPECT_LT(::fabs(filtered_.twist.twist.linear.x - odom.twist.twist.linear.x), 0.1); EXPECT_LT(::fabs(filtered_.pose.pose.position.y + 15), 1.0); resetFilter(); } TEST(InterfacesTest, PoseBasicIO) { ros::NodeHandle nh; ros::Publisher posePub = nh.advertise("/pose_input0", 5); ros::Subscriber filteredSub = nh.subscribe("/odometry/filtered", 1, &filterCallback); geometry_msgs::PoseWithCovarianceStamped pose; pose.pose.pose.position.x = 20.0; pose.pose.pose.position.y = 10.0; pose.pose.pose.position.z = -40.0; pose.pose.pose.orientation.x = 0; pose.pose.pose.orientation.y = 0; pose.pose.pose.orientation.z = 0; pose.pose.pose.orientation.w = 1; for (size_t ind = 0; ind < 36; ind+=7) { pose.pose.covariance[ind] = 1e-6; } pose.header.frame_id = "odom"; ros::Rate loopRate = ros::Rate(50); for (size_t i = 0; i < 50; ++i) { pose.header.stamp = ros::Time::now(); posePub.publish(pose); ros::spinOnce(); loopRate.sleep(); pose.header.seq++; } // Now check the values from the callback EXPECT_LT(::fabs(filtered_.pose.pose.position.x - pose.pose.pose.position.x), 0.1); EXPECT_LT(::fabs(filtered_.pose.pose.position.y), 0.1); // Configuration for this variable for this sensor is false EXPECT_LT(::fabs(filtered_.pose.pose.position.z - pose.pose.pose.position.z), 0.1); EXPECT_LT(filtered_.pose.covariance[0], 0.5); EXPECT_LT(filtered_.pose.covariance[7], 0.25); // Configuration for this variable for this sensor is false EXPECT_LT(filtered_.pose.covariance[14], 0.5); resetFilter(); } TEST(InterfacesTest, TwistBasicIO) { ros::NodeHandle nh; ros::Publisher twistPub = nh.advertise("/twist_input0", 5); ros::Subscriber filteredSub = nh.subscribe("/odometry/filtered", 1, &filterCallback); geometry_msgs::TwistWithCovarianceStamped twist; twist.twist.twist.linear.x = 5.0; twist.twist.twist.linear.y = 0; twist.twist.twist.linear.z = 0; twist.twist.twist.angular.x = 0; twist.twist.twist.angular.y = 0; twist.twist.twist.angular.z = 0; for (size_t ind = 0; ind < 36; ind+=7) { twist.twist.covariance[ind] = 1e-6; } twist.header.frame_id = "base_link"; ros::Rate loopRate = ros::Rate(20); for (size_t i = 0; i < 400; ++i) { twist.header.stamp = ros::Time::now(); twistPub.publish(twist); ros::spinOnce(); loopRate.sleep(); twist.header.seq++; } ros::spinOnce(); EXPECT_LT(::fabs(filtered_.twist.twist.linear.x - twist.twist.twist.linear.x), 0.1); EXPECT_LT(::fabs(filtered_.pose.pose.position.x - 100.0), 2.0); resetFilter(); twist.twist.twist.linear.x = 0.0; twist.twist.twist.linear.y = 5.0; loopRate = ros::Rate(20); for (size_t i = 0; i < 200; ++i) { twist.header.stamp = ros::Time::now(); twistPub.publish(twist); ros::spinOnce(); loopRate.sleep(); twist.header.seq++; } ros::spinOnce(); EXPECT_LT(::fabs(filtered_.twist.twist.linear.y - twist.twist.twist.linear.y), 0.1); EXPECT_LT(::fabs(filtered_.pose.pose.position.y - 50.0), 1.0); resetFilter(); twist.twist.twist.linear.y = 0.0; twist.twist.twist.linear.z = 5.0; loopRate = ros::Rate(20); for (size_t i = 0; i < 100; ++i) { twist.header.stamp = ros::Time::now(); twistPub.publish(twist); ros::spinOnce(); loopRate.sleep(); twist.header.seq++; } ros::spinOnce(); EXPECT_LT(::fabs(filtered_.twist.twist.linear.z - twist.twist.twist.linear.z), 0.1); EXPECT_LT(::fabs(filtered_.pose.pose.position.z - 25.0), 1.0); resetFilter(); twist.twist.twist.linear.z = 0.0; twist.twist.twist.linear.x = 1.0; twist.twist.twist.angular.z = (M_PI/2) / (100.0 * 0.05); loopRate = ros::Rate(20); for (size_t i = 0; i < 100; ++i) { twist.header.stamp = ros::Time::now(); twistPub.publish(twist); ros::spinOnce(); loopRate.sleep(); twist.header.seq++; } ros::spinOnce(); EXPECT_LT(::fabs(filtered_.twist.twist.linear.x - twist.twist.twist.linear.x), 0.1); EXPECT_LT(::fabs(filtered_.twist.twist.angular.z - twist.twist.twist.angular.z), 0.1); EXPECT_LT(::fabs(filtered_.pose.pose.position.x - filtered_.pose.pose.position.y), 0.5); resetFilter(); twist.twist.twist.linear.x = 0.0; twist.twist.twist.angular.z = 0.0; twist.twist.twist.angular.x = -(M_PI/2) / (100.0 * 0.05); // First, roll the vehicle on its side loopRate = ros::Rate(20); for (size_t i = 0; i < 100; ++i) { twist.header.stamp = ros::Time::now(); twistPub.publish(twist); ros::spinOnce(); loopRate.sleep(); twist.header.seq++; } ros::spinOnce(); twist.twist.twist.angular.x = 0.0; twist.twist.twist.angular.y = (M_PI/2) / (100.0 * 0.05); // Now, pitch it down (positive pitch velocity in vehicle frame) loopRate = ros::Rate(20); for (size_t i = 0; i < 100; ++i) { twist.header.stamp = ros::Time::now(); twistPub.publish(twist); ros::spinOnce(); loopRate.sleep(); twist.header.seq++; } ros::spinOnce(); twist.twist.twist.angular.y = 0.0; twist.twist.twist.linear.x = 3.0; // We should now be on our side and facing -Y. Move forward in // the vehicle frame X direction, and make sure Y decreases in // the world frame. loopRate = ros::Rate(20); for (size_t i = 0; i < 100; ++i) { twist.header.stamp = ros::Time::now(); twistPub.publish(twist); ros::spinOnce(); loopRate.sleep(); twist.header.seq++; } ros::spinOnce(); EXPECT_LT(::fabs(filtered_.twist.twist.linear.x - twist.twist.twist.linear.x), 0.1); EXPECT_LT(::fabs(filtered_.pose.pose.position.y + 15), 1.0); resetFilter(); } TEST(InterfacesTest, ImuPoseBasicIO) { ros::NodeHandle nh; ros::Publisher imuPub = nh.advertise("/imu_input0", 5); ros::Subscriber filteredSub = nh.subscribe("/odometry/filtered", 1, &filterCallback); sensor_msgs::Imu imu; tf2::Quaternion quat; quat.setRPY(M_PI/4, -M_PI/4, M_PI/2); imu.orientation = tf2::toMsg(quat); for (size_t ind = 0; ind < 9; ind+=4) { imu.orientation_covariance[ind] = 1e-6; } imu.header.frame_id = "base_link"; // Make sure the pose reset worked. Test will timeout // if this fails. ros::Rate loopRate(50); for (size_t i = 0; i < 50; ++i) { imu.header.stamp = ros::Time::now(); imuPub.publish(imu); ros::spinOnce(); loopRate.sleep(); imu.header.seq++; } // Now check the values from the callback tf2::fromMsg(filtered_.pose.pose.orientation, quat); tf2::Matrix3x3 mat(quat); double r, p, y; mat.getRPY(r, p, y); EXPECT_LT(::fabs(r - M_PI/4), 0.1); EXPECT_LT(::fabs(p + M_PI/4), 0.1); EXPECT_LT(::fabs(y - M_PI/2), 0.1); EXPECT_LT(filtered_.pose.covariance[21], 0.5); EXPECT_LT(filtered_.pose.covariance[28], 0.25); EXPECT_LT(filtered_.pose.covariance[35], 0.5); resetFilter(); // Test to see if the orientation data is ignored when we set the // first covariance value to -1 sensor_msgs::Imu imuIgnore; imuIgnore.orientation.x = 0.1; imuIgnore.orientation.y = 0.2; imuIgnore.orientation.z = 0.3; imuIgnore.orientation.w = 0.4; imuIgnore.orientation_covariance[0] = -1; loopRate = ros::Rate(50); for (size_t i = 0; i < 50; ++i) { imuIgnore.header.stamp = ros::Time::now(); imuPub.publish(imuIgnore); loopRate.sleep(); ros::spinOnce(); imuIgnore.header.seq++; } tf2::fromMsg(filtered_.pose.pose.orientation, quat); mat.setRotation(quat); mat.getRPY(r, p, y); EXPECT_LT(::fabs(r), 1e-3); EXPECT_LT(::fabs(p), 1e-3); EXPECT_LT(::fabs(y), 1e-3); resetFilter(); } TEST(InterfacesTest, ImuTwistBasicIO) { ros::NodeHandle nh; ros::Publisher imuPub = nh.advertise("/imu_input1", 5); ros::Subscriber filteredSub = nh.subscribe("/odometry/filtered", 1, &filterCallback); sensor_msgs::Imu imu; tf2::Quaternion quat; imu.angular_velocity.x = (M_PI / 2.0); for (size_t ind = 0; ind < 9; ind+=4) { imu.angular_velocity_covariance[ind] = 1e-6; } imu.header.frame_id = "base_link"; ros::Rate loopRate(50); for (size_t i = 0; i < 50; ++i) { imu.header.stamp = ros::Time::now(); imuPub.publish(imu); loopRate.sleep(); ros::spinOnce(); imu.header.seq++; } // Now check the values from the callback tf2::fromMsg(filtered_.pose.pose.orientation, quat); tf2::Matrix3x3 mat(quat); double r, p, y; mat.getRPY(r, p, y); // Tolerances may seem loose, but the initial state covariances // are tiny, so the filter is sluggish to accept velocity data EXPECT_LT(::fabs(r - M_PI / 2.0), 0.7); EXPECT_LT(::fabs(p), 0.1); EXPECT_LT(::fabs(y), 0.1); EXPECT_LT(filtered_.twist.covariance[21], 1e-3); EXPECT_LT(filtered_.pose.covariance[21], 0.1); resetFilter(); imu.angular_velocity.x = 0.0; imu.angular_velocity.y = -(M_PI / 2.0); // Make sure the pose reset worked. Test will timeout // if this fails. loopRate = ros::Rate(50); for (size_t i = 0; i < 50; ++i) { imu.header.stamp = ros::Time::now(); imuPub.publish(imu); loopRate.sleep(); ros::spinOnce(); imu.header.seq++; } // Now check the values from the callback tf2::fromMsg(filtered_.pose.pose.orientation, quat); mat.setRotation(quat); mat.getRPY(r, p, y); EXPECT_LT(::fabs(r), 0.1); EXPECT_LT(::fabs(p + M_PI / 2.0), 0.7); EXPECT_LT(::fabs(y), 0.1); EXPECT_LT(filtered_.twist.covariance[28], 1e-3); EXPECT_LT(filtered_.pose.covariance[28], 0.1); resetFilter(); imu.angular_velocity.y = 0; imu.angular_velocity.z = M_PI / 4.0; // Make sure the pose reset worked. Test will timeout // if this fails. loopRate = ros::Rate(50); for (size_t i = 0; i < 50; ++i) { imu.header.stamp = ros::Time::now(); imuPub.publish(imu); loopRate.sleep(); ros::spinOnce(); imu.header.seq++; } // Now check the values from the callback tf2::fromMsg(filtered_.pose.pose.orientation, quat); mat.setRotation(quat); mat.getRPY(r, p, y); EXPECT_LT(::fabs(r), 0.1); EXPECT_LT(::fabs(p), 0.1); EXPECT_LT(::fabs(y - M_PI / 4.0), 0.7); EXPECT_LT(filtered_.twist.covariance[35], 1e-3); EXPECT_LT(filtered_.pose.covariance[35], 0.1); resetFilter(); // Test to see if the angular velocity data is ignored when we set the // first covariance value to -1 sensor_msgs::Imu imuIgnore; imuIgnore.angular_velocity.x = 100; imuIgnore.angular_velocity.y = 100; imuIgnore.angular_velocity.z = 100; imuIgnore.angular_velocity_covariance[0] = -1; loopRate = ros::Rate(50); for (size_t i = 0; i < 50; ++i) { imuIgnore.header.stamp = ros::Time::now(); imuPub.publish(imuIgnore); loopRate.sleep(); ros::spinOnce(); imuIgnore.header.seq++; } tf2::fromMsg(filtered_.pose.pose.orientation, quat); mat.setRotation(quat); mat.getRPY(r, p, y); EXPECT_LT(::fabs(r), 1e-3); EXPECT_LT(::fabs(p), 1e-3); EXPECT_LT(::fabs(y), 1e-3); resetFilter(); } TEST(InterfacesTest, ImuAccBasicIO) { ros::NodeHandle nh; ros::Publisher imuPub = nh.advertise("/imu_input2", 5); ros::Subscriber filteredSub = nh.subscribe("/odometry/filtered", 1, &filterCallback); sensor_msgs::Imu imu; imu.header.frame_id = "base_link"; imu.linear_acceleration_covariance[0] = 1e-6; imu.linear_acceleration_covariance[4] = 1e-6; imu.linear_acceleration_covariance[8] = 1e-6; imu.linear_acceleration.x = 1; imu.linear_acceleration.y = -1; imu.linear_acceleration.z = 1; // Move with constant acceleration for 1 second, // then check our velocity. ros::Rate loopRate(50); for (size_t i = 0; i < 50; ++i) { imu.header.stamp = ros::Time::now(); imuPub.publish(imu); loopRate.sleep(); ros::spinOnce(); imu.header.seq++; } EXPECT_LT(::fabs(filtered_.twist.twist.linear.x - 1.0), 0.4); EXPECT_LT(::fabs(filtered_.twist.twist.linear.y + 1.0), 0.4); EXPECT_LT(::fabs(filtered_.twist.twist.linear.z - 1.0), 0.4); imu.linear_acceleration.x = 0.0; imu.linear_acceleration.y = 0.0; imu.linear_acceleration.z = 0.0; // Now move for another second, and see where we // end up loopRate = ros::Rate(50); for (size_t i = 0; i < 50; ++i) { imu.header.stamp = ros::Time::now(); imuPub.publish(imu); loopRate.sleep(); ros::spinOnce(); imu.header.seq++; } EXPECT_LT(::fabs(filtered_.pose.pose.position.x - 1.2), 0.4); EXPECT_LT(::fabs(filtered_.pose.pose.position.y + 1.2), 0.4); EXPECT_LT(::fabs(filtered_.pose.pose.position.z - 1.2), 0.4); resetFilter(); // Test to see if the linear acceleration data is ignored when we set the // first covariance value to -1 sensor_msgs::Imu imuIgnore; imuIgnore.linear_acceleration.x = 1000; imuIgnore.linear_acceleration.y = 1000; imuIgnore.linear_acceleration.z = 1000; imuIgnore.linear_acceleration_covariance[0] = -1; loopRate = ros::Rate(50); for (size_t i = 0; i < 50; ++i) { imuIgnore.header.stamp = ros::Time::now(); imuPub.publish(imuIgnore); loopRate.sleep(); ros::spinOnce(); imuIgnore.header.seq++; } EXPECT_LT(::fabs(filtered_.pose.pose.position.x), 1e-3); EXPECT_LT(::fabs(filtered_.pose.pose.position.y), 1e-3); EXPECT_LT(::fabs(filtered_.pose.pose.position.z), 1e-3); resetFilter(); } TEST(InterfacesTest, OdomDifferentialIO) { ros::NodeHandle nh; ros::Publisher odomPub = nh.advertise("/odom_input1", 5); ros::Subscriber filteredSub = nh.subscribe("/odometry/filtered", 1, &filterCallback); nav_msgs::Odometry odom; odom.pose.pose.position.x = 20.0; odom.pose.pose.position.y = 10.0; odom.pose.pose.position.z = -40.0; odom.pose.pose.orientation.w = 1; odom.pose.covariance[0] = 2.0; odom.pose.covariance[7] = 2.0; odom.pose.covariance[14] = 2.0; odom.pose.covariance[21] = 0.2; odom.pose.covariance[28] = 0.2; odom.pose.covariance[35] = 0.2; odom.header.frame_id = "odom"; odom.child_frame_id = "base_link"; // No guaranteeing that the zero state // we're expecting to see here isn't just // a result of zeroing it out previously, // so check 10 times in succession. size_t zeroCount = 0; while (zeroCount++ < 10) { odom.header.stamp = ros::Time::now(); odomPub.publish(odom); ros::spinOnce(); EXPECT_LT(::fabs(filtered_.pose.pose.position.x), 0.01); EXPECT_LT(::fabs(filtered_.pose.pose.position.y), 0.01); EXPECT_LT(::fabs(filtered_.pose.pose.position.z), 0.01); EXPECT_LT(::fabs(filtered_.pose.pose.orientation.x), 0.01); EXPECT_LT(::fabs(filtered_.pose.pose.orientation.y), 0.01); EXPECT_LT(::fabs(filtered_.pose.pose.orientation.z), 0.01); EXPECT_LT(::fabs(filtered_.pose.pose.orientation.w - 1), 0.01); ros::Duration(0.1).sleep(); odom.header.seq++; } for (size_t ind = 0; ind < 36; ind+=7) { odom.pose.covariance[ind] = 1e-6; } // Slowly move the position, and hope that the // differential position keeps up ros::Rate loopRate(20); for (size_t i = 0; i < 100; ++i) { odom.pose.pose.position.x += 0.01; odom.pose.pose.position.y += 0.02; odom.pose.pose.position.z -= 0.03; odom.header.stamp = ros::Time::now(); odomPub.publish(odom); ros::spinOnce(); loopRate.sleep(); odom.header.seq++; } ros::spinOnce(); EXPECT_LT(::fabs(filtered_.pose.pose.position.x - 1), 0.2); EXPECT_LT(::fabs(filtered_.pose.pose.position.y - 2), 0.4); EXPECT_LT(::fabs(filtered_.pose.pose.position.z + 3), 0.6); resetFilter(); } TEST(InterfacesTest, PoseDifferentialIO) { ros::NodeHandle nh; ros::Publisher posePub = nh.advertise("/pose_input1", 5); ros::Subscriber filteredSub = nh.subscribe("/odometry/filtered", 1, &filterCallback); geometry_msgs::PoseWithCovarianceStamped pose; pose.pose.pose.position.x = 20.0; pose.pose.pose.position.y = 10.0; pose.pose.pose.position.z = -40.0; pose.pose.pose.orientation.w = 1; pose.pose.covariance[0] = 2.0; pose.pose.covariance[7] = 2.0; pose.pose.covariance[14] = 2.0; pose.pose.covariance[21] = 0.2; pose.pose.covariance[28] = 0.2; pose.pose.covariance[35] = 0.2; pose.header.frame_id = "odom"; // No guaranteeing that the zero state // we're expecting to see here isn't just // a result of zeroing it out previously, // so check 10 times in succession. size_t zeroCount = 0; while (zeroCount++ < 10) { pose.header.stamp = ros::Time::now(); posePub.publish(pose); ros::spinOnce(); EXPECT_LT(::fabs(filtered_.pose.pose.position.x), 0.01); EXPECT_LT(::fabs(filtered_.pose.pose.position.y), 0.01); EXPECT_LT(::fabs(filtered_.pose.pose.position.z), 0.01); EXPECT_LT(::fabs(filtered_.pose.pose.orientation.x), 0.01); EXPECT_LT(::fabs(filtered_.pose.pose.orientation.y), 0.01); EXPECT_LT(::fabs(filtered_.pose.pose.orientation.z), 0.01); EXPECT_LT(::fabs(filtered_.pose.pose.orientation.w - 1), 0.01); ros::Duration(0.1).sleep(); pose.header.seq++; } // ...but only if we give the measurement a tiny covariance for (size_t ind = 0; ind < 36; ind+=7) { pose.pose.covariance[ind] = 1e-6; } // Issue this location repeatedly, and see if we get // a final reported position of (1, 2, -3) ros::Rate loopRate(20); for (size_t i = 0; i < 100; ++i) { pose.pose.pose.position.x += 0.01; pose.pose.pose.position.y += 0.02; pose.pose.pose.position.z -= 0.03; pose.header.stamp = ros::Time::now(); posePub.publish(pose); ros::spinOnce(); loopRate.sleep(); pose.header.seq++; } ros::spinOnce(); EXPECT_LT(::fabs(filtered_.pose.pose.position.x - 1), 0.2); EXPECT_LT(::fabs(filtered_.pose.pose.position.y - 2), 0.4); EXPECT_LT(::fabs(filtered_.pose.pose.position.z + 3), 0.6); resetFilter(); } TEST(InterfacesTest, ImuDifferentialIO) { ros::NodeHandle nh; ros::Publisher imu0Pub = nh.advertise("/imu_input0", 5); ros::Publisher imu1Pub = nh.advertise("/imu_input1", 5); ros::Publisher imuPub = nh.advertise("/imu_input3", 5); ros::Subscriber filteredSub = nh.subscribe("/odometry/filtered", 1, &filterCallback); sensor_msgs::Imu imu; imu.header.frame_id = "base_link"; tf2::Quaternion quat; const double roll = M_PI/2.0; const double pitch = -M_PI; const double yaw = -M_PI/4.0; quat.setRPY(roll, pitch, yaw); imu.orientation = tf2::toMsg(quat); imu.orientation_covariance[0] = 0.02; imu.orientation_covariance[4] = 0.02; imu.orientation_covariance[8] = 0.02; imu.angular_velocity_covariance[0] = 0.02; imu.angular_velocity_covariance[4] = 0.02; imu.angular_velocity_covariance[8] = 0.02; size_t setCount = 0; while (setCount++ < 10) { imu.header.stamp = ros::Time::now(); imu0Pub.publish(imu); // Use this to move the absolute orientation imu1Pub.publish(imu); // Use this to keep velocities at 0 ros::spinOnce(); ros::Duration(0.1).sleep(); imu.header.seq++; } size_t zeroCount = 0; while (zeroCount++ < 10) { imu.header.stamp = ros::Time::now(); imuPub.publish(imu); ros::spinOnce(); ros::Duration(0.1).sleep(); imu.header.seq++; } double rollFinal = roll; double pitchFinal = pitch; double yawFinal = yaw; // Move the orientation slowly, and see if we // can push it to 0 ros::Rate loopRate(20); for (size_t i = 0; i < 100; ++i) { yawFinal -= 0.01 * (3.0 * M_PI/4.0); quat.setRPY(rollFinal, pitchFinal, yawFinal); imu.orientation = tf2::toMsg(quat); imu.header.stamp = ros::Time::now(); imuPub.publish(imu); ros::spinOnce(); loopRate.sleep(); imu.header.seq++; } ros::spinOnce(); // Move the orientation slowly, and see if we // can push it to 0 loopRate = ros::Rate(20); for (size_t i = 0; i < 100; ++i) { rollFinal += 0.01 * (M_PI/2.0); quat.setRPY(rollFinal, pitchFinal, yawFinal); imu.orientation = tf2::toMsg(quat); imu.header.stamp = ros::Time::now(); imuPub.publish(imu); ros::spinOnce(); loopRate.sleep(); imu.header.seq++; } ros::spinOnce(); tf2::fromMsg(filtered_.pose.pose.orientation, quat); tf2::Matrix3x3 mat(quat); mat.getRPY(rollFinal, pitchFinal, yawFinal); EXPECT_LT(::fabs(rollFinal), 0.2); EXPECT_LT(::fabs(pitchFinal), 0.2); EXPECT_LT(::fabs(yawFinal), 0.2); resetFilter(); } int main(int argc, char **argv) { testing::InitGoogleTest(&argc, argv); ros::init(argc, argv, "ekf_navigation_node-test-interfaces"); ros::Time::init(); // Give ekf_localization_node time to initialize ros::Duration(2.0).sleep(); return RUN_ALL_TESTS(); } ================================================ FILE: src/robot_localization/test/test_ekf_localization_node_interfaces.test ================================================ [true, false, true, false, false, false, false, false, false, false, false, false, false, false, false] [true, true, true, true, true, true, false, false, false, false, false, false, false, false, false] [false, false, false, false, false, false, true, true, true, true, true, true, false, false, false] [true, false, true, false, false, false, false, false, false, false, false, false, false, false, false] [true, true, true, true, true, true, false, false, false, false, false, false, false, false, false] [false, false, false, false, false, false, true, true, true, true, true, true, false, false, false] [false, false, false, true, true, true, false, false, false, false, false, false, false, false, false] [false, false, false, false, false, false, false, false, false, true, true, true, false, false, false] [false, false, false, false, false, false, false, false, false, false, false, false, true, true, true] [false, false, false, true, true, true, false, false, false, false, false, false, false, false, false] [0.03, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.4, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.025, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.025, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01] ================================================ FILE: src/robot_localization/test/test_filter_base.cpp ================================================ /* * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * 1. Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * 2. Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * 3. Neither the name of the copyright holder nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #include "robot_localization/filter_base.h" #include "robot_localization/filter_common.h" #include #include #include #include #include using RobotLocalization::STATE_SIZE; using RobotLocalization::Measurement; namespace RobotLocalization { class FilterDerived : public FilterBase { public: double val; FilterDerived() : val(0) { } void correct(const Measurement &measurement) { EXPECT_EQ(val, measurement.time_); EXPECT_EQ(measurement.topicName_, "topic"); EXPECT_EQ(measurement.updateVector_.size(), 10); for (size_t i = 0; i < measurement.updateVector_.size(); ++i) { EXPECT_EQ(measurement.updateVector_[i], true); } } void predict(const double refTime, const double delta) { val = delta; } }; class FilterDerived2 : public FilterBase { public: FilterDerived2() { } void correct(const Measurement &measurement) { } void predict(const double refTime, const double delta) { } void processMeasurement(const Measurement &measurement) { FilterBase::processMeasurement(measurement); } }; } // namespace RobotLocalization TEST(FilterBaseTest, MeasurementStruct) { RobotLocalization::Measurement meas1; RobotLocalization::Measurement meas2; EXPECT_EQ(meas1.topicName_, std::string("")); EXPECT_EQ(meas1.time_, 0); EXPECT_EQ(meas2.time_, 0); // Comparison test is true if the first // argument is > the second, so should // be false if they're equal. EXPECT_EQ(meas1(meas1, meas2), false); EXPECT_EQ(meas2(meas2, meas1), false); meas1.time_ = 100; meas2.time_ = 200; EXPECT_EQ(meas1(meas1, meas2), false); EXPECT_EQ(meas1(meas2, meas1), true); EXPECT_EQ(meas2(meas1, meas2), false); EXPECT_EQ(meas2(meas2, meas1), true); } TEST(FilterBaseTest, DerivedFilterGetSet) { using RobotLocalization::FilterDerived; FilterDerived derived; // With the ostream argument as NULL, // the debug flag will remain false. derived.setDebug(true); EXPECT_FALSE(derived.getDebug()); // Now set the stream and do it again std::stringstream os; derived.setDebug(true, &os); EXPECT_TRUE(derived.getDebug()); // Simple get/set checks double timeout = 7.4; derived.setSensorTimeout(timeout); EXPECT_EQ(derived.getSensorTimeout(), timeout); double lastMeasTime = 3.83; derived.setLastMeasurementTime(lastMeasTime); EXPECT_EQ(derived.getLastMeasurementTime(), lastMeasTime); Eigen::MatrixXd pnCovar(STATE_SIZE, STATE_SIZE); for (size_t i = 0; i < STATE_SIZE; ++i) { for (size_t j = 0; j < STATE_SIZE; ++j) { pnCovar(i, j) = static_cast(i * j); } } derived.setProcessNoiseCovariance(pnCovar); EXPECT_EQ(derived.getProcessNoiseCovariance(), pnCovar); Eigen::VectorXd state(STATE_SIZE); state.setZero(); derived.setState(state); EXPECT_EQ(derived.getState(), state); EXPECT_EQ(derived.getInitializedStatus(), false); } TEST(FilterBaseTest, MeasurementProcessing) { using RobotLocalization::FilterDerived2; FilterDerived2 derived; Measurement meas; Eigen::VectorXd measurement(STATE_SIZE); for (size_t i = 0; i < STATE_SIZE; ++i) { measurement[i] = 0.1 * static_cast(i); } Eigen::MatrixXd measurementCovariance(STATE_SIZE, STATE_SIZE); for (size_t i = 0; i < STATE_SIZE; ++i) { for (size_t j = 0; j < STATE_SIZE; ++j) { measurementCovariance(i, j) = 0.1 * static_cast(i * j); } } meas.topicName_ = "odomTest"; meas.measurement_ = measurement; meas.covariance_ = measurementCovariance; meas.updateVector_.resize(STATE_SIZE, true); meas.time_ = 1000; // The filter shouldn't be initializedyet EXPECT_FALSE(derived.getInitializedStatus()); derived.processMeasurement(meas); // Now it's initialized, and the entire filter state // should be equal to the first state EXPECT_TRUE(derived.getInitializedStatus()); EXPECT_EQ(derived.getState(), measurement); // Process a measurement and make sure it updates the // lastMeasurementTime variable meas.time_ = 1002; derived.processMeasurement(meas); EXPECT_EQ(derived.getLastMeasurementTime(), meas.time_); } int main(int argc, char **argv) { testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); } ================================================ FILE: src/robot_localization/test/test_filter_base_diagnostics_timestamps.cpp ================================================ /* * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * 1. Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * 2. Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * 3. Neither the name of the copyright holder nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #include #include #include #include #include #include "robot_localization/filter_base.h" #include "robot_localization/filter_common.h" #include "robot_localization/SetPose.h" #include #include #include namespace RobotLocalization { /* Convenience functions to get valid messages. */ geometry_msgs::PoseWithCovarianceStamped getValidPose() { geometry_msgs::PoseWithCovarianceStamped pose_msg; pose_msg.header.frame_id = "base_link"; pose_msg.pose.pose.position.x = 1; pose_msg.pose.pose.orientation.w = 1; for (size_t i = 0; i < 6 ; i++) { pose_msg.pose.covariance[i*6 + i] = 1; } return pose_msg; } geometry_msgs::TwistWithCovarianceStamped getValidTwist() { geometry_msgs::TwistWithCovarianceStamped twist_msg; twist_msg.header.frame_id = "base_link"; for (size_t i = 0; i < 6 ; i++) { twist_msg.twist.covariance[i*6 + i] = 1; } return twist_msg; } sensor_msgs::Imu getValidImu() { sensor_msgs::Imu imu_msg; imu_msg.header.frame_id = "base_link"; imu_msg.orientation.w = 1; for (size_t i = 0; i < 3 ; i++) { imu_msg.orientation_covariance[i * 3 + i] = 1; imu_msg.angular_velocity_covariance[i * 3 + i] = 1; imu_msg.linear_acceleration_covariance[i * 3 + i] = 1; } return imu_msg; } nav_msgs::Odometry getValidOdometry() { nav_msgs::Odometry odom_msg; odom_msg.header.frame_id = "odom"; odom_msg.child_frame_id = "base_link"; odom_msg.pose = getValidPose().pose; odom_msg.twist = getValidTwist().twist; return odom_msg; } /* Helper class to handle the setup and message publishing for the testcases. It provides convenience to send valid messages with a specified timestamp. All diagnostic messages are stored into the public diagnostics attribute. */ class DiagnosticsHelper { private: ros::Publisher odom_pub_; ros::Publisher pose_pub_; ros::Publisher twist_pub_; ros::Publisher imu_pub_; geometry_msgs::PoseWithCovarianceStamped pose_msg_; geometry_msgs::TwistWithCovarianceStamped twist_msg_; nav_msgs::Odometry odom_msg_; sensor_msgs::Imu imu_msg_; ros::Subscriber diagnostic_sub_; ros::ServiceClient set_pose_; public: std::vector< diagnostic_msgs::DiagnosticArray > diagnostics; DiagnosticsHelper() { ros::NodeHandle nh; ros::NodeHandle nhLocal("~"); // ready the valid messages. pose_msg_ = getValidPose(); twist_msg_ = getValidTwist(); odom_msg_ = getValidOdometry(); imu_msg_ = getValidImu(); // subscribe to diagnostics and create publishers for the odometry messages. odom_pub_ = nh.advertise("example/odom", 10); pose_pub_ = nh.advertise("example/pose", 10); twist_pub_ = nh.advertise("example/twist", 10); imu_pub_ = nh.advertise("example/imu/data", 10); diagnostic_sub_ = nh.subscribe("/diagnostics", 10, &DiagnosticsHelper::diagnosticCallback, this); set_pose_ = nh.serviceClient("/set_pose"); } void diagnosticCallback(const diagnostic_msgs::DiagnosticArrayPtr &msg) { diagnostics.push_back(*msg); } void publishMessages(ros::Time t) { odom_msg_.header.stamp = t; odom_msg_.header.seq++; odom_pub_.publish(odom_msg_); pose_msg_.header.stamp = t; pose_msg_.header.seq++; pose_pub_.publish(pose_msg_); twist_msg_.header.stamp = t; twist_msg_.header.seq++; twist_pub_.publish(twist_msg_); imu_msg_.header.stamp = t; imu_msg_.header.seq++; imu_pub_.publish(imu_msg_); } void setPose(ros::Time t) { robot_localization::SetPose pose_; pose_.request.pose = getValidPose(); pose_.request.pose.header.stamp = t; set_pose_.call(pose_); } }; } // namespace RobotLocalization /* First test; we run for a bit; then send messagse with an empty timestamp. Then we check if the diagnostics showed a warning. */ TEST(FilterBaseDiagnosticsTest, EmptyTimestamps) { RobotLocalization::DiagnosticsHelper dh_; // keep track of which diagnostic messages are detected. bool received_warning_imu = false; bool received_warning_odom = false; bool received_warning_twist = false; bool received_warning_pose = false; // For about a second, send correct messages. ros::Rate loopRate(10); for (size_t i = 0; i < 10; ++i) { ros::spinOnce(); dh_.publishMessages(ros::Time::now()); loopRate.sleep(); } ros::spinOnce(); // create an empty timestamp and send all messages with this empty timestamp. ros::Time empty; empty.fromSec(0); dh_.publishMessages(empty); ros::spinOnce(); // The filter runs and sends the diagnostics every second. // Just run this for two seconds to ensure we get all the diagnostic message. for (size_t i = 0; i < 20; ++i) { ros::spinOnce(); loopRate.sleep(); } /* Now the diagnostic messages have to be investigated to see whether they contain our warning. */ for (size_t i=0; i < dh_.diagnostics.size(); i++) { for (size_t status_index=0; status_index < dh_.diagnostics[i].status.size(); status_index++) { for (size_t key=0; key < dh_.diagnostics[i].status[status_index].values.size(); key++) { diagnostic_msgs::KeyValue kv = dh_.diagnostics[i].status[status_index].values[key]; // Now the keys can be checked to see whether we found our warning. if (kv.key == "imu0_timestamp") { received_warning_imu = true; } if (kv.key == "odom0_timestamp") { received_warning_odom = true; } if (kv.key == "twist0_timestamp") { received_warning_twist = true; } if (kv.key == "pose0_timestamp") { received_warning_pose = true; } } } } EXPECT_TRUE(received_warning_imu); EXPECT_TRUE(received_warning_odom); EXPECT_TRUE(received_warning_twist); EXPECT_TRUE(received_warning_pose); } TEST(FilterBaseDiagnosticsTest, TimestampsBeforeSetPose) { RobotLocalization::DiagnosticsHelper dh_; // keep track of which diagnostic messages are detected. bool received_warning_imu = false; bool received_warning_odom = false; bool received_warning_twist = false; bool received_warning_pose = false; // For about a second, send correct messages. ros::Rate loopRate(10); for (size_t i = 0; i < 10; ++i) { ros::spinOnce(); dh_.publishMessages(ros::Time::now()); loopRate.sleep(); } ros::spinOnce(); // Set the pose to the current timestamp. dh_.setPose(ros::Time::now()); ros::spinOnce(); // send messages from one second before that pose reset. dh_.publishMessages(ros::Time::now() - ros::Duration(1)); // The filter runs and sends the diagnostics every second. // Just run this for two seconds to ensure we get all the diagnostic message. for (size_t i = 0; i < 20; ++i) { ros::spinOnce(); loopRate.sleep(); } /* Now the diagnostic messages have to be investigated to see whether they contain our warning. */ for (size_t i=0; i < dh_.diagnostics.size(); i++) { for (size_t status_index=0; status_index < dh_.diagnostics[i].status.size(); status_index++) { for (size_t key=0; key < dh_.diagnostics[i].status[status_index].values.size(); key++) { diagnostic_msgs::KeyValue kv = dh_.diagnostics[i].status[status_index].values[key]; // Now the keys can be checked to see whether we found our warning. if (kv.key == "imu0_timestamp") { received_warning_imu = true; } if (kv.key == "odom0_timestamp") { received_warning_odom = true; } if (kv.key == "twist0_timestamp") { received_warning_twist = true; } if (kv.key == "pose0_timestamp") { received_warning_pose = true; } } } } EXPECT_TRUE(received_warning_imu); EXPECT_TRUE(received_warning_odom); EXPECT_TRUE(received_warning_twist); EXPECT_TRUE(received_warning_pose); } TEST(FilterBaseDiagnosticsTest, TimestampsBeforePrevious) { RobotLocalization::DiagnosticsHelper dh_; // keep track of which diagnostic messages are detected. // we have more things to check here because the messages get split over // various callbacks if they pass the check if they predate the set_pose time. bool received_warning_imu_accel = false; bool received_warning_imu_pose = false; bool received_warning_imu_twist = false; bool received_warning_odom_twist = false; bool received_warning_twist = false; bool received_warning_pose = false; // For two seconds send correct messages. ros::Rate loopRate(10); for (size_t i = 0; i < 20; ++i) { ros::spinOnce(); dh_.publishMessages(ros::Time::now()); loopRate.sleep(); } ros::spinOnce(); // Send message that is one second in the past. dh_.publishMessages(ros::Time::now() - ros::Duration(1)); // The filter runs and sends the diagnostics every second. // Just run this for two seconds to ensure we get all the diagnostic message. for (size_t i = 0; i < 20; ++i) { ros::spinOnce(); loopRate.sleep(); } /* Now the diagnostic messages have to be investigated to see whether they contain our warning. */ for (size_t i=0; i < dh_.diagnostics.size(); i++) { for (size_t status_index=0; status_index < dh_.diagnostics[i].status.size(); status_index++) { for (size_t key=0; key < dh_.diagnostics[i].status[status_index].values.size(); key++) { diagnostic_msgs::KeyValue kv = dh_.diagnostics[i].status[status_index].values[key]; // Now the keys can be checked to see whether we found our warning. if (kv.key == "imu0_acceleration_timestamp") { received_warning_imu_accel = true; } if (kv.key == "imu0_pose_timestamp") { received_warning_imu_pose = true; } if (kv.key == "imu0_twist_timestamp") { received_warning_imu_twist = true; } if (kv.key == "odom0_twist_timestamp") { received_warning_twist = true; } if (kv.key == "pose0_timestamp") { received_warning_pose = true; } if (kv.key == "twist0_timestamp") { received_warning_odom_twist = true; } } } } EXPECT_TRUE(received_warning_imu_accel); EXPECT_TRUE(received_warning_imu_pose); EXPECT_TRUE(received_warning_imu_twist); EXPECT_TRUE(received_warning_odom_twist); EXPECT_TRUE(received_warning_pose); EXPECT_TRUE(received_warning_twist); } int main(int argc, char **argv) { ros::init(argc, argv, "filter_base_diagnostics_timestamps-test-interfaces"); ros::Time::init(); // Give ekf_localization_node time to initialize ros::Duration(2.0).sleep(); testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); } ================================================ FILE: src/robot_localization/test/test_filter_base_diagnostics_timestamps.test ================================================ [false, false, false, false, false, false, true, false, false, false, false, false, false, false, false] [true, true, false, false, false, false, false, false, false, false, false, false, false, false, false] [false, false, false, false, false, false, true, true, true, true, true, true, false, false, false] [false, false, false, true, true, true, false, false, false, true, true, true, true, true, true] ================================================ FILE: src/robot_localization/test/test_localization_node_bag_pose_tester.cpp ================================================ /* * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * 1. Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * 2. Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * 3. Neither the name of the copyright holder nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #include #include #include #include #include #include nav_msgs::Odometry filtered_; void filterCallback(const nav_msgs::OdometryConstPtr &msg) { filtered_ = *msg; } TEST(BagTest, PoseCheck) { ros::NodeHandle nh; ros::NodeHandle nhLocal("~"); double finalX = 0; double finalY = 0; double finalZ = 0; double tolerance = 0; bool outputFinalPosition = false; std::string finalPositionFile; nhLocal.getParam("final_x", finalX); nhLocal.getParam("final_y", finalY); nhLocal.getParam("final_z", finalZ); nhLocal.getParam("tolerance", tolerance); nhLocal.param("output_final_position", outputFinalPosition, false); nhLocal.param("output_location", finalPositionFile, std::string("test.txt")); ros::Subscriber filteredSub = nh.subscribe("/odometry/filtered", 1, &filterCallback); while (ros::ok()) { ros::spinOnce(); ros::Duration(0.0333333).sleep(); } if (outputFinalPosition) { try { std::ofstream posOut; posOut.open(finalPositionFile.c_str(), std::ofstream::app); posOut << filtered_.pose.pose.position.x << " " << filtered_.pose.pose.position.y << " " << filtered_.pose.pose.position.z << std::endl; posOut.close(); } catch(...) { ROS_ERROR_STREAM("Unable to open output file.\n"); } } double xDiff = filtered_.pose.pose.position.x - finalX; double yDiff = filtered_.pose.pose.position.y - finalY; double zDiff = filtered_.pose.pose.position.z - finalZ; EXPECT_LT(::sqrt(xDiff*xDiff + yDiff*yDiff + zDiff*zDiff), tolerance); } int main(int argc, char **argv) { testing::InitGoogleTest(&argc, argv); ros::init(argc, argv, "localization_node-bag-pose-tester"); ros::Time::init(); // Give ekf_localization_node time to initialize ros::Duration(2.0).sleep(); return RUN_ALL_TESTS(); } ================================================ FILE: src/robot_localization/test/test_robot_localization_estimator.cpp ================================================ /* * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * 1. Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * 2. Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * 3. Neither the name of the copyright holder nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #include "robot_localization/robot_localization_estimator.h" #include #include #include TEST(RLETest, StateBuffer) { // Generate a few estimator states std::vector states; for ( int i = 0; i < 10; i++ ) { /* * t = i s; * x = i m; * vx = 1.0 m/s; */ RobotLocalization::EstimatorState state; state.time_stamp = i; state.state(RobotLocalization::StateMemberX) = i; state.state(RobotLocalization::StateMemberY) = 0; state.state(RobotLocalization::StateMemberZ) = 0; state.state(RobotLocalization::StateMemberRoll) = 0; state.state(RobotLocalization::StateMemberPitch) = 0; state.state(RobotLocalization::StateMemberYaw) = 0; state.state(RobotLocalization::StateMemberVx) = 1; state.state(RobotLocalization::StateMemberVy) = 0; state.state(RobotLocalization::StateMemberVz) = 0; state.state(RobotLocalization::StateMemberVroll) = 0; state.state(RobotLocalization::StateMemberVpitch) = 0; state.state(RobotLocalization::StateMemberVyaw) = 0; state.state(RobotLocalization::StateMemberAx) = 0; state.state(RobotLocalization::StateMemberAy) = 0; state.state(RobotLocalization::StateMemberAz) = 0; states.push_back(state); } // Instantiate a robot localization estimator with a buffer capacity of 5 int buffer_capacity = 5; Eigen::MatrixXd process_noise_covariance = Eigen::MatrixXd::Identity(RobotLocalization::STATE_SIZE, RobotLocalization::STATE_SIZE); RobotLocalization::RobotLocalizationEstimator estimator(buffer_capacity, RobotLocalization::FilterTypes::EKF, process_noise_covariance); RobotLocalization::EstimatorState state; // Add the states in chronological order for ( int i = 0; i < 6; i++ ) { estimator.setState(states[i]); // Check that the state is added correctly estimator.getState(states[i].time_stamp, state); EXPECT_EQ(state.time_stamp, states[i].time_stamp); } // We filled the buffer with more states that it can hold, so its size should now be equal to the capacity EXPECT_EQ(estimator.getSize(), buffer_capacity); // Clear the buffer and check if it's really empty afterwards estimator.clearBuffer(); EXPECT_EQ(estimator.getSize(), 0); // Add states at time 1 through 3 inclusive to the buffer (buffer is not yet full) for ( int i = 1; i < 4; i++ ) { estimator.setState(states[i]); } // Now add a state at time 0, but let's change it a bit (set StateMemberY=12) so that we can inspect if it is // correctly added to the buffer. RobotLocalization::EstimatorState state_2 = states[0]; state_2.state(RobotLocalization::StateMemberY) = 12; estimator.setState(state_2); EXPECT_EQ(RobotLocalization::EstimatorResults::Exact, estimator.getState(states[0].time_stamp, state)); // Check if the state is correctly added EXPECT_EQ(state.state, state_2.state); // Add some more states. State at t=0 should now be dropped, so we should get the prediction, which means y=0 for ( int i = 5; i < 8; i++ ) { estimator.setState(states[i]); } EXPECT_EQ(RobotLocalization::EstimatorResults::ExtrapolationIntoPast, estimator.getState(states[0].time_stamp, state)); EXPECT_EQ(states[0].state, state.state); // Estimate a state that is not in the buffer, but can be determined by interpolation. The predicted state vector // should be equal to the designed state at the requested time. EXPECT_EQ(RobotLocalization::EstimatorResults::Interpolation, estimator.getState(states[4].time_stamp, state)); EXPECT_EQ(states[4].state, state.state); // Estimate a state that is not in the buffer, but can be determined by extrapolation into the future. The predicted // state vector should be equal to the designed state at the requested time. EXPECT_EQ(RobotLocalization::EstimatorResults::ExtrapolationIntoFuture, estimator.getState(states[8].time_stamp, state)); EXPECT_EQ(states[8].state, state.state); // Add missing state somewhere in the middle estimator.setState(states[4]); // Overwrite state at t=3 (oldest state now in the buffer) and check if it's correctly overwritten. state_2 = states[3]; state_2.state(RobotLocalization::StateMemberVy) = -1.0; estimator.setState(state_2); EXPECT_EQ(RobotLocalization::EstimatorResults::Exact, estimator.getState(states[3].time_stamp, state)); EXPECT_EQ(state_2.state, state.state); // Add state that came too late estimator.setState(states[0]); // Check if getState needed to do extrapolation into the past EXPECT_EQ(estimator.getState(states[0].time_stamp, state), RobotLocalization::EstimatorResults::ExtrapolationIntoPast); // Check state at t=0. This can only work correctly if the state at t=3 is // overwritten and the state at zero is not in the buffer. EXPECT_DOUBLE_EQ(3.0, state.state(RobotLocalization::StateMemberY)); } int main(int argc, char **argv) { ros::init(argc, argv, "test_robot_localization_estimator"); testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); } ================================================ FILE: src/robot_localization/test/test_robot_localization_estimator.test ================================================ ================================================ FILE: src/robot_localization/test/test_ros_robot_localization_listener.cpp ================================================ /* * Copyright (c) 2016, TNO IVS, Helmond * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * 1. Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * 2. Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * 3. Neither the name of the copyright holder nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #include "robot_localization/ros_robot_localization_listener.h" #include "robot_localization/filter_common.h" #include #include #include #include RobotLocalization::RosRobotLocalizationListener* g_listener; TEST(LocalizationListenerTest, testGetStateOfBaseLink) { ros::spinOnce(); ros::Time time2(1001); Eigen::VectorXd state(RobotLocalization::STATE_SIZE); Eigen::MatrixXd covariance(RobotLocalization::STATE_SIZE, RobotLocalization::STATE_SIZE); std::string base_frame("base_link"); g_listener->getState(time2, base_frame, state, covariance); EXPECT_DOUBLE_EQ(1.0, state(RobotLocalization::StateMemberX)); EXPECT_DOUBLE_EQ(0.0, state(RobotLocalization::StateMemberY)); EXPECT_DOUBLE_EQ(0.0, state(RobotLocalization::StateMemberZ)); EXPECT_FLOAT_EQ(M_PI/4, state(RobotLocalization::StateMemberRoll)); EXPECT_FLOAT_EQ(0.0, state(RobotLocalization::StateMemberPitch)); EXPECT_FLOAT_EQ(0.0, state(RobotLocalization::StateMemberYaw)); EXPECT_DOUBLE_EQ(M_PI/4.0, state(RobotLocalization::StateMemberVroll)); EXPECT_DOUBLE_EQ(0.0, state(RobotLocalization::StateMemberVpitch)); EXPECT_DOUBLE_EQ(0.0, state(RobotLocalization::StateMemberVyaw)); } TEST(LocalizationListenerTest, GetStateOfRelatedFrame) { ros::spinOnce(); Eigen::VectorXd state(RobotLocalization::STATE_SIZE); Eigen::MatrixXd covariance(RobotLocalization::STATE_SIZE, RobotLocalization::STATE_SIZE); ros::Time time1(1000); ros::Time time2(1001); std::string sensor_frame("sensor"); EXPECT_TRUE(g_listener->getState(time1, sensor_frame, state, covariance) ); EXPECT_FLOAT_EQ(0.0, state(RobotLocalization::StateMemberX)); EXPECT_FLOAT_EQ(1.0, state(RobotLocalization::StateMemberY)); EXPECT_FLOAT_EQ(0.0, state(RobotLocalization::StateMemberZ)); EXPECT_FLOAT_EQ(0.0, state(RobotLocalization::StateMemberRoll)); EXPECT_FLOAT_EQ(0.0, state(RobotLocalization::StateMemberPitch)); EXPECT_FLOAT_EQ(M_PI/2, state(RobotLocalization::StateMemberYaw)); EXPECT_TRUE(1e-12 > state(RobotLocalization::StateMemberVx)); EXPECT_FLOAT_EQ(-1.0, state(RobotLocalization::StateMemberVy)); EXPECT_FLOAT_EQ(M_PI/4.0, state(RobotLocalization::StateMemberVz)); EXPECT_TRUE(1e-12 > state(RobotLocalization::StateMemberVroll)); EXPECT_FLOAT_EQ(-M_PI/4.0, state(RobotLocalization::StateMemberVpitch)); EXPECT_FLOAT_EQ(0.0, state(RobotLocalization::StateMemberVyaw)); EXPECT_TRUE(g_listener->getState(time2, sensor_frame, state, covariance)); EXPECT_FLOAT_EQ(1.0, state(RobotLocalization::StateMemberX)); EXPECT_FLOAT_EQ(sqrt(2)/2.0, state(RobotLocalization::StateMemberY)); EXPECT_FLOAT_EQ(sqrt(2)/2.0, state(RobotLocalization::StateMemberZ)); EXPECT_TRUE(1e-12 > state(RobotLocalization::StateMemberRoll)); EXPECT_TRUE(1e-12 > fabs(-M_PI/4.0 - state(RobotLocalization::StateMemberPitch))); EXPECT_FLOAT_EQ(M_PI/2, state(RobotLocalization::StateMemberYaw)); EXPECT_TRUE(1e-12 > state(RobotLocalization::StateMemberVx)); EXPECT_FLOAT_EQ(-1.0, state(RobotLocalization::StateMemberVy)); EXPECT_FLOAT_EQ(M_PI/4, state(RobotLocalization::StateMemberVz)); EXPECT_TRUE(1e-12 > state(RobotLocalization::StateMemberVroll)); EXPECT_FLOAT_EQ(-M_PI/4.0, state(RobotLocalization::StateMemberVpitch)); EXPECT_FLOAT_EQ(0, state(RobotLocalization::StateMemberVyaw)); } int main(int argc, char **argv) { ros::init(argc, argv, "test_robot_localization_estimator"); g_listener = new RobotLocalization::RosRobotLocalizationListener(); testing::InitGoogleTest(&argc, argv); int res = RUN_ALL_TESTS(); delete g_listener; return res; } ================================================ FILE: src/robot_localization/test/test_ros_robot_localization_listener.test ================================================ [true, false, true, false, false, false, false, false, false, false, false, false, false, false, false] [true, true, true, true, true, true, false, false, false, false, false, false, false, false, false] [false, false, false, false, false, false, true, true, true, true, true, true, false, false, false] [true, false, true, false, false, false, false, false, false, false, false, false, false, false, false] [true, true, true, true, true, true, false, false, false, false, false, false, false, false, false] [false, false, false, false, false, false, true, true, true, true, true, true, false, false, false] [false, false, false, true, true, true, false, false, false, false, false, false, false, false, false] [false, false, false, false, false, false, false, false, false, true, true, true, false, false, false] [false, false, false, false, false, false, false, false, false, false, false, false, true, true, true] [false, false, false, true, true, true, false, false, false, false, false, false, false, false, false] [0.03, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.4, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.025, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.025, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01] ================================================ FILE: src/robot_localization/test/test_ros_robot_localization_listener_publisher.cpp ================================================ /* * Copyright (c) 2016, TNO IVS, Helmond * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * 1. Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * 2. Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * 3. Neither the name of the copyright holder nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #include #include #include #include #include #include int main(int argc, char **argv) { ros::init(argc, argv, "test_robot_localization_listener_publisher"); ros::NodeHandle nh; ros::Publisher odom_pub = nh.advertise("odometry/filtered", 1); ros::Publisher accel_pub = nh.advertise("accel/filtered", 1); tf2_ros::StaticTransformBroadcaster transform_broadcaster; ros::Time end_time = ros::Time::now() + ros::Duration(10); while (ros::ok() && ros::Time::now() < end_time) { ros::Time time1(1000); double x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az; x = y = z = roll = pitch = yaw = vy = vz = vroll = vpitch = vyaw = ax = ay = az = 0.0; vx = 1.0; vroll = M_PI/4.0; tf2::Quaternion q; q.setRPY(0, 0, 0); nav_msgs::Odometry odom_msg; odom_msg.header.stamp = time1; odom_msg.header.frame_id = "map"; odom_msg.child_frame_id = "base_link"; odom_msg.pose.pose.position.x = x; odom_msg.pose.pose.position.y = y; odom_msg.pose.pose.position.y = z; odom_msg.pose.pose.orientation.x = q.x(); odom_msg.pose.pose.orientation.y = q.y(); odom_msg.pose.pose.orientation.z = q.z(); odom_msg.pose.pose.orientation.w = q.w(); odom_msg.twist.twist.linear.x = vx; odom_msg.twist.twist.linear.y = vy; odom_msg.twist.twist.linear.z = vz; odom_msg.twist.twist.angular.x = vroll; odom_msg.twist.twist.angular.y = vpitch; odom_msg.twist.twist.angular.z = vyaw; geometry_msgs::AccelWithCovarianceStamped accel_msg; accel_msg.header.stamp = time1; accel_msg.header.frame_id = "base_link"; accel_msg.accel.accel.linear.x = ax; accel_msg.accel.accel.linear.y = ay; accel_msg.accel.accel.linear.z = az; accel_msg.accel.accel.angular.x = 0; accel_msg.accel.accel.angular.y = 0; accel_msg.accel.accel.angular.z = 0; odom_pub.publish(odom_msg); accel_pub.publish(accel_msg); geometry_msgs::TransformStamped transformStamped; transformStamped.header.stamp = ros::Time::now(); transformStamped.header.frame_id = "base_link"; transformStamped.child_frame_id = "sensor"; transformStamped.transform.translation.x = 0.0; transformStamped.transform.translation.y = 1.0; transformStamped.transform.translation.z = 0.0; { tf2::Quaternion q; q.setRPY(0, 0, M_PI/2); transformStamped.transform.rotation.x = q.x(); transformStamped.transform.rotation.y = q.y(); transformStamped.transform.rotation.z = q.z(); transformStamped.transform.rotation.w = q.w(); transform_broadcaster.sendTransform(transformStamped); } ros::Duration(0.1).sleep(); } return 0; } ================================================ FILE: src/robot_localization/test/test_ukf.cpp ================================================ /* * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * 1. Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * 2. Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * 3. Neither the name of the copyright holder nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #include "robot_localization/ros_filter_types.h" #include #include #include using RobotLocalization::Ukf; using RobotLocalization::RosUkf; using RobotLocalization::STATE_SIZE; class RosUkfPassThrough : public RosUkf { public: explicit RosUkfPassThrough(std::vector &args) : RosUkf(args) { } Ukf &getFilter() { return filter_; } }; TEST(UkfTest, Measurements) { std::vector args; args.push_back(0.001); args.push_back(0); args.push_back(2); RosUkfPassThrough ukf(args); Eigen::MatrixXd initialCovar(15, 15); initialCovar.setIdentity(); initialCovar *= 0.5; ukf.getFilter().setEstimateErrorCovariance(initialCovar); EXPECT_EQ(ukf.getFilter().getEstimateErrorCovariance(), initialCovar); Eigen::VectorXd measurement(STATE_SIZE); for (size_t i = 0; i < STATE_SIZE; ++i) { measurement[i] = i * 0.01 * STATE_SIZE; } Eigen::MatrixXd measurementCovariance(STATE_SIZE, STATE_SIZE); measurementCovariance.setIdentity(); for (size_t i = 0; i < STATE_SIZE; ++i) { measurementCovariance(i, i) = 1e-9; } std::vector updateVector(STATE_SIZE, true); // Ensure that measurements are being placed in the queue correctly ros::Time time; time.fromSec(1000); ukf.enqueueMeasurement("odom0", measurement, measurementCovariance, updateVector, std::numeric_limits::max(), time); ukf.integrateMeasurements(ros::Time(1001)); EXPECT_EQ(ukf.getFilter().getState(), measurement); EXPECT_EQ(ukf.getFilter().getEstimateErrorCovariance(), measurementCovariance); ukf.getFilter().setEstimateErrorCovariance(initialCovar); // Now fuse another measurement and check the output. // We know what the filter's state should be when // this is complete, so we'll check the difference and // make sure it's suitably small. Eigen::VectorXd measurement2 = measurement; measurement2 *= 2.0; for (size_t i = 0; i < STATE_SIZE; ++i) { measurementCovariance(i, i) = 1e-9; } time.fromSec(1002); ukf.enqueueMeasurement("odom0", measurement2, measurementCovariance, updateVector, std::numeric_limits::max(), time); ukf.integrateMeasurements(ros::Time(1003)); measurement = measurement2.eval() - ukf.getFilter().getState(); for (size_t i = 0; i < STATE_SIZE; ++i) { EXPECT_LT(::fabs(measurement[i]), 0.001); } } int main(int argc, char **argv) { ros::init(argc, argv, "ukf"); testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); } ================================================ FILE: src/robot_localization/test/test_ukf.test ================================================ ================================================ FILE: src/robot_localization/test/test_ukf_localization_node_bag1.test ================================================ [false, false, false, false, false, false, true, true, true, false, false, false, false, false, false] [false, false, false, true, true, true, false, false, false, true, true, false, true, true, true] [0.05, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.05, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.06, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.06, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.025, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.025, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.04, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.02, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.015] [1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9] ================================================ FILE: src/robot_localization/test/test_ukf_localization_node_bag2.test ================================================ [false, false, false, false, false, false, true, true, true, false, false, true, false, false, false] [false, false, false, true, true, true, false, false, false, true, true, true, true, true, true] [0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.06, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.025, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.025, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.05, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.002, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.002, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.004, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01] [1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9] ================================================ FILE: src/robot_localization/test/test_ukf_localization_node_bag3.test ================================================ [false, false, true, false, false, false, true, true, false, false, false, true, false, false, false] [false, false, false, true, true, true, false, false, false, true, true, true, false, false, false] [0.03, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.4, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.025, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.025, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01] ================================================ FILE: src/robot_localization/test/test_ukf_localization_node_interfaces.cpp ================================================ /* * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * 1. Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * 2. Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * 3. Neither the name of the copyright holder nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #include "robot_localization/SetPose.h" #include #include #include #include #include #include #include #include #include nav_msgs::Odometry filtered_; bool stateUpdated_; void resetFilter() { ros::NodeHandle nh; ros::ServiceClient client = nh.serviceClient("/set_pose"); robot_localization::SetPose setPose; setPose.request.pose.pose.pose.orientation.w = 1; setPose.request.pose.header.frame_id = "odom"; for (size_t ind = 0; ind < 36; ind+=7) { setPose.request.pose.pose.covariance[ind] = 1e-6; } setPose.request.pose.header.stamp = ros::Time::now(); client.call(setPose); setPose.request.pose.header.seq++; ros::spinOnce(); ros::Duration(0.01).sleep(); stateUpdated_ = false; double deltaX = 0.0; double deltaY = 0.0; double deltaZ = 0.0; while (!stateUpdated_ || ::sqrt(deltaX * deltaX + deltaY * deltaY + deltaZ * deltaZ) > 0.1) { ros::spinOnce(); ros::Duration(0.01).sleep(); deltaX = filtered_.pose.pose.position.x - setPose.request.pose.pose.pose.position.x; deltaY = filtered_.pose.pose.position.y - setPose.request.pose.pose.pose.position.y; deltaZ = filtered_.pose.pose.position.z - setPose.request.pose.pose.pose.position.z; } EXPECT_LT(::sqrt(deltaX * deltaX + deltaY * deltaY + deltaZ * deltaZ), 0.1); } void filterCallback(const nav_msgs::OdometryConstPtr &msg) { filtered_ = *msg; stateUpdated_ = true; } TEST(InterfacesTest, OdomPoseBasicIO) { stateUpdated_ = false; ros::NodeHandle nh; ros::Publisher odomPub = nh.advertise("/odom_input0", 5); ros::Subscriber filteredSub = nh.subscribe("/odometry/filtered", 1, &filterCallback); nav_msgs::Odometry odom; odom.pose.pose.position.x = 20.0; odom.pose.pose.position.y = 10.0; odom.pose.pose.position.z = -40.0; odom.pose.covariance[0] = 2.0; odom.pose.covariance[7] = 2.0; odom.pose.covariance[14] = 2.0; odom.header.frame_id = "odom"; odom.child_frame_id = "base_link"; ros::Rate loopRate(50); for (size_t i = 0; i < 50; ++i) { odom.header.stamp = ros::Time::now(); odomPub.publish(odom); ros::spinOnce(); loopRate.sleep(); odom.header.seq++; } // Now check the values from the callback EXPECT_LT(::fabs(filtered_.pose.pose.position.x - odom.pose.pose.position.x), 0.01); EXPECT_LT(::fabs(filtered_.pose.pose.position.y), 0.01); // Configuration for this variable for this sensor is false EXPECT_LT(::fabs(filtered_.pose.pose.position.z - odom.pose.pose.position.z), 0.01); EXPECT_LT(filtered_.pose.covariance[0], 0.5); EXPECT_LT(filtered_.pose.covariance[7], 0.25); // Configuration for this variable for this sensor is false EXPECT_LT(filtered_.pose.covariance[14], 0.6); resetFilter(); } TEST(InterfacesTest, OdomTwistBasicIO) { ros::NodeHandle nh; ros::Publisher odomPub = nh.advertise("/odom_input2", 5); ros::Subscriber filteredSub = nh.subscribe("/odometry/filtered", 1, &filterCallback); nav_msgs::Odometry odom; odom.twist.twist.linear.x = 5.0; odom.twist.twist.linear.y = 0.0; odom.twist.twist.linear.z = 0.0; odom.twist.twist.angular.x = 0.0; odom.twist.twist.angular.y = 0.0; odom.twist.twist.angular.z = 0.0; for (size_t ind = 0; ind < 36; ind+=7) { odom.twist.covariance[ind] = 1e-6; } odom.header.frame_id = "odom"; odom.child_frame_id = "base_link"; ros::Rate loopRate(20); for (size_t i = 0; i < 400; ++i) { odom.header.stamp = ros::Time::now(); odomPub.publish(odom); ros::spinOnce(); loopRate.sleep(); odom.header.seq++; } ros::spinOnce(); EXPECT_LT(::fabs(filtered_.twist.twist.linear.x - odom.twist.twist.linear.x), 0.1); EXPECT_LT(::fabs(filtered_.pose.pose.position.x - 100.0), 2.0); resetFilter(); odom.twist.twist.linear.x = 0.0; odom.twist.twist.linear.y = 5.0; loopRate = ros::Rate(20); for (size_t i = 0; i < 200; ++i) { odom.header.stamp = ros::Time::now(); odomPub.publish(odom); ros::spinOnce(); loopRate.sleep(); odom.header.seq++; } ros::spinOnce(); EXPECT_LT(::fabs(filtered_.twist.twist.linear.y - odom.twist.twist.linear.y), 0.1); EXPECT_LT(::fabs(filtered_.pose.pose.position.y - 50.0), 1.0); resetFilter(); odom.twist.twist.linear.y = 0.0; odom.twist.twist.linear.z = 5.0; loopRate = ros::Rate(20); for (size_t i = 0; i < 100; ++i) { odom.header.stamp = ros::Time::now(); odomPub.publish(odom); ros::spinOnce(); loopRate.sleep(); odom.header.seq++; } ros::spinOnce(); EXPECT_LT(::fabs(filtered_.twist.twist.linear.z - odom.twist.twist.linear.z), 0.1); EXPECT_LT(::fabs(filtered_.pose.pose.position.z - 25.0), 1.0); resetFilter(); odom.twist.twist.linear.z = 0.0; odom.twist.twist.linear.x = 1.0; odom.twist.twist.angular.z = (M_PI/2) / (100.0 * 0.05); loopRate = ros::Rate(20); for (size_t i = 0; i < 100; ++i) { odom.header.stamp = ros::Time::now(); odomPub.publish(odom); ros::spinOnce(); loopRate.sleep(); odom.header.seq++; } ros::spinOnce(); EXPECT_LT(::fabs(filtered_.twist.twist.linear.x - odom.twist.twist.linear.x), 0.1); EXPECT_LT(::fabs(filtered_.twist.twist.angular.z - odom.twist.twist.angular.z), 0.1); EXPECT_LT(::fabs(filtered_.pose.pose.position.x - filtered_.pose.pose.position.y), 0.5); resetFilter(); odom.twist.twist.linear.x = 0.0; odom.twist.twist.angular.z = 0.0; odom.twist.twist.angular.x = -(M_PI/2) / (100.0 * 0.05); // First, roll the vehicle on its side loopRate = ros::Rate(20); for (size_t i = 0; i < 100; ++i) { odom.header.stamp = ros::Time::now(); odomPub.publish(odom); ros::spinOnce(); loopRate.sleep(); odom.header.seq++; } ros::spinOnce(); odom.twist.twist.angular.x = 0.0; odom.twist.twist.angular.y = (M_PI/2) / (100.0 * 0.05); // Now, pitch it down (positive pitch velocity in vehicle frame) loopRate = ros::Rate(20); for (size_t i = 0; i < 100; ++i) { odom.header.stamp = ros::Time::now(); odomPub.publish(odom); ros::spinOnce(); loopRate.sleep(); odom.header.seq++; } ros::spinOnce(); odom.twist.twist.angular.y = 0.0; odom.twist.twist.linear.x = 3.0; // We should now be on our side and facing -Y. Move forward in // the vehicle frame X direction, and make sure Y decreases in // the world frame. loopRate = ros::Rate(20); for (size_t i = 0; i < 100; ++i) { odom.header.stamp = ros::Time::now(); odomPub.publish(odom); ros::spinOnce(); loopRate.sleep(); odom.header.seq++; } ros::spinOnce(); EXPECT_LT(::fabs(filtered_.twist.twist.linear.x - odom.twist.twist.linear.x), 0.1); EXPECT_LT(::fabs(filtered_.pose.pose.position.y + 15), 1.0); resetFilter(); } TEST(InterfacesTest, PoseBasicIO) { ros::NodeHandle nh; ros::Publisher posePub = nh.advertise("/pose_input0", 5); ros::Subscriber filteredSub = nh.subscribe("/odometry/filtered", 1, &filterCallback); geometry_msgs::PoseWithCovarianceStamped pose; pose.pose.pose.position.x = 20.0; pose.pose.pose.position.y = 10.0; pose.pose.pose.position.z = -40.0; pose.pose.pose.orientation.x = 0; pose.pose.pose.orientation.y = 0; pose.pose.pose.orientation.z = 0; pose.pose.pose.orientation.w = 1; for (size_t ind = 0; ind < 36; ind+=7) { pose.pose.covariance[ind] = 1e-6; } pose.header.frame_id = "odom"; ros::Rate loopRate = ros::Rate(50); for (size_t i = 0; i < 50; ++i) { pose.header.stamp = ros::Time::now(); posePub.publish(pose); ros::spinOnce(); loopRate.sleep(); pose.header.seq++; } // Now check the values from the callback EXPECT_LT(::fabs(filtered_.pose.pose.position.x - pose.pose.pose.position.x), 0.1); EXPECT_LT(::fabs(filtered_.pose.pose.position.y), 0.1); // Configuration for this variable for this sensor is false EXPECT_LT(::fabs(filtered_.pose.pose.position.z - pose.pose.pose.position.z), 0.1); EXPECT_LT(filtered_.pose.covariance[0], 0.5); EXPECT_LT(filtered_.pose.covariance[7], 0.25); // Configuration for this variable for this sensor is false EXPECT_LT(filtered_.pose.covariance[14], 0.5); resetFilter(); } TEST(InterfacesTest, TwistBasicIO) { ros::NodeHandle nh; ros::Publisher twistPub = nh.advertise("/twist_input0", 5); ros::Subscriber filteredSub = nh.subscribe("/odometry/filtered", 1, &filterCallback); geometry_msgs::TwistWithCovarianceStamped twist; twist.twist.twist.linear.x = 5.0; twist.twist.twist.linear.y = 0; twist.twist.twist.linear.z = 0; twist.twist.twist.angular.x = 0; twist.twist.twist.angular.y = 0; twist.twist.twist.angular.z = 0; for (size_t ind = 0; ind < 36; ind+=7) { twist.twist.covariance[ind] = 1e-6; } twist.header.frame_id = "base_link"; ros::Rate loopRate = ros::Rate(20); for (size_t i = 0; i < 400; ++i) { twist.header.stamp = ros::Time::now(); twistPub.publish(twist); ros::spinOnce(); loopRate.sleep(); twist.header.seq++; } ros::spinOnce(); EXPECT_LT(::fabs(filtered_.twist.twist.linear.x - twist.twist.twist.linear.x), 0.1); EXPECT_LT(::fabs(filtered_.pose.pose.position.x - 100.0), 2.0); resetFilter(); twist.twist.twist.linear.x = 0.0; twist.twist.twist.linear.y = 5.0; loopRate = ros::Rate(20); for (size_t i = 0; i < 200; ++i) { twist.header.stamp = ros::Time::now(); twistPub.publish(twist); ros::spinOnce(); loopRate.sleep(); twist.header.seq++; } ros::spinOnce(); EXPECT_LT(::fabs(filtered_.twist.twist.linear.y - twist.twist.twist.linear.y), 0.1); EXPECT_LT(::fabs(filtered_.pose.pose.position.y - 50.0), 1.0); resetFilter(); twist.twist.twist.linear.y = 0.0; twist.twist.twist.linear.z = 5.0; loopRate = ros::Rate(20); for (size_t i = 0; i < 100; ++i) { twist.header.stamp = ros::Time::now(); twistPub.publish(twist); ros::spinOnce(); loopRate.sleep(); twist.header.seq++; } ros::spinOnce(); EXPECT_LT(::fabs(filtered_.twist.twist.linear.z - twist.twist.twist.linear.z), 0.1); EXPECT_LT(::fabs(filtered_.pose.pose.position.z - 25.0), 1.0); resetFilter(); twist.twist.twist.linear.z = 0.0; twist.twist.twist.linear.x = 1.0; twist.twist.twist.angular.z = (M_PI/2) / (100.0 * 0.05); loopRate = ros::Rate(20); for (size_t i = 0; i < 100; ++i) { twist.header.stamp = ros::Time::now(); twistPub.publish(twist); ros::spinOnce(); loopRate.sleep(); twist.header.seq++; } ros::spinOnce(); EXPECT_LT(::fabs(filtered_.twist.twist.linear.x - twist.twist.twist.linear.x), 0.1); EXPECT_LT(::fabs(filtered_.twist.twist.angular.z - twist.twist.twist.angular.z), 0.1); EXPECT_LT(::fabs(filtered_.pose.pose.position.x - filtered_.pose.pose.position.y), 0.5); resetFilter(); twist.twist.twist.linear.x = 0.0; twist.twist.twist.angular.z = 0.0; twist.twist.twist.angular.x = -(M_PI/2) / (100.0 * 0.05); // First, roll the vehicle on its side loopRate = ros::Rate(20); for (size_t i = 0; i < 100; ++i) { twist.header.stamp = ros::Time::now(); twistPub.publish(twist); ros::spinOnce(); loopRate.sleep(); twist.header.seq++; } ros::spinOnce(); twist.twist.twist.angular.x = 0.0; twist.twist.twist.angular.y = (M_PI/2) / (100.0 * 0.05); // Now, pitch it down (positive pitch velocity in vehicle frame) loopRate = ros::Rate(20); for (size_t i = 0; i < 100; ++i) { twist.header.stamp = ros::Time::now(); twistPub.publish(twist); ros::spinOnce(); loopRate.sleep(); twist.header.seq++; } ros::spinOnce(); twist.twist.twist.angular.y = 0.0; twist.twist.twist.linear.x = 3.0; // We should now be on our side and facing -Y. Move forward in // the vehicle frame X direction, and make sure Y decreases in // the world frame. loopRate = ros::Rate(20); for (size_t i = 0; i < 100; ++i) { twist.header.stamp = ros::Time::now(); twistPub.publish(twist); ros::spinOnce(); loopRate.sleep(); twist.header.seq++; } ros::spinOnce(); EXPECT_LT(::fabs(filtered_.twist.twist.linear.x - twist.twist.twist.linear.x), 0.1); EXPECT_LT(::fabs(filtered_.pose.pose.position.y + 15), 1.0); resetFilter(); } TEST(InterfacesTest, ImuPoseBasicIO) { ros::NodeHandle nh; ros::Publisher imuPub = nh.advertise("/imu_input0", 5); ros::Subscriber filteredSub = nh.subscribe("/odometry/filtered", 1, &filterCallback); sensor_msgs::Imu imu; tf2::Quaternion quat; quat.setRPY(M_PI/4, -M_PI/4, M_PI/2); imu.orientation = tf2::toMsg(quat); for (size_t ind = 0; ind < 9; ind+=4) { imu.orientation_covariance[ind] = 1e-6; } imu.header.frame_id = "base_link"; // Make sure the pose reset worked. Test will timeout // if this fails. ros::Rate loopRate(50); for (size_t i = 0; i < 50; ++i) { imu.header.stamp = ros::Time::now(); imuPub.publish(imu); ros::spinOnce(); loopRate.sleep(); imu.header.seq++; } // Now check the values from the callback tf2::fromMsg(filtered_.pose.pose.orientation, quat); tf2::Matrix3x3 mat(quat); double r, p, y; mat.getRPY(r, p, y); EXPECT_LT(::fabs(r - M_PI/4), 0.1); EXPECT_LT(::fabs(p + M_PI/4), 0.1); EXPECT_LT(::fabs(y - M_PI/2), 0.1); EXPECT_LT(filtered_.pose.covariance[21], 0.5); EXPECT_LT(filtered_.pose.covariance[28], 0.25); EXPECT_LT(filtered_.pose.covariance[35], 0.5); resetFilter(); // Test to see if the orientation data is ignored when we set the // first covariance value to -1 sensor_msgs::Imu imuIgnore; imuIgnore.orientation.x = 0.1; imuIgnore.orientation.y = 0.2; imuIgnore.orientation.z = 0.3; imuIgnore.orientation.w = 0.4; imuIgnore.orientation_covariance[0] = -1; loopRate = ros::Rate(50); for (size_t i = 0; i < 50; ++i) { imuIgnore.header.stamp = ros::Time::now(); imuPub.publish(imuIgnore); loopRate.sleep(); ros::spinOnce(); imuIgnore.header.seq++; } tf2::fromMsg(filtered_.pose.pose.orientation, quat); mat.setRotation(quat); mat.getRPY(r, p, y); EXPECT_LT(::fabs(r), 1e-3); EXPECT_LT(::fabs(p), 1e-3); EXPECT_LT(::fabs(y), 1e-3); resetFilter(); } TEST(InterfacesTest, ImuTwistBasicIO) { ros::NodeHandle nh; ros::Publisher imuPub = nh.advertise("/imu_input1", 5); ros::Subscriber filteredSub = nh.subscribe("/odometry/filtered", 1, &filterCallback); sensor_msgs::Imu imu; tf2::Quaternion quat; imu.angular_velocity.x = (M_PI / 2.0); for (size_t ind = 0; ind < 9; ind+=4) { imu.angular_velocity_covariance[ind] = 1e-6; } imu.header.frame_id = "base_link"; ros::Rate loopRate(50); for (size_t i = 0; i < 50; ++i) { imu.header.stamp = ros::Time::now(); imuPub.publish(imu); loopRate.sleep(); ros::spinOnce(); imu.header.seq++; } // Now check the values from the callback tf2::fromMsg(filtered_.pose.pose.orientation, quat); tf2::Matrix3x3 mat(quat); double r, p, y; mat.getRPY(r, p, y); // Tolerances may seem loose, but the initial state covariances // are tiny, so the filter is sluggish to accept velocity data EXPECT_LT(::fabs(r - M_PI / 2.0), 0.7); EXPECT_LT(::fabs(p), 0.1); EXPECT_LT(::fabs(y), 0.1); EXPECT_LT(filtered_.twist.covariance[21], 1e-3); EXPECT_LT(filtered_.pose.covariance[21], 0.1); resetFilter(); imu.angular_velocity.x = 0.0; imu.angular_velocity.y = -(M_PI / 2.0); // Make sure the pose reset worked. Test will timeout // if this fails. loopRate = ros::Rate(50); for (size_t i = 0; i < 50; ++i) { imu.header.stamp = ros::Time::now(); imuPub.publish(imu); loopRate.sleep(); ros::spinOnce(); imu.header.seq++; } // Now check the values from the callback tf2::fromMsg(filtered_.pose.pose.orientation, quat); tf2::Quaternion expected_quat(tf2::Vector3(0., 1., 0.), -M_PI/2.0); EXPECT_LT(std::abs(tf2Angle(expected_quat.getAxis(), quat.getAxis())), 0.1); EXPECT_LT(std::abs(expected_quat.getAngle() - quat.getAngle()), 0.7); EXPECT_LT(filtered_.twist.covariance[28], 1e-3); EXPECT_LT(filtered_.pose.covariance[28], 0.1); resetFilter(); imu.angular_velocity.y = 0; imu.angular_velocity.z = M_PI / 4.0; // Make sure the pose reset worked. Test will timeout // if this fails. loopRate = ros::Rate(50); for (size_t i = 0; i < 50; ++i) { imu.header.stamp = ros::Time::now(); imuPub.publish(imu); loopRate.sleep(); ros::spinOnce(); imu.header.seq++; } // Now check the values from the callback tf2::fromMsg(filtered_.pose.pose.orientation, quat); mat.setRotation(quat); mat.getRPY(r, p, y); EXPECT_LT(::fabs(r), 0.1); EXPECT_LT(::fabs(p), 0.1); EXPECT_LT(::fabs(y - M_PI / 4.0), 0.7); EXPECT_LT(filtered_.twist.covariance[35], 1e-3); EXPECT_LT(filtered_.pose.covariance[35], 0.1); resetFilter(); // Test to see if the angular velocity data is ignored when we set the // first covariance value to -1 sensor_msgs::Imu imuIgnore; imuIgnore.angular_velocity.x = 100; imuIgnore.angular_velocity.y = 100; imuIgnore.angular_velocity.z = 100; imuIgnore.angular_velocity_covariance[0] = -1; loopRate = ros::Rate(50); for (size_t i = 0; i < 50; ++i) { imuIgnore.header.stamp = ros::Time::now(); imuPub.publish(imuIgnore); loopRate.sleep(); ros::spinOnce(); imuIgnore.header.seq++; } tf2::fromMsg(filtered_.pose.pose.orientation, quat); mat.setRotation(quat); mat.getRPY(r, p, y); EXPECT_LT(::fabs(r), 1e-3); EXPECT_LT(::fabs(p), 1e-3); EXPECT_LT(::fabs(y), 1e-3); resetFilter(); } TEST(InterfacesTest, ImuAccBasicIO) { ros::NodeHandle nh; ros::Publisher imuPub = nh.advertise("/imu_input2", 5); ros::Subscriber filteredSub = nh.subscribe("/odometry/filtered", 1, &filterCallback); sensor_msgs::Imu imu; imu.header.frame_id = "base_link"; imu.linear_acceleration_covariance[0] = 1e-6; imu.linear_acceleration_covariance[4] = 1e-6; imu.linear_acceleration_covariance[8] = 1e-6; imu.linear_acceleration.x = 1; imu.linear_acceleration.y = -1; imu.linear_acceleration.z = 1; // Move with constant acceleration for 1 second, // then check our velocity. ros::Rate loopRate(50); for (size_t i = 0; i < 50; ++i) { imu.header.stamp = ros::Time::now(); imuPub.publish(imu); loopRate.sleep(); ros::spinOnce(); imu.header.seq++; } EXPECT_LT(::fabs(filtered_.twist.twist.linear.x - 1.0), 0.4); EXPECT_LT(::fabs(filtered_.twist.twist.linear.y + 1.0), 0.4); EXPECT_LT(::fabs(filtered_.twist.twist.linear.z - 1.0), 0.4); imu.linear_acceleration.x = 0.0; imu.linear_acceleration.y = 0.0; imu.linear_acceleration.z = 0.0; // Now move for another second, and see where we // end up loopRate = ros::Rate(50); for (size_t i = 0; i < 50; ++i) { imu.header.stamp = ros::Time::now(); imuPub.publish(imu); loopRate.sleep(); ros::spinOnce(); imu.header.seq++; } EXPECT_LT(::fabs(filtered_.pose.pose.position.x - 1.2), 0.4); EXPECT_LT(::fabs(filtered_.pose.pose.position.y + 1.2), 0.4); EXPECT_LT(::fabs(filtered_.pose.pose.position.z - 1.2), 0.4); resetFilter(); // Test to see if the linear acceleration data is ignored when we set the // first covariance value to -1 sensor_msgs::Imu imuIgnore; imuIgnore.linear_acceleration.x = 1000; imuIgnore.linear_acceleration.y = 1000; imuIgnore.linear_acceleration.z = 1000; imuIgnore.linear_acceleration_covariance[0] = -1; loopRate = ros::Rate(50); for (size_t i = 0; i < 50; ++i) { imuIgnore.header.stamp = ros::Time::now(); imuPub.publish(imuIgnore); loopRate.sleep(); ros::spinOnce(); imuIgnore.header.seq++; } EXPECT_LT(::fabs(filtered_.pose.pose.position.x), 1e-3); EXPECT_LT(::fabs(filtered_.pose.pose.position.y), 1e-3); EXPECT_LT(::fabs(filtered_.pose.pose.position.z), 1e-3); resetFilter(); } TEST(InterfacesTest, OdomDifferentialIO) { ros::NodeHandle nh; ros::Publisher odomPub = nh.advertise("/odom_input1", 5); ros::Subscriber filteredSub = nh.subscribe("/odometry/filtered", 1, &filterCallback); nav_msgs::Odometry odom; odom.pose.pose.position.x = 20.0; odom.pose.pose.position.y = 10.0; odom.pose.pose.position.z = -40.0; odom.pose.pose.orientation.w = 1; odom.pose.covariance[0] = 2.0; odom.pose.covariance[7] = 2.0; odom.pose.covariance[14] = 2.0; odom.pose.covariance[21] = 0.2; odom.pose.covariance[28] = 0.2; odom.pose.covariance[35] = 0.2; odom.header.frame_id = "odom"; odom.child_frame_id = "base_link"; // No guaranteeing that the zero state // we're expecting to see here isn't just // a result of zeroing it out previously, // so check 10 times in succession. size_t zeroCount = 0; while (zeroCount++ < 10) { odom.header.stamp = ros::Time::now(); odomPub.publish(odom); ros::spinOnce(); EXPECT_LT(::fabs(filtered_.pose.pose.position.x), 0.01); EXPECT_LT(::fabs(filtered_.pose.pose.position.y), 0.01); EXPECT_LT(::fabs(filtered_.pose.pose.position.z), 0.01); EXPECT_LT(::fabs(filtered_.pose.pose.orientation.x), 0.01); EXPECT_LT(::fabs(filtered_.pose.pose.orientation.y), 0.01); EXPECT_LT(::fabs(filtered_.pose.pose.orientation.z), 0.01); EXPECT_LT(::fabs(filtered_.pose.pose.orientation.w - 1), 0.01); ros::Duration(0.1).sleep(); odom.header.seq++; } for (size_t ind = 0; ind < 36; ind+=7) { odom.pose.covariance[ind] = 1e-6; } // Slowly move the position, and hope that the // differential position keeps up ros::Rate loopRate(20); for (size_t i = 0; i < 100; ++i) { odom.pose.pose.position.x += 0.01; odom.pose.pose.position.y += 0.02; odom.pose.pose.position.z -= 0.03; odom.header.stamp = ros::Time::now(); odomPub.publish(odom); ros::spinOnce(); loopRate.sleep(); odom.header.seq++; } ros::spinOnce(); EXPECT_LT(::fabs(filtered_.pose.pose.position.x - 1), 0.2); EXPECT_LT(::fabs(filtered_.pose.pose.position.y - 2), 0.4); EXPECT_LT(::fabs(filtered_.pose.pose.position.z + 3), 0.6); resetFilter(); } TEST(InterfacesTest, PoseDifferentialIO) { ros::NodeHandle nh; ros::Publisher posePub = nh.advertise("/pose_input1", 5); ros::Subscriber filteredSub = nh.subscribe("/odometry/filtered", 1, &filterCallback); geometry_msgs::PoseWithCovarianceStamped pose; pose.pose.pose.position.x = 20.0; pose.pose.pose.position.y = 10.0; pose.pose.pose.position.z = -40.0; pose.pose.pose.orientation.w = 1; pose.pose.covariance[0] = 2.0; pose.pose.covariance[7] = 2.0; pose.pose.covariance[14] = 2.0; pose.pose.covariance[21] = 0.2; pose.pose.covariance[28] = 0.2; pose.pose.covariance[35] = 0.2; pose.header.frame_id = "odom"; // No guaranteeing that the zero state // we're expecting to see here isn't just // a result of zeroing it out previously, // so check 10 times in succession. size_t zeroCount = 0; while (zeroCount++ < 10) { pose.header.stamp = ros::Time::now(); posePub.publish(pose); ros::spinOnce(); EXPECT_LT(::fabs(filtered_.pose.pose.position.x), 0.01); EXPECT_LT(::fabs(filtered_.pose.pose.position.y), 0.01); EXPECT_LT(::fabs(filtered_.pose.pose.position.z), 0.01); EXPECT_LT(::fabs(filtered_.pose.pose.orientation.x), 0.01); EXPECT_LT(::fabs(filtered_.pose.pose.orientation.y), 0.01); EXPECT_LT(::fabs(filtered_.pose.pose.orientation.z), 0.01); EXPECT_LT(::fabs(filtered_.pose.pose.orientation.w - 1), 0.01); ros::Duration(0.1).sleep(); pose.header.seq++; } // ...but only if we give the measurement a tiny covariance for (size_t ind = 0; ind < 36; ind+=7) { pose.pose.covariance[ind] = 1e-6; } // Issue this location repeatedly, and see if we get // a final reported position of (1, 2, -3) ros::Rate loopRate(20); for (size_t i = 0; i < 100; ++i) { pose.pose.pose.position.x += 0.01; pose.pose.pose.position.y += 0.02; pose.pose.pose.position.z -= 0.03; pose.header.stamp = ros::Time::now(); posePub.publish(pose); ros::spinOnce(); loopRate.sleep(); pose.header.seq++; } ros::spinOnce(); EXPECT_LT(::fabs(filtered_.pose.pose.position.x - 1), 0.2); EXPECT_LT(::fabs(filtered_.pose.pose.position.y - 2), 0.4); EXPECT_LT(::fabs(filtered_.pose.pose.position.z + 3), 0.6); resetFilter(); } TEST(InterfacesTest, ImuDifferentialIO) { ros::NodeHandle nh; ros::Publisher imu0Pub = nh.advertise("/imu_input0", 5); ros::Publisher imu1Pub = nh.advertise("/imu_input1", 5); ros::Publisher imuPub = nh.advertise("/imu_input3", 5); ros::Subscriber filteredSub = nh.subscribe("/odometry/filtered", 1, &filterCallback); sensor_msgs::Imu imu; imu.header.frame_id = "base_link"; tf2::Quaternion quat; const double roll = M_PI/2.0; const double pitch = -M_PI; const double yaw = -M_PI/4.0; quat.setRPY(roll, pitch, yaw); imu.orientation = tf2::toMsg(quat); imu.orientation_covariance[0] = 0.02; imu.orientation_covariance[4] = 0.02; imu.orientation_covariance[8] = 0.02; imu.angular_velocity_covariance[0] = 0.02; imu.angular_velocity_covariance[4] = 0.02; imu.angular_velocity_covariance[8] = 0.02; size_t setCount = 0; while (setCount++ < 10) { imu.header.stamp = ros::Time::now(); imu0Pub.publish(imu); // Use this to move the absolute orientation imu1Pub.publish(imu); // Use this to keep velocities at 0 ros::spinOnce(); ros::Duration(0.1).sleep(); imu.header.seq++; } size_t zeroCount = 0; while (zeroCount++ < 10) { imu.header.stamp = ros::Time::now(); imuPub.publish(imu); ros::spinOnce(); ros::Duration(0.1).sleep(); imu.header.seq++; } double rollFinal = roll; double pitchFinal = pitch; double yawFinal = yaw; // Move the orientation slowly, and see if we // can push it to 0 ros::Rate loopRate(20); for (size_t i = 0; i < 100; ++i) { yawFinal -= 0.01 * (3.0 * M_PI/4.0); quat.setRPY(rollFinal, pitchFinal, yawFinal); imu.orientation = tf2::toMsg(quat); imu.header.stamp = ros::Time::now(); imuPub.publish(imu); ros::spinOnce(); loopRate.sleep(); imu.header.seq++; } ros::spinOnce(); // Move the orientation slowly, and see if we // can push it to 0 loopRate = ros::Rate(20); for (size_t i = 0; i < 100; ++i) { rollFinal += 0.01 * (M_PI/2.0); quat.setRPY(rollFinal, pitchFinal, yawFinal); imu.orientation = tf2::toMsg(quat); imu.header.stamp = ros::Time::now(); imuPub.publish(imu); ros::spinOnce(); loopRate.sleep(); imu.header.seq++; } ros::spinOnce(); tf2::fromMsg(filtered_.pose.pose.orientation, quat); tf2::Matrix3x3 mat(quat); mat.getRPY(rollFinal, pitchFinal, yawFinal); EXPECT_LT(::fabs(rollFinal), 0.2); EXPECT_LT(::fabs(pitchFinal), 0.2); EXPECT_LT(::fabs(yawFinal), 0.2); resetFilter(); } int main(int argc, char **argv) { testing::InitGoogleTest(&argc, argv); ros::init(argc, argv, "ukf_navigation_node-test-interfaces"); ros::Time::init(); // Give ukf_localization_node time to initialize ros::Duration(2.0).sleep(); return RUN_ALL_TESTS(); } ================================================ FILE: src/robot_localization/test/test_ukf_localization_node_interfaces.test ================================================ [true, false, true, false, false, false, false, false, false, false, false, false, false, false, false] [true, true, true, true, true, true, false, false, false, false, false, false, false, false, false] [false, false, false, false, false, false, true, true, true, true, true, true, false, false, false] [true, false, true, false, false, false, false, false, false, false, false, false, false, false, false] [true, true, true, true, true, true, false, false, false, false, false, false, false, false, false] [false, false, false, false, false, false, true, true, true, true, true, true, false, false, false] [false, false, false, true, true, true, false, false, false, false, false, false, false, false, false] [false, false, false, false, false, false, false, false, false, true, true, true, false, false, false] [false, false, false, false, false, false, false, false, false, false, false, false, true, true, true] [false, false, false, true, true, true, false, false, false, false, false, false, false, false, false] [0.03, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.4, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.025, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.025, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01]